From 0112c69ed5eb09a8e0e3555c629a218f5c954223 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Mon, 3 Nov 2025 08:11:18 +0000 Subject: [PATCH 01/35] update vln yaml; fix import agent --- scripts/eval/configs/vln_r2r.yaml | 6 +++--- scripts/eval/start_server.py | 19 ++----------------- setup.cfg | 2 +- 3 files changed, 6 insertions(+), 21 deletions(-) diff --git a/scripts/eval/configs/vln_r2r.yaml b/scripts/eval/configs/vln_r2r.yaml index 379f6d7..ed8361c 100644 --- a/scripts/eval/configs/vln_r2r.yaml +++ b/scripts/eval/configs/vln_r2r.yaml @@ -69,9 +69,9 @@ habitat: look_down: type: LookDownAction agent_index: 0 - + dataset: type: R2RVLN-v1 split: val_seen - scenes_dir: data/scene_data/ - data_path: data/vln_ce/raw_data/r2r/{split}/{split}.json.gz \ No newline at end of file + scenes_dir: data/scene_data/mp3d_ce + data_path: data/vln_ce/raw_data/r2r/{split}/{split}.json.gz diff --git a/scripts/eval/start_server.py b/scripts/eval/start_server.py index 5a03cd7..60e6007 100644 --- a/scripts/eval/start_server.py +++ b/scripts/eval/start_server.py @@ -5,27 +5,15 @@ sys.path.append('./src/diffusion-policy') import argparse -import glob import importlib import importlib.util -import os import sys +# Import for agent registry side effects — do not remove +from internnav.agent import Agent # noqa: F401 from internnav.utils import AgentServer -# import all agents to register them -def auto_register_agents(agent_dir: str): - # Get all Python files in the agents directory - agent_modules = glob.glob(os.path.join(agent_dir, '*.py')) - - # Import each module to trigger the registration - for module in agent_modules: - if not module.endswith('__init__.py'): # Avoid importing __init__.py itself - module_name = os.path.basename(module)[:-3] # Remove the .py extension - importlib.import_module(f'internnav.agent.{module_name}') # Replace 'agents' with your module's package - - def load_eval_cfg(config_path, attr_name='eval_cfg'): spec = importlib.util.spec_from_file_location("eval_config_module", config_path) config_module = importlib.util.module_from_spec(spec) @@ -37,9 +25,6 @@ def load_eval_cfg(config_path, attr_name='eval_cfg'): if __name__ == '__main__': print("Starting Agent Server...") - print("Registering agents...") - auto_register_agents('internnav/agent') - parser = argparse.ArgumentParser() parser.add_argument('--host', type=str, default='localhost') parser.add_argument( diff --git a/setup.cfg b/setup.cfg index 3aeaebe..b6a3f5b 100644 --- a/setup.cfg +++ b/setup.cfg @@ -45,4 +45,4 @@ per-file-ignores=*/__init__.py:F401 ignore=E402,E501,W503,E203,D401,R504,R505,SIM102,SIM117,E711,E226 max-line-length = 120 max-complexity = 30 -exclude=_*,.vscode,.git,docs/**,**/test/**,**/lcmtypes/**,*.ipynb,scripts/**,internnav/projects/** +exclude=_*,.vscode,.git,docs/**,**/test/**,**/lcmtypes/**,*.ipynb From 05ea2a304b2c7afec6ff93e7cab35004a47b6eae Mon Sep 17 00:00:00 2001 From: wangyukai Date: Mon, 10 Nov 2025 05:37:18 +0000 Subject: [PATCH 02/35] update habitat, using evaluator and config; env and agent is WIP --- internnav/configs/evaluator/__init__.py | 6 +- internnav/evaluator/__init__.py | 2 + internnav/evaluator/distributed_base.py | 131 +++ internnav/evaluator/habitat_vln_evaluator.py | 460 +++++----- internnav/internnav_habitat/__init__.py | 2 + internnav/internnav_habitat/habitat_env.py | 126 +++ .../habitat_n1_agent_temp.py | 263 ++++++ .../habitat_vln_evaluator.py | 842 ++++++++++++++++++ internnav/internnav_habitat/measures.py | 560 ++++++++++++ internnav/internnav_habitat/refactor_notes.md | 66 ++ internnav/internnav_habitat/utils.py | 0 scripts/eval/bash/torchrun_eval.sh | 20 + scripts/eval/configs/comm_cfg.py | 16 + scripts/eval/configs/habitat_cfg.py | 60 ++ scripts/eval/configs/vln_r2r.yaml | 2 +- scripts/eval/eval.py | 20 +- 16 files changed, 2306 insertions(+), 270 deletions(-) create mode 100644 internnav/evaluator/distributed_base.py create mode 100644 internnav/internnav_habitat/__init__.py create mode 100644 internnav/internnav_habitat/habitat_env.py create mode 100644 internnav/internnav_habitat/habitat_n1_agent_temp.py create mode 100644 internnav/internnav_habitat/habitat_vln_evaluator.py create mode 100644 internnav/internnav_habitat/measures.py create mode 100644 internnav/internnav_habitat/refactor_notes.md create mode 100644 internnav/internnav_habitat/utils.py create mode 100644 scripts/eval/bash/torchrun_eval.sh create mode 100644 scripts/eval/configs/comm_cfg.py create mode 100644 scripts/eval/configs/habitat_cfg.py diff --git a/internnav/configs/evaluator/__init__.py b/internnav/configs/evaluator/__init__.py index ab770c5..27e63a3 100644 --- a/internnav/configs/evaluator/__init__.py +++ b/internnav/configs/evaluator/__init__.py @@ -59,9 +59,9 @@ class EvalCfg(BaseModel): eval_type: Optional[str] = None eval_settings: Optional[Dict[str, Any]] = {} agent: Optional[AgentCfg] = None - env: EnvCfg - task: TaskCfg - dataset: EvalDatasetCfg + env: EnvCfg = None + task: TaskCfg = None + dataset: EvalDatasetCfg = None __all__ = [ diff --git a/internnav/evaluator/__init__.py b/internnav/evaluator/__init__.py index 88393e5..e831ea5 100644 --- a/internnav/evaluator/__init__.py +++ b/internnav/evaluator/__init__.py @@ -1,3 +1,5 @@ +# register habitat TODO +import internnav.internnav_habitat # noqa: F401 from internnav.evaluator.base import Evaluator from internnav.evaluator.vln_multi_evaluator import VlnMultiEvaluator diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py new file mode 100644 index 0000000..3244305 --- /dev/null +++ b/internnav/evaluator/distributed_base.py @@ -0,0 +1,131 @@ +import json +import os +from datetime import datetime + +import torch + +from internnav.configs.evaluator import EvalCfg +from internnav.evaluator.base import Evaluator +from internnav.utils.dist import dist, get_rank, get_world_size + + +def init_distributed_mode(args): + if 'SLURM_PROCID' in os.environ: + args.rank = int(os.environ['SLURM_PROCID']) + args.world_size = int(os.environ['SLURM_NTASKS']) + + num_gpus = torch.cuda.device_count() + args.gpu = args.rank % num_gpus + args.local_rank = args.gpu + + node_list = os.environ['SLURM_NODELIST'] + print(f'Node list: {node_list}') + # addr = subprocess.getoutput(f'scontrol show hostname {node_list} | head -n1') + + os.environ['MASTER_PORT'] = str(getattr(args, 'port', '29529')) + # os.environ['MASTER_ADDR'] = addr + os.environ['WORLD_SIZE'] = str(args.world_size) + os.environ['LOCAL_RANK'] = str(args.gpu) + os.environ['RANK'] = str(args.rank) + elif 'RANK' in os.environ and 'WORLD_SIZE' in os.environ: + args.rank = int(os.environ["RANK"]) + args.world_size = int(os.environ['WORLD_SIZE']) + args.gpu = int(os.environ['LOCAL_RANK']) + args.local_rank = args.gpu + else: + print('Not using distributed mode') + # setup_for_distributed(is_master=True) # hack + args.distributed = False + return + + args.distributed = True + + torch.cuda.set_device(args.gpu) + args.dist_backend = 'nccl' + print('| distributed init (rank {}): {}, gpu {}'.format(args.rank, args.dist_url, args.gpu), flush=True) + dist.init_process_group( + backend=args.dist_backend, + init_method=args.dist_url, + world_size=args.world_size, + rank=args.rank, + timeout=datetime.timedelta(0, 7200), + ) + dist.barrier() + # setup_for_distributed(args.rank == 0) + + +class DistributedEvaluator(Evaluator): + """ + Base class of distributed evaluators. + """ + + def __init__(self, cfg: EvalCfg): + # distributed setting + import os + import socket + + print( + f"Rank {os.getenv('RANK')} / {os.getenv('WORLD_SIZE')} on {socket.gethostname()}:{os.getenv('MASTER_PORT')}" + ) + # init_distributed_mode(args) + # local_rank = args.local_rank + # np.random.seed(local_rank) + cfg.env.env_settings['idx'] = get_rank() + cfg.env.env_settings['world_size'] = get_world_size() + + # set agent port based on rank + cfg.agent.agent_settings['port'] = 8000 + get_rank() + # start_server(cfg.agent.agent_settings['port']) + + super().__init__(cfg) + + def eval(self): + # 1. 每个 rank 本地跑一遍 + local_metrics = self.eval_action() # dict[str, Tensor], 每个 Tensor shape [N] + # 取出设备 & 本地样本数 + device = next(iter(local_metrics.values())).device + local_count = torch.tensor([len(next(iter(local_metrics.values())))], dtype=torch.long, device=device) + + # 2. 全局样本数 + world_size = get_world_size() + global_count = local_count.clone() + if world_size > 1: + dist.all_reduce(global_count, op=dist.ReduceOp.SUM) + + # 3. 对每个 metric 做全局 sum / mean + result_all = {} + for name, tensor in local_metrics.items(): + # tensor: [N] + local_sum = tensor.sum() + global_sum = local_sum.clone() + if world_size > 1: + dist.all_reduce(global_sum, op=dist.ReduceOp.SUM) + + mean_val = (global_sum / global_count).item() + result_all[name] = mean_val + + # 4. 统计全局 episode 数 + result_all["length"] = int(global_count.item()) + + # 5. 打印 + 只在 rank 0 写文件 + print(result_all) + if get_rank() == 0: + os.makedirs(self.args.output_path, exist_ok=True) + out_path = os.path.join(self.args.output_path, "result.json") + with open(out_path, "a") as f: + f.write(json.dumps(result_all) + "\n") + + return result_all + + def eval_action(self): + """ + 跑当前 rank 的 episodes, 返回一个 dict: + { + "success": tensor([0., 1., ...], device=...), + "spl": tensor([...]), + "os": tensor([...]), + "ne": tensor([...]), + ... + } + """ + raise NotImplementedError diff --git a/internnav/evaluator/habitat_vln_evaluator.py b/internnav/evaluator/habitat_vln_evaluator.py index 3bf4c54..e901ae3 100644 --- a/internnav/evaluator/habitat_vln_evaluator.py +++ b/internnav/evaluator/habitat_vln_evaluator.py @@ -26,14 +26,11 @@ from habitat_baselines.config.default import get_config as get_habitat_config from omegaconf import OmegaConf from PIL import Image, ImageDraw, ImageFont -from torch import Tensor from transformers.image_utils import to_numpy_array from internnav.model.utils.vln_utils import ( chunk_token, - image_resize, open_image, - rho_theta, split_and_clean, traj_to_actions, ) @@ -68,8 +65,8 @@ def __init__( with habitat.config.read_write(self.config): # self.config.habitat.task.measurements.success.success_distance=3.0 - self.config.habitat.dataset.split = self.split - self.config.habitat.task.measurements.update( + self.config.habitat.dataset.split = self.split # refactor: why args and yaml both have split + self.config.habitat.task.measurements.update( # refactor: move to yaml { "top_down_map": TopDownMapMeasurementConfig( map_padding=3, @@ -104,6 +101,7 @@ def __init__( self.model = model self.processor = processor + # refactor: this part used in three places prompt = "You are an autonomous navigation assistant. Your task is to . Where should you go next to stay on track? Please output the next waypoint\'s coordinates in the image. Please output STOP when you have successfully completed the task." answer = "" self.conversation = [{"from": "human", "value": prompt}, {"from": "gpt", "value": answer}] @@ -134,260 +132,12 @@ def __init__( self.num_future_steps = args.num_future_steps self.num_history = args.num_history - def preprocess_depth_image_v2( - self, depth_image, do_depth_scale=True, depth_scale=1000, target_height=None, target_width=None - ): - if target_height is None: - target_height = self.image_processor.crop_size['height'] # 384 - target_width = self.image_processor.crop_size['width'] # 384 - - resized_depth_image = depth_image.resize((target_width, target_height), Image.NEAREST) - - img = to_numpy_array(resized_depth_image) - if do_depth_scale: - img = img / depth_scale - - return img, (target_width, target_height) - - def get_intrinsic_matrix(self, sensor_cfg) -> np.ndarray: - width = sensor_cfg.width - height = sensor_cfg.height - fov = sensor_cfg.hfov - fx = (width / 2.0) / np.tan(np.deg2rad(fov / 2.0)) - fy = fx # Assuming square pixels (fx = fy) - cx = (width - 1.0) / 2.0 - cy = (height - 1.0) / 2.0 - - intrinsic_matrix = np.array( - [[fx, 0.0, cx, 0.0], [0.0, fy, cy, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]] - ) - return intrinsic_matrix - - def preprocess_instrinsic(self, intrinsic, ori_size, target_size): # (V, 4, 4) (resize_shape) (h, w) - intrinsic = copy.deepcopy(intrinsic) - if len(intrinsic.shape) == 2: - intrinsic = intrinsic[None, :, :] # (1, 4, 4) or (B, 4, 4) - - intrinsic[:, 0] /= ori_size[0] / target_size[0] # width - intrinsic[:, 1] /= ori_size[1] / target_size[1] # height - - # for crop transform - intrinsic[:, 0, 2] -= (target_size[0] - target_size[1]) / 2 - - if intrinsic.shape[0] == 1: - intrinsic = intrinsic.squeeze(0) - - return intrinsic - - def get_axis_align_matrix(self): - ma = np.array([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) - return ma - - def xyz_yaw_to_tf_matrix(self, xyz: np.ndarray, yaw: float) -> np.ndarray: - x, y, z = xyz - transformation_matrix = np.array( - [ - [np.cos(yaw), -np.sin(yaw), 0, x], - [np.sin(yaw), np.cos(yaw), 0, y], - [0, 0, 1, z], - [0, 0, 0, 1], - ] - ) - return transformation_matrix - - def xyz_pitch_to_tf_matrix(self, xyz: np.ndarray, pitch: float) -> np.ndarray: - """Converts a given position and pitch angle to a 4x4 transformation matrix. - - Args: - xyz (np.ndarray): A 3D vector representing the position. - pitch (float): The pitch angle in radians for y axis. - Returns: - np.ndarray: A 4x4 transformation matrix. - """ - - x, y, z = xyz - transformation_matrix = np.array( - [ - [np.cos(pitch), 0, np.sin(pitch), x], - [0, 1, 0, y], - [-np.sin(pitch), 0, np.cos(pitch), z], - [0, 0, 0, 1], - ] - ) - return transformation_matrix - - def xyz_yaw_pitch_to_tf_matrix(self, xyz: np.ndarray, yaw: float, pitch: float) -> np.ndarray: - """Converts a given position and yaw, pitch angles to a 4x4 transformation matrix. - - Args: - xyz (np.ndarray): A 3D vector representing the position. - yaw (float): The yaw angle in radians. - pitch (float): The pitch angle in radians for y axis. - Returns: - np.ndarray: A 4x4 transformation matrix. - """ - x, y, z = xyz - rot1 = self.xyz_yaw_to_tf_matrix(xyz, yaw)[:3, :3] - rot2 = self.xyz_pitch_to_tf_matrix(xyz, pitch)[:3, :3] - transformation_matrix = np.eye(4) - transformation_matrix[:3, :3] = rot1 @ rot2 - transformation_matrix[:3, 3] = xyz - return transformation_matrix - - def pixel_to_gps(self, pixel, depth, intrinsic, tf_camera_to_episodic): - ''' - Args: - pixel: (2,) - [u, v] pixel coordinates - depth: (H, W) - depth image where depth[v, u] gives depth in meters - intrinsic: (4, 4) - camera intrinsic matrix - tf_camera_to_episodic: (4, 4) - transformation from camera to episodic frame - Returns: - (x, y): (x, y) coordinates in the episodic frame - ''' - v, u = pixel - z = depth[v, u] - print("depthhhhhhhhhhhhhh", z) - - x = (u - intrinsic[0, 2]) * z / intrinsic[0, 0] - y = (v - intrinsic[1, 2]) * z / intrinsic[1, 1] - point_camera = np.array([x, y, z, 1.0]) - - # Transform to episodic frame - point_episodic = tf_camera_to_episodic @ point_camera - point_episodic = point_episodic[:3] / point_episodic[3] - - x = point_episodic[0] - y = point_episodic[1] - - return (x, y) # same as habitat gps - + # refactor def config_env(self) -> Env: env = Env(config=self.config) # env.episodes = env.episodes[0:1] return env - def dot_matrix_two_dimensional( - self, - image_or_image_path, - save_path=None, - dots_size_w=8, - dots_size_h=8, - save_img=False, - font_path='fonts/arial.ttf', - pixel_goal=None, - ): - """ - takes an original image as input, save the processed image to save_path. Each dot is labeled with two-dimensional Cartesian coordinates (x,y). Suitable for single-image tasks. - control args: - 1. dots_size_w: the number of columns of the dots matrix - 2. dots_size_h: the number of rows of the dots matrix - """ - with open_image(image_or_image_path) as img: - if img.mode != 'RGB': - img = img.convert('RGB') - draw = ImageDraw.Draw(img, 'RGB') - - width, height = img.size - grid_size_w = dots_size_w + 1 - grid_size_h = dots_size_h + 1 - cell_width = width / grid_size_w - cell_height = height / grid_size_h - - font = ImageFont.truetype(font_path, width // 40) # Adjust font size if needed; default == width // 40 - - target_i = target_j = None - if pixel_goal is not None: - y_pixel, x_pixel = pixel_goal[0], pixel_goal[1] - # Validate pixel coordinates - if not (0 <= x_pixel < width and 0 <= y_pixel < height): - raise ValueError(f"pixel_goal {pixel_goal} exceeds image dimensions ({width}x{height})") - - # Convert to grid coordinates - target_i = round(x_pixel / cell_width) - target_j = round(y_pixel / cell_height) - - # Validate grid bounds - if not (1 <= target_i <= dots_size_w and 1 <= target_j <= dots_size_h): - raise ValueError( - f"pixel_goal {pixel_goal} maps to grid ({target_j},{target_i}), " - f"valid range is (1,1)-({dots_size_h},{dots_size_w})" - ) - - count = 0 - - for j in range(1, grid_size_h): - for i in range(1, grid_size_w): - x = int(i * cell_width) - y = int(j * cell_height) - - pixel_color = img.getpixel((x, y)) - # choose a more contrasting color from black and white - if pixel_color[0] + pixel_color[1] + pixel_color[2] >= 255 * 3 / 2: - opposite_color = (0, 0, 0) - else: - opposite_color = (255, 255, 255) - - if pixel_goal is not None and i == target_i and j == target_j: - opposite_color = (255, 0, 0) # Red for target - - circle_radius = width // 240 # Adjust dot size if needed; default == width // 240 - draw.ellipse( - [(x - circle_radius, y - circle_radius), (x + circle_radius, y + circle_radius)], - fill=opposite_color, - ) - - text_x, text_y = x + 3, y - count_w = count // dots_size_w - count_h = count % dots_size_w - label_str = f"({count_w+1},{count_h+1})" - draw.text((text_x, text_y), label_str, fill=opposite_color, font=font) - count += 1 - if save_img: - print(">>> dots overlaid image processed, stored in", save_path) - img.save(save_path) - return img - - def _pointnav( - self, - goal: np.ndarray, - depth: np.ndarray, - step_id: int, - robot_xy: np.ndarray, - robot_heading: float, - stop: bool = False, - ) -> Tensor: - ''' - Args: - goal (np.ndarray): goal position - stop (bool): whether to stop - Returns: - action: action tensor - ''' - - masks = torch.tensor([step_id != 0], dtype=torch.bool, device="cuda") - if not np.array_equal(goal, self._last_goal): - if np.linalg.norm(goal - self._last_goal) > 0.1: - self._pointnav_policy.reset() - print('Pointnav policy reset!') - masks = torch.zeros_like(masks) - self._last_goal = goal - rho, theta = rho_theta(robot_xy, robot_heading, goal) - rho_theta_tensor = torch.tensor([[rho, theta]], device="cuda", dtype=torch.float32) - obs_pointnav = { - "depth": image_resize( - depth, - (self._pointnav_depth_image_shape[0], self._pointnav_depth_image_shape[1]), - channels_last=True, - interpolation_mode="area", - ), - "pointgoal_with_gps_compass": rho_theta_tensor, - } - - if rho < self._pointnav_stop_radius and stop: - return 0 - action = self._pointnav_policy.act(obs_pointnav, masks, deterministic=True) - return action - def eval_action(self, idx) -> None: # noqa: C901 self.model.eval() env = self.config_env() @@ -414,6 +164,7 @@ def eval_action(self, idx) -> None: # noqa: C901 oss.append(res['os']) nes.append(res['ne']) + # refactor: why sort to scene: [episode] but nothing actually used for scene in sorted(scene_episode_dict.keys()): episodes = scene_episode_dict[scene] scene_id = scene.split('/')[-2] @@ -430,6 +181,7 @@ def eval_action(self, idx) -> None: # noqa: C901 if [scene_id, episode_id, episode_instruction] in done_res: continue + # refactor env warm up env.current_episode = episode observations = env.reset() @@ -465,6 +217,7 @@ def eval_action(self, idx) -> None: # noqa: C901 local_actions = [] while not env.episode_over and step_id <= 500: + # refactor agent get action rgb = observations["rgb"] depth = observations["depth"] x, y = observations["gps"] @@ -743,6 +496,7 @@ def eval_action(self, idx) -> None: # noqa: C901 print("step_id", step_id, "action", action) + # refactor: core if action == 5: env.step(action) observations = env.step(action) @@ -802,10 +556,194 @@ def parse_actions(self, output): actions = itertools.chain.from_iterable(actions) return list(actions) - def preprocess_qwenvl(self, source): - prompt = random.choice(self.conjunctions) + DEFAULT_IMAGE_TOKEN - if len(source[0]["value"]) != 0: - source[0]["value"] += f" {prompt}." - else: - source[0]["value"] = f"{prompt}." # Please output the next waypoint\'s coordinates in the image." - return source + def preprocess_depth_image_v2( + self, depth_image, do_depth_scale=True, depth_scale=1000, target_height=None, target_width=None + ): + if target_height is None: + target_height = self.image_processor.crop_size['height'] # 384 + target_width = self.image_processor.crop_size['width'] # 384 + + resized_depth_image = depth_image.resize((target_width, target_height), Image.NEAREST) + + img = to_numpy_array(resized_depth_image) + if do_depth_scale: + img = img / depth_scale + + return img, (target_width, target_height) + + def get_intrinsic_matrix(self, sensor_cfg) -> np.ndarray: + width = sensor_cfg.width + height = sensor_cfg.height + fov = sensor_cfg.hfov + fx = (width / 2.0) / np.tan(np.deg2rad(fov / 2.0)) + fy = fx # Assuming square pixels (fx = fy) + cx = (width - 1.0) / 2.0 + cy = (height - 1.0) / 2.0 + + intrinsic_matrix = np.array( + [[fx, 0.0, cx, 0.0], [0.0, fy, cy, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]] + ) + return intrinsic_matrix + + def get_axis_align_matrix(self): + ma = np.array([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) + return ma + + def xyz_yaw_to_tf_matrix(self, xyz: np.ndarray, yaw: float) -> np.ndarray: + x, y, z = xyz + transformation_matrix = np.array( + [ + [np.cos(yaw), -np.sin(yaw), 0, x], + [np.sin(yaw), np.cos(yaw), 0, y], + [0, 0, 1, z], + [0, 0, 0, 1], + ] + ) + return transformation_matrix + + def xyz_pitch_to_tf_matrix(self, xyz: np.ndarray, pitch: float) -> np.ndarray: + """Converts a given position and pitch angle to a 4x4 transformation matrix. + + Args: + xyz (np.ndarray): A 3D vector representing the position. + pitch (float): The pitch angle in radians for y axis. + Returns: + np.ndarray: A 4x4 transformation matrix. + """ + + x, y, z = xyz + transformation_matrix = np.array( + [ + [np.cos(pitch), 0, np.sin(pitch), x], + [0, 1, 0, y], + [-np.sin(pitch), 0, np.cos(pitch), z], + [0, 0, 0, 1], + ] + ) + return transformation_matrix + + def xyz_yaw_pitch_to_tf_matrix(self, xyz: np.ndarray, yaw: float, pitch: float) -> np.ndarray: + """Converts a given position and yaw, pitch angles to a 4x4 transformation matrix. + + Args: + xyz (np.ndarray): A 3D vector representing the position. + yaw (float): The yaw angle in radians. + pitch (float): The pitch angle in radians for y axis. + Returns: + np.ndarray: A 4x4 transformation matrix. + """ + x, y, z = xyz + rot1 = self.xyz_yaw_to_tf_matrix(xyz, yaw)[:3, :3] + rot2 = self.xyz_pitch_to_tf_matrix(xyz, pitch)[:3, :3] + transformation_matrix = np.eye(4) + transformation_matrix[:3, :3] = rot1 @ rot2 + transformation_matrix[:3, 3] = xyz + return transformation_matrix + + def pixel_to_gps(self, pixel, depth, intrinsic, tf_camera_to_episodic): + ''' + Args: + pixel: (2,) - [u, v] pixel coordinates + depth: (H, W) - depth image where depth[v, u] gives depth in meters + intrinsic: (4, 4) - camera intrinsic matrix + tf_camera_to_episodic: (4, 4) - transformation from camera to episodic frame + Returns: + (x, y): (x, y) coordinates in the episodic frame + ''' + v, u = pixel + z = depth[v, u] + print("depthhhhhhhhhhhhhh", z) + + x = (u - intrinsic[0, 2]) * z / intrinsic[0, 0] + y = (v - intrinsic[1, 2]) * z / intrinsic[1, 1] + point_camera = np.array([x, y, z, 1.0]) + + # Transform to episodic frame + point_episodic = tf_camera_to_episodic @ point_camera + point_episodic = point_episodic[:3] / point_episodic[3] + + x = point_episodic[0] + y = point_episodic[1] + + return (x, y) # same as habitat gps + + def dot_matrix_two_dimensional( + self, + image_or_image_path, + save_path=None, + dots_size_w=8, + dots_size_h=8, + save_img=False, + font_path='fonts/arial.ttf', + pixel_goal=None, + ): + """ + takes an original image as input, save the processed image to save_path. Each dot is labeled with two-dimensional Cartesian coordinates (x,y). Suitable for single-image tasks. + control args: + 1. dots_size_w: the number of columns of the dots matrix + 2. dots_size_h: the number of rows of the dots matrix + """ + with open_image(image_or_image_path) as img: + if img.mode != 'RGB': + img = img.convert('RGB') + draw = ImageDraw.Draw(img, 'RGB') + + width, height = img.size + grid_size_w = dots_size_w + 1 + grid_size_h = dots_size_h + 1 + cell_width = width / grid_size_w + cell_height = height / grid_size_h + + font = ImageFont.truetype(font_path, width // 40) # Adjust font size if needed; default == width // 40 + + target_i = target_j = None + if pixel_goal is not None: + y_pixel, x_pixel = pixel_goal[0], pixel_goal[1] + # Validate pixel coordinates + if not (0 <= x_pixel < width and 0 <= y_pixel < height): + raise ValueError(f"pixel_goal {pixel_goal} exceeds image dimensions ({width}x{height})") + + # Convert to grid coordinates + target_i = round(x_pixel / cell_width) + target_j = round(y_pixel / cell_height) + + # Validate grid bounds + if not (1 <= target_i <= dots_size_w and 1 <= target_j <= dots_size_h): + raise ValueError( + f"pixel_goal {pixel_goal} maps to grid ({target_j},{target_i}), " + f"valid range is (1,1)-({dots_size_h},{dots_size_w})" + ) + + count = 0 + + for j in range(1, grid_size_h): + for i in range(1, grid_size_w): + x = int(i * cell_width) + y = int(j * cell_height) + + pixel_color = img.getpixel((x, y)) + # choose a more contrasting color from black and white + if pixel_color[0] + pixel_color[1] + pixel_color[2] >= 255 * 3 / 2: + opposite_color = (0, 0, 0) + else: + opposite_color = (255, 255, 255) + + if pixel_goal is not None and i == target_i and j == target_j: + opposite_color = (255, 0, 0) # Red for target + + circle_radius = width // 240 # Adjust dot size if needed; default == width // 240 + draw.ellipse( + [(x - circle_radius, y - circle_radius), (x + circle_radius, y + circle_radius)], + fill=opposite_color, + ) + + text_x, text_y = x + 3, y + count_w = count // dots_size_w + count_h = count % dots_size_w + label_str = f"({count_w+1},{count_h+1})" + draw.text((text_x, text_y), label_str, fill=opposite_color, font=font) + count += 1 + if save_img: + print(">>> dots overlaid image processed, stored in", save_path) + img.save(save_path) + return img diff --git a/internnav/internnav_habitat/__init__.py b/internnav/internnav_habitat/__init__.py new file mode 100644 index 0000000..af9bee9 --- /dev/null +++ b/internnav/internnav_habitat/__init__.py @@ -0,0 +1,2 @@ +from internnav.internnav_habitat.habitat_env import HabitatEnv +from internnav.internnav_habitat.habitat_vln_evaluator import HabitatVlnEvaluator diff --git a/internnav/internnav_habitat/habitat_env.py b/internnav/internnav_habitat/habitat_env.py new file mode 100644 index 0000000..6b10215 --- /dev/null +++ b/internnav/internnav_habitat/habitat_env.py @@ -0,0 +1,126 @@ +import json +import os +from typing import Any, Dict, List, Optional + +from internnav.configs.evaluator import EnvCfg, TaskCfg +from internnav.env import base + + +@base.Env.register('habitat') +class HabitatEnv(base.Env): + def __init__(self, env_config: EnvCfg, task_config: TaskCfg): + """ + env_settings include: + - config_path: str, path to habitat config yaml file + - split: str, dataset split to use + """ + try: + from habitat import Env + except ImportError as e: + raise RuntimeError( + "Habitat modules could not be imported. " "Make sure both repositories are installed and on PYTHONPATH." + ) from e + + super().__init__(env_config, task_config) + + self.config = env_config.env_settings['habitat_config'] + self.env = Env(self.config) + + self.episodes = self.generate_episodes() + self.sort_episodes_by_scene() + + self.index = env_config.env_settings.get('idx', 0) + self.world_size = env_config.env_settings.get('world_size', 1) + self._current_episode_index: int = 0 + self._last_obs: Optional[Dict[str, Any]] = None + + self.step_id = 0 + self.is_running = True + + def generate_episodes(self) -> List[Any]: + """ + Generate list of episodes for the current split + """ + episodes = [] + + # sort episode by scene + scene_episode_dict = {} + for episode in self.env.episodes: + if episode.scene_id not in scene_episode_dict: + scene_episode_dict[episode.scene_id] = [] + scene_episode_dict[episode.scene_id].append(episode) + + done_res = set() + + if os.path.exists(os.path.join(self.output_path, 'result.json')): + with open(os.path.join(self.output_path, 'result.json'), 'r') as f: + for line in f.readlines(): + res = json.loads(line) + done_res.add((res["scene_id"], res["episode_id"], res["episode_instruction"])) + + for scene in sorted(scene_episode_dict.keys()): + episodes = scene_episode_dict[scene] + scene_id = scene.split('/')[-2] + for episode in episodes[self.index :: self.world_size]: + episode_instruction = ( + episode.instruction.instruction_text + if 'objectnav' not in self.config_path + else episode.object_category + ) + episode_id = int(episode.episode_id) + if (scene_id, episode_id, episode_instruction) in done_res: + continue + episodes.append(episode) + return episodes + + def reset(self): + """ + load next episode and return first observation + """ + # no more episodes + if not (0 <= self._current_episode_index < len(self.episodes)): + self.is_running = False + return + + # Manually set to next episode in habitat + self.env.current_episode = self.episodes[self._current_episode_index] + self._current_episode_index += 1 + + # Habitat reset + self._last_obs = self.env.reset() + self.step_id = 0 + + return self._last_obs + + def step(self, action: List[Any]): + """ + step the environment with given action + + Args: action: List[Any], action for each env in the batch + + Return: obs, terminated + """ + self._last_obs = self.env.step(action) + terminated = self.env.episode_over + return self._last_obs, terminated + + def close(self): + print('Vln Env close') + self.env.close() + + def render(self): + self.env.render() + + def get_observation(self) -> Dict[str, Any]: + return self.env.get_observations() + + def get_metrics(self) -> Dict[str, Any]: + return self.env.get_metrics() + + def sort_episodes_by_scene(self, key_list: List[str]): + sorted_episodes = [] + episode_dict = {ep.episode_id: ep for ep in self.episodes} + for key in key_list: + if key in episode_dict: + sorted_episodes.append(episode_dict[key]) + self.episodes = sorted_episodes diff --git a/internnav/internnav_habitat/habitat_n1_agent_temp.py b/internnav/internnav_habitat/habitat_n1_agent_temp.py new file mode 100644 index 0000000..598ab25 --- /dev/null +++ b/internnav/internnav_habitat/habitat_n1_agent_temp.py @@ -0,0 +1,263 @@ +import copy +import itertools +import os +import re +import sys +import time +from datetime import datetime +from pathlib import Path + +import numpy as np +import torch + +sys.path.append(str(Path(__file__).parent.parent.parent)) + +from collections import OrderedDict + +from PIL import Image +from transformers import AutoProcessor + +from internnav.model.basemodel.internvla_n1.internvla_n1 import InternVLAN1ForCausalLM +from internnav.model.utils.vln_utils import S2Output, split_and_clean, traj_to_actions + +DEFAULT_IMAGE_TOKEN = "" + + +class InternVLAN1AsyncAgent: + def __init__(self, args): + self.device = torch.device(args.device) + self.save_dir = "test_data/" + datetime.now().strftime("%Y%m%d_%H%M%S") + print(f"args.model_path{args.model_path}") + + device = torch.device("cuda") + if args.mode == 'dual_system': + self.model = InternVLAN1ForCausalLM.from_pretrained( + args.model_path, + torch_dtype=torch.bfloat16, + attn_implementation="flash_attention_2", + device_map={"": device}, + ) + else: + raise ValueError(f"Invalid mode: {args.mode}") + + self.model.eval() + self.model.to(self.device) + + self.processor = AutoProcessor.from_pretrained(args.model_path) + self.processor.tokenizer.padding_side = 'left' + + self.resize_w = args.resize_w + self.resize_h = args.resize_h + self.num_history = args.num_history + self.PLAN_STEP_GAP = args.plan_step_gap + + prompt = "You are an autonomous navigation assistant. Your task is to . Where should you go next to stay on track? Please output the next waypoint's coordinates in the image. Please output STOP when you have successfully completed the task." + answer = "" + self.conversation = [{"from": "human", "value": prompt}, {"from": "gpt", "value": answer}] + self.conjunctions = [ + 'you can see ', + 'in front of you is ', + 'there is ', + 'you can spot ', + 'you are toward the ', + 'ahead of you is ', + 'in your sight is ', + ] + + self.actions2idx = OrderedDict( + { + 'STOP': [0], + "↑": [1], + "←": [2], + "→": [3], + "↓": [5], + } + ) + + self.rgb_list = [] + self.depth_list = [] + self.pose_list = [] + self.episode_idx = 0 + self.conversation_history = [] + self.llm_output = "" + self.past_key_values = None + self.last_s2_idx = -100 + + # output + self.output_action = None + self.output_latent = None + self.output_pixel = None + self.pixel_goal_rgb = None + self.pixel_goal_depth = None + + def reset(self): + self.rgb_list = [] + self.depth_list = [] + self.pose_list = [] + self.episode_idx = 0 + self.conversation_history = [] + self.llm_output = "" + self.past_key_values = None + + self.output_action = None + self.output_latent = None + self.output_pixel = None + self.pixel_goal_rgb = None + self.pixel_goal_depth = None + + self.save_dir = "test_data/" + datetime.now().strftime("%Y%m%d_%H%M%S") + os.makedirs(self.save_dir, exist_ok=True) + + def parse_actions(self, output): + action_patterns = '|'.join(re.escape(action) for action in self.actions2idx) + regex = re.compile(action_patterns) + matches = regex.findall(output) + actions = [self.actions2idx[match] for match in matches] + actions = itertools.chain.from_iterable(actions) + return list(actions) + + def step_no_infer(self, rgb, depth, pose): + image = Image.fromarray(rgb).convert('RGB') + image = image.resize((self.resize_w, self.resize_h)) + self.rgb_list.append(image) + image.save(f"{self.save_dir}/debug_raw_{self.episode_idx: 04d}.jpg") + self.episode_idx += 1 + + def trajectory_tovw(self, trajectory, kp=1.0): + subgoal = trajectory[-1] + linear_vel, angular_vel = kp * np.linalg.norm(subgoal[:2]), kp * subgoal[2] + linear_vel = np.clip(linear_vel, 0, 0.5) + angular_vel = np.clip(angular_vel, -0.5, 0.5) + return linear_vel, angular_vel + + def step(self, rgb, depth, pose, instruction, intrinsic, look_down=False): + dual_sys_output = S2Output() + no_output_flag = self.output_action is None and self.output_latent is None + if (self.episode_idx - self.last_s2_idx > self.PLAN_STEP_GAP) or look_down or no_output_flag: + self.output_action, self.output_latent, self.output_pixel = self.step_s2( + rgb, depth, pose, instruction, intrinsic, look_down + ) + self.last_s2_idx = self.episode_idx + dual_sys_output.output_pixel = self.output_pixel + self.pixel_goal_rgb = copy.deepcopy(rgb) + self.pixel_goal_depth = copy.deepcopy(depth) + else: + self.step_no_infer(rgb, depth, pose) + + if self.output_action is not None: + dual_sys_output.output_action = copy.deepcopy(self.output_action) + self.output_action = None + elif self.output_latent is not None: + processed_pixel_rgb = np.array(Image.fromarray(self.pixel_goal_rgb).resize((224, 224))) / 255 + processed_pixel_depth = np.array(Image.fromarray(self.pixel_goal_depth).resize((224, 224))) + processed_rgb = np.array(Image.fromarray(rgb).resize((224, 224))) / 255 + processed_depth = np.array(Image.fromarray(depth).resize((224, 224))) + rgbs = ( + torch.stack([torch.from_numpy(processed_pixel_rgb), torch.from_numpy(processed_rgb)]) + .unsqueeze(0) + .to(self.device) + ) + depths = ( + torch.stack([torch.from_numpy(processed_pixel_depth), torch.from_numpy(processed_depth)]) + .unsqueeze(0) + .unsqueeze(-1) + .to(self.device) + ) + trajectories = self.step_s1(self.output_latent, rgbs, depths) + + dual_sys_output.output_trajectory = traj_to_actions(trajectories, use_discrate_action=False) + + return dual_sys_output + + def step_s2(self, rgb, depth, pose, instruction, intrinsic, look_down=False): + image = Image.fromarray(rgb).convert('RGB') + if not look_down: + image = image.resize((self.resize_w, self.resize_h)) + self.rgb_list.append(image) + image.save(f"{self.save_dir}/debug_raw_{self.episode_idx: 04d}.jpg") + else: + image.save(f"{self.save_dir}/debug_raw_{self.episode_idx: 04d}_look_down.jpg") + if not look_down: + self.conversation_history = [] + self.past_key_values = None + + sources = copy.deepcopy(self.conversation) + sources[0]["value"] = sources[0]["value"].replace('.', instruction) + cur_images = self.rgb_list[-1:] + if self.episode_idx == 0: + history_id = [] + else: + history_id = np.unique(np.linspace(0, self.episode_idx - 1, self.num_history, dtype=np.int32)).tolist() + placeholder = (DEFAULT_IMAGE_TOKEN + '\n') * len(history_id) + sources[0]["value"] += f' These are your historical observations: {placeholder}.' + + history_id = sorted(history_id) + self.input_images = [self.rgb_list[i] for i in history_id] + cur_images + input_img_id = 0 + self.episode_idx += 1 + else: + self.input_images.append(image) + input_img_id = -1 + assert self.llm_output != "", "Last llm_output should not be empty when look down" + sources = [{"from": "human", "value": ""}, {"from": "gpt", "value": ""}] + self.conversation_history.append( + {'role': 'assistant', 'content': [{'type': 'text', 'text': self.llm_output}]} + ) + + prompt = self.conjunctions[0] + DEFAULT_IMAGE_TOKEN + sources[0]["value"] += f" {prompt}." + prompt_instruction = copy.deepcopy(sources[0]["value"]) + parts = split_and_clean(prompt_instruction) + + content = [] + for i in range(len(parts)): + if parts[i] == "": + content.append({"type": "image", "image": self.input_images[input_img_id]}) + input_img_id += 1 + else: + content.append({"type": "text", "text": parts[i]}) + + self.conversation_history.append({'role': 'user', 'content': content}) + + text = self.processor.apply_chat_template(self.conversation_history, tokenize=False, add_generation_prompt=True) + + inputs = self.processor(text=[text], images=self.input_images, return_tensors="pt").to(self.device) + t0 = time.time() + with torch.no_grad(): + outputs = self.model.generate( + **inputs, + max_new_tokens=128, + do_sample=False, + use_cache=True, + past_key_values=self.past_key_values, + return_dict_in_generate=True, + raw_input_ids=copy.deepcopy(inputs.input_ids), + ) + output_ids = outputs.sequences + + t1 = time.time() + self.llm_output = self.processor.tokenizer.decode( + output_ids[0][inputs.input_ids.shape[1] :], skip_special_tokens=True + ) + with open(f"{self.save_dir}/llm_output_{self.episode_idx: 04d}.txt", 'w') as f: + f.write(self.llm_output) + self.last_output_ids = copy.deepcopy(output_ids[0]) + self.past_key_values = copy.deepcopy(outputs.past_key_values) + print(f"output {self.episode_idx} {self.llm_output} cost: {t1 - t0}s") + if bool(re.search(r'\d', self.llm_output)): + coord = [int(c) for c in re.findall(r'\d+', self.llm_output)] + pixel_goal = [int(coord[1]), int(coord[0])] + image_grid_thw = torch.cat([thw.unsqueeze(0) for thw in inputs.image_grid_thw], dim=0) + pixel_values = inputs.pixel_values + t0 = time.time() + with torch.no_grad(): + traj_latents = self.model.generate_latents(output_ids, pixel_values, image_grid_thw) + return None, traj_latents, pixel_goal + + else: + action_seq = self.parse_actions(self.llm_output) + return action_seq, None, None + + def step_s1(self, latent, rgb, depth): + all_trajs = self.model.generate_traj(latent, rgb, depth, use_async=True) + return all_trajs diff --git a/internnav/internnav_habitat/habitat_vln_evaluator.py b/internnav/internnav_habitat/habitat_vln_evaluator.py new file mode 100644 index 0000000..99e8fdc --- /dev/null +++ b/internnav/internnav_habitat/habitat_vln_evaluator.py @@ -0,0 +1,842 @@ +import argparse +import json +import os +import sys + +sys.path.append('./src/diffusion-policy') +import copy +import itertools +import random +import re +from collections import OrderedDict + +import habitat +import numpy as np +import quaternion +import torch +import tqdm +from depth_camera_filtering import filter_depth +from PIL import Image, ImageDraw, ImageFont +from transformers import AutoProcessor, Qwen2_5_VLForConditionalGeneration +from transformers.image_utils import to_numpy_array + +# Import for Habitat registry side effects — do not remove +import internnav.env.utils.habitat_extensions.measures # noqa: F401 +from internnav.configs.evaluator import EvalCfg +from internnav.evaluator.base import Evaluator +from internnav.model.basemodel.internvla_n1.internvla_n1 import InternVLAN1ForCausalLM +from internnav.model.utils.vln_utils import ( + chunk_token, + open_image, + split_and_clean, + traj_to_actions, +) +from internnav.utils.dist import dist, get_rank, get_world_size, init_distributed_mode + +try: + from habitat import Env + from habitat.config.default import get_agent_config + from habitat.config.default_structured_configs import ( + CollisionsMeasurementConfig, + FogOfWarConfig, + TopDownMapMeasurementConfig, + ) + from habitat.tasks.nav.shortest_path_follower import ShortestPathFollower + from habitat.utils.visualizations.utils import ( + images_to_video, + observations_to_image, + ) + from habitat_baselines.config.default import get_config as get_habitat_config +except Exception as e: + print("Habitat Error:", e) + print("Habitat Evaluation is not loaded.") + + +DEFAULT_IMAGE_TOKEN = "" + + +@Evaluator.register('habitat_vln') +class HabitatVlnEvaluator(Evaluator): + def __init__(self, cfg: EvalCfg): + args = argparse.Namespace(**cfg.eval_settings) + self.args = args + self.save_video = args.save_video + + # distributed setting + import os + import socket + + print( + f"Rank {os.getenv('RANK')} / {os.getenv('WORLD_SIZE')} on {socket.gethostname()}:{os.getenv('MASTER_PORT')}" + ) + init_distributed_mode(args) + local_rank = args.local_rank + np.random.seed(local_rank) + cfg.env.env_settings['idx'] = get_rank() + cfg.env.env_settings['world_size'] = get_world_size() + + self.world_size = get_world_size() + self.output_path = args.output_path # TODO: modify by rank + self.epoch = 0 + + # create habitat config + self.config_path = cfg.env.env_settings['config_path'] + self.config = get_habitat_config(self.config_path) + self.agent_config = get_agent_config(self.config.habitat.simulator) + self.sim_sensors_config = self.config.habitat.simulator.agents.main_agent.sim_sensors + + with habitat.config.read_write(self.config): + self.config.habitat.task.measurements.update( + { + "top_down_map": TopDownMapMeasurementConfig( + map_padding=3, + map_resolution=1024, + draw_source=True, + draw_border=True, + draw_shortest_path=True, + draw_view_points=True, + draw_goal_positions=True, + draw_goal_aabbs=True, + fog_of_war=FogOfWarConfig( + draw=True, + visibility_dist=5.0, + fov=90, + ), + ), + "collisions": CollisionsMeasurementConfig(), + } + ) + cfg.env.env_settings['habitat_config'] = self.config + + # init agent and env + # super().__init__(cfg) + + # ------------------------------------- model ------------------------------------------ + processor = AutoProcessor.from_pretrained(args.model_path) + processor.tokenizer.padding_side = 'left' + + device = torch.device(f"cuda:{local_rank}") + if args.mode == 'dual_system': + model = InternVLAN1ForCausalLM.from_pretrained( + args.model_path, + torch_dtype=torch.bfloat16, + attn_implementation="flash_attention_2", + device_map={"": device}, + ) + elif args.mode == 'system2': + model = Qwen2_5_VLForConditionalGeneration.from_pretrained( + args.model_path, + torch_dtype=torch.bfloat16, + attn_implementation="flash_attention_2", + device_map={"": device}, + ) + else: + raise ValueError(f"Invalid mode: {args.mode}") + + model.eval() + self.device = device + + # ------------------------------------- old ------------------------------------------ + self._camera_height = self.sim_sensors_config.rgb_sensor.position[1] + self._min_depth = self.sim_sensors_config.depth_sensor.min_depth + self._max_depth = self.sim_sensors_config.depth_sensor.max_depth + + camera_fov_rad = np.deg2rad(self.sim_sensors_config.depth_sensor.hfov) + self._camera_fov = camera_fov_rad + self._fx = self._fy = self.sim_sensors_config.depth_sensor.width / (2 * np.tan(camera_fov_rad / 2)) + + self.model = model + self.processor = processor + + # refactor: this part used in three places + prompt = "You are an autonomous navigation assistant. Your task is to . Where should you go next to stay on track? Please output the next waypoint\'s coordinates in the image. Please output STOP when you have successfully completed the task." + answer = "" + self.conversation = [{"from": "human", "value": prompt}, {"from": "gpt", "value": answer}] + + self.conjunctions = [ + 'you can see ', + 'in front of you is ', + 'there is ', + 'you can spot ', + 'you are toward the ', + 'ahead of you is ', + 'in your sight is ', + ] + + self.actions2idx = OrderedDict( + { + 'STOP': [0], + "↑": [1], + "←": [2], + "→": [3], + "↓": [5], + } + ) + + self.objectnav_instructions = ["Search for the {target_object}."] + + self.num_frames = args.num_frames + self.num_future_steps = args.num_future_steps + self.num_history = args.num_history + # ------------------------------------- remove ------------------------------------------ + + def eval(self): + # * 3. do eval + sucs, spls, oss, nes, ep_num = self.eval_action(self.args.local_rank) + ep_num_all = [torch.zeros_like(ep_num) for _ in range(self.world_size)] + # import ipdb; ipdb.set_trace() + world_size = get_world_size() + dist.all_gather(ep_num_all, ep_num) + sucs_all = [torch.zeros(ep_num_all[i], dtype=sucs.dtype).to(sucs.device) for i in range(world_size)] + spls_all = [torch.zeros(ep_num_all[i], dtype=spls.dtype).to(spls.device) for i in range(world_size)] + oss_all = [torch.zeros(ep_num_all[i], dtype=oss.dtype).to(oss.device) for i in range(world_size)] + nes_all = [torch.zeros(ep_num_all[i], dtype=nes.dtype).to(nes.device) for i in range(world_size)] + dist.barrier() + dist.all_gather(sucs_all, sucs) + dist.all_gather(spls_all, spls) + dist.all_gather(oss_all, oss) + dist.all_gather(nes_all, nes) + + sucs_all = torch.cat(sucs_all, dim=0) + spls_all = torch.cat(spls_all, dim=0) + oss_all = torch.cat(oss_all, dim=0) + nes_all = torch.cat(nes_all, dim=0) + result_all = { + "sucs_all": (sum(sucs_all) / len(sucs_all)).item(), + "spls_all": (sum(spls_all) / len(spls_all)).item(), + "oss_all": (sum(oss_all) / len(oss_all)).item(), + "nes_all": (sum(nes_all) / len(nes_all)).item(), + 'length': len(sucs_all), + } + + print(result_all) + if get_rank() == 0: + with open(os.path.join(self.args.output_path, 'result.json'), 'a') as f: + f.write(json.dumps(result_all)) + + def _eval_action(self): + obs = self.env.reset() + action = self.agent.reset() + while not self.env.is_running(): + action = self.agent.step(action, obs) + obs, terminated = self.env.step(action) + if terminated: + obs = self.env.reset() + self.agent.reset() + self.env.update_metric() + + # refactor + def config_env(self) -> Env: + env = Env(config=self.config) + # env.episodes = env.episodes[0:1] + return env + + def eval_action(self, idx=0) -> None: # noqa: C901 + self.model.eval() + env = self.config_env() + scene_episode_dict = {} + for episode in env.episodes: + if episode.scene_id not in scene_episode_dict: + scene_episode_dict[episode.scene_id] = [] + scene_episode_dict[episode.scene_id].append(episode) + + intrinsic_matrix = self.get_intrinsic_matrix( + self.config.habitat.simulator.agents.main_agent.sim_sensors.rgb_sensor + ) + sucs, spls, oss, nes = [], [], [], [] + done_res = [] + + if os.path.exists(os.path.join(self.output_path, 'result.json')): + with open(os.path.join(self.output_path, 'result.json'), 'r') as f: + for line in f.readlines(): + res = json.loads(line) + done_res.append([res["scene_id"], res["episode_id"], res["episode_instruction"]]) + if get_rank() == 0: # noqa: F405 TODO this need to keep in evaluator + sucs.append(res['success']) + spls.append(res['spl']) + oss.append(res['os']) + nes.append(res['ne']) + + # refactor: sort to scene: [episode] but nothing actually used + for scene in sorted(scene_episode_dict.keys()): + episodes = scene_episode_dict[scene] + scene_id = scene.split('/')[-2] + print(f"scene_id = {scene_id}") + process_bar = tqdm.tqdm(range(len(episodes[idx :: self.world_size])), desc=f"scene {scene_id}") + for episode in episodes[idx :: self.world_size]: + episode_instruction = ( + episode.instruction.instruction_text + if 'objectnav' not in self.config_path + else episode.object_category + ) + print("episode start", episode_instruction) + episode_id = int(episode.episode_id) + if [scene_id, episode_id, episode_instruction] in done_res: + continue + + # refactor env warm up + env.current_episode = episode + observations = env.reset() + + agent_state = env.sim.get_agent_state() + rotation = agent_state.rotation + translation = agent_state.position + rotation_matrix = quaternion.as_rotation_matrix(rotation) + transformation_matrix = np.eye(4) + transformation_matrix[:3, :3] = rotation_matrix + transformation_matrix[:3, 3] = translation + + agent = ShortestPathFollower(env.sim, 0.25, False) + + os.makedirs(os.path.join(self.output_path, f'check_sim_{self.epoch}'), exist_ok=True) + Image.fromarray(observations['rgb']).save( + os.path.join(self.output_path, f'check_sim_{self.epoch}', f'rgb_{idx}.jpg') + ) + + vis_frames = [] + step_id = 0 + + if self.save_video: + os.makedirs(os.path.join(self.output_path, f'vis_{self.epoch}', f'{scene_id}'), exist_ok=True) + initial_height = env.sim.get_agent_state().position[1] + + rgb_list = [] + action_seq = [] + output_ids = None + + goal = None + action = None + messages = [] + local_actions = [] + + while not env.episode_over and step_id <= 500: + # refactor agent get action + rgb = observations["rgb"] + depth = observations["depth"] + x, y = observations["gps"] + camera_yaw = observations["compass"][0] + depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) + depth = depth * (self._max_depth - self._min_depth) + self._min_depth + depth = depth * 1000 + + agent_state = env.sim.get_agent_state() + height = agent_state.position[1] - initial_height + camera_position = np.array([x, -y, self._camera_height + height]) + tf_camera_to_episodic = ( + self.xyz_yaw_pitch_to_tf_matrix(camera_position, camera_yaw, np.deg2rad(30)) + @ self.get_axis_align_matrix() + ) + + image = Image.fromarray(rgb).convert('RGB') + save_raw_image = image.copy() + + save_dot = False + if action == 5: + look_down_image = image + save_raw_image = look_down_image.copy() + look_down_depth, resize_shape = self.preprocess_depth_image_v2( + Image.fromarray(depth.astype(np.uint16), mode='I;16'), + do_depth_scale=True, + depth_scale=1000, + target_height=224, + target_width=224, + ) + look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() + look_down_depth[look_down_depth > 5.0] = 5.0 + else: + image = image.resize((self.args.resize_w, self.args.resize_h)) + rgb_list.append(image) + + if self.args.mode == 'dual_system': + down_observations = env.step(5) + down_observations = env.step(5) + + look_down_image = Image.fromarray(down_observations["rgb"]).convert('RGB') + depth = down_observations["depth"] + depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) + depth = depth * (self._max_depth - self._min_depth) + self._min_depth + depth = depth * 1000 + look_down_depth, resize_shape = self.preprocess_depth_image_v2( + Image.fromarray(depth.astype(np.uint16), mode='I;16'), + do_depth_scale=True, + depth_scale=1000, + target_height=224, + target_width=224, + ) + look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() + look_down_depth[look_down_depth > 5.0] = 5.0 + + env.step(4) + env.step(4) + + info = env.get_metrics() + + if len(action_seq) == 0 and goal is None: + if action != 5: + sources = copy.deepcopy(self.conversation) + sources[0]["value"] = sources[0]["value"].replace( + '.', episode.instruction.instruction_text[:-1] + ) + cur_images = rgb_list[-1:] + if step_id == 0: + history_id = [] + else: + history_id = np.unique( + np.linspace(0, step_id - 1, self.num_history, dtype=np.int32) + ).tolist() + placeholder = (DEFAULT_IMAGE_TOKEN + '\n') * len(history_id) + sources[0]["value"] += f' These are your historical observations: {placeholder}.' + + history_id = sorted(history_id) + print('history_idddddddd', step_id, history_id) + input_images = [rgb_list[i] for i in history_id] + cur_images + input_img_id = 0 + else: + assert action == 5 + sources = [{"from": "human", "value": ""}, {"from": "gpt", "value": ""}] + input_images += [look_down_image] + # messages.append( + # {'role': 'assistant', 'content': [{'type': 'text', 'text': llm_outputs}]} # noqa: F405 + # ) + input_img_id = -1 + + prompt = random.choice(self.conjunctions) + DEFAULT_IMAGE_TOKEN + sources[0]["value"] += f" {prompt}." + print('sources', step_id, sources) + prompt_instruction = copy.deepcopy(sources[0]["value"]) + parts = split_and_clean(prompt_instruction) + + content = [] + for i in range(len(parts)): + if parts[i] == "": + content.append({"type": "image", "image": input_images[input_img_id]}) + input_img_id += 1 + else: + content.append({"type": "text", "text": parts[i]}) + + messages.append({'role': 'user', 'content': content}) + + print('step_id', step_id, 'messages:', messages) + + text = self.processor.apply_chat_template(messages, tokenize=False, add_generation_prompt=True) + + inputs = self.processor(text=[text], images=input_images, return_tensors="pt").to( + self.model.device + ) + + with torch.no_grad(): + output_ids = self.model.generate(**inputs, max_new_tokens=128, do_sample=False) + + llm_outputs = self.processor.tokenizer.decode( + output_ids[0][inputs.input_ids.shape[1] :], skip_special_tokens=True + ) + print('step_id:', step_id, 'output text:', llm_outputs) + + if bool(re.search(r'\d', llm_outputs)): + forward_action = 0 + coord = [int(c) for c in re.findall(r'\d+', llm_outputs)] + pixel_goal = [int(coord[1]), int(coord[0])] + + goal = self.pixel_to_gps(pixel_goal, depth / 1000, intrinsic_matrix, tf_camera_to_episodic) + print('before', goal, depth.shape) + goal = (transformation_matrix @ np.array([-goal[1], 0, -goal[0], 1]))[:3] + + if not env.sim.pathfinder.is_navigable(np.array(goal)): + goal = np.array(env.sim.pathfinder.snap_point(np.array(goal))) + + # look down --> horizontal + env.step(4) + env.step(4) + + # Forking logic based on mode + if self.args.mode == 'system2': + action = agent.get_next_action(goal) + if action == 0: + goal = None + output_ids = None + action = 2 # random action + print('conduct a random action 2') + observations = env.step(action) + step_id += 1 + messages = [] + continue + else: # dual-system logic + local_actions = [] + pixel_values = inputs.pixel_values + image_grid_thw = torch.cat([thw.unsqueeze(0) for thw in inputs.image_grid_thw], dim=0) + + with torch.no_grad(): + traj_latents = self.model.generate_latents(output_ids, pixel_values, image_grid_thw) + + # prepocess align with navdp + image_dp = ( + torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 + ) + pix_goal_image = copy.copy(image_dp) + images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) + depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) + pix_goal_depth = copy.copy(depth_dp) + depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) + + with torch.no_grad(): + dp_actions = self.model.generate_traj( + traj_latents, images_dp, depths_dp, use_async=True + ) + + random_choice = np.random.choice(dp_actions.shape[0]) + if self.args.continuous_traj: + action_list = traj_to_actions(dp_actions) + if len(action_list) < 8: + action_list += [0] * (8 - len(action_list)) + else: + action_list = chunk_token(dp_actions[random_choice]) + + local_actions = action_list + if len(local_actions) >= 4: + local_actions = local_actions[:4] + action = local_actions[0] + if action == 0: + goal = None + output_ids = None + action = 2 # random action + print('conduct a random action 2') + observations = env.step(action) + step_id += 1 + messages = [] + continue + + print('predicted goal', pixel_goal, goal, flush=True) + else: + action_seq = self.parse_actions(llm_outputs) + print('actions', action_seq, flush=True) + + if len(action_seq) != 0: + action = action_seq[0] + action_seq.pop(0) + elif goal is not None: + # Forking logic based on mode + if self.args.mode == 'system2': + action = agent.get_next_action(goal) + action = action.detach().cpu().numpy()[0] if isinstance(action, torch.Tensor) else action + action = action[0] if hasattr(action, "__len__") else action + else: # dual-system logic + if len(local_actions) == 0: + # navdp + local_actions = [] + image_dp = ( + torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 + ) + + images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) + depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) + + depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) + with torch.no_grad(): + dp_actions = self.model.generate_traj( + traj_latents, images_dp, depths_dp, use_async=True + ) + + random_choice = np.random.choice(dp_actions.shape[0]) + if self.args.continuous_traj: + action_list = traj_to_actions(dp_actions) + if len(action_list) < 8: + action_list += [0] * (8 - len(action_list)) + else: + action_list = chunk_token(dp_actions[random_choice]) + print("first action_list", action_list) + + local_actions = action_list + if len(local_actions) >= 4: + local_actions = local_actions[:4] + # if len(local_actions) >= 2: + # local_actions = local_actions[:2] + + print("local_actions", local_actions) + + action = local_actions.pop(0) + # navdp + else: + action = local_actions.pop(0) + + forward_action += 1 + print('forward_action', forward_action, flush=True) + if forward_action > 8: + goal = None + output_ids = None + messages = [] + step_id += 1 + forward_action = 0 + local_actions = [] + continue + if action == 0: + goal = None + output_ids = None + messages = [] + step_id += 1 + forward_action = 0 + local_actions = [] + continue + else: + action = 0 + + if info['top_down_map'] is not None: + if save_dot: + save_raw_image = self.dot_matrix_two_dimensional( + save_raw_image, save_img=False, save_path=f'test_{step_id}.jpg', pixel_goal=pixel_goal + ) + frame = observations_to_image({'rgb': np.asarray(save_raw_image)}, info) + vis_frames.append(frame) + + print("step_id", step_id, "action", action) + + # refactor: core + if action == 5: + env.step(action) + observations = env.step(action) + else: + observations = env.step(action) + step_id += 1 + messages = [] + + process_bar.update(1) + + metrics = env.get_metrics() + if self.save_video: + images_to_video( + vis_frames, + os.path.join(self.output_path, f'vis_{self.epoch}', f'{scene_id}'), + f'{episode_id:04d}', + fps=6, + quality=9, + ) + vis_frames.clear() + sucs.append(metrics['success']) + spls.append(metrics['spl']) + oss.append(metrics['oracle_success']) + nes.append(metrics["distance_to_goal"]) + print( + f"scene_episode {scene_id}_{episode_id:04d} success: {metrics['success']}, spl: {metrics['spl']}, os: {metrics['oracle_success']}, ne: {metrics['distance_to_goal']}" + ) + + result = { + "scene_id": scene_id, + "episode_id": episode_id, + "success": metrics["success"], + "spl": metrics["spl"], + "os": metrics['oracle_success'], + "ne": metrics["distance_to_goal"], + "steps": step_id, + "episode_instruction": episode_instruction, + } + + with open(os.path.join(self.output_path, 'result.json'), 'a') as f: + f.write(json.dumps(result) + "\n") + env.close() + return ( + torch.tensor(sucs).to(self.device), + torch.tensor(spls).to(self.device), + torch.tensor(oss).to(self.device), + torch.tensor(nes).to(self.device), + torch.tensor(len(sucs)).to(self.device), + ) + + def parse_actions(self, output): + action_patterns = '|'.join(re.escape(action) for action in self.actions2idx) + # import ipdb; ipdb.set_trace() + regex = re.compile(action_patterns) + matches = regex.findall(output) + actions = [self.actions2idx[match] for match in matches] + actions = itertools.chain.from_iterable(actions) + return list(actions) + + def preprocess_depth_image_v2( + self, depth_image, do_depth_scale=True, depth_scale=1000, target_height=None, target_width=None + ): + if target_height is None: + target_height = self.image_processor.crop_size['height'] # 384 + target_width = self.image_processor.crop_size['width'] # 384 + + resized_depth_image = depth_image.resize((target_width, target_height), Image.NEAREST) + + img = to_numpy_array(resized_depth_image) + if do_depth_scale: + img = img / depth_scale + + return img, (target_width, target_height) + + def get_intrinsic_matrix(self, sensor_cfg) -> np.ndarray: + width = sensor_cfg.width + height = sensor_cfg.height + fov = sensor_cfg.hfov + fx = (width / 2.0) / np.tan(np.deg2rad(fov / 2.0)) + fy = fx # Assuming square pixels (fx = fy) + cx = (width - 1.0) / 2.0 + cy = (height - 1.0) / 2.0 + + intrinsic_matrix = np.array( + [[fx, 0.0, cx, 0.0], [0.0, fy, cy, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]] + ) + return intrinsic_matrix + + def get_axis_align_matrix(self): + ma = np.array([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) + return ma + + def xyz_yaw_to_tf_matrix(self, xyz: np.ndarray, yaw: float) -> np.ndarray: + x, y, z = xyz + transformation_matrix = np.array( + [ + [np.cos(yaw), -np.sin(yaw), 0, x], + [np.sin(yaw), np.cos(yaw), 0, y], + [0, 0, 1, z], + [0, 0, 0, 1], + ] + ) + return transformation_matrix + + def xyz_pitch_to_tf_matrix(self, xyz: np.ndarray, pitch: float) -> np.ndarray: + """Converts a given position and pitch angle to a 4x4 transformation matrix. + + Args: + xyz (np.ndarray): A 3D vector representing the position. + pitch (float): The pitch angle in radians for y axis. + Returns: + np.ndarray: A 4x4 transformation matrix. + """ + + x, y, z = xyz + transformation_matrix = np.array( + [ + [np.cos(pitch), 0, np.sin(pitch), x], + [0, 1, 0, y], + [-np.sin(pitch), 0, np.cos(pitch), z], + [0, 0, 0, 1], + ] + ) + return transformation_matrix + + def xyz_yaw_pitch_to_tf_matrix(self, xyz: np.ndarray, yaw: float, pitch: float) -> np.ndarray: + """Converts a given position and yaw, pitch angles to a 4x4 transformation matrix. + + Args: + xyz (np.ndarray): A 3D vector representing the position. + yaw (float): The yaw angle in radians. + pitch (float): The pitch angle in radians for y axis. + Returns: + np.ndarray: A 4x4 transformation matrix. + """ + x, y, z = xyz + rot1 = self.xyz_yaw_to_tf_matrix(xyz, yaw)[:3, :3] + rot2 = self.xyz_pitch_to_tf_matrix(xyz, pitch)[:3, :3] + transformation_matrix = np.eye(4) + transformation_matrix[:3, :3] = rot1 @ rot2 + transformation_matrix[:3, 3] = xyz + return transformation_matrix + + def pixel_to_gps(self, pixel, depth, intrinsic, tf_camera_to_episodic): + ''' + Args: + pixel: (2,) - [u, v] pixel coordinates + depth: (H, W) - depth image where depth[v, u] gives depth in meters + intrinsic: (4, 4) - camera intrinsic matrix + tf_camera_to_episodic: (4, 4) - transformation from camera to episodic frame + Returns: + (x, y): (x, y) coordinates in the episodic frame + ''' + v, u = pixel + z = depth[v, u] + print("depthhhhhhhhhhhhhh", z) + + x = (u - intrinsic[0, 2]) * z / intrinsic[0, 0] + y = (v - intrinsic[1, 2]) * z / intrinsic[1, 1] + point_camera = np.array([x, y, z, 1.0]) + + # Transform to episodic frame + point_episodic = tf_camera_to_episodic @ point_camera + point_episodic = point_episodic[:3] / point_episodic[3] + + x = point_episodic[0] + y = point_episodic[1] + + return (x, y) # same as habitat gps + + def dot_matrix_two_dimensional( + self, + image_or_image_path, + save_path=None, + dots_size_w=8, + dots_size_h=8, + save_img=False, + font_path='fonts/arial.ttf', + pixel_goal=None, + ): + """ + takes an original image as input, save the processed image to save_path. Each dot is labeled with two-dimensional Cartesian coordinates (x,y). Suitable for single-image tasks. + control args: + 1. dots_size_w: the number of columns of the dots matrix + 2. dots_size_h: the number of rows of the dots matrix + """ + with open_image(image_or_image_path) as img: + if img.mode != 'RGB': + img = img.convert('RGB') + draw = ImageDraw.Draw(img, 'RGB') + + width, height = img.size + grid_size_w = dots_size_w + 1 + grid_size_h = dots_size_h + 1 + cell_width = width / grid_size_w + cell_height = height / grid_size_h + + font = ImageFont.truetype(font_path, width // 40) # Adjust font size if needed; default == width // 40 + + target_i = target_j = None + if pixel_goal is not None: + y_pixel, x_pixel = pixel_goal[0], pixel_goal[1] + # Validate pixel coordinates + if not (0 <= x_pixel < width and 0 <= y_pixel < height): + raise ValueError(f"pixel_goal {pixel_goal} exceeds image dimensions ({width}x{height})") + + # Convert to grid coordinates + target_i = round(x_pixel / cell_width) + target_j = round(y_pixel / cell_height) + + # Validate grid bounds + if not (1 <= target_i <= dots_size_w and 1 <= target_j <= dots_size_h): + raise ValueError( + f"pixel_goal {pixel_goal} maps to grid ({target_j},{target_i}), " + f"valid range is (1,1)-({dots_size_h},{dots_size_w})" + ) + + count = 0 + + for j in range(1, grid_size_h): + for i in range(1, grid_size_w): + x = int(i * cell_width) + y = int(j * cell_height) + + pixel_color = img.getpixel((x, y)) + # choose a more contrasting color from black and white + if pixel_color[0] + pixel_color[1] + pixel_color[2] >= 255 * 3 / 2: + opposite_color = (0, 0, 0) + else: + opposite_color = (255, 255, 255) + + if pixel_goal is not None and i == target_i and j == target_j: + opposite_color = (255, 0, 0) # Red for target + + circle_radius = width // 240 # Adjust dot size if needed; default == width // 240 + draw.ellipse( + [(x - circle_radius, y - circle_radius), (x + circle_radius, y + circle_radius)], + fill=opposite_color, + ) + + text_x, text_y = x + 3, y + count_w = count // dots_size_w + count_h = count % dots_size_w + label_str = f"({count_w+1},{count_h+1})" + draw.text((text_x, text_y), label_str, fill=opposite_color, font=font) + count += 1 + if save_img: + print(">>> dots overlaid image processed, stored in", save_path) + img.save(save_path) + return img diff --git a/internnav/internnav_habitat/measures.py b/internnav/internnav_habitat/measures.py new file mode 100644 index 0000000..5dddcae --- /dev/null +++ b/internnav/internnav_habitat/measures.py @@ -0,0 +1,560 @@ +from typing import Any, List, Union + +import numpy as np +from habitat.core.embodied_task import EmbodiedTask, Measure +from habitat.core.registry import registry +from habitat.core.simulator import Simulator +from habitat.core.utils import try_cv2_import +from habitat.tasks.nav.nav import DistanceToGoal +from numpy import ndarray + +cv2 = try_cv2_import() + + +def euclidean_distance(pos_a: Union[List[float], ndarray], pos_b: Union[List[float], ndarray]) -> float: + return np.linalg.norm(np.array(pos_b) - np.array(pos_a), ord=2) + + +@registry.register_measure +class PathLength(Measure): + """Path Length (PL) + PL = sum(geodesic_distance(agent_prev_position, agent_position) + over all agent positions. + """ + + cls_uuid: str = "path_length" + + def __init__(self, sim: Simulator, *args: Any, **kwargs: Any): + self._sim = sim + super().__init__(**kwargs) + + def _get_uuid(self, *args: Any, **kwargs: Any) -> str: + return self.cls_uuid + + def reset_metric(self, *args: Any, **kwargs: Any): + self._previous_position = self._sim.get_agent_state().position + self._metric = 0.0 + + def update_metric(self, *args: Any, **kwargs: Any): + current_position = self._sim.get_agent_state().position + self._metric += euclidean_distance(current_position, self._previous_position) + self._previous_position = current_position + + +@registry.register_measure +class OracleNavigationError(Measure): + """Oracle Navigation Error (ONE) + ONE = min(geosdesic_distance(agent_pos, goal)) over all points in the + agent path. + """ + + cls_uuid: str = "oracle_navigation_error" + + def _get_uuid(self, *args: Any, **kwargs: Any) -> str: + return self.cls_uuid + + def reset_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): + task.measurements.check_measure_dependencies(self.uuid, [DistanceToGoal.cls_uuid]) + self._metric = float("inf") + self.update_metric(task=task) + + def update_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): + distance_to_target = task.measurements.measures[DistanceToGoal.cls_uuid].get_metric() + self._metric = min(self._metric, distance_to_target) + + +@registry.register_measure +class OracleSuccess(Measure): + """Oracle Success Rate (OSR). OSR = I(ONE <= goal_radius)""" + + cls_uuid: str = "oracle_success" + + # def __init__(self, *args: Any, config: Config, **kwargs: Any): + # self._config = config + # super().__init__() + + def __init__(self, *args: Any, config: Any, **kwargs: Any): + print(f"in oracle success init: args = {args}, kwargs = {kwargs}") + self._config = config + super().__init__() + + def _get_uuid(self, *args: Any, **kwargs: Any) -> str: + return self.cls_uuid + + def reset_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): + task.measurements.check_measure_dependencies(self.uuid, [DistanceToGoal.cls_uuid]) + self._metric = 0.0 + self.update_metric(task=task) + + def update_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): + d = task.measurements.measures[DistanceToGoal.cls_uuid].get_metric() + # self._metric = float(self._metric or d < self._config["success_distance"]) + self._metric = float(self._metric or d < 3.0) + + +@registry.register_measure +class OracleSPL(Measure): + """OracleSPL (Oracle Success weighted by Path Length) + OracleSPL = max(SPL) over all points in the agent path. + """ + + cls_uuid: str = "oracle_spl" + + def _get_uuid(self, *args: Any, **kwargs: Any) -> str: + return self.cls_uuid + + def reset_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): + task.measurements.check_measure_dependencies(self.uuid, ["spl"]) + self._metric = 0.0 + + def update_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): + spl = task.measurements.measures["spl"].get_metric() + self._metric = max(self._metric, spl) + + +@registry.register_measure +class StepsTaken(Measure): + """Counts the number of times update_metric() is called. This is equal to + the number of times that the agent takes an action. STOP counts as an + action. + """ + + cls_uuid: str = "steps_taken" + + def _get_uuid(self, *args: Any, **kwargs: Any) -> str: + return self.cls_uuid + + def reset_metric(self, *args: Any, **kwargs: Any): + self._metric = 0.0 + + def update_metric(self, *args: Any, **kwargs: Any): + self._metric += 1.0 + + +# import gzip +# import json +# import pickle +# from dtw import dtw +# from fastdtw import fastdtw +# from habitat.config import Config +# from utils import maps +# from habitat_extensions.task import RxRVLNCEDatasetV1 +# from habitat.tasks.nav.nav import DistanceToGoal, Success +# from habitat.tasks.utils import cartesian_to_polar +# from habitat.utils.geometry_utils import quaternion_rotate_vector +# from habitat.utils.visualizations import fog_of_war +# from habitat.utils.visualizations import maps as habitat_maps +# from habitat.core.dataset import Episode +# from habitat.core.embodied_task import Action, EmbodiedTask, Measure +# from habitat.core.logging import logger + +# @registry.register_measure +# class WaypointRewardMeasure(Measure): +# """A reward measure used for training VLN-CE agents via RL.""" + +# def __init__( +# self, *args: Any, sim: Simulator, config: Config, **kwargs: Any +# ) -> None: +# self._sim = sim +# self._slack_reward = config.slack_reward +# self._use_distance_scaled_slack_reward = ( +# config.use_distance_scaled_slack_reward +# ) +# self._scale_slack_on_prediction = config.scale_slack_on_prediction +# self._success_reward = config.success_reward +# self._distance_scalar = config.distance_scalar +# self._prev_position = None +# super().__init__() + +# def reset_metric( +# self, *args: Any, task: EmbodiedTask, **kwargs: Any +# ) -> None: +# task.measurements.check_measure_dependencies( +# self.uuid, [DistanceToGoal.cls_uuid, Success.cls_uuid] +# ) +# self._previous_distance_to_goal = task.measurements.measures[ +# "distance_to_goal" +# ].get_metric() +# self._metric = 0.0 +# self._prev_position = np.take( +# self._sim.get_agent_state().position, [0, 2] +# ) + +# def _get_scaled_slack_reward(self, action: Action) -> float: +# if isinstance(action["action"], int): +# return self._slack_reward + +# if not self._use_distance_scaled_slack_reward: +# return self._slack_reward + +# agent_pos = np.take(self._sim.get_agent_state().position, [0, 2]) +# slack_distance = ( +# action["action_args"]["r"] +# if self._scale_slack_on_prediction and action["action"] != "STOP" +# else np.linalg.norm(self._prev_position - agent_pos) +# ) +# scaled_slack_reward = self._slack_reward * slack_distance / 0.25 +# self._prev_position = agent_pos +# return min(self._slack_reward, scaled_slack_reward) + +# def _progress_to_goal(self, task: EmbodiedTask) -> float: +# distance_to_goal = task.measurements.measures[ +# "distance_to_goal" +# ].get_metric() +# distance_to_goal_delta = ( +# self._previous_distance_to_goal - distance_to_goal +# ) +# if np.isnan(distance_to_goal_delta) or np.isinf( +# distance_to_goal_delta +# ): +# l = self._sim.get_agent_state().position +# logger.error( +# f"\nNaN or inf encountered in distance measure. agent location: {l}", +# ) +# distance_to_goal_delta = -1.0 +# self._previous_distance_to_goal = distance_to_goal +# return self._distance_scalar * distance_to_goal_delta + +# def update_metric( +# self, *args: Any, action: Action, task: EmbodiedTask, **kwargs: Any +# ) -> None: +# reward = self._get_scaled_slack_reward(action) +# reward += self._progress_to_goal(task) +# reward += ( +# self._success_reward +# * task.measurements.measures["success"].get_metric() +# ) +# self._metric = reward + +# @staticmethod +# def _get_uuid(*args: Any, **kwargs: Any) -> str: +# return "waypoint_reward_measure" + + +# @registry.register_measure +# class NDTW(Measure): +# """NDTW (Normalized Dynamic Time Warping) +# ref: https://arxiv.org/abs/1907.05446 +# """ + +# cls_uuid: str = "ndtw" + +# def __init__( +# self, *args: Any, sim: Simulator, config: Config, **kwargs: Any +# ): +# self._sim = sim +# self._config = config +# self.dtw_func = fastdtw if config.FDTW else dtw + +# if "{role}" in config.GT_PATH: +# self.gt_json = {} +# for role in RxRVLNCEDatasetV1.annotation_roles: +# with gzip.open( +# config.GT_PATH.format(split=config.SPLIT, role=role), "rt" +# ) as f: +# self.gt_json.update(json.load(f)) +# else: +# with gzip.open( +# config.GT_PATH.format(split=config.SPLIT), "rt" +# ) as f: +# self.gt_json = json.load(f) + +# super().__init__() + +# def _get_uuid(self, *args: Any, **kwargs: Any) -> str: +# return self.cls_uuid + +# def reset_metric(self, *args: Any, episode, **kwargs: Any): +# self.locations = [] +# self.gt_locations = self.gt_json[episode.episode_id]["locations"] +# self.update_metric() + +# def update_metric(self, *args: Any, **kwargs: Any): +# current_position = self._sim.get_agent_state().position.tolist() +# if len(self.locations) == 0: +# self.locations.append(current_position) +# else: +# if current_position == self.locations[-1]: +# return +# self.locations.append(current_position) + +# dtw_distance = self.dtw_func( +# self.locations, self.gt_locations, dist=euclidean_distance +# )[0] + +# nDTW = np.exp( +# -dtw_distance +# / (len(self.gt_locations) * self._config.SUCCESS_DISTANCE) +# ) +# self._metric = nDTW + + +# @registry.register_measure +# class SDTW(Measure): +# """SDTW (Success Weighted be nDTW) +# ref: https://arxiv.org/abs/1907.05446 +# """ + +# cls_uuid: str = "sdtw" + +# def _get_uuid(self, *args: Any, **kwargs: Any) -> str: +# return self.cls_uuid + +# def reset_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): +# task.measurements.check_measure_dependencies( +# self.uuid, [NDTW.cls_uuid, Success.cls_uuid] +# ) +# self.update_metric(task=task) + +# def update_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): +# ep_success = task.measurements.measures[Success.cls_uuid].get_metric() +# nDTW = task.measurements.measures[NDTW.cls_uuid].get_metric() +# self._metric = ep_success * nDTW + + +# @registry.register_measure +# class TopDownMapVLNCE(Measure): +# """A top down map that optionally shows VLN-related visual information +# such as MP3D node locations and MP3D agent traversals. +# """ + +# cls_uuid: str = "top_down_map_vlnce" + +# def __init__( +# self, *args: Any, sim: Simulator, config: Config, **kwargs: Any +# ) -> None: +# self._sim = sim +# self._config = config +# self._step_count = None +# self._map_resolution = config.MAP_RESOLUTION +# self._previous_xy_location = None +# self._top_down_map = None +# self._meters_per_pixel = None +# self.current_node = "" +# with open(self._config.GRAPHS_FILE, "rb") as f: +# self._conn_graphs = pickle.load(f) +# super().__init__() + +# def _get_uuid(self, *args: Any, **kwargs: Any) -> str: +# return self.cls_uuid + +# def get_original_map(self) -> ndarray: +# top_down_map = habitat_maps.get_topdown_map_from_sim( +# self._sim, +# map_resolution=self._map_resolution, +# draw_border=self._config.DRAW_BORDER, +# meters_per_pixel=self._meters_per_pixel, +# ) + +# self._fog_of_war_mask = None +# if self._config.FOG_OF_WAR.DRAW: +# self._fog_of_war_mask = np.zeros_like(top_down_map) + +# return top_down_map + +# def reset_metric( +# self, *args: Any, episode: Episode, **kwargs: Any +# ) -> None: +# self._scene_id = episode.scene_id.split("/")[-2] +# self._step_count = 0 +# self._metric = None +# self._meters_per_pixel = habitat_maps.calculate_meters_per_pixel( +# self._map_resolution, self._sim +# ) +# self._top_down_map = self.get_original_map() +# agent_position = self._sim.get_agent_state().position +# scene_id = episode.scene_id.split("/")[-1].split(".")[0] +# a_x, a_y = habitat_maps.to_grid( +# agent_position[2], +# agent_position[0], +# self._top_down_map.shape[0:2], +# sim=self._sim, +# ) +# self._previous_xy_location = (a_y, a_x) + +# if self._config.FOG_OF_WAR.DRAW: +# self._fog_of_war_mask = fog_of_war.reveal_fog_of_war( +# self._top_down_map, +# self._fog_of_war_mask, +# np.array([a_x, a_y]), +# self.get_polar_angle(), +# fov=self._config.FOG_OF_WAR.FOV, +# max_line_len=self._config.FOG_OF_WAR.VISIBILITY_DIST +# / habitat_maps.calculate_meters_per_pixel( +# self._map_resolution, sim=self._sim +# ), +# ) + +# if self._config.DRAW_FIXED_WAYPOINTS: +# maps.draw_mp3d_nodes( +# self._top_down_map, +# self._sim, +# episode, +# self._conn_graphs[scene_id], +# self._meters_per_pixel, +# ) + +# if self._config.DRAW_SHORTEST_PATH: +# shortest_path_points = self._sim.get_straight_shortest_path_points( +# agent_position, episode.goals[0].position +# ) +# maps.draw_straight_shortest_path_points( +# self._top_down_map, +# self._sim, +# self._map_resolution, +# shortest_path_points, +# ) + +# if self._config.DRAW_REFERENCE_PATH: +# maps.draw_reference_path( +# self._top_down_map, +# self._sim, +# episode, +# self._map_resolution, +# self._meters_per_pixel, +# ) + +# # draw source and target points last to avoid overlap +# if self._config.DRAW_SOURCE_AND_TARGET: +# maps.draw_source_and_target( +# self._top_down_map, +# self._sim, +# episode, +# self._meters_per_pixel, +# ) + +# # MP3D START NODE +# self._nearest_node = maps.get_nearest_node( +# self._conn_graphs[scene_id], np.take(agent_position, (0, 2)) +# ) +# nn_position = self._conn_graphs[self._scene_id].nodes[ +# self._nearest_node +# ]["position"] +# self.s_x, self.s_y = habitat_maps.to_grid( +# nn_position[2], +# nn_position[0], +# self._top_down_map.shape[0:2], +# self._sim, +# ) +# self.update_metric() + +# def update_metric(self, *args: Any, **kwargs: Any) -> None: +# self._step_count += 1 +# ( +# house_map, +# map_agent_pos, +# ) = self.update_map(self._sim.get_agent_state().position) + +# self._metric = { +# "map": house_map, +# "fog_of_war_mask": self._fog_of_war_mask, +# "agent_map_coord": map_agent_pos, +# "agent_angle": self.get_polar_angle(), +# "bounds": { +# k: v +# for k, v in zip( +# ["lower", "upper"], +# self._sim.pathfinder.get_bounds(), +# ) +# }, +# "meters_per_px": self._meters_per_pixel, +# } + +# def get_polar_angle(self) -> float: +# agent_state = self._sim.get_agent_state() +# # quaternion is in x, y, z, w format +# ref_rotation = agent_state.rotation + +# heading_vector = quaternion_rotate_vector( +# ref_rotation.inverse(), np.array([0, 0, -1]) +# ) + +# phi = cartesian_to_polar(-heading_vector[2], heading_vector[0])[1] +# z_neg_z_flip = np.pi +# return np.array(phi) + z_neg_z_flip + +# def update_map(self, agent_position: List[float]) -> None: +# a_x, a_y = habitat_maps.to_grid( +# agent_position[2], +# agent_position[0], +# self._top_down_map.shape[0:2], +# self._sim, +# ) +# # Don't draw over the source point +# gradient_color = 15 + min( +# self._step_count * 245 // self._config.MAX_EPISODE_STEPS, 245 +# ) +# if self._top_down_map[a_x, a_y] != maps.MAP_SOURCE_POINT_INDICATOR: +# maps.drawline( +# self._top_down_map, +# self._previous_xy_location, +# (a_y, a_x), +# gradient_color, +# thickness=int( +# self._map_resolution * 1.4 / maps.MAP_THICKNESS_SCALAR +# ), +# style="filled", +# ) + +# if self._config.FOG_OF_WAR.DRAW: +# self._fog_of_war_mask = fog_of_war.reveal_fog_of_war( +# self._top_down_map, +# self._fog_of_war_mask, +# np.array([a_x, a_y]), +# self.get_polar_angle(), +# self._config.FOG_OF_WAR.FOV, +# max_line_len=self._config.FOG_OF_WAR.VISIBILITY_DIST +# / habitat_maps.calculate_meters_per_pixel( +# self._map_resolution, sim=self._sim +# ), +# ) + +# point_padding = int(0.2 / self._meters_per_pixel) +# prev_nearest_node = self._nearest_node +# self._nearest_node = maps.update_nearest_node( +# self._conn_graphs[self._scene_id], +# self._nearest_node, +# np.take(agent_position, (0, 2)), +# ) +# if ( +# self._nearest_node != prev_nearest_node +# and self._config.DRAW_MP3D_AGENT_PATH +# ): +# nn_position = self._conn_graphs[self._scene_id].nodes[ +# self._nearest_node +# ]["position"] +# (prev_s_x, prev_s_y) = (self.s_x, self.s_y) +# self.s_x, self.s_y = habitat_maps.to_grid( +# nn_position[2], +# nn_position[0], +# self._top_down_map.shape[0:2], +# self._sim, +# ) +# self._top_down_map[ +# self.s_x +# - int(2.0 / 3.0 * point_padding) : self.s_x +# + int(2.0 / 3.0 * point_padding) +# + 1, +# self.s_y +# - int(2.0 / 3.0 * point_padding) : self.s_y +# + int(2.0 / 3.0 * point_padding) +# + 1, +# ] = gradient_color + +# maps.drawline( +# self._top_down_map, +# (prev_s_y, prev_s_x), +# (self.s_y, self.s_x), +# gradient_color, +# thickness=int( +# 1.0 +# / 2.0 +# * np.round( +# self._map_resolution / maps.MAP_THICKNESS_SCALAR +# ) +# ), +# ) + +# self._previous_xy_location = (a_y, a_x) +# map_agent_pos = (a_x, a_y) +# return self._top_down_map, map_agent_pos diff --git a/internnav/internnav_habitat/refactor_notes.md b/internnav/internnav_habitat/refactor_notes.md new file mode 100644 index 0000000..7a197b4 --- /dev/null +++ b/internnav/internnav_habitat/refactor_notes.md @@ -0,0 +1,66 @@ +# Refactoring `habitat_vln_evaluator` + +This note explains how to split the current `VLNEvaluator` implementation into the +framework's `Env` and `Agent` abstractions. + +## 1. Construction and configuration (lines 45-135) +* **Environment**: Habitat config loading, dataset split selection, sensor parameter + extraction, and measurement registration belong to the environment setup. These + responsibilities configure and own the simulator state and therefore should be + moved into a `HabitatVLNEnv` class that extends `Env`.【F:internnav/evaluator/habitat_vln_evaluator.py†L45-L103】 +* **Agent**: Model handles, prompt bootstrapping, conversation history, action + vocabulary, and instruction templates are part of the policy logic and should be + carried by a dedicated `HabitatVLNAgent` subclass. These fields initialize the + reasoning model rather than the simulator.【F:internnav/evaluator/habitat_vln_evaluator.py†L104-L135】 + +## 2. Perception utilities (lines 137-236) +Depth pre-processing, intrinsic matrix computation, coordinate transforms, and GPS +projection are tied to the simulator sensor geometry. They should move into the +`HabitatVLNEnv` so that observation tensors returned to the agent are already in a +consistent world frame.【F:internnav/evaluator/habitat_vln_evaluator.py†L137-L236】 + +## 3. Visualization helper (lines 238-309) +The dot-matrix overlay operates purely on rendered frames and can stay as an +environment utility. The helper should become a method of the environment (or a +separate visualization module) so evaluators can call it regardless of the agent. +【F:internnav/evaluator/habitat_vln_evaluator.py†L238-L309】 + +## 4. Low-level point navigation (lines 311-347) +The `_pointnav` helper controls a waypoint-following controller that consumes +processed observations and outputs low-level actions. Because it interacts with the +robot's state (goal resets, depth resizing, point-goal calculation), it fits inside +the environment. The agent can request point-goal actions through a method such as +`HabitatVLNEnv.pointnav(goal, depth, ...)`.【F:internnav/evaluator/habitat_vln_evaluator.py†L311-L347】 + +## 5. Main evaluation loop (lines 349-520) +* **Environment**: Episode iteration, resetting, stepping, intrinsic assembly, and + metric gathering should be owned by the environment. Wrapping Habitat's episode + lifecycle in `HabitatVLNEnv` keeps the evaluator thin and deterministic. +* **Agent**: Generating waypoint predictions, maintaining conversation turns, and + deciding discrete actions are policy responsibilities. The evaluator should ask + the new agent for an action by passing observations (RGB, depth, state metadata) + returned by the environment wrapper.【F:internnav/evaluator/habitat_vln_evaluator.py†L349-L520】 + +## 6. Language and action parsing (lines 522-680) +Instruction processing (`split_and_clean`, dynamic prompt assembly) and action string +parsing convert model text into executable commands. These should be encapsulated in +`HabitatVLNAgent` so the evaluator only receives structured actions (e.g., STOP, +MOVE, LOOK).【F:internnav/evaluator/habitat_vln_evaluator.py†L522-L680】 + +## 7. Metric aggregation and exports (lines 682-745) +Writing JSON lines, aggregating SPL/OS/NE, and optional video dumping can remain in +the evaluator, but the raw metrics originate from the environment through +`HabitatVLNEnv.get_metrics()` and rendering helpers. The evaluator should simply +post-process the aggregated numbers.【F:internnav/evaluator/habitat_vln_evaluator.py†L682-L745】 + +## Resulting structure +1. **`internnav/env/habitat_vln_env.py`**: wraps Habitat configuration, episode + control, sensor processing, point-nav helper, and visualization utilities. +2. **`internnav/agent/habitat_vln_agent.py`**: encapsulates the vision-language + model, prompt management, observation parsing, and action decoding. +3. **`internnav/evaluator/habitat_vln_evaluator.py`**: becomes a thin coordinator + that instantiates the env/agent via the registry, loops over episodes, and logs + metrics. + +This split brings the Habitat evaluator in line with the existing framework while +keeping domain-specific functionality in focused components. diff --git a/internnav/internnav_habitat/utils.py b/internnav/internnav_habitat/utils.py new file mode 100644 index 0000000..e69de29 diff --git a/scripts/eval/bash/torchrun_eval.sh b/scripts/eval/bash/torchrun_eval.sh new file mode 100644 index 0000000..fa99d40 --- /dev/null +++ b/scripts/eval/bash/torchrun_eval.sh @@ -0,0 +1,20 @@ +# use to run distributed eval with 4 gpus on single node + +# MID_RUN_NAME="InternVLA-N1" +# torchrun \ +# --nproc_per_node=8 \ +# --master_port=2333 \ +# scripts/eval/eval.py \ +# --config scripts/eval/configs/habitat_cfg.py \ +# > logs/${MID_RUN_NAME}_log.txt 2>&1 + +# CUDA_VISIBLE_DEVICES=6,7 +MID_RUN_NAME="InternVLA-N1" +torchrun \ + --nproc_per_node=8 \ + --master_port=29501 \ + scripts/eval/eval_habitat.py \ + --model_path checkpoints/InternVLA-N1 \ + --continuous_traj \ + --output_path logs/habitat/test_new_checkpoint2 \ + > logs/${MID_RUN_NAME}_old_log1.txt 2>&1 diff --git a/scripts/eval/configs/comm_cfg.py b/scripts/eval/configs/comm_cfg.py new file mode 100644 index 0000000..3c1b7bb --- /dev/null +++ b/scripts/eval/configs/comm_cfg.py @@ -0,0 +1,16 @@ +from internnav.configs.agent import AgentCfg +from internnav.configs.evaluator import EnvCfg, EvalCfg, EvalDatasetCfg, TaskCfg + +eval_cfg = EvalCfg( + agent=AgentCfg( + server_port=8087, + model_name='cma', + ckpt_path='checkpoints/r2r/fine_tuned/cma_plus', + model_settings={}, + ), + env=EnvCfg['internutopia'], + task=TaskCfg['vln_pe'], + dataset=EvalDatasetCfg['mp3d'], + eval_type='internutopia_vln', + eval_settings={'save_to_json': False, 'vis_output': True}, +) diff --git a/scripts/eval/configs/habitat_cfg.py b/scripts/eval/configs/habitat_cfg.py new file mode 100644 index 0000000..aaa702d --- /dev/null +++ b/scripts/eval/configs/habitat_cfg.py @@ -0,0 +1,60 @@ +from internnav.configs.agent import AgentCfg +from internnav.configs.evaluator import EnvCfg, EvalCfg + +eval_cfg = EvalCfg( + agent=AgentCfg( + server_port=8087, + model_name='internvla_n1', + ckpt_path='', + model_settings={ + 'env_num': 1, + 'sim_num': 1, + 'model_path': "checkpoints/InternVLA-N1", + 'camera_intrinsic': [[585.0, 0.0, 320.0], [0.0, 585.0, 240.0], [0.0, 0.0, 1.0]], + 'width': 640, + 'height': 480, + 'hfov': 79, + 'resize_w': 384, + 'resize_h': 384, + 'max_new_tokens': 1024, + 'num_frames': 32, + 'num_history': 8, + 'num_future_steps': 4, + 'device': 'cuda:0', + 'predict_step_nums': 32, + 'continuous_traj': True, + # debug + 'vis_debug': True, # If vis_debug=True, you can get visualization results + 'vis_debug_path': './logs/test/vis_debug', + }, + ), + env=EnvCfg( + env_type='habitat', + env_settings={ + # habitat sim specifications - agent, sensors, tasks, measures etc. are defined in the habitat config file + 'config_path': 'scripts/eval/configs/vln_r2r.yaml', + }, + ), + eval_type='habitat_vln', + eval_settings={ + # all current parse args + "local_rank": 0, # node rank + "output_path": "./logs/habitat/test_refactor_debug", # output directory for logs/results + "save_video": False, # whether to save videos + "world_size": 1, # number of distributed processes + "rank": 0, # rank of current process + "gpu": 0, # gpu id to use + "port": "2333", # communication port + "dist_url": "env://", # url for distributed setup + "mode": "dual_system", # inference mode: dual_system or system2 + "model_path": "checkpoints/InternVLA-N1", # path to model checkpoint + "num_future_steps": 4, # number of future steps for prediction + "num_frames": 32, # number of frames used in evaluation + "num_history": 8, + "resize_w": 384, # image resize width + "resize_h": 384, # image resize height + "predict_step_nums": 32, # number of steps to predict + "continuous_traj": True, # whether to use continuous trajectory + "max_new_tokens": 1024, # maximum number of tokens for generation + }, +) diff --git a/scripts/eval/configs/vln_r2r.yaml b/scripts/eval/configs/vln_r2r.yaml index ed8361c..e6b1a89 100644 --- a/scripts/eval/configs/vln_r2r.yaml +++ b/scripts/eval/configs/vln_r2r.yaml @@ -72,6 +72,6 @@ habitat: dataset: type: R2RVLN-v1 - split: val_seen + split: val_unseen scenes_dir: data/scene_data/mp3d_ce data_path: data/vln_ce/raw_data/r2r/{split}/{split}.json.gz diff --git a/scripts/eval/eval.py b/scripts/eval/eval.py index 68c507a..79d0cda 100644 --- a/scripts/eval/eval.py +++ b/scripts/eval/eval.py @@ -5,7 +5,6 @@ import argparse import importlib.util -from internnav.configs.evaluator.vln_default_config import get_config from internnav.evaluator import Evaluator # This file is the main file @@ -19,6 +18,9 @@ def parse_args(): default='scripts/eval/configs/h1_rdp_cfg.py', help='eval config file path, e.g. scripts/eval/configs/h1_cma_cfg.py', ) + parser.add_argument('--port', type=int, default=None) + parser.add_argument('--host', type=str, default=None) + parser.add_argument('--dist_eval', action="store_true", default=False) return parser.parse_args() @@ -33,10 +35,18 @@ def load_eval_cfg(config_path, attr_name='eval_cfg'): def main(): args = parse_args() evaluator_cfg = load_eval_cfg(args.config, attr_name='eval_cfg') - cfg = get_config(evaluator_cfg) - print(cfg) - evaluator = Evaluator.init(cfg) - print(type(evaluator)) + + # fill in evaluator default config + if evaluator_cfg.eval_type == 'vln_multi': + from internnav.configs.evaluator.vln_default_config import get_config + + evaluator_cfg = get_config(evaluator_cfg) + elif evaluator_cfg.eval_type == 'habitat_vln': + # TODO: add default config + pass + + # create evaluator based on sim backend and run eval + evaluator = Evaluator.init(evaluator_cfg) evaluator.eval() From 99024017aded29c1b5d65cd7d0b19de362db3858 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Tue, 11 Nov 2025 08:31:43 +0000 Subject: [PATCH 03/35] add distributed_base evaluator --- internnav/evaluator/__init__.py | 3 +- internnav/evaluator/distributed_base.py | 213 ++++++++++-------- .../habitat_vln_evaluator.py | 125 +++++----- internnav/utils/comm_utils/server.py | 39 ++++ scripts/eval/bash/torchrun_eval.sh | 30 +-- scripts/eval/configs/habitat_cfg.py | 1 + scripts/eval/eval_habitat.py | 127 ----------- scripts/iros_challenge/start_eval_iros.sh | 2 +- 8 files changed, 240 insertions(+), 300 deletions(-) delete mode 100644 scripts/eval/eval_habitat.py diff --git a/internnav/evaluator/__init__.py b/internnav/evaluator/__init__.py index e831ea5..fda0a88 100644 --- a/internnav/evaluator/__init__.py +++ b/internnav/evaluator/__init__.py @@ -1,6 +1,7 @@ -# register habitat TODO +# register habitat import internnav.internnav_habitat # noqa: F401 from internnav.evaluator.base import Evaluator +from internnav.evaluator.distributed_base import DistributedEvaluator from internnav.evaluator.vln_multi_evaluator import VlnMultiEvaluator __all__ = ['Evaluator', 'VlnMultiEvaluator'] diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index 3244305..a0f06a2 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -1,57 +1,13 @@ +import argparse import json import os -from datetime import datetime +import numpy as np import torch from internnav.configs.evaluator import EvalCfg from internnav.evaluator.base import Evaluator -from internnav.utils.dist import dist, get_rank, get_world_size - - -def init_distributed_mode(args): - if 'SLURM_PROCID' in os.environ: - args.rank = int(os.environ['SLURM_PROCID']) - args.world_size = int(os.environ['SLURM_NTASKS']) - - num_gpus = torch.cuda.device_count() - args.gpu = args.rank % num_gpus - args.local_rank = args.gpu - - node_list = os.environ['SLURM_NODELIST'] - print(f'Node list: {node_list}') - # addr = subprocess.getoutput(f'scontrol show hostname {node_list} | head -n1') - - os.environ['MASTER_PORT'] = str(getattr(args, 'port', '29529')) - # os.environ['MASTER_ADDR'] = addr - os.environ['WORLD_SIZE'] = str(args.world_size) - os.environ['LOCAL_RANK'] = str(args.gpu) - os.environ['RANK'] = str(args.rank) - elif 'RANK' in os.environ and 'WORLD_SIZE' in os.environ: - args.rank = int(os.environ["RANK"]) - args.world_size = int(os.environ['WORLD_SIZE']) - args.gpu = int(os.environ['LOCAL_RANK']) - args.local_rank = args.gpu - else: - print('Not using distributed mode') - # setup_for_distributed(is_master=True) # hack - args.distributed = False - return - - args.distributed = True - - torch.cuda.set_device(args.gpu) - args.dist_backend = 'nccl' - print('| distributed init (rank {}): {}, gpu {}'.format(args.rank, args.dist_url, args.gpu), flush=True) - dist.init_process_group( - backend=args.dist_backend, - init_method=args.dist_url, - world_size=args.world_size, - rank=args.rank, - timeout=datetime.timedelta(0, 7200), - ) - dist.barrier() - # setup_for_distributed(args.rank == 0) +from internnav.utils.dist import dist, get_rank, get_world_size, init_distributed_mode class DistributedEvaluator(Evaluator): @@ -61,53 +17,106 @@ class DistributedEvaluator(Evaluator): def __init__(self, cfg: EvalCfg): # distributed setting - import os import socket print( f"Rank {os.getenv('RANK')} / {os.getenv('WORLD_SIZE')} on {socket.gethostname()}:{os.getenv('MASTER_PORT')}" ) - # init_distributed_mode(args) - # local_rank = args.local_rank - # np.random.seed(local_rank) + + args = argparse.Namespace(**cfg.eval_settings) + self.args = args + + init_distributed_mode(args) + + self.local_rank = args.local_rank + np.random.seed(self.local_rank) + self.world_size = get_world_size() + self.output_path = args.output_path # TODO: modify by rank + cfg.env.env_settings['idx'] = get_rank() cfg.env.env_settings['world_size'] = get_world_size() + # -------- initialize agent config (either remote server or local agent) -------- # set agent port based on rank - cfg.agent.agent_settings['port'] = 8000 + get_rank() + # cfg.agent.agent_settings['port'] = 8000 + get_rank() # start_server(cfg.agent.agent_settings['port']) - super().__init__(cfg) + self.eval_config = cfg + # self.env = Env.init(cfg.env, cfg.task) + # self.agent = AgentClient(config.agent) def eval(self): - # 1. 每个 rank 本地跑一遍 - local_metrics = self.eval_action() # dict[str, Tensor], 每个 Tensor shape [N] - # 取出设备 & 本地样本数 - device = next(iter(local_metrics.values())).device - local_count = torch.tensor([len(next(iter(local_metrics.values())))], dtype=torch.long, device=device) + """ + Uniform distributed evaluation pipeline: + + 1. Call subclass's eval_action() to get local per-episode tensors. + 2. Use dist all_gather (+ padding) to build global tensors for each metric. + 3. Call subclass's calc_metrics(global_metrics) to compute scalar metrics. + 4. Print + rank 0 writes result.json. + """ + local_metrics = self.eval_action() # dict[str, Tensor], each [N_local] + + if not local_metrics: + raise RuntimeError("eval_action() returned empty metrics dict.") + + first_tensor = next(iter(local_metrics.values())) + device = first_tensor.device + local_len = first_tensor.shape[0] - # 2. 全局样本数 world_size = get_world_size() - global_count = local_count.clone() - if world_size > 1: - dist.all_reduce(global_count, op=dist.ReduceOp.SUM) - - # 3. 对每个 metric 做全局 sum / mean - result_all = {} - for name, tensor in local_metrics.items(): - # tensor: [N] - local_sum = tensor.sum() - global_sum = local_sum.clone() - if world_size > 1: - dist.all_reduce(global_sum, op=dist.ReduceOp.SUM) - - mean_val = (global_sum / global_count).item() - result_all[name] = mean_val - - # 4. 统计全局 episode 数 - result_all["length"] = int(global_count.item()) - - # 5. 打印 + 只在 rank 0 写文件 + + # -------- 1) Handle non-distributed / world_size == 1 -------- + if world_size == 1: + global_metrics = {name: tensor.detach().cpu() for name, tensor in local_metrics.items()} + total_len = int(local_len) + else: + # -------- 2) Gather lengths from all ranks -------- + local_len_t = torch.tensor([local_len], dtype=torch.long, device=device) + len_list = [torch.zeros_like(local_len_t) for _ in range(world_size)] + dist.all_gather(len_list, local_len_t) + lens = torch.stack(len_list).cpu() # shape [world_size, 1] + lens = lens.view(-1) # [world_size] + max_len = int(lens.max().item()) + total_len = int(lens.sum().item()) + + # -------- 3) For each metric, pad + all_gather + unpad -------- + global_metrics = {} + for name, tensor in local_metrics.items(): + assert tensor.shape[0] == local_len, ( + f"Metric {name} length ({tensor.shape[0]}) " f"!= first metric length ({local_len})" + ) + + # pad to max_len on this rank + padded = torch.zeros( + max_len, + dtype=tensor.dtype, + device=device, + ) + padded[:local_len] = tensor + + # gather padded tensors from all ranks + gathered = [torch.zeros_like(padded) for _ in range(world_size)] + dist.all_gather(gathered, padded) + + # unpad & concat using true lengths + parts = [] + for rank in range(world_size): + cur_len = int(lens[rank].item()) + if cur_len > 0: + parts.append(gathered[rank][:cur_len]) + if parts: + global_tensor = torch.cat(parts, dim=0) + else: + # no episodes at all (edge case) + global_tensor = torch.empty(0, dtype=tensor.dtype) + + global_metrics[name] = global_tensor.detach().cpu() + + # -------- 4) Let subclass compute final metrics from global tensors -------- + result_all = self.calc_metrics(global_metrics) + result_all.setdefault("length", total_len) + + # -------- 5) Logging -------- print(result_all) if get_rank() == 0: os.makedirs(self.args.output_path, exist_ok=True) @@ -117,15 +126,43 @@ def eval(self): return result_all - def eval_action(self): + # ================= ABSTRACT HOOKS ================= + + def eval_action(self) -> dict: + """ + Run evaluation on this rank and return per-episode metrics. + + Returns + ------- + dict[str, torch.Tensor] + Example: + { + "sucs": tensor([0., 1., ...], device=...), + "spls": tensor([...]), + "oss": tensor([...]), + "nes": tensor([...]), + } + """ + raise NotImplementedError + + def calc_metrics(self, global_metrics: dict) -> dict: """ - 跑当前 rank 的 episodes, 返回一个 dict: - { - "success": tensor([0., 1., ...], device=...), - "spl": tensor([...]), - "os": tensor([...]), - "ne": tensor([...]), - ... - } + Compute final scalar metrics from global per-episode tensors. + + Parameters + ---------- + global_metrics : dict[str, torch.Tensor] + For each metric name, a 1-D CPU tensor with all episodes across all ranks. + Example: + { + "sucs": tensor([...], dtype=torch.float32), + "spls": tensor([...]), + ... + } + + Returns + ------- + dict[str, float] + Final scalar metrics to log. """ raise NotImplementedError diff --git a/internnav/internnav_habitat/habitat_vln_evaluator.py b/internnav/internnav_habitat/habitat_vln_evaluator.py index 99e8fdc..ef18ec0 100644 --- a/internnav/internnav_habitat/habitat_vln_evaluator.py +++ b/internnav/internnav_habitat/habitat_vln_evaluator.py @@ -10,7 +10,6 @@ import re from collections import OrderedDict -import habitat import numpy as np import quaternion import torch @@ -23,7 +22,7 @@ # Import for Habitat registry side effects — do not remove import internnav.env.utils.habitat_extensions.measures # noqa: F401 from internnav.configs.evaluator import EvalCfg -from internnav.evaluator.base import Evaluator +from internnav.evaluator import DistributedEvaluator, Evaluator from internnav.model.basemodel.internvla_n1.internvla_n1 import InternVLAN1ForCausalLM from internnav.model.utils.vln_utils import ( chunk_token, @@ -31,9 +30,9 @@ split_and_clean, traj_to_actions, ) -from internnav.utils.dist import dist, get_rank, get_world_size, init_distributed_mode try: + import habitat from habitat import Env from habitat.config.default import get_agent_config from habitat.config.default_structured_configs import ( @@ -56,28 +55,12 @@ @Evaluator.register('habitat_vln') -class HabitatVlnEvaluator(Evaluator): +class HabitatVlnEvaluator(DistributedEvaluator): def __init__(self, cfg: EvalCfg): args = argparse.Namespace(**cfg.eval_settings) self.args = args self.save_video = args.save_video - - # distributed setting - import os - import socket - - print( - f"Rank {os.getenv('RANK')} / {os.getenv('WORLD_SIZE')} on {socket.gethostname()}:{os.getenv('MASTER_PORT')}" - ) - init_distributed_mode(args) - local_rank = args.local_rank - np.random.seed(local_rank) - cfg.env.env_settings['idx'] = get_rank() - cfg.env.env_settings['world_size'] = get_world_size() - - self.world_size = get_world_size() - self.output_path = args.output_path # TODO: modify by rank - self.epoch = 0 + self.epoch = args.epoch # create habitat config self.config_path = cfg.env.env_settings['config_path'] @@ -109,13 +92,13 @@ def __init__(self, cfg: EvalCfg): cfg.env.env_settings['habitat_config'] = self.config # init agent and env - # super().__init__(cfg) + super().__init__(cfg) # ------------------------------------- model ------------------------------------------ processor = AutoProcessor.from_pretrained(args.model_path) processor.tokenizer.padding_side = 'left' - device = torch.device(f"cuda:{local_rank}") + device = torch.device(f"cuda:{self.local_rank}") if args.mode == 'dual_system': model = InternVLAN1ForCausalLM.from_pretrained( args.model_path, @@ -136,15 +119,6 @@ def __init__(self, cfg: EvalCfg): model.eval() self.device = device - # ------------------------------------- old ------------------------------------------ - self._camera_height = self.sim_sensors_config.rgb_sensor.position[1] - self._min_depth = self.sim_sensors_config.depth_sensor.min_depth - self._max_depth = self.sim_sensors_config.depth_sensor.max_depth - - camera_fov_rad = np.deg2rad(self.sim_sensors_config.depth_sensor.hfov) - self._camera_fov = camera_fov_rad - self._fx = self._fy = self.sim_sensors_config.depth_sensor.width / (2 * np.tan(camera_fov_rad / 2)) - self.model = model self.processor = processor @@ -178,41 +152,56 @@ def __init__(self, cfg: EvalCfg): self.num_frames = args.num_frames self.num_future_steps = args.num_future_steps self.num_history = args.num_history + + # ------------------------------------- old ------------------------------------------ + self._camera_height = self.sim_sensors_config.rgb_sensor.position[1] + self._min_depth = self.sim_sensors_config.depth_sensor.min_depth + self._max_depth = self.sim_sensors_config.depth_sensor.max_depth + + camera_fov_rad = np.deg2rad(self.sim_sensors_config.depth_sensor.hfov) + self._camera_fov = camera_fov_rad + self._fx = self._fy = self.sim_sensors_config.depth_sensor.width / (2 * np.tan(camera_fov_rad / 2)) + # ------------------------------------- remove ------------------------------------------ - def eval(self): - # * 3. do eval - sucs, spls, oss, nes, ep_num = self.eval_action(self.args.local_rank) - ep_num_all = [torch.zeros_like(ep_num) for _ in range(self.world_size)] - # import ipdb; ipdb.set_trace() - world_size = get_world_size() - dist.all_gather(ep_num_all, ep_num) - sucs_all = [torch.zeros(ep_num_all[i], dtype=sucs.dtype).to(sucs.device) for i in range(world_size)] - spls_all = [torch.zeros(ep_num_all[i], dtype=spls.dtype).to(spls.device) for i in range(world_size)] - oss_all = [torch.zeros(ep_num_all[i], dtype=oss.dtype).to(oss.device) for i in range(world_size)] - nes_all = [torch.zeros(ep_num_all[i], dtype=nes.dtype).to(nes.device) for i in range(world_size)] - dist.barrier() - dist.all_gather(sucs_all, sucs) - dist.all_gather(spls_all, spls) - dist.all_gather(oss_all, oss) - dist.all_gather(nes_all, nes) - - sucs_all = torch.cat(sucs_all, dim=0) - spls_all = torch.cat(spls_all, dim=0) - oss_all = torch.cat(oss_all, dim=0) - nes_all = torch.cat(nes_all, dim=0) - result_all = { - "sucs_all": (sum(sucs_all) / len(sucs_all)).item(), - "spls_all": (sum(spls_all) / len(spls_all)).item(), - "oss_all": (sum(oss_all) / len(oss_all)).item(), - "nes_all": (sum(nes_all) / len(nes_all)).item(), - 'length': len(sucs_all), + def eval_action(self): + """ + Run local episodes on this rank. + + Returns dict[str, Tensor] on GPU (1D tensors of same length). + """ + # Old behavior was something like: + # sucs, spls, oss, nes, ep_num = self.eval_action(self.args.local_rank) + # Now just implement the actual eval here and return dict. + + sucs, spls, oss, nes, _ = self._run_local_eval(self.args.local_rank) + + return { + "sucs": sucs, # shape [N_local] + "spls": spls, # shape [N_local] + "oss": oss, # shape [N_local] + "nes": nes, # shape [N_local] } - print(result_all) - if get_rank() == 0: - with open(os.path.join(self.args.output_path, 'result.json'), 'a') as f: - f.write(json.dumps(result_all)) + def calc_metrics(self, global_metrics: dict) -> dict: + """ + global_metrics["sucs"] etc. are global 1-D CPU tensors with all episodes. + """ + sucs_all = global_metrics["sucs"] + spls_all = global_metrics["spls"] + oss_all = global_metrics["oss"] + nes_all = global_metrics["nes"] + + # avoid /0 if no episodes + denom = max(len(sucs_all), 1) + + return { + "sucs_all": float(sucs_all.mean().item()) if denom > 0 else 0.0, + "spls_all": float(spls_all.mean().item()) if denom > 0 else 0.0, + "oss_all": float(oss_all.mean().item()) if denom > 0 else 0.0, + "nes_all": float(nes_all.mean().item()) if denom > 0 else 0.0, + # "length" will be filled by base class + } def _eval_action(self): obs = self.env.reset() @@ -228,10 +217,10 @@ def _eval_action(self): # refactor def config_env(self) -> Env: env = Env(config=self.config) - # env.episodes = env.episodes[0:1] + env.episodes = env.episodes[0:2] # for debug return env - def eval_action(self, idx=0) -> None: # noqa: C901 + def _run_local_eval(self, idx=0) -> None: # noqa: C901 self.model.eval() env = self.config_env() scene_episode_dict = {} @@ -250,8 +239,8 @@ def eval_action(self, idx=0) -> None: # noqa: C901 with open(os.path.join(self.output_path, 'result.json'), 'r') as f: for line in f.readlines(): res = json.loads(line) - done_res.append([res["scene_id"], res["episode_id"], res["episode_instruction"]]) - if get_rank() == 0: # noqa: F405 TODO this need to keep in evaluator + done_res.append([res["scene_id"], res["episode_id"]]) + if idx == 0: # noqa: F405 TODO this need to keep in evaluator sucs.append(res['success']) spls.append(res['spl']) oss.append(res['os']) @@ -271,7 +260,7 @@ def eval_action(self, idx=0) -> None: # noqa: C901 ) print("episode start", episode_instruction) episode_id = int(episode.episode_id) - if [scene_id, episode_id, episode_instruction] in done_res: + if [scene_id, episode_id] in done_res: continue # refactor env warm up diff --git a/internnav/utils/comm_utils/server.py b/internnav/utils/comm_utils/server.py index 2d3bf27..fbe143b 100644 --- a/internnav/utils/comm_utils/server.py +++ b/internnav/utils/comm_utils/server.py @@ -1,5 +1,6 @@ #!/usr/bin/env python import base64 +import multiprocessing import pickle from typing import Dict @@ -77,3 +78,41 @@ def run(self, reload=False): reload=reload, reload_dirs=['./internnav/agent/', './internnav/model/'], ) + + +def start_server(host='localhost', port=8087, dist=False): + """ + start a server in the backgrouond process + + Args: + host + port + + Returns: + The rank of the process group + -1, if not part of the group + + """ + ctx = multiprocessing.get_context("spawn") + p = ctx.Process(target=_run_server if not dist else _run_server_dist, args=(host, port)) + p.daemon = True + p.start() + print(f"Server started on {host}:{port} (pid={p.pid})") + return p + + +def _run_server_dist(host='localhost', port=8087): + import torch + + from internnav.utils.dist import get_rank + + device_idx = get_rank() + torch.cuda.set_device(device_idx) + print(f"Server using GPU {device_idx}") + server = AgentServer(host, port) + server.run() + + +def _run_server(host='localhost', port=8087): + server = AgentServer(host, port) + server.run() diff --git a/scripts/eval/bash/torchrun_eval.sh b/scripts/eval/bash/torchrun_eval.sh index fa99d40..8a68922 100644 --- a/scripts/eval/bash/torchrun_eval.sh +++ b/scripts/eval/bash/torchrun_eval.sh @@ -1,20 +1,20 @@ # use to run distributed eval with 4 gpus on single node +MID_RUN_NAME="InternVLA-N1" +torchrun \ + --nproc_per_node=2 \ + --master_port=2333 \ + scripts/eval/eval.py \ + --config scripts/eval/configs/habitat_cfg.py \ + > logs/${MID_RUN_NAME}_log.txt 2>&1 + +# CUDA_VISIBLE_DEVICES=6,7 # MID_RUN_NAME="InternVLA-N1" # torchrun \ # --nproc_per_node=8 \ -# --master_port=2333 \ -# scripts/eval/eval.py \ -# --config scripts/eval/configs/habitat_cfg.py \ -# > logs/${MID_RUN_NAME}_log.txt 2>&1 - -# CUDA_VISIBLE_DEVICES=6,7 -MID_RUN_NAME="InternVLA-N1" -torchrun \ - --nproc_per_node=8 \ - --master_port=29501 \ - scripts/eval/eval_habitat.py \ - --model_path checkpoints/InternVLA-N1 \ - --continuous_traj \ - --output_path logs/habitat/test_new_checkpoint2 \ - > logs/${MID_RUN_NAME}_old_log1.txt 2>&1 +# --master_port=29501 \ +# scripts/eval/eval_habitat.py \ +# --model_path checkpoints/InternVLA-N1 \ +# --continuous_traj \ +# --output_path logs/habitat/test_new_checkpoint2 \ +# > logs/${MID_RUN_NAME}_old_log1.txt 2>&1 diff --git a/scripts/eval/configs/habitat_cfg.py b/scripts/eval/configs/habitat_cfg.py index aaa702d..6e3445a 100644 --- a/scripts/eval/configs/habitat_cfg.py +++ b/scripts/eval/configs/habitat_cfg.py @@ -41,6 +41,7 @@ "local_rank": 0, # node rank "output_path": "./logs/habitat/test_refactor_debug", # output directory for logs/results "save_video": False, # whether to save videos + "epoch": 0, # epoch number for logging "world_size": 1, # number of distributed processes "rank": 0, # rank of current process "gpu": 0, # gpu id to use diff --git a/scripts/eval/eval_habitat.py b/scripts/eval/eval_habitat.py deleted file mode 100644 index e78a8d6..0000000 --- a/scripts/eval/eval_habitat.py +++ /dev/null @@ -1,127 +0,0 @@ -import argparse -import json -import os -import sys - -sys.path.append('./src/diffusion-policy') - -import numpy as np -import torch -from transformers import AutoProcessor, Qwen2_5_VLForConditionalGeneration - -# Import for Habitat registry side effects — do not remove -import internnav.env.utils.habitat_extensions.measures # noqa: F401 -from internnav.evaluator.habitat_vln_evaluator import VLNEvaluator -from internnav.model.basemodel.internvla_n1.internvla_n1 import InternVLAN1ForCausalLM -from internnav.utils.dist import * - - -def parse_args(): - - parser = argparse.ArgumentParser(description='Evaluate InternVLA-N1 on Habitat') - parser.add_argument("--mode", default='dual_system', type=str, help="inference mode: dual_system or system2") - parser.add_argument("--local_rank", default=0, type=int, help="node rank") - parser.add_argument("--model_path", type=str, default="") - parser.add_argument("--habitat_config_path", type=str, default='scripts/eval/configs/vln_r2r.yaml') - parser.add_argument("--eval_split", type=str, default='val_unseen') - parser.add_argument("--output_path", type=str, default='./logs/habitat/test') #! - parser.add_argument("--num_future_steps", type=int, default=4) - parser.add_argument("--num_frames", type=int, default=32) - parser.add_argument("--save_video", action="store_true", default=False) - parser.add_argument("--num_history", type=int, default=8) - parser.add_argument("--resize_w", type=int, default=384) - parser.add_argument("--resize_h", type=int, default=384) - parser.add_argument("--predict_step_nums", type=int, default=16) - parser.add_argument("--continuous_traj", action="store_true", default=False) - parser.add_argument("--max_new_tokens", type=int, default=1024) - - parser.add_argument('--world_size', default=1, type=int, help='number of distributed processes') - parser.add_argument('--rank', default=0, type=int, help='rank') - parser.add_argument('--gpu', default=0, type=int, help='gpu') - parser.add_argument('--port', default='2333') - parser.add_argument('--dist_url', default='env://', help='url used to set up distributed training') - parser.add_argument('--device', default='cuda', help='device to use for training / testing') - - return parser.parse_args() - - -def main(): - args = parse_args() - - init_distributed_mode(args) - local_rank = args.local_rank - np.random.seed(local_rank) - - # * 1. Load model and tokenizer. Currently, we support two modes: dual_system and system2 in Habitat. - processor = AutoProcessor.from_pretrained(args.model_path) - processor.tokenizer.padding_side = 'left' - - device = torch.device(f"cuda:{local_rank}") - if args.mode == 'dual_system': - model = InternVLAN1ForCausalLM.from_pretrained( - args.model_path, - torch_dtype=torch.bfloat16, - attn_implementation="flash_attention_2", - device_map={"": device}, - ) - elif args.mode == 'system2': - model = Qwen2_5_VLForConditionalGeneration.from_pretrained( - args.model_path, - torch_dtype=torch.bfloat16, - attn_implementation="flash_attention_2", - device_map={"": device}, - ) - else: - raise ValueError(f"Invalid mode: {args.mode}") - - model.eval() - world_size = get_world_size() - - # * 2. initialize evaluator - evaluator = VLNEvaluator( - config_path=args.habitat_config_path, - split=args.eval_split, - env_num=world_size, - output_path=args.output_path, - model=model, - processor=processor, - epoch=0, - args=args, - ) - - # * 3. do eval - sucs, spls, oss, nes, ep_num = evaluator.eval_action(idx=get_rank()) - ep_num_all = [torch.zeros_like(ep_num) for _ in range(world_size)] - - # import ipdb; ipdb.set_trace() - dist.all_gather(ep_num_all, ep_num) - sucs_all = [torch.zeros(ep_num_all[i], dtype=sucs.dtype).to(sucs.device) for i in range(world_size)] - spls_all = [torch.zeros(ep_num_all[i], dtype=spls.dtype).to(spls.device) for i in range(world_size)] - oss_all = [torch.zeros(ep_num_all[i], dtype=oss.dtype).to(oss.device) for i in range(world_size)] - nes_all = [torch.zeros(ep_num_all[i], dtype=nes.dtype).to(nes.device) for i in range(world_size)] - dist.barrier() - dist.all_gather(sucs_all, sucs) - dist.all_gather(spls_all, spls) - dist.all_gather(oss_all, oss) - dist.all_gather(nes_all, nes) - - sucs_all = torch.cat(sucs_all, dim=0) - spls_all = torch.cat(spls_all, dim=0) - oss_all = torch.cat(oss_all, dim=0) - nes_all = torch.cat(nes_all, dim=0) - result_all = { - "sucs_all": (sum(sucs_all) / len(sucs_all)).item(), - "spls_all": (sum(spls_all) / len(spls_all)).item(), - "oss_all": (sum(oss_all) / len(oss_all)).item(), - "nes_all": (sum(nes_all) / len(nes_all)).item(), - 'length': len(sucs_all), - } - - print(result_all) - if get_rank() == 0: - with open(os.path.join(args.output_path, f'result.json'), 'a') as f: - f.write(json.dumps(result_all)) - - -if __name__ == '__main__': - main() diff --git a/scripts/iros_challenge/start_eval_iros.sh b/scripts/iros_challenge/start_eval_iros.sh index d5f43ac..335b614 100755 --- a/scripts/iros_challenge/start_eval_iros.sh +++ b/scripts/iros_challenge/start_eval_iros.sh @@ -47,7 +47,7 @@ if [ -n "$processes" ]; then echo "kill: $pid" done fi -python internnav/agent/utils/server.py --config scripts/eval/configs/challenge_cfg.py > "$SERVER_LOG" 2>&1 & +python scripts/eval/start_server.py --config scripts/eval/configs/challenge_cfg.py > "$SERVER_LOG" 2>&1 & START_COMMAND_KUJIALE="python -u scripts/eval/eval_iros.py --config $CONFIG --default_config scripts/eval/configs/challenge_kujiale_cfg.py --split $SPLIT" From 0d00014a29b376065cb38db6592c28401019bf24 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Wed, 12 Nov 2025 05:18:37 +0000 Subject: [PATCH 04/35] Habitat env applied, distributed evaluator applied; clean evaluator and agent created --- internnav/evaluator/distributed_base.py | 21 +- internnav/internnav_habitat/habitat_env.py | 104 ++- .../habitat_n1_agent_temp.py | 871 ++++++++++++++---- .../habitat_vln_evaluator.py | 779 ++++++++-------- .../habitat_vln_evaluator_clean.py | 128 +++ internnav/utils/dist.py | 147 ++- scripts/eval/bash/torchrun_eval.sh | 2 +- scripts/eval/configs/habitat_cfg.py | 41 +- setup.cfg | 2 +- 9 files changed, 1346 insertions(+), 749 deletions(-) create mode 100644 internnav/internnav_habitat/habitat_vln_evaluator_clean.py diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index a0f06a2..f30d058 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -1,4 +1,3 @@ -import argparse import json import os @@ -6,7 +5,8 @@ import torch from internnav.configs.evaluator import EvalCfg -from internnav.evaluator.base import Evaluator +from internnav.env import Env +from internnav.evaluator import Evaluator from internnav.utils.dist import dist, get_rank, get_world_size, init_distributed_mode @@ -23,17 +23,16 @@ def __init__(self, cfg: EvalCfg): f"Rank {os.getenv('RANK')} / {os.getenv('WORLD_SIZE')} on {socket.gethostname()}:{os.getenv('MASTER_PORT')}" ) - args = argparse.Namespace(**cfg.eval_settings) - self.args = args + self.output_path = cfg.eval_settings["output_path"] # TODO: unsafe for distribution - init_distributed_mode(args) + init_distributed_mode() - self.local_rank = args.local_rank + self.local_rank = get_rank() np.random.seed(self.local_rank) self.world_size = get_world_size() - self.output_path = args.output_path # TODO: modify by rank - cfg.env.env_settings['idx'] = get_rank() + # habitat env also need rank to split dataset + cfg.env.env_settings['local_rank'] = get_rank() cfg.env.env_settings['world_size'] = get_world_size() # -------- initialize agent config (either remote server or local agent) -------- @@ -42,7 +41,7 @@ def __init__(self, cfg: EvalCfg): # start_server(cfg.agent.agent_settings['port']) self.eval_config = cfg - # self.env = Env.init(cfg.env, cfg.task) + self.env = Env.init(cfg.env, cfg.task) # self.agent = AgentClient(config.agent) def eval(self): @@ -119,8 +118,8 @@ def eval(self): # -------- 5) Logging -------- print(result_all) if get_rank() == 0: - os.makedirs(self.args.output_path, exist_ok=True) - out_path = os.path.join(self.args.output_path, "result.json") + os.makedirs(self.output_path, exist_ok=True) + out_path = os.path.join(self.output_path, "result.json") with open(out_path, "a") as f: f.write(json.dumps(result_all) + "\n") diff --git a/internnav/internnav_habitat/habitat_env.py b/internnav/internnav_habitat/habitat_env.py index 6b10215..6376974 100644 --- a/internnav/internnav_habitat/habitat_env.py +++ b/internnav/internnav_habitat/habitat_env.py @@ -11,8 +11,9 @@ class HabitatEnv(base.Env): def __init__(self, env_config: EnvCfg, task_config: TaskCfg): """ env_settings include: - - config_path: str, path to habitat config yaml file - - split: str, dataset split to use + - habitat_config: loaded from get_habitat_config + - local_rank: int, rank index for sharding + - world_size: int, total number of ranks """ try: from habitat import Env @@ -24,54 +25,59 @@ def __init__(self, env_config: EnvCfg, task_config: TaskCfg): super().__init__(env_config, task_config) self.config = env_config.env_settings['habitat_config'] - self.env = Env(self.config) + self._env = Env(self.config) - self.episodes = self.generate_episodes() - self.sort_episodes_by_scene() - - self.index = env_config.env_settings.get('idx', 0) + self.local_rank = env_config.env_settings.get('local_rank', 0) self.world_size = env_config.env_settings.get('world_size', 1) self._current_episode_index: int = 0 self._last_obs: Optional[Dict[str, Any]] = None - self.step_id = 0 self.is_running = True + self.output_path = env_config.env_settings.get('output_path', './output') + + # generate episodes + # self._env.episodes = self._env.episodes[0:1] # for debug + self.episodes = self.generate_episodes() + print(self.episodes) def generate_episodes(self) -> List[Any]: """ - Generate list of episodes for the current split + Generate list of episodes for the current split, already: + - grouped by scene + - filtered by done_res (the path is self.output_path/progress.json) + - sharded by (local_rank, world_size) """ - episodes = [] + all_episodes = [] - # sort episode by scene - scene_episode_dict = {} - for episode in self.env.episodes: - if episode.scene_id not in scene_episode_dict: - scene_episode_dict[episode.scene_id] = [] - scene_episode_dict[episode.scene_id].append(episode) + # group episodes by scene + scene_episode_dict: Dict[str, List[Any]] = {} + for episode in self._env.episodes: + scene_episode_dict.setdefault(episode.scene_id, []).append(episode) + # load done_res done_res = set() - - if os.path.exists(os.path.join(self.output_path, 'result.json')): - with open(os.path.join(self.output_path, 'result.json'), 'r') as f: - for line in f.readlines(): + result_path = os.path.join(self.output_path, 'progress.json') + if os.path.exists(result_path): + with open(result_path, 'r') as f: + for line in f: res = json.loads(line) - done_res.add((res["scene_id"], res["episode_id"], res["episode_instruction"])) + # only skip if current format has scene_id + if "scene_id" in res: + done_res.add((res["scene_id"], res["episode_id"])) + # iterate scenes in order, collect all episodes for scene in sorted(scene_episode_dict.keys()): - episodes = scene_episode_dict[scene] + per_scene_eps = scene_episode_dict[scene] scene_id = scene.split('/')[-2] - for episode in episodes[self.index :: self.world_size]: - episode_instruction = ( - episode.instruction.instruction_text - if 'objectnav' not in self.config_path - else episode.object_category - ) + + # shard by rank index / world_size + for episode in per_scene_eps[self.local_rank :: self.world_size]: episode_id = int(episode.episode_id) - if (scene_id, episode_id, episode_instruction) in done_res: + if (scene_id, episode_id) in done_res: continue - episodes.append(episode) - return episodes + all_episodes.append(episode) + + return all_episodes def reset(self): """ @@ -83,12 +89,11 @@ def reset(self): return # Manually set to next episode in habitat - self.env.current_episode = self.episodes[self._current_episode_index] + self._env.current_episode = self.episodes[self._current_episode_index] self._current_episode_index += 1 # Habitat reset - self._last_obs = self.env.reset() - self.step_id = 0 + self._last_obs = self._env.reset() return self._last_obs @@ -98,29 +103,26 @@ def step(self, action: List[Any]): Args: action: List[Any], action for each env in the batch - Return: obs, terminated + Return: obs, reward, done, info """ - self._last_obs = self.env.step(action) - terminated = self.env.episode_over - return self._last_obs, terminated + obs = self._env.step(action) + done = self._env.episode_over + info = self._env.get_metrics() + reward = info.get('reward', 0.0) + return obs, reward, done, info def close(self): - print('Vln Env close') - self.env.close() + print('Habitat Env close') + self._env.close() def render(self): - self.env.render() + self._env.render() def get_observation(self) -> Dict[str, Any]: - return self.env.get_observations() + return self._env.get_observations() def get_metrics(self) -> Dict[str, Any]: - return self.env.get_metrics() - - def sort_episodes_by_scene(self, key_list: List[str]): - sorted_episodes = [] - episode_dict = {ep.episode_id: ep for ep in self.episodes} - for key in key_list: - if key in episode_dict: - sorted_episodes.append(episode_dict[key]) - self.episodes = sorted_episodes + return self._env.get_metrics() + + def get_current_episode(self): + return self._env.current_episode diff --git a/internnav/internnav_habitat/habitat_n1_agent_temp.py b/internnav/internnav_habitat/habitat_n1_agent_temp.py index 598ab25..0cea910 100644 --- a/internnav/internnav_habitat/habitat_n1_agent_temp.py +++ b/internnav/internnav_habitat/habitat_n1_agent_temp.py @@ -3,8 +3,6 @@ import os import re import sys -import time -from datetime import datetime from pathlib import Path import numpy as np @@ -15,23 +13,34 @@ from collections import OrderedDict from PIL import Image -from transformers import AutoProcessor +from transformers import AutoProcessor, Qwen2_5_VLForConditionalGeneration from internnav.model.basemodel.internvla_n1.internvla_n1 import InternVLAN1ForCausalLM -from internnav.model.utils.vln_utils import S2Output, split_and_clean, traj_to_actions +from internnav.model.utils.vln_utils import split_and_clean, traj_to_actions DEFAULT_IMAGE_TOKEN = "" -class InternVLAN1AsyncAgent: - def __init__(self, args): - self.device = torch.device(args.device) - self.save_dir = "test_data/" + datetime.now().strftime("%Y%m%d_%H%M%S") - print(f"args.model_path{args.model_path}") +class HabitatAgent: + def __init__(self, model, processor, args, device): + self.model = model + self.processor = processor + self.args = args + self.device = device + # ------------------------------------- model ------------------------------------------ + processor = AutoProcessor.from_pretrained(args.model_path) + processor.tokenizer.padding_side = 'left' - device = torch.device("cuda") + device = torch.device(f"cuda:{self.local_rank}") if args.mode == 'dual_system': - self.model = InternVLAN1ForCausalLM.from_pretrained( + model = InternVLAN1ForCausalLM.from_pretrained( + args.model_path, + torch_dtype=torch.bfloat16, + attn_implementation="flash_attention_2", + device_map={"": device}, + ) + elif args.mode == 'system2': + model = Qwen2_5_VLForConditionalGeneration.from_pretrained( args.model_path, torch_dtype=torch.bfloat16, attn_implementation="flash_attention_2", @@ -40,20 +49,17 @@ def __init__(self, args): else: raise ValueError(f"Invalid mode: {args.mode}") - self.model.eval() - self.model.to(self.device) + model.eval() + self.device = device - self.processor = AutoProcessor.from_pretrained(args.model_path) - self.processor.tokenizer.padding_side = 'left' + self.model = model + self.processor = processor - self.resize_w = args.resize_w - self.resize_h = args.resize_h - self.num_history = args.num_history - self.PLAN_STEP_GAP = args.plan_step_gap - - prompt = "You are an autonomous navigation assistant. Your task is to . Where should you go next to stay on track? Please output the next waypoint's coordinates in the image. Please output STOP when you have successfully completed the task." + # refactor: this part used in three places + prompt = "You are an autonomous navigation assistant. Your task is to . Where should you go next to stay on track? Please output the next waypoint\'s coordinates in the image. Please output STOP when you have successfully completed the task." answer = "" self.conversation = [{"from": "human", "value": prompt}, {"from": "gpt", "value": answer}] + self.conjunctions = [ 'you can see ', 'in front of you is ', @@ -74,190 +80,671 @@ def __init__(self, args): } ) + self.objectnav_instructions = ["Search for the {target_object}."] + + self.num_frames = args.num_frames + self.num_future_steps = args.num_future_steps + self.num_history = args.num_history + + def reset(self, episode, env): + """Clear all per-episode state.""" self.rgb_list = [] - self.depth_list = [] - self.pose_list = [] - self.episode_idx = 0 - self.conversation_history = [] - self.llm_output = "" - self.past_key_values = None - self.last_s2_idx = -100 - - # output - self.output_action = None - self.output_latent = None - self.output_pixel = None - self.pixel_goal_rgb = None - self.pixel_goal_depth = None - - def reset(self): - self.rgb_list = [] - self.depth_list = [] - self.pose_list = [] - self.episode_idx = 0 - self.conversation_history = [] - self.llm_output = "" - self.past_key_values = None - - self.output_action = None - self.output_latent = None - self.output_pixel = None - self.pixel_goal_rgb = None - self.pixel_goal_depth = None - - self.save_dir = "test_data/" + datetime.now().strftime("%Y%m%d_%H%M%S") - os.makedirs(self.save_dir, exist_ok=True) + self.action_seq = [] + self.output_ids = None + self.goal = None + self.messages = [] + self.local_actions = [] + self.forward_action = 0 + + # maybe store initial transforms you need for this ep: + self.initial_agent_state = env.get_agent_state() + self.initial_height = self.initial_agent_state.position[1] + + def act(self, observations, env, info): + """ + Pure policy step: + - given obs (rgb/depth/gps/compass) + optional env/info + - update internal state (goal, messages, local_actions, etc.) + - return a single action (int) + """ + # 1) unpack obs: rgb, depth, gps, compass, etc. + # 2) handle 'look down' case + # 3) maybe call LLM to get pixel goal or action_seq + # 4) maybe call diffusion policy to get local_actions + # 5) choose final `action` (0..5) + # 6) return `action` + return action + + def _run_local_eval(self, idx=0) -> None: # noqa: C901 + """ + Run local evaluation on this rank. + + Important: if resuming from previous results, need to read from / write to "self.output_path/progress.json". + For each episode, save the result dict in jsonl format to that file. + In Env, the episodes are already filtered by this file, tasks that have the same (scene_id, episode_id) are skipped. + + + Returns + ------- + dict[str, Tensor]: + { + "sucs": [N_local], + "spls": [N_local], + "oss": [N_local], + "nes": [N_local], + } + """ + # Create / get env + # self.env = self.env # HabitatEnv from DistributedEvaluator + + sucs, spls, oss, nes = [], [], [], [] + self.model.eval() + + # resume from previous results + # TODO: Current read write op is not distributed safe + if os.path.exists(os.path.join(self.output_path, 'progress.json')): + with open(os.path.join(self.output_path, 'progress.json'), 'r') as f: + for line in f.readlines(): + res = json.loads(line) + if "scene_id" not in res: + print("This evaluation has already finished!") + return ( + torch.tensor(sucs).to(self.device), + torch.tensor(spls).to(self.device), + torch.tensor(oss).to(self.device), + torch.tensor(nes).to(self.device), + torch.tensor(len(sucs)).to(self.device), + ) + if idx == 0: # noqa: F405 TODO this need to keep in evaluator + sucs.append(res['success']) + spls.append(res['spl']) + oss.append(res['os']) + nes.append(res['ne']) + + # Episode loop is now driven by env.reset() + env.is_running + process_bar = tqdm.tqdm(total=len(self.env.episodes), desc=f"Eval Epoch {self.epoch} Rank {idx}") + while self.env.is_running: + + # ------------ 1. Start of episode ------------ + observations = self.env.reset() + if not self.env.is_running or observations is None: + break + + # ---- episode meta (scene_id, episode_id, instruction) ---- + # we get it from the underlying habitat env + episode = self.env.get_current_episode() + scene_id = episode.scene_id.split('/')[-2] + episode_id = int(episode.episode_id) + episode_instruction = ( + episode.instruction.instruction_text if 'objectnav' not in self.config_path else episode.object_category + ) + print("episode start", episode_instruction) + + agent_state = self.env._env.sim.get_agent_state() + rotation = agent_state.rotation + translation = agent_state.position + rotation_matrix = quaternion.as_rotation_matrix(rotation) + transformation_matrix = np.eye(4) + transformation_matrix[:3, :3] = rotation_matrix + transformation_matrix[:3, 3] = translation + + agent = ShortestPathFollower(self.env._env.sim, 0.25, False) + + os.makedirs(os.path.join(self.output_path, f'check_sim_{self.epoch}'), exist_ok=True) + Image.fromarray(observations['rgb']).save( + os.path.join(self.output_path, f'check_sim_{self.epoch}', f'rgb_{idx}.jpg') + ) + + vis_frames = [] + step_id = 0 + + if self.save_video: + os.makedirs(os.path.join(self.output_path, f'vis_{self.epoch}', f'{scene_id}'), exist_ok=True) + initial_height = self.env._env.sim.get_agent_state().position[1] + + rgb_list = [] + action_seq = [] + output_ids = None + + goal = None + action = None + messages = [] + local_actions = [] + + done = False + + # ---------- 2. Episode step loop ----------- + while (not done) and (step_id <= self.max_steps_per_episode): + # refactor agent get action + rgb = observations["rgb"] + depth = observations["depth"] + x, y = observations["gps"] + camera_yaw = observations["compass"][0] + depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) + depth = depth * (self._max_depth - self._min_depth) + self._min_depth + depth = depth * 1000 + + agent_state = self.env._env.sim.get_agent_state() + height = agent_state.position[1] - initial_height + camera_position = np.array([x, -y, self._camera_height + height]) + tf_camera_to_episodic = ( + self.xyz_yaw_pitch_to_tf_matrix(camera_position, camera_yaw, np.deg2rad(30)) + @ self.get_axis_align_matrix() + ) + + image = Image.fromarray(rgb).convert('RGB') + save_raw_image = image.copy() + + save_dot = False + if action == 5: + look_down_image = image + save_raw_image = look_down_image.copy() + look_down_depth, resize_shape = self.preprocess_depth_image_v2( + Image.fromarray(depth.astype(np.uint16), mode='I;16'), + do_depth_scale=True, + depth_scale=1000, + target_height=224, + target_width=224, + ) + look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() + look_down_depth[look_down_depth > 5.0] = 5.0 + else: + image = image.resize((self.args.resize_w, self.args.resize_h)) + rgb_list.append(image) + + if self.args.mode == 'dual_system': + down_observations, _, done, _ = self.env.step(5) + down_observations, _, done, _ = self.env.step(5) + + look_down_image = Image.fromarray(down_observations["rgb"]).convert('RGB') + depth = down_observations["depth"] + depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) + depth = depth * (self._max_depth - self._min_depth) + self._min_depth + depth = depth * 1000 + look_down_depth, resize_shape = self.preprocess_depth_image_v2( + Image.fromarray(depth.astype(np.uint16), mode='I;16'), + do_depth_scale=True, + depth_scale=1000, + target_height=224, + target_width=224, + ) + look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() + look_down_depth[look_down_depth > 5.0] = 5.0 + + self.env.step(4) + self.env.step(4) + + info = self.env.get_metrics() + + if len(action_seq) == 0 and goal is None: + if action != 5: + sources = copy.deepcopy(self.conversation) + sources[0]["value"] = sources[0]["value"].replace( + '.', episode.instruction.instruction_text[:-1] + ) + cur_images = rgb_list[-1:] + if step_id == 0: + history_id = [] + else: + history_id = np.unique( + np.linspace(0, step_id - 1, self.num_history, dtype=np.int32) + ).tolist() + placeholder = (DEFAULT_IMAGE_TOKEN + '\n') * len(history_id) + sources[0]["value"] += f' These are your historical observations: {placeholder}.' + + history_id = sorted(history_id) + print('history_idddddddd', step_id, history_id) + input_images = [rgb_list[i] for i in history_id] + cur_images + input_img_id = 0 + else: + assert action == 5 + sources = [{"from": "human", "value": ""}, {"from": "gpt", "value": ""}] + input_images += [look_down_image] + # messages.append( + # {'role': 'assistant', 'content': [{'type': 'text', 'text': llm_outputs}]} # noqa: F405 + # ) + input_img_id = -1 + + prompt = random.choice(self.conjunctions) + DEFAULT_IMAGE_TOKEN + sources[0]["value"] += f" {prompt}." + print('sources', step_id, sources) + prompt_instruction = copy.deepcopy(sources[0]["value"]) + parts = split_and_clean(prompt_instruction) + + content = [] + for i in range(len(parts)): + if parts[i] == "": + content.append({"type": "image", "image": input_images[input_img_id]}) + input_img_id += 1 + else: + content.append({"type": "text", "text": parts[i]}) + + messages.append({'role': 'user', 'content': content}) + + print('step_id', step_id, 'messages:', messages) + + text = self.processor.apply_chat_template(messages, tokenize=False, add_generation_prompt=True) + + inputs = self.processor(text=[text], images=input_images, return_tensors="pt").to(self.model.device) + + with torch.no_grad(): + output_ids = self.model.generate(**inputs, max_new_tokens=128, do_sample=False) + + llm_outputs = self.processor.tokenizer.decode( + output_ids[0][inputs.input_ids.shape[1] :], skip_special_tokens=True + ) + print('step_id:', step_id, 'output text:', llm_outputs) + + if bool(re.search(r'\d', llm_outputs)): + forward_action = 0 + coord = [int(c) for c in re.findall(r'\d+', llm_outputs)] + pixel_goal = [int(coord[1]), int(coord[0])] + + intrinsic_matrix = self.get_intrinsic_matrix( + self.config.habitat.simulator.agents.main_agent.sim_sensors.rgb_sensor + ) + goal = self.pixel_to_gps(pixel_goal, depth / 1000, intrinsic_matrix, tf_camera_to_episodic) + print('before', goal, depth.shape) + goal = (transformation_matrix @ np.array([-goal[1], 0, -goal[0], 1]))[:3] + + if not self.env._env.sim.pathfinder.is_navigable(np.array(goal)): + goal = np.array(self.env._env.sim.pathfinder.snap_point(np.array(goal))) + + # look down --> horizontal + self.env.step(4) + self.env.step(4) + + # Forking logic based on mode + if self.args.mode == 'system2': + action = agent.get_next_action(goal) + if action == 0: + goal = None + output_ids = None + action = 2 # random action + print('conduct a random action 2') + observations = self.env.step(action) + step_id += 1 + messages = [] + continue + else: # dual-system logic + local_actions = [] + pixel_values = inputs.pixel_values + image_grid_thw = torch.cat([thw.unsqueeze(0) for thw in inputs.image_grid_thw], dim=0) + + with torch.no_grad(): + traj_latents = self.model.generate_latents(output_ids, pixel_values, image_grid_thw) + + # prepocess align with navdp + image_dp = ( + torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 + ) + pix_goal_image = copy.copy(image_dp) + images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) + depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) + pix_goal_depth = copy.copy(depth_dp) + depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) + + with torch.no_grad(): + dp_actions = self.model.generate_traj( + traj_latents, images_dp, depths_dp, use_async=True + ) + + random_choice = np.random.choice(dp_actions.shape[0]) + if self.args.continuous_traj: + action_list = traj_to_actions(dp_actions) + if len(action_list) < 8: + action_list += [0] * (8 - len(action_list)) + else: + action_list = chunk_token(dp_actions[random_choice]) + + local_actions = action_list + if len(local_actions) >= 4: + local_actions = local_actions[:4] + action = local_actions[0] + if action == 0: + goal = None + output_ids = None + action = 2 # random action + print('conduct a random action 2') + observations = self.env.step(action) + step_id += 1 + messages = [] + continue + + print('predicted goal', pixel_goal, goal, flush=True) + else: + action_seq = self.parse_actions(llm_outputs) + print('actions', action_seq, flush=True) + + if len(action_seq) != 0: + action = action_seq[0] + action_seq.pop(0) + elif goal is not None: + # Forking logic based on mode + if self.args.mode == 'system2': + action = agent.get_next_action(goal) + action = action.detach().cpu().numpy()[0] if isinstance(action, torch.Tensor) else action + action = action[0] if hasattr(action, "__len__") else action + else: # dual-system logic + if len(local_actions) == 0: + # navdp + local_actions = [] + image_dp = ( + torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 + ) + + images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) + depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) + + depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) + with torch.no_grad(): + dp_actions = self.model.generate_traj( + traj_latents, images_dp, depths_dp, use_async=True + ) + + random_choice = np.random.choice(dp_actions.shape[0]) + if self.args.continuous_traj: + action_list = traj_to_actions(dp_actions) + if len(action_list) < 8: + action_list += [0] * (8 - len(action_list)) + else: + action_list = chunk_token(dp_actions[random_choice]) + print("first action_list", action_list) + + local_actions = action_list + if len(local_actions) >= 4: + local_actions = local_actions[:4] + # if len(local_actions) >= 2: + # local_actions = local_actions[:2] + + print("local_actions", local_actions) + + action = local_actions.pop(0) + # navdp + else: + action = local_actions.pop(0) + + forward_action += 1 + print('forward_action', forward_action, flush=True) + if forward_action > 8: + goal = None + output_ids = None + messages = [] + step_id += 1 + forward_action = 0 + local_actions = [] + continue + if action == 0: + goal = None + output_ids = None + messages = [] + step_id += 1 + forward_action = 0 + local_actions = [] + continue + else: + action = 0 + + if info['top_down_map'] is not None: + if save_dot: + save_raw_image = self.dot_matrix_two_dimensional( + save_raw_image, save_img=False, save_path=f'test_{step_id}.jpg', pixel_goal=pixel_goal + ) + if self.save_video: + frame = observations_to_image({'rgb': np.asarray(save_raw_image)}, info) + vis_frames.append(frame) + + print("step_id", step_id, "action", action) + + # refactor: core + if action == 5: + self.env.step(action) + observations, _, done, _ = self.env.step(action) + else: + observations, _, done, _ = self.env.step(action) + step_id += 1 + messages = [] + + # ---------- 3. End of episode ----------- + # Update result and write progress to the output_path/progress.json + + process_bar.update(1) + + # After the episode finishes, collect metrics: + metrics = self.env.get_metrics() + + sucs.append(metrics['success']) + spls.append(metrics['spl']) + oss.append(metrics['oracle_success']) + nes.append(metrics["distance_to_goal"]) + + print( + f"scene_episode {scene_id}_{episode_id:04d} success: {metrics['success']}, " + f"spl: {metrics['spl']}, os: {metrics['oracle_success']}, " + f"ne: {metrics['distance_to_goal']}" + ) + + # Write per-episode result.json entry (still per-rank) + result = { + "scene_id": scene_id, + "episode_id": episode_id, + "success": metrics["success"], + "spl": metrics["spl"], + "os": metrics['oracle_success'], + "ne": metrics["distance_to_goal"], + "steps": step_id, + "episode_instruction": episode_instruction, + } + os.makedirs(self.output_path, exist_ok=True) + with open(os.path.join(self.output_path, 'progress.json'), 'a') as f: + f.write(json.dumps(result) + "\n") + + self.env.close() + + return { + "sucs": torch.tensor(sucs, device=self.device), + "spls": torch.tensor(spls, device=self.device), + "oss": torch.tensor(oss, device=self.device), + "nes": torch.tensor(nes, device=self.device), + } def parse_actions(self, output): action_patterns = '|'.join(re.escape(action) for action in self.actions2idx) + # import ipdb; ipdb.set_trace() regex = re.compile(action_patterns) matches = regex.findall(output) actions = [self.actions2idx[match] for match in matches] actions = itertools.chain.from_iterable(actions) return list(actions) - def step_no_infer(self, rgb, depth, pose): - image = Image.fromarray(rgb).convert('RGB') - image = image.resize((self.resize_w, self.resize_h)) - self.rgb_list.append(image) - image.save(f"{self.save_dir}/debug_raw_{self.episode_idx: 04d}.jpg") - self.episode_idx += 1 - - def trajectory_tovw(self, trajectory, kp=1.0): - subgoal = trajectory[-1] - linear_vel, angular_vel = kp * np.linalg.norm(subgoal[:2]), kp * subgoal[2] - linear_vel = np.clip(linear_vel, 0, 0.5) - angular_vel = np.clip(angular_vel, -0.5, 0.5) - return linear_vel, angular_vel - - def step(self, rgb, depth, pose, instruction, intrinsic, look_down=False): - dual_sys_output = S2Output() - no_output_flag = self.output_action is None and self.output_latent is None - if (self.episode_idx - self.last_s2_idx > self.PLAN_STEP_GAP) or look_down or no_output_flag: - self.output_action, self.output_latent, self.output_pixel = self.step_s2( - rgb, depth, pose, instruction, intrinsic, look_down - ) - self.last_s2_idx = self.episode_idx - dual_sys_output.output_pixel = self.output_pixel - self.pixel_goal_rgb = copy.deepcopy(rgb) - self.pixel_goal_depth = copy.deepcopy(depth) - else: - self.step_no_infer(rgb, depth, pose) - - if self.output_action is not None: - dual_sys_output.output_action = copy.deepcopy(self.output_action) - self.output_action = None - elif self.output_latent is not None: - processed_pixel_rgb = np.array(Image.fromarray(self.pixel_goal_rgb).resize((224, 224))) / 255 - processed_pixel_depth = np.array(Image.fromarray(self.pixel_goal_depth).resize((224, 224))) - processed_rgb = np.array(Image.fromarray(rgb).resize((224, 224))) / 255 - processed_depth = np.array(Image.fromarray(depth).resize((224, 224))) - rgbs = ( - torch.stack([torch.from_numpy(processed_pixel_rgb), torch.from_numpy(processed_rgb)]) - .unsqueeze(0) - .to(self.device) - ) - depths = ( - torch.stack([torch.from_numpy(processed_pixel_depth), torch.from_numpy(processed_depth)]) - .unsqueeze(0) - .unsqueeze(-1) - .to(self.device) - ) - trajectories = self.step_s1(self.output_latent, rgbs, depths) + def preprocess_depth_image_v2( + self, depth_image, do_depth_scale=True, depth_scale=1000, target_height=None, target_width=None + ): + if target_height is None: + target_height = self.image_processor.crop_size['height'] # 384 + target_width = self.image_processor.crop_size['width'] # 384 - dual_sys_output.output_trajectory = traj_to_actions(trajectories, use_discrate_action=False) + resized_depth_image = depth_image.resize((target_width, target_height), Image.NEAREST) - return dual_sys_output + img = to_numpy_array(resized_depth_image) + if do_depth_scale: + img = img / depth_scale - def step_s2(self, rgb, depth, pose, instruction, intrinsic, look_down=False): - image = Image.fromarray(rgb).convert('RGB') - if not look_down: - image = image.resize((self.resize_w, self.resize_h)) - self.rgb_list.append(image) - image.save(f"{self.save_dir}/debug_raw_{self.episode_idx: 04d}.jpg") - else: - image.save(f"{self.save_dir}/debug_raw_{self.episode_idx: 04d}_look_down.jpg") - if not look_down: - self.conversation_history = [] - self.past_key_values = None - - sources = copy.deepcopy(self.conversation) - sources[0]["value"] = sources[0]["value"].replace('.', instruction) - cur_images = self.rgb_list[-1:] - if self.episode_idx == 0: - history_id = [] - else: - history_id = np.unique(np.linspace(0, self.episode_idx - 1, self.num_history, dtype=np.int32)).tolist() - placeholder = (DEFAULT_IMAGE_TOKEN + '\n') * len(history_id) - sources[0]["value"] += f' These are your historical observations: {placeholder}.' - - history_id = sorted(history_id) - self.input_images = [self.rgb_list[i] for i in history_id] + cur_images - input_img_id = 0 - self.episode_idx += 1 - else: - self.input_images.append(image) - input_img_id = -1 - assert self.llm_output != "", "Last llm_output should not be empty when look down" - sources = [{"from": "human", "value": ""}, {"from": "gpt", "value": ""}] - self.conversation_history.append( - {'role': 'assistant', 'content': [{'type': 'text', 'text': self.llm_output}]} - ) + return img, (target_width, target_height) - prompt = self.conjunctions[0] + DEFAULT_IMAGE_TOKEN - sources[0]["value"] += f" {prompt}." - prompt_instruction = copy.deepcopy(sources[0]["value"]) - parts = split_and_clean(prompt_instruction) - - content = [] - for i in range(len(parts)): - if parts[i] == "": - content.append({"type": "image", "image": self.input_images[input_img_id]}) - input_img_id += 1 - else: - content.append({"type": "text", "text": parts[i]}) - - self.conversation_history.append({'role': 'user', 'content': content}) - - text = self.processor.apply_chat_template(self.conversation_history, tokenize=False, add_generation_prompt=True) - - inputs = self.processor(text=[text], images=self.input_images, return_tensors="pt").to(self.device) - t0 = time.time() - with torch.no_grad(): - outputs = self.model.generate( - **inputs, - max_new_tokens=128, - do_sample=False, - use_cache=True, - past_key_values=self.past_key_values, - return_dict_in_generate=True, - raw_input_ids=copy.deepcopy(inputs.input_ids), - ) - output_ids = outputs.sequences + def get_intrinsic_matrix(self, sensor_cfg) -> np.ndarray: + width = sensor_cfg.width + height = sensor_cfg.height + fov = sensor_cfg.hfov + fx = (width / 2.0) / np.tan(np.deg2rad(fov / 2.0)) + fy = fx # Assuming square pixels (fx = fy) + cx = (width - 1.0) / 2.0 + cy = (height - 1.0) / 2.0 - t1 = time.time() - self.llm_output = self.processor.tokenizer.decode( - output_ids[0][inputs.input_ids.shape[1] :], skip_special_tokens=True + intrinsic_matrix = np.array( + [[fx, 0.0, cx, 0.0], [0.0, fy, cy, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]] ) - with open(f"{self.save_dir}/llm_output_{self.episode_idx: 04d}.txt", 'w') as f: - f.write(self.llm_output) - self.last_output_ids = copy.deepcopy(output_ids[0]) - self.past_key_values = copy.deepcopy(outputs.past_key_values) - print(f"output {self.episode_idx} {self.llm_output} cost: {t1 - t0}s") - if bool(re.search(r'\d', self.llm_output)): - coord = [int(c) for c in re.findall(r'\d+', self.llm_output)] - pixel_goal = [int(coord[1]), int(coord[0])] - image_grid_thw = torch.cat([thw.unsqueeze(0) for thw in inputs.image_grid_thw], dim=0) - pixel_values = inputs.pixel_values - t0 = time.time() - with torch.no_grad(): - traj_latents = self.model.generate_latents(output_ids, pixel_values, image_grid_thw) - return None, traj_latents, pixel_goal - - else: - action_seq = self.parse_actions(self.llm_output) - return action_seq, None, None - - def step_s1(self, latent, rgb, depth): - all_trajs = self.model.generate_traj(latent, rgb, depth, use_async=True) - return all_trajs + return intrinsic_matrix + + def get_axis_align_matrix(self): + ma = np.array([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) + return ma + + def xyz_yaw_to_tf_matrix(self, xyz: np.ndarray, yaw: float) -> np.ndarray: + x, y, z = xyz + transformation_matrix = np.array( + [ + [np.cos(yaw), -np.sin(yaw), 0, x], + [np.sin(yaw), np.cos(yaw), 0, y], + [0, 0, 1, z], + [0, 0, 0, 1], + ] + ) + return transformation_matrix + + def xyz_pitch_to_tf_matrix(self, xyz: np.ndarray, pitch: float) -> np.ndarray: + """Converts a given position and pitch angle to a 4x4 transformation matrix. + + Args: + xyz (np.ndarray): A 3D vector representing the position. + pitch (float): The pitch angle in radians for y axis. + Returns: + np.ndarray: A 4x4 transformation matrix. + """ + + x, y, z = xyz + transformation_matrix = np.array( + [ + [np.cos(pitch), 0, np.sin(pitch), x], + [0, 1, 0, y], + [-np.sin(pitch), 0, np.cos(pitch), z], + [0, 0, 0, 1], + ] + ) + return transformation_matrix + + def xyz_yaw_pitch_to_tf_matrix(self, xyz: np.ndarray, yaw: float, pitch: float) -> np.ndarray: + """Converts a given position and yaw, pitch angles to a 4x4 transformation matrix. + + Args: + xyz (np.ndarray): A 3D vector representing the position. + yaw (float): The yaw angle in radians. + pitch (float): The pitch angle in radians for y axis. + Returns: + np.ndarray: A 4x4 transformation matrix. + """ + x, y, z = xyz + rot1 = self.xyz_yaw_to_tf_matrix(xyz, yaw)[:3, :3] + rot2 = self.xyz_pitch_to_tf_matrix(xyz, pitch)[:3, :3] + transformation_matrix = np.eye(4) + transformation_matrix[:3, :3] = rot1 @ rot2 + transformation_matrix[:3, 3] = xyz + return transformation_matrix + + def pixel_to_gps(self, pixel, depth, intrinsic, tf_camera_to_episodic): + ''' + Args: + pixel: (2,) - [u, v] pixel coordinates + depth: (H, W) - depth image where depth[v, u] gives depth in meters + intrinsic: (4, 4) - camera intrinsic matrix + tf_camera_to_episodic: (4, 4) - transformation from camera to episodic frame + Returns: + (x, y): (x, y) coordinates in the episodic frame + ''' + v, u = pixel + z = depth[v, u] + print("depthhhhhhhhhhhhhh", z) + + x = (u - intrinsic[0, 2]) * z / intrinsic[0, 0] + y = (v - intrinsic[1, 2]) * z / intrinsic[1, 1] + point_camera = np.array([x, y, z, 1.0]) + + # Transform to episodic frame + point_episodic = tf_camera_to_episodic @ point_camera + point_episodic = point_episodic[:3] / point_episodic[3] + + x = point_episodic[0] + y = point_episodic[1] + + return (x, y) # same as habitat gps + + def dot_matrix_two_dimensional( + self, + image_or_image_path, + save_path=None, + dots_size_w=8, + dots_size_h=8, + save_img=False, + font_path='fonts/arial.ttf', + pixel_goal=None, + ): + """ + takes an original image as input, save the processed image to save_path. Each dot is labeled with two-dimensional Cartesian coordinates (x,y). Suitable for single-image tasks. + control args: + 1. dots_size_w: the number of columns of the dots matrix + 2. dots_size_h: the number of rows of the dots matrix + """ + with open_image(image_or_image_path) as img: + if img.mode != 'RGB': + img = img.convert('RGB') + draw = ImageDraw.Draw(img, 'RGB') + + width, height = img.size + grid_size_w = dots_size_w + 1 + grid_size_h = dots_size_h + 1 + cell_width = width / grid_size_w + cell_height = height / grid_size_h + + font = ImageFont.truetype(font_path, width // 40) # Adjust font size if needed; default == width // 40 + + target_i = target_j = None + if pixel_goal is not None: + y_pixel, x_pixel = pixel_goal[0], pixel_goal[1] + # Validate pixel coordinates + if not (0 <= x_pixel < width and 0 <= y_pixel < height): + raise ValueError(f"pixel_goal {pixel_goal} exceeds image dimensions ({width}x{height})") + + # Convert to grid coordinates + target_i = round(x_pixel / cell_width) + target_j = round(y_pixel / cell_height) + + # Validate grid bounds + if not (1 <= target_i <= dots_size_w and 1 <= target_j <= dots_size_h): + raise ValueError( + f"pixel_goal {pixel_goal} maps to grid ({target_j},{target_i}), " + f"valid range is (1,1)-({dots_size_h},{dots_size_w})" + ) + + count = 0 + + for j in range(1, grid_size_h): + for i in range(1, grid_size_w): + x = int(i * cell_width) + y = int(j * cell_height) + + pixel_color = img.getpixel((x, y)) + # choose a more contrasting color from black and white + if pixel_color[0] + pixel_color[1] + pixel_color[2] >= 255 * 3 / 2: + opposite_color = (0, 0, 0) + else: + opposite_color = (255, 255, 255) + + if pixel_goal is not None and i == target_i and j == target_j: + opposite_color = (255, 0, 0) # Red for target + + circle_radius = width // 240 # Adjust dot size if needed; default == width // 240 + draw.ellipse( + [(x - circle_radius, y - circle_radius), (x + circle_radius, y + circle_radius)], + fill=opposite_color, + ) + + text_x, text_y = x + 3, y + count_w = count // dots_size_w + count_h = count % dots_size_w + label_str = f"({count_w+1},{count_h+1})" + draw.text((text_x, text_y), label_str, fill=opposite_color, font=font) + count += 1 + if save_img: + print(">>> dots overlaid image processed, stored in", save_path) + img.save(save_path) + return img diff --git a/internnav/internnav_habitat/habitat_vln_evaluator.py b/internnav/internnav_habitat/habitat_vln_evaluator.py index ef18ec0..ba86d6d 100644 --- a/internnav/internnav_habitat/habitat_vln_evaluator.py +++ b/internnav/internnav_habitat/habitat_vln_evaluator.py @@ -33,7 +33,6 @@ try: import habitat - from habitat import Env from habitat.config.default import get_agent_config from habitat.config.default_structured_configs import ( CollisionsMeasurementConfig, @@ -41,10 +40,7 @@ TopDownMapMeasurementConfig, ) from habitat.tasks.nav.shortest_path_follower import ShortestPathFollower - from habitat.utils.visualizations.utils import ( - images_to_video, - observations_to_image, - ) + from habitat.utils.visualizations.utils import observations_to_image from habitat_baselines.config.default import get_config as get_habitat_config except Exception as e: print("Habitat Error:", e) @@ -58,9 +54,10 @@ class HabitatVlnEvaluator(DistributedEvaluator): def __init__(self, cfg: EvalCfg): args = argparse.Namespace(**cfg.eval_settings) - self.args = args self.save_video = args.save_video self.epoch = args.epoch + self.max_steps_per_episode = args.max_steps_per_episode + self.output_path = args.output_path # create habitat config self.config_path = cfg.env.env_settings['config_path'] @@ -90,31 +87,34 @@ def __init__(self, cfg: EvalCfg): } ) cfg.env.env_settings['habitat_config'] = self.config + cfg.env.env_settings['output_path'] = self.output_path # init agent and env super().__init__(cfg) # ------------------------------------- model ------------------------------------------ - processor = AutoProcessor.from_pretrained(args.model_path) + self.model_args = argparse.Namespace(**cfg.agent.model_settings) + + processor = AutoProcessor.from_pretrained(self.model_args.model_path) processor.tokenizer.padding_side = 'left' device = torch.device(f"cuda:{self.local_rank}") - if args.mode == 'dual_system': + if self.model_args.mode == 'dual_system': model = InternVLAN1ForCausalLM.from_pretrained( - args.model_path, + self.model_args.model_path, torch_dtype=torch.bfloat16, attn_implementation="flash_attention_2", device_map={"": device}, ) - elif args.mode == 'system2': + elif self.model_args.mode == 'system2': model = Qwen2_5_VLForConditionalGeneration.from_pretrained( - args.model_path, + self.model_args.model_path, torch_dtype=torch.bfloat16, attn_implementation="flash_attention_2", device_map={"": device}, ) else: - raise ValueError(f"Invalid mode: {args.mode}") + raise ValueError(f"Invalid mode: {self.model_args.mode}") model.eval() self.device = device @@ -149,9 +149,9 @@ def __init__(self, cfg: EvalCfg): self.objectnav_instructions = ["Search for the {target_object}."] - self.num_frames = args.num_frames - self.num_future_steps = args.num_future_steps - self.num_history = args.num_history + self.num_frames = self.model_args.num_frames + self.num_future_steps = self.model_args.num_future_steps + self.num_history = self.model_args.num_history # ------------------------------------- old ------------------------------------------ self._camera_height = self.sim_sensors_config.rgb_sensor.position[1] @@ -162,8 +162,6 @@ def __init__(self, cfg: EvalCfg): self._camera_fov = camera_fov_rad self._fx = self._fy = self.sim_sensors_config.depth_sensor.width / (2 * np.tan(camera_fov_rad / 2)) - # ------------------------------------- remove ------------------------------------------ - def eval_action(self): """ Run local episodes on this rank. @@ -171,10 +169,10 @@ def eval_action(self): Returns dict[str, Tensor] on GPU (1D tensors of same length). """ # Old behavior was something like: - # sucs, spls, oss, nes, ep_num = self.eval_action(self.args.local_rank) + # sucs, spls, oss, nes, ep_num = self.eval_action(self.local_rank) # Now just implement the actual eval here and return dict. - sucs, spls, oss, nes, _ = self._run_local_eval(self.args.local_rank) + sucs, spls, oss, nes, _ = self._run_local_eval(self.local_rank) return { "sucs": sucs, # shape [N_local] @@ -203,126 +201,153 @@ def calc_metrics(self, global_metrics: dict) -> dict: # "length" will be filled by base class } - def _eval_action(self): - obs = self.env.reset() - action = self.agent.reset() - while not self.env.is_running(): - action = self.agent.step(action, obs) - obs, terminated = self.env.step(action) - if terminated: - obs = self.env.reset() - self.agent.reset() - self.env.update_metric() - - # refactor - def config_env(self) -> Env: - env = Env(config=self.config) - env.episodes = env.episodes[0:2] # for debug - return env - def _run_local_eval(self, idx=0) -> None: # noqa: C901 - self.model.eval() - env = self.config_env() - scene_episode_dict = {} - for episode in env.episodes: - if episode.scene_id not in scene_episode_dict: - scene_episode_dict[episode.scene_id] = [] - scene_episode_dict[episode.scene_id].append(episode) - - intrinsic_matrix = self.get_intrinsic_matrix( - self.config.habitat.simulator.agents.main_agent.sim_sensors.rgb_sensor - ) + """ + Run local evaluation on this rank. + + Important: if resuming from previous results, need to read from / write to "self.output_path/progress.json". + For each episode, save the result dict in jsonl format to that file. + In Env, the episodes are already filtered by this file, tasks that have the same (scene_id, episode_id) are skipped. + + + Returns + ------- + dict[str, Tensor]: + { + "sucs": [N_local], + "spls": [N_local], + "oss": [N_local], + "nes": [N_local], + } + """ + # Create / get env + # self.env = self.env # HabitatEnv from DistributedEvaluator + sucs, spls, oss, nes = [], [], [], [] - done_res = [] + self.model.eval() - if os.path.exists(os.path.join(self.output_path, 'result.json')): - with open(os.path.join(self.output_path, 'result.json'), 'r') as f: + # resume from previous results + # TODO: Current read write op is not distributed safe + if os.path.exists(os.path.join(self.output_path, 'progress.json')): + with open(os.path.join(self.output_path, 'progress.json'), 'r') as f: for line in f.readlines(): res = json.loads(line) - done_res.append([res["scene_id"], res["episode_id"]]) + if "scene_id" not in res: + print("This evaluation has already finished!") + return ( + torch.tensor(sucs).to(self.device), + torch.tensor(spls).to(self.device), + torch.tensor(oss).to(self.device), + torch.tensor(nes).to(self.device), + torch.tensor(len(sucs)).to(self.device), + ) if idx == 0: # noqa: F405 TODO this need to keep in evaluator sucs.append(res['success']) spls.append(res['spl']) oss.append(res['os']) nes.append(res['ne']) - # refactor: sort to scene: [episode] but nothing actually used - for scene in sorted(scene_episode_dict.keys()): - episodes = scene_episode_dict[scene] - scene_id = scene.split('/')[-2] - print(f"scene_id = {scene_id}") - process_bar = tqdm.tqdm(range(len(episodes[idx :: self.world_size])), desc=f"scene {scene_id}") - for episode in episodes[idx :: self.world_size]: - episode_instruction = ( - episode.instruction.instruction_text - if 'objectnav' not in self.config_path - else episode.object_category - ) - print("episode start", episode_instruction) - episode_id = int(episode.episode_id) - if [scene_id, episode_id] in done_res: - continue - - # refactor env warm up - env.current_episode = episode - observations = env.reset() - - agent_state = env.sim.get_agent_state() - rotation = agent_state.rotation - translation = agent_state.position - rotation_matrix = quaternion.as_rotation_matrix(rotation) - transformation_matrix = np.eye(4) - transformation_matrix[:3, :3] = rotation_matrix - transformation_matrix[:3, 3] = translation - - agent = ShortestPathFollower(env.sim, 0.25, False) - - os.makedirs(os.path.join(self.output_path, f'check_sim_{self.epoch}'), exist_ok=True) - Image.fromarray(observations['rgb']).save( - os.path.join(self.output_path, f'check_sim_{self.epoch}', f'rgb_{idx}.jpg') + # Episode loop is now driven by env.reset() + env.is_running + process_bar = tqdm.tqdm(total=len(self.env.episodes), desc=f"Eval Epoch {self.epoch} Rank {idx}") + while self.env.is_running: + + # ------------ 1. Start of episode ------------ + observations = self.env.reset() + if not self.env.is_running or observations is None: + break + + # ---- episode meta (scene_id, episode_id, instruction) ---- + # we get it from the underlying habitat env + episode = self.env.get_current_episode() + scene_id = episode.scene_id.split('/')[-2] + episode_id = int(episode.episode_id) + episode_instruction = ( + episode.instruction.instruction_text if 'objectnav' not in self.config_path else episode.object_category + ) + print("episode start", episode_instruction) + + agent_state = self.env._env.sim.get_agent_state() + rotation = agent_state.rotation + translation = agent_state.position + rotation_matrix = quaternion.as_rotation_matrix(rotation) + transformation_matrix = np.eye(4) + transformation_matrix[:3, :3] = rotation_matrix + transformation_matrix[:3, 3] = translation + + agent = ShortestPathFollower(self.env._env.sim, 0.25, False) + + # save first frame per rank to validate sim quality + os.makedirs(os.path.join(self.output_path, f'check_sim_{self.epoch}'), exist_ok=True) + Image.fromarray(observations['rgb']).save( + os.path.join(self.output_path, f'check_sim_{self.epoch}', f'rgb_{idx}.jpg') + ) + + vis_frames = [] + step_id = 0 + + if self.save_video: + os.makedirs(os.path.join(self.output_path, f'vis_{self.epoch}', f'{scene_id}'), exist_ok=True) + initial_height = self.env._env.sim.get_agent_state().position[1] + + rgb_list = [] + action_seq = [] + output_ids = None + + goal = None + action = None + messages = [] + local_actions = [] + + done = False + + # ---------- 2. Episode step loop ----------- + while (not done) and (step_id <= self.max_steps_per_episode): + # refactor agent get action + rgb = observations["rgb"] + depth = observations["depth"] + x, y = observations["gps"] + camera_yaw = observations["compass"][0] + depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) + depth = depth * (self._max_depth - self._min_depth) + self._min_depth + depth = depth * 1000 + + agent_state = self.env._env.sim.get_agent_state() + height = agent_state.position[1] - initial_height + camera_position = np.array([x, -y, self._camera_height + height]) + tf_camera_to_episodic = ( + self.xyz_yaw_pitch_to_tf_matrix(camera_position, camera_yaw, np.deg2rad(30)) + @ self.get_axis_align_matrix() ) - vis_frames = [] - step_id = 0 - - if self.save_video: - os.makedirs(os.path.join(self.output_path, f'vis_{self.epoch}', f'{scene_id}'), exist_ok=True) - initial_height = env.sim.get_agent_state().position[1] - - rgb_list = [] - action_seq = [] - output_ids = None - - goal = None - action = None - messages = [] - local_actions = [] - - while not env.episode_over and step_id <= 500: - # refactor agent get action - rgb = observations["rgb"] - depth = observations["depth"] - x, y = observations["gps"] - camera_yaw = observations["compass"][0] - depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) - depth = depth * (self._max_depth - self._min_depth) + self._min_depth - depth = depth * 1000 - - agent_state = env.sim.get_agent_state() - height = agent_state.position[1] - initial_height - camera_position = np.array([x, -y, self._camera_height + height]) - tf_camera_to_episodic = ( - self.xyz_yaw_pitch_to_tf_matrix(camera_position, camera_yaw, np.deg2rad(30)) - @ self.get_axis_align_matrix() + image = Image.fromarray(rgb).convert('RGB') + save_raw_image = image.copy() + + save_dot = False + if action == 5: + look_down_image = image + save_raw_image = look_down_image.copy() + look_down_depth, resize_shape = self.preprocess_depth_image_v2( + Image.fromarray(depth.astype(np.uint16), mode='I;16'), + do_depth_scale=True, + depth_scale=1000, + target_height=224, + target_width=224, ) - - image = Image.fromarray(rgb).convert('RGB') - save_raw_image = image.copy() - - save_dot = False - if action == 5: - look_down_image = image - save_raw_image = look_down_image.copy() + look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() + look_down_depth[look_down_depth > 5.0] = 5.0 + else: + image = image.resize((self.model_args.resize_w, self.model_args.resize_h)) + rgb_list.append(image) + + if self.model_args.mode == 'dual_system': + down_observations, _, done, _ = self.env.step(5) + down_observations, _, done, _ = self.env.step(5) + + look_down_image = Image.fromarray(down_observations["rgb"]).convert('RGB') + depth = down_observations["depth"] + depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) + depth = depth * (self._max_depth - self._min_depth) + self._min_depth + depth = depth * 1000 look_down_depth, resize_shape = self.preprocess_depth_image_v2( Image.fromarray(depth.astype(np.uint16), mode='I;16'), do_depth_scale=True, @@ -332,295 +357,277 @@ def _run_local_eval(self, idx=0) -> None: # noqa: C901 ) look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() look_down_depth[look_down_depth > 5.0] = 5.0 - else: - image = image.resize((self.args.resize_w, self.args.resize_h)) - rgb_list.append(image) - - if self.args.mode == 'dual_system': - down_observations = env.step(5) - down_observations = env.step(5) - - look_down_image = Image.fromarray(down_observations["rgb"]).convert('RGB') - depth = down_observations["depth"] - depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) - depth = depth * (self._max_depth - self._min_depth) + self._min_depth - depth = depth * 1000 - look_down_depth, resize_shape = self.preprocess_depth_image_v2( - Image.fromarray(depth.astype(np.uint16), mode='I;16'), - do_depth_scale=True, - depth_scale=1000, - target_height=224, - target_width=224, - ) - look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() - look_down_depth[look_down_depth > 5.0] = 5.0 - env.step(4) - env.step(4) + self.env.step(4) + self.env.step(4) - info = env.get_metrics() + info = self.env.get_metrics() - if len(action_seq) == 0 and goal is None: - if action != 5: - sources = copy.deepcopy(self.conversation) - sources[0]["value"] = sources[0]["value"].replace( - '.', episode.instruction.instruction_text[:-1] - ) - cur_images = rgb_list[-1:] - if step_id == 0: - history_id = [] - else: - history_id = np.unique( - np.linspace(0, step_id - 1, self.num_history, dtype=np.int32) - ).tolist() - placeholder = (DEFAULT_IMAGE_TOKEN + '\n') * len(history_id) - sources[0]["value"] += f' These are your historical observations: {placeholder}.' - - history_id = sorted(history_id) - print('history_idddddddd', step_id, history_id) - input_images = [rgb_list[i] for i in history_id] + cur_images - input_img_id = 0 + if len(action_seq) == 0 and goal is None: + if action != 5: + sources = copy.deepcopy(self.conversation) + sources[0]["value"] = sources[0]["value"].replace( + '.', episode.instruction.instruction_text[:-1] + ) + cur_images = rgb_list[-1:] + if step_id == 0: + history_id = [] else: - assert action == 5 - sources = [{"from": "human", "value": ""}, {"from": "gpt", "value": ""}] - input_images += [look_down_image] - # messages.append( - # {'role': 'assistant', 'content': [{'type': 'text', 'text': llm_outputs}]} # noqa: F405 - # ) - input_img_id = -1 - - prompt = random.choice(self.conjunctions) + DEFAULT_IMAGE_TOKEN - sources[0]["value"] += f" {prompt}." - print('sources', step_id, sources) - prompt_instruction = copy.deepcopy(sources[0]["value"]) - parts = split_and_clean(prompt_instruction) - - content = [] - for i in range(len(parts)): - if parts[i] == "": - content.append({"type": "image", "image": input_images[input_img_id]}) - input_img_id += 1 - else: - content.append({"type": "text", "text": parts[i]}) + history_id = np.unique( + np.linspace(0, step_id - 1, self.num_history, dtype=np.int32) + ).tolist() + placeholder = (DEFAULT_IMAGE_TOKEN + '\n') * len(history_id) + sources[0]["value"] += f' These are your historical observations: {placeholder}.' + + history_id = sorted(history_id) + print('history_idddddddd', step_id, history_id) + input_images = [rgb_list[i] for i in history_id] + cur_images + input_img_id = 0 + else: + assert action == 5 + sources = [{"from": "human", "value": ""}, {"from": "gpt", "value": ""}] + input_images += [look_down_image] + # messages.append( + # {'role': 'assistant', 'content': [{'type': 'text', 'text': llm_outputs}]} # noqa: F405 + # ) + input_img_id = -1 + + prompt = random.choice(self.conjunctions) + DEFAULT_IMAGE_TOKEN + sources[0]["value"] += f" {prompt}." + print('sources', step_id, sources) + prompt_instruction = copy.deepcopy(sources[0]["value"]) + parts = split_and_clean(prompt_instruction) + + content = [] + for i in range(len(parts)): + if parts[i] == "": + content.append({"type": "image", "image": input_images[input_img_id]}) + input_img_id += 1 + else: + content.append({"type": "text", "text": parts[i]}) - messages.append({'role': 'user', 'content': content}) + messages.append({'role': 'user', 'content': content}) - print('step_id', step_id, 'messages:', messages) + print('step_id', step_id, 'messages:', messages) - text = self.processor.apply_chat_template(messages, tokenize=False, add_generation_prompt=True) + text = self.processor.apply_chat_template(messages, tokenize=False, add_generation_prompt=True) - inputs = self.processor(text=[text], images=input_images, return_tensors="pt").to( - self.model.device - ) + inputs = self.processor(text=[text], images=input_images, return_tensors="pt").to(self.model.device) - with torch.no_grad(): - output_ids = self.model.generate(**inputs, max_new_tokens=128, do_sample=False) + with torch.no_grad(): + output_ids = self.model.generate(**inputs, max_new_tokens=128, do_sample=False) + + llm_outputs = self.processor.tokenizer.decode( + output_ids[0][inputs.input_ids.shape[1] :], skip_special_tokens=True + ) + print('step_id:', step_id, 'output text:', llm_outputs) - llm_outputs = self.processor.tokenizer.decode( - output_ids[0][inputs.input_ids.shape[1] :], skip_special_tokens=True + if bool(re.search(r'\d', llm_outputs)): + forward_action = 0 + coord = [int(c) for c in re.findall(r'\d+', llm_outputs)] + pixel_goal = [int(coord[1]), int(coord[0])] + + intrinsic_matrix = self.get_intrinsic_matrix( + self.config.habitat.simulator.agents.main_agent.sim_sensors.rgb_sensor ) - print('step_id:', step_id, 'output text:', llm_outputs) - - if bool(re.search(r'\d', llm_outputs)): - forward_action = 0 - coord = [int(c) for c in re.findall(r'\d+', llm_outputs)] - pixel_goal = [int(coord[1]), int(coord[0])] - - goal = self.pixel_to_gps(pixel_goal, depth / 1000, intrinsic_matrix, tf_camera_to_episodic) - print('before', goal, depth.shape) - goal = (transformation_matrix @ np.array([-goal[1], 0, -goal[0], 1]))[:3] - - if not env.sim.pathfinder.is_navigable(np.array(goal)): - goal = np.array(env.sim.pathfinder.snap_point(np.array(goal))) - - # look down --> horizontal - env.step(4) - env.step(4) - - # Forking logic based on mode - if self.args.mode == 'system2': - action = agent.get_next_action(goal) - if action == 0: - goal = None - output_ids = None - action = 2 # random action - print('conduct a random action 2') - observations = env.step(action) - step_id += 1 - messages = [] - continue - else: # dual-system logic - local_actions = [] - pixel_values = inputs.pixel_values - image_grid_thw = torch.cat([thw.unsqueeze(0) for thw in inputs.image_grid_thw], dim=0) - - with torch.no_grad(): - traj_latents = self.model.generate_latents(output_ids, pixel_values, image_grid_thw) - - # prepocess align with navdp - image_dp = ( - torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 - ) - pix_goal_image = copy.copy(image_dp) - images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) - depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) - pix_goal_depth = copy.copy(depth_dp) - depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) - - with torch.no_grad(): - dp_actions = self.model.generate_traj( - traj_latents, images_dp, depths_dp, use_async=True - ) - - random_choice = np.random.choice(dp_actions.shape[0]) - if self.args.continuous_traj: - action_list = traj_to_actions(dp_actions) - if len(action_list) < 8: - action_list += [0] * (8 - len(action_list)) - else: - action_list = chunk_token(dp_actions[random_choice]) - - local_actions = action_list - if len(local_actions) >= 4: - local_actions = local_actions[:4] - action = local_actions[0] - if action == 0: - goal = None - output_ids = None - action = 2 # random action - print('conduct a random action 2') - observations = env.step(action) - step_id += 1 - messages = [] - continue - - print('predicted goal', pixel_goal, goal, flush=True) - else: - action_seq = self.parse_actions(llm_outputs) - print('actions', action_seq, flush=True) + goal = self.pixel_to_gps(pixel_goal, depth / 1000, intrinsic_matrix, tf_camera_to_episodic) + print('before', goal, depth.shape) + goal = (transformation_matrix @ np.array([-goal[1], 0, -goal[0], 1]))[:3] + + if not self.env._env.sim.pathfinder.is_navigable(np.array(goal)): + goal = np.array(self.env._env.sim.pathfinder.snap_point(np.array(goal))) + + # look down --> horizontal + self.env.step(4) + self.env.step(4) - if len(action_seq) != 0: - action = action_seq[0] - action_seq.pop(0) - elif goal is not None: # Forking logic based on mode - if self.args.mode == 'system2': + if self.model_args.mode == 'system2': action = agent.get_next_action(goal) - action = action.detach().cpu().numpy()[0] if isinstance(action, torch.Tensor) else action - action = action[0] if hasattr(action, "__len__") else action + if action == 0: + goal = None + output_ids = None + action = 2 # random action + print('conduct a random action 2') + observations = self.env.step(action) + step_id += 1 + messages = [] + continue else: # dual-system logic - if len(local_actions) == 0: - # navdp - local_actions = [] - image_dp = ( - torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 + local_actions = [] + pixel_values = inputs.pixel_values + image_grid_thw = torch.cat([thw.unsqueeze(0) for thw in inputs.image_grid_thw], dim=0) + + with torch.no_grad(): + traj_latents = self.model.generate_latents(output_ids, pixel_values, image_grid_thw) + + # prepocess align with navdp + image_dp = ( + torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 + ) + pix_goal_image = copy.copy(image_dp) + images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) + depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) + pix_goal_depth = copy.copy(depth_dp) + depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) + + with torch.no_grad(): + dp_actions = self.model.generate_traj( + traj_latents, images_dp, depths_dp, use_async=True ) - images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) - depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) - - depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) - with torch.no_grad(): - dp_actions = self.model.generate_traj( - traj_latents, images_dp, depths_dp, use_async=True - ) - - random_choice = np.random.choice(dp_actions.shape[0]) - if self.args.continuous_traj: - action_list = traj_to_actions(dp_actions) - if len(action_list) < 8: - action_list += [0] * (8 - len(action_list)) - else: - action_list = chunk_token(dp_actions[random_choice]) - print("first action_list", action_list) - - local_actions = action_list - if len(local_actions) >= 4: - local_actions = local_actions[:4] - # if len(local_actions) >= 2: - # local_actions = local_actions[:2] - - print("local_actions", local_actions) - - action = local_actions.pop(0) - # navdp + random_choice = np.random.choice(dp_actions.shape[0]) + if self.model_args.continuous_traj: + action_list = traj_to_actions(dp_actions) + if len(action_list) < 8: + action_list += [0] * (8 - len(action_list)) else: - action = local_actions.pop(0) - - forward_action += 1 - print('forward_action', forward_action, flush=True) - if forward_action > 8: - goal = None - output_ids = None - messages = [] - step_id += 1 - forward_action = 0 - local_actions = [] - continue - if action == 0: - goal = None - output_ids = None - messages = [] - step_id += 1 - forward_action = 0 - local_actions = [] - continue + action_list = chunk_token(dp_actions[random_choice]) + + local_actions = action_list + if len(local_actions) >= 4: + local_actions = local_actions[:4] + action = local_actions[0] + if action == 0: + goal = None + output_ids = None + action = 2 # random action + print('conduct a random action 2') + observations = self.env.step(action) + step_id += 1 + messages = [] + continue + + print('predicted goal', pixel_goal, goal, flush=True) else: - action = 0 - - if info['top_down_map'] is not None: - if save_dot: - save_raw_image = self.dot_matrix_two_dimensional( - save_raw_image, save_img=False, save_path=f'test_{step_id}.jpg', pixel_goal=pixel_goal + action_seq = self.parse_actions(llm_outputs) + print('actions', action_seq, flush=True) + + if len(action_seq) != 0: + action = action_seq[0] + action_seq.pop(0) + elif goal is not None: + # Forking logic based on mode + if self.model_args.mode == 'system2': + action = agent.get_next_action(goal) + action = action.detach().cpu().numpy()[0] if isinstance(action, torch.Tensor) else action + action = action[0] if hasattr(action, "__len__") else action + else: # dual-system logic + if len(local_actions) == 0: + # navdp + local_actions = [] + image_dp = ( + torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 ) - frame = observations_to_image({'rgb': np.asarray(save_raw_image)}, info) - vis_frames.append(frame) - print("step_id", step_id, "action", action) + images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) + depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) - # refactor: core - if action == 5: - env.step(action) - observations = env.step(action) - else: - observations = env.step(action) + depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) + with torch.no_grad(): + dp_actions = self.model.generate_traj( + traj_latents, images_dp, depths_dp, use_async=True + ) + + random_choice = np.random.choice(dp_actions.shape[0]) + if self.model_args.continuous_traj: + action_list = traj_to_actions(dp_actions) + if len(action_list) < 8: + action_list += [0] * (8 - len(action_list)) + else: + action_list = chunk_token(dp_actions[random_choice]) + print("first action_list", action_list) + + local_actions = action_list + if len(local_actions) >= 4: + local_actions = local_actions[:4] + # if len(local_actions) >= 2: + # local_actions = local_actions[:2] + + print("local_actions", local_actions) + + action = local_actions.pop(0) + # navdp + else: + action = local_actions.pop(0) + + forward_action += 1 + print('forward_action', forward_action, flush=True) + if forward_action > 8: + goal = None + output_ids = None + messages = [] step_id += 1 + forward_action = 0 + local_actions = [] + continue + if action == 0: + goal = None + output_ids = None messages = [] + step_id += 1 + forward_action = 0 + local_actions = [] + continue + else: + action = 0 + + if info['top_down_map'] is not None: + if save_dot: + save_raw_image = self.dot_matrix_two_dimensional( + save_raw_image, save_img=False, save_path=f'test_{step_id}.jpg', pixel_goal=pixel_goal + ) + if self.save_video: + frame = observations_to_image({'rgb': np.asarray(save_raw_image)}, info) + vis_frames.append(frame) - process_bar.update(1) + print("step_id", step_id, "action", action) - metrics = env.get_metrics() - if self.save_video: - images_to_video( - vis_frames, - os.path.join(self.output_path, f'vis_{self.epoch}', f'{scene_id}'), - f'{episode_id:04d}', - fps=6, - quality=9, - ) - vis_frames.clear() - sucs.append(metrics['success']) - spls.append(metrics['spl']) - oss.append(metrics['oracle_success']) - nes.append(metrics["distance_to_goal"]) - print( - f"scene_episode {scene_id}_{episode_id:04d} success: {metrics['success']}, spl: {metrics['spl']}, os: {metrics['oracle_success']}, ne: {metrics['distance_to_goal']}" - ) + # refactor: core + if action == 5: + self.env.step(action) + observations, _, done, _ = self.env.step(action) + else: + observations, _, done, _ = self.env.step(action) + step_id += 1 + messages = [] - result = { - "scene_id": scene_id, - "episode_id": episode_id, - "success": metrics["success"], - "spl": metrics["spl"], - "os": metrics['oracle_success'], - "ne": metrics["distance_to_goal"], - "steps": step_id, - "episode_instruction": episode_instruction, - } + # ---------- 3. End of episode ----------- + # Update result and write progress to the output_path/progress.json + + process_bar.update(1) + + # After the episode finishes, collect metrics: + metrics = self.env.get_metrics() + + sucs.append(metrics['success']) + spls.append(metrics['spl']) + oss.append(metrics['oracle_success']) + nes.append(metrics["distance_to_goal"]) + + print( + f"scene_episode {scene_id}_{episode_id:04d} success: {metrics['success']}, " + f"spl: {metrics['spl']}, os: {metrics['oracle_success']}, " + f"ne: {metrics['distance_to_goal']}" + ) + + # Write per-episode result.json entry (still per-rank) + result = { + "scene_id": scene_id, + "episode_id": episode_id, + "success": metrics["success"], + "spl": metrics["spl"], + "os": metrics['oracle_success'], + "ne": metrics["distance_to_goal"], + "steps": step_id, + "episode_instruction": episode_instruction, + } + os.makedirs(self.output_path, exist_ok=True) + with open(os.path.join(self.output_path, 'progress.json'), 'a') as f: + f.write(json.dumps(result) + "\n") + + self.env.close() - with open(os.path.join(self.output_path, 'result.json'), 'a') as f: - f.write(json.dumps(result) + "\n") - env.close() return ( torch.tensor(sucs).to(self.device), torch.tensor(spls).to(self.device), diff --git a/internnav/internnav_habitat/habitat_vln_evaluator_clean.py b/internnav/internnav_habitat/habitat_vln_evaluator_clean.py new file mode 100644 index 0000000..ff5e60b --- /dev/null +++ b/internnav/internnav_habitat/habitat_vln_evaluator_clean.py @@ -0,0 +1,128 @@ +import argparse +import sys + +sys.path.append('./src/diffusion-policy') + + +# Import for Habitat registry side effects — do not remove +import internnav.env.utils.habitat_extensions.measures # noqa: F401 +from internnav.configs.evaluator import EvalCfg +from internnav.evaluator import DistributedEvaluator, Evaluator + +try: + import habitat + from habitat.config.default import get_agent_config + from habitat.config.default_structured_configs import ( + CollisionsMeasurementConfig, + FogOfWarConfig, + TopDownMapMeasurementConfig, + ) + from habitat_baselines.config.default import get_config as get_habitat_config +except Exception as e: + print("Habitat Error:", e) + print("Habitat Evaluation is not loaded.") + + +DEFAULT_IMAGE_TOKEN = "" + + +@Evaluator.register('habitat_vln') +class HabitatVlnEvaluator(DistributedEvaluator): + def __init__(self, cfg: EvalCfg): + args = argparse.Namespace(**cfg.eval_settings) + self.args = args + self.save_video = args.save_video + self.epoch = args.epoch + self.max_steps_per_episode = args.max_steps_per_episode + self.output_path = args.output_path + + # create habitat config + self.config_path = cfg.env.env_settings['config_path'] + self.config = get_habitat_config(self.config_path) + self.agent_config = get_agent_config(self.config.habitat.simulator) + self.sim_sensors_config = self.config.habitat.simulator.agents.main_agent.sim_sensors + + with habitat.config.read_write(self.config): + self.config.habitat.task.measurements.update( + { + "top_down_map": TopDownMapMeasurementConfig( + map_padding=3, + map_resolution=1024, + draw_source=True, + draw_border=True, + draw_shortest_path=True, + draw_view_points=True, + draw_goal_positions=True, + draw_goal_aabbs=True, + fog_of_war=FogOfWarConfig( + draw=True, + visibility_dist=5.0, + fov=90, + ), + ), + "collisions": CollisionsMeasurementConfig(), + } + ) + cfg.env.env_settings['habitat_config'] = self.config + cfg.env.env_settings['output_path'] = self.output_path + + # init agent and env + super().__init__(cfg) + + def eval_action(self): + """ + Run local episodes on this rank. + + Returns dict[str, Tensor] on GPU (1D tensors of same length). + """ + sucs, spls, oss, nes = [], [], [], [] + env = self.env + + while env.is_running: + obs = env.reset() + if not env.is_running or obs is None: + break + + episode = env.env.current_episode + self.agent.reset(episode, env) + + done = False + step_id = 0 + while not done and step_id <= self.max_steps_per_episode: + action = self.agent.act(obs, env, info=None) + obs, reward, done, info = env.step(action) + step_id += 1 + + m = env.get_metrics() + sucs.append(m["success"]) + spls.append(m["spl"]) + oss.append(m["oracle_success"]) + nes.append(m["distance_to_goal"]) + + env.close() + return { + "sucs": sucs, # shape [N_local] + "spls": spls, # shape [N_local] + "oss": oss, # shape [N_local] + "nes": nes, # shape [N_local] + } + + def calc_metrics(self, global_metrics: dict) -> dict: + """ + global_metrics["sucs"] etc. are global 1-D CPU tensors with all episodes. + """ + sucs_all = global_metrics["sucs"] + spls_all = global_metrics["spls"] + oss_all = global_metrics["oss"] + nes_all = global_metrics["nes"] + + # avoid /0 if no episodes + denom = max(len(sucs_all), 1) + + return { + "sucs_all": float(sucs_all.mean().item()) if denom > 0 else 0.0, + "spls_all": float(spls_all.mean().item()) if denom > 0 else 0.0, + "oss_all": float(oss_all.mean().item()) if denom > 0 else 0.0, + "nes_all": float(nes_all.mean().item()) if denom > 0 else 0.0, + # "length" will be filled by base class + } diff --git a/internnav/utils/dist.py b/internnav/utils/dist.py index 7994e25..82c14a3 100644 --- a/internnav/utils/dist.py +++ b/internnav/utils/dist.py @@ -1,13 +1,13 @@ -import os -import time import builtins import datetime +import os import subprocess +import time +from collections import defaultdict, deque import torch import torch.distributed as dist -from collections import defaultdict, deque class SmoothedValue(object): def __init__(self, window_size=20, fmt=None): @@ -60,11 +60,8 @@ def value(self): def __str__(self): return self.fmt.format( - median=self.median, - avg=self.avg, - global_avg=self.global_avg, - max=self.max, - value=self.value) + median=self.median, avg=self.avg, global_avg=self.global_avg, max=self.max, value=self.value + ) class MetricLogger(object): @@ -86,15 +83,12 @@ def __getattr__(self, attr): return self.meters[attr] if attr in self.__dict__: return self.__dict__[attr] - raise AttributeError("'{}' object has no attribute '{}'".format( - type(self).__name__, attr)) + raise AttributeError("'{}' object has no attribute '{}'".format(type(self).__name__, attr)) def __str__(self): loss_str = [] for name, meter in self.meters.items(): - loss_str.append( - "{}: {}".format(name, str(meter)) - ) + loss_str.append("{}: {}".format(name, str(meter))) return self.delimiter.join(loss_str) def synchronize_between_processes(self): @@ -113,14 +107,7 @@ def log_every(self, iterable, print_freq, header=None): iter_time = SmoothedValue(fmt='{avg:.4f}') data_time = SmoothedValue(fmt='{avg:.4f}') space_fmt = ':' + str(len(str(len(iterable)))) + 'd' - log_msg = [ - header, - '[{0' + space_fmt + '}/{1}]', - 'eta: {eta}', - '{meters}', - 'time: {time}', - 'data: {data}' - ] + log_msg = [header, '[{0' + space_fmt + '}/{1}]', 'eta: {eta}', '{meters}', 'time: {time}', 'data: {data}'] if torch.cuda.is_available(): log_msg.append('max mem: {memory:.0f}') log_msg = self.delimiter.join(log_msg) @@ -133,22 +120,28 @@ def log_every(self, iterable, print_freq, header=None): eta_seconds = iter_time.global_avg * (len(iterable) - i) eta_string = str(datetime.timedelta(seconds=int(eta_seconds))) if torch.cuda.is_available(): - print(log_msg.format( - i, len(iterable), eta=eta_string, - meters=str(self), - time=str(iter_time), data=str(data_time), - memory=torch.cuda.max_memory_allocated() / MB)) + print( + log_msg.format( + i, + len(iterable), + eta=eta_string, + meters=str(self), + time=str(iter_time), + data=str(data_time), + memory=torch.cuda.max_memory_allocated() / MB, + ) + ) else: - print(log_msg.format( - i, len(iterable), eta=eta_string, - meters=str(self), - time=str(iter_time), data=str(data_time))) + print( + log_msg.format( + i, len(iterable), eta=eta_string, meters=str(self), time=str(iter_time), data=str(data_time) + ) + ) i += 1 end = time.time() total_time = time.time() - start_time total_time_str = str(datetime.timedelta(seconds=int(total_time))) - print('{} Total time: {} ({:.4f} s / it)'.format( - header, total_time_str, total_time / len(iterable))) + print('{} Total time: {} ({:.4f} s / it)'.format(header, total_time_str, total_time / len(iterable))) def setup_for_distributed(is_master): @@ -197,57 +190,51 @@ def save_on_master(*args, **kwargs): torch.save(*args, **kwargs) -def init_distributed_mode(args): - if 'SLURM_PROCID' in os.environ: - args.rank = int(os.environ['SLURM_PROCID']) - args.world_size = int(os.environ['SLURM_NTASKS']) - +def init_distributed_mode(port=29529, backend="nccl", timeout_hours=2): + # Fast-path: torchrun provides these + if all(k in os.environ for k in ["RANK", "WORLD_SIZE", "LOCAL_RANK", "MASTER_ADDR", "MASTER_PORT"]): + rank = int(os.environ["RANK"]) + world_size = int(os.environ["WORLD_SIZE"]) + local_rank = int(os.environ["LOCAL_RANK"]) + + # SLURM path: derive env then fall back to env:// + elif "SLURM_PROCID" in os.environ: + rank = int(os.environ["SLURM_PROCID"]) + world_size = int(os.environ["SLURM_NTASKS"]) num_gpus = torch.cuda.device_count() - args.gpu = args.rank % num_gpus - args.local_rank = args.gpu - - node_list = os.environ['SLURM_NODELIST'] - print(f'Node list: {node_list}') - addr = subprocess.getoutput(f'scontrol show hostname {node_list} | head -n1') - - os.environ['MASTER_PORT'] = str(getattr(args, 'port', '29529')) - os.environ['MASTER_ADDR'] = addr - os.environ['WORLD_SIZE'] = str(args.world_size) - os.environ['LOCAL_RANK'] = str(args.gpu) - os.environ['RANK'] = str(args.rank) - elif 'RANK' in os.environ and 'WORLD_SIZE' in os.environ: - args.rank = int(os.environ["RANK"]) - args.world_size = int(os.environ['WORLD_SIZE']) - args.gpu = int(os.environ['LOCAL_RANK']) - args.local_rank = args.gpu + local_rank = rank % max(1, num_gpus) + + # pick first node as master + nodelist = os.environ["SLURM_NODELIST"] + master_addr = subprocess.getoutput(f"scontrol show hostname {nodelist} | head -n1") + os.environ.setdefault("MASTER_ADDR", master_addr) + os.environ.setdefault("MASTER_PORT", str(port)) + os.environ["RANK"] = str(rank) + os.environ["WORLD_SIZE"] = str(world_size) + os.environ["LOCAL_RANK"] = str(local_rank) + else: - print('Not using distributed mode') - setup_for_distributed(is_master=True) # hack - args.distributed = False + print("Not using distributed mode") + setup_for_distributed(is_master=True) return - args.distributed = True + # Device selection must happen before NCCL init + torch.cuda.set_device(local_rank) + + dist.init_process_group(backend=backend, init_method="env://", timeout=datetime.timedelta(hours=timeout_hours)) + setup_for_distributed(dist.get_rank() == 0) - torch.cuda.set_device(args.gpu) - args.dist_backend = 'nccl' - print('| distributed init (rank {}): {}, gpu {}'.format(args.rank, args.dist_url, args.gpu), flush=True) - dist.init_process_group(backend=args.dist_backend, - init_method=args.dist_url, - world_size=args.world_size, - rank=args.rank, - timeout=datetime.timedelta(0, 7200)) - dist.barrier() - setup_for_distributed(args.rank == 0) def save_model(args, epoch, model_without_ddp, optimizer, checkpoint_path): to_save = { - 'model': model_without_ddp.state_dict(), - 'optimizer': optimizer.state_dict(), - 'epoch': epoch, - 'args': args, - } + 'model': model_without_ddp.state_dict(), + 'optimizer': optimizer.state_dict(), + 'epoch': epoch, + 'args': args, + } save_on_master(to_save, checkpoint_path) + def all_reduce_mean(x): world_size = get_world_size() if world_size > 1: @@ -257,11 +244,16 @@ def all_reduce_mean(x): return x_reduce.item() else: return x - + + def fsdp_auto_wrap_policy(model, transformer_layer_names): import functools - from torch.distributed.fsdp.wrap import _or_policy, lambda_auto_wrap_policy, transformer_auto_wrap_policy + from torch.distributed.fsdp.wrap import ( + _or_policy, + lambda_auto_wrap_policy, + transformer_auto_wrap_policy, + ) def lambda_policy_fn(module): if ( @@ -274,9 +266,8 @@ def lambda_policy_fn(module): lambda_policy = functools.partial(lambda_auto_wrap_policy, lambda_fn=lambda_policy_fn) transformer_wrap_policy = functools.partial( - transformer_auto_wrap_policy, - transformer_layer_cls=set(transformer_layer_names) + transformer_auto_wrap_policy, transformer_layer_cls=set(transformer_layer_names) ) auto_wrap_policy = functools.partial(_or_policy, policies=[lambda_policy, transformer_wrap_policy]) - return auto_wrap_policy \ No newline at end of file + return auto_wrap_policy diff --git a/scripts/eval/bash/torchrun_eval.sh b/scripts/eval/bash/torchrun_eval.sh index 8a68922..ae3993c 100644 --- a/scripts/eval/bash/torchrun_eval.sh +++ b/scripts/eval/bash/torchrun_eval.sh @@ -2,7 +2,7 @@ MID_RUN_NAME="InternVLA-N1" torchrun \ - --nproc_per_node=2 \ + --nproc_per_node=1 \ --master_port=2333 \ scripts/eval/eval.py \ --config scripts/eval/configs/habitat_cfg.py \ diff --git a/scripts/eval/configs/habitat_cfg.py b/scripts/eval/configs/habitat_cfg.py index 6e3445a..18a8680 100644 --- a/scripts/eval/configs/habitat_cfg.py +++ b/scripts/eval/configs/habitat_cfg.py @@ -7,25 +7,16 @@ model_name='internvla_n1', ckpt_path='', model_settings={ - 'env_num': 1, - 'sim_num': 1, - 'model_path': "checkpoints/InternVLA-N1", - 'camera_intrinsic': [[585.0, 0.0, 320.0], [0.0, 585.0, 240.0], [0.0, 0.0, 1.0]], - 'width': 640, - 'height': 480, - 'hfov': 79, - 'resize_w': 384, - 'resize_h': 384, - 'max_new_tokens': 1024, - 'num_frames': 32, - 'num_history': 8, - 'num_future_steps': 4, - 'device': 'cuda:0', - 'predict_step_nums': 32, - 'continuous_traj': True, - # debug - 'vis_debug': True, # If vis_debug=True, you can get visualization results - 'vis_debug_path': './logs/test/vis_debug', + "mode": "dual_system", # inference mode: dual_system or system2 + "model_path": "checkpoints/InternVLA-N1", # path to model checkpoint + "num_future_steps": 4, # number of future steps for prediction + "num_frames": 32, # number of frames used in evaluation + "num_history": 8, + "resize_w": 384, # image resize width + "resize_h": 384, # image resize height + "predict_step_nums": 32, # number of steps to predict + "continuous_traj": True, # whether to use continuous trajectory + "max_new_tokens": 1024, # maximum number of tokens for generation }, ), env=EnvCfg( @@ -42,20 +33,12 @@ "output_path": "./logs/habitat/test_refactor_debug", # output directory for logs/results "save_video": False, # whether to save videos "epoch": 0, # epoch number for logging + "max_steps_per_episode": 500, # maximum steps per episode + # distributed settings "world_size": 1, # number of distributed processes "rank": 0, # rank of current process "gpu": 0, # gpu id to use "port": "2333", # communication port "dist_url": "env://", # url for distributed setup - "mode": "dual_system", # inference mode: dual_system or system2 - "model_path": "checkpoints/InternVLA-N1", # path to model checkpoint - "num_future_steps": 4, # number of future steps for prediction - "num_frames": 32, # number of frames used in evaluation - "num_history": 8, - "resize_w": 384, # image resize width - "resize_h": 384, # image resize height - "predict_step_nums": 32, # number of steps to predict - "continuous_traj": True, # whether to use continuous trajectory - "max_new_tokens": 1024, # maximum number of tokens for generation }, ) diff --git a/setup.cfg b/setup.cfg index b6a3f5b..0bbee65 100644 --- a/setup.cfg +++ b/setup.cfg @@ -45,4 +45,4 @@ per-file-ignores=*/__init__.py:F401 ignore=E402,E501,W503,E203,D401,R504,R505,SIM102,SIM117,E711,E226 max-line-length = 120 max-complexity = 30 -exclude=_*,.vscode,.git,docs/**,**/test/**,**/lcmtypes/**,*.ipynb +exclude=_*,.vscode,.git,docs/**,**/test/**,**/lcmtypes/**,*.ipynb,internnav/internnav_habitat/habitat_n1_agent_temp.py From 7e25e7243da20e78dc5625b36753775c01cf7e87 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Wed, 12 Nov 2025 07:06:20 +0000 Subject: [PATCH 05/35] fix observation issues --- internnav/evaluator/__init__.py | 5 +- internnav/evaluator/distributed_base.py | 28 +- internnav/evaluator/habitat_vln_evaluator.py | 749 ------------------ .../habitat_vln_evaluator.py | 11 +- ..._clean.py => habitat_vln_evaluator_new.py} | 0 scripts/eval/bash/torchrun_eval.sh | 2 +- scripts/eval/configs/habitat_cfg.py | 4 +- setup.cfg | 2 +- 8 files changed, 34 insertions(+), 767 deletions(-) delete mode 100644 internnav/evaluator/habitat_vln_evaluator.py rename internnav/internnav_habitat/{habitat_vln_evaluator_clean.py => habitat_vln_evaluator_new.py} (100%) diff --git a/internnav/evaluator/__init__.py b/internnav/evaluator/__init__.py index fda0a88..07a7208 100644 --- a/internnav/evaluator/__init__.py +++ b/internnav/evaluator/__init__.py @@ -1,7 +1,8 @@ -# register habitat -import internnav.internnav_habitat # noqa: F401 from internnav.evaluator.base import Evaluator from internnav.evaluator.distributed_base import DistributedEvaluator from internnav.evaluator.vln_multi_evaluator import VlnMultiEvaluator +# register habitat +import internnav.internnav_habitat # noqa: F401 # isort: skip + __all__ = ['Evaluator', 'VlnMultiEvaluator'] diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index f30d058..94bfc06 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -13,9 +13,14 @@ class DistributedEvaluator(Evaluator): """ Base class of distributed evaluators. + + Args: + cfg (EvalCfg): evaluation configuration + init_env (bool): whether to initialize the environment + init_agent (bool): whether to initialize the agent """ - def __init__(self, cfg: EvalCfg): + def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True): # distributed setting import socket @@ -35,14 +40,23 @@ def __init__(self, cfg: EvalCfg): cfg.env.env_settings['local_rank'] = get_rank() cfg.env.env_settings['world_size'] = get_world_size() + self.eval_config = cfg + + if init_env: + self.env = Env.init(cfg.env, cfg.task) + # -------- initialize agent config (either remote server or local agent) -------- - # set agent port based on rank - # cfg.agent.agent_settings['port'] = 8000 + get_rank() - # start_server(cfg.agent.agent_settings['port']) + if init_agent: + if cfg.remote_agent: + # set agent port based on rank + from internnav.utils import AgentClient - self.eval_config = cfg - self.env = Env.init(cfg.env, cfg.task) - # self.agent = AgentClient(config.agent) + cfg.agent.agent_settings['port'] = 8000 + get_rank() + self.agent = AgentClient(cfg.agent) + else: + from internnav.agent import Agent + + self.agent = Agent(cfg.agent) def eval(self): """ diff --git a/internnav/evaluator/habitat_vln_evaluator.py b/internnav/evaluator/habitat_vln_evaluator.py deleted file mode 100644 index e901ae3..0000000 --- a/internnav/evaluator/habitat_vln_evaluator.py +++ /dev/null @@ -1,749 +0,0 @@ -import argparse -import copy -import itertools -import json -import os -import random -import re -from collections import OrderedDict -from typing import Any - -import habitat -import numpy as np -import quaternion -import torch -import tqdm -from depth_camera_filtering import filter_depth -from habitat import Env -from habitat.config.default import get_agent_config -from habitat.config.default_structured_configs import ( - CollisionsMeasurementConfig, - FogOfWarConfig, - TopDownMapMeasurementConfig, -) -from habitat.tasks.nav.shortest_path_follower import ShortestPathFollower -from habitat.utils.visualizations.utils import images_to_video, observations_to_image -from habitat_baselines.config.default import get_config as get_habitat_config -from omegaconf import OmegaConf -from PIL import Image, ImageDraw, ImageFont -from transformers.image_utils import to_numpy_array - -from internnav.model.utils.vln_utils import ( - chunk_token, - open_image, - split_and_clean, - traj_to_actions, -) -from internnav.utils.dist import * # noqa: F403 - -DEFAULT_IMAGE_TOKEN = "" - - -class VLNEvaluator: - def __init__( - self, - config_path: str, - split: str = "val_seen", - env_num: int = 1, - output_path: str = None, - model: Any = None, - processor: Any = None, - epoch: int = 0, - args: argparse.Namespace = None, - ): - self.args = args - self.device = torch.device('cuda') - self.split = split - self.env_num = env_num - self.save_video = args.save_video - self.output_path = output_path - self.epoch = epoch - self.config_path = config_path - self.config = get_habitat_config(config_path) - self.agent_config = get_agent_config(self.config.habitat.simulator) - self.sim_sensors_config = self.config.habitat.simulator.agents.main_agent.sim_sensors - - with habitat.config.read_write(self.config): - # self.config.habitat.task.measurements.success.success_distance=3.0 - self.config.habitat.dataset.split = self.split # refactor: why args and yaml both have split - self.config.habitat.task.measurements.update( # refactor: move to yaml - { - "top_down_map": TopDownMapMeasurementConfig( - map_padding=3, - map_resolution=1024, - draw_source=True, - draw_border=True, - draw_shortest_path=True, - draw_view_points=True, - draw_goal_positions=True, - draw_goal_aabbs=True, - fog_of_war=FogOfWarConfig( - draw=True, - visibility_dist=5.0, - fov=90, - ), - ), - "collisions": CollisionsMeasurementConfig(), - } - ) - - print(f"config = {type(self.config)}") - print(OmegaConf.to_yaml(self.config)) - - self._camera_height = self.sim_sensors_config.rgb_sensor.position[1] - self._min_depth = self.sim_sensors_config.depth_sensor.min_depth - self._max_depth = self.sim_sensors_config.depth_sensor.max_depth - - camera_fov_rad = np.deg2rad(self.sim_sensors_config.depth_sensor.hfov) - self._camera_fov = camera_fov_rad - self._fx = self._fy = self.sim_sensors_config.depth_sensor.width / (2 * np.tan(camera_fov_rad / 2)) - - self.model = model - self.processor = processor - - # refactor: this part used in three places - prompt = "You are an autonomous navigation assistant. Your task is to . Where should you go next to stay on track? Please output the next waypoint\'s coordinates in the image. Please output STOP when you have successfully completed the task." - answer = "" - self.conversation = [{"from": "human", "value": prompt}, {"from": "gpt", "value": answer}] - - self.conjunctions = [ - 'you can see ', - 'in front of you is ', - 'there is ', - 'you can spot ', - 'you are toward the ', - 'ahead of you is ', - 'in your sight is ', - ] - - self.actions2idx = OrderedDict( - { - 'STOP': [0], - "↑": [1], - "←": [2], - "→": [3], - "↓": [5], - } - ) - - self.objectnav_instructions = ["Search for the {target_object}."] - - self.num_frames = args.num_frames - self.num_future_steps = args.num_future_steps - self.num_history = args.num_history - - # refactor - def config_env(self) -> Env: - env = Env(config=self.config) - # env.episodes = env.episodes[0:1] - return env - - def eval_action(self, idx) -> None: # noqa: C901 - self.model.eval() - env = self.config_env() - scene_episode_dict = {} - for episode in env.episodes: - if episode.scene_id not in scene_episode_dict: - scene_episode_dict[episode.scene_id] = [] - scene_episode_dict[episode.scene_id].append(episode) - - intrinsic_matrix = self.get_intrinsic_matrix( - self.config.habitat.simulator.agents.main_agent.sim_sensors.rgb_sensor - ) - sucs, spls, oss, nes = [], [], [], [] - done_res = [] - - if os.path.exists(os.path.join(self.output_path, 'result.json')): - with open(os.path.join(self.output_path, 'result.json'), 'r') as f: - for line in f.readlines(): - res = json.loads(line) - done_res.append([res["scene_id"], res["episode_id"], res["episode_instruction"]]) - if get_rank() == 0: # noqa: F405 - sucs.append(res['success']) - spls.append(res['spl']) - oss.append(res['os']) - nes.append(res['ne']) - - # refactor: why sort to scene: [episode] but nothing actually used - for scene in sorted(scene_episode_dict.keys()): - episodes = scene_episode_dict[scene] - scene_id = scene.split('/')[-2] - print(f"scene_id = {scene_id}") - process_bar = tqdm.tqdm(range(len(episodes[idx :: self.env_num])), desc=f"scene {scene_id}") - for episode in episodes[idx :: self.env_num]: - episode_instruction = ( - episode.instruction.instruction_text - if 'objectnav' not in self.config_path - else episode.object_category - ) - print("episode start", episode_instruction) - episode_id = int(episode.episode_id) - if [scene_id, episode_id, episode_instruction] in done_res: - continue - - # refactor env warm up - env.current_episode = episode - observations = env.reset() - - agent_state = env.sim.get_agent_state() - rotation = agent_state.rotation - translation = agent_state.position - rotation_matrix = quaternion.as_rotation_matrix(rotation) - transformation_matrix = np.eye(4) - transformation_matrix[:3, :3] = rotation_matrix - transformation_matrix[:3, 3] = translation - - agent = ShortestPathFollower(env.sim, 0.25, False) - - os.makedirs(os.path.join(self.output_path, f'check_sim_{self.epoch}'), exist_ok=True) - Image.fromarray(observations['rgb']).save( - os.path.join(self.output_path, f'check_sim_{self.epoch}', f'rgb_{idx}.jpg') - ) - - vis_frames = [] - step_id = 0 - - if self.save_video: - os.makedirs(os.path.join(self.output_path, f'vis_{self.epoch}', f'{scene_id}'), exist_ok=True) - initial_height = env.sim.get_agent_state().position[1] - - rgb_list = [] - action_seq = [] - output_ids = None - - goal = None - action = None - messages = [] - local_actions = [] - - while not env.episode_over and step_id <= 500: - # refactor agent get action - rgb = observations["rgb"] - depth = observations["depth"] - x, y = observations["gps"] - camera_yaw = observations["compass"][0] - depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) - depth = depth * (self._max_depth - self._min_depth) + self._min_depth - depth = depth * 1000 - - agent_state = env.sim.get_agent_state() - height = agent_state.position[1] - initial_height - camera_position = np.array([x, -y, self._camera_height + height]) - tf_camera_to_episodic = ( - self.xyz_yaw_pitch_to_tf_matrix(camera_position, camera_yaw, np.deg2rad(30)) - @ self.get_axis_align_matrix() - ) - - image = Image.fromarray(rgb).convert('RGB') - save_raw_image = image.copy() - - save_dot = False - if action == 5: - look_down_image = image - save_raw_image = look_down_image.copy() - look_down_depth, resize_shape = self.preprocess_depth_image_v2( - Image.fromarray(depth.astype(np.uint16), mode='I;16'), - do_depth_scale=True, - depth_scale=1000, - target_height=224, - target_width=224, - ) - look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() - look_down_depth[look_down_depth > 5.0] = 5.0 - else: - image = image.resize((self.args.resize_w, self.args.resize_h)) - rgb_list.append(image) - - if self.args.mode == 'dual_system': - down_observations = env.step(5) - down_observations = env.step(5) - - look_down_image = Image.fromarray(down_observations["rgb"]).convert('RGB') - depth = down_observations["depth"] - depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) - depth = depth * (self._max_depth - self._min_depth) + self._min_depth - depth = depth * 1000 - look_down_depth, resize_shape = self.preprocess_depth_image_v2( - Image.fromarray(depth.astype(np.uint16), mode='I;16'), - do_depth_scale=True, - depth_scale=1000, - target_height=224, - target_width=224, - ) - look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() - look_down_depth[look_down_depth > 5.0] = 5.0 - - env.step(4) - env.step(4) - - info = env.get_metrics() - - if len(action_seq) == 0 and goal is None: - if action != 5: - sources = copy.deepcopy(self.conversation) - sources[0]["value"] = sources[0]["value"].replace( - '.', episode.instruction.instruction_text[:-1] - ) - cur_images = rgb_list[-1:] - if step_id == 0: - history_id = [] - else: - history_id = np.unique( - np.linspace(0, step_id - 1, self.num_history, dtype=np.int32) - ).tolist() - placeholder = (DEFAULT_IMAGE_TOKEN + '\n') * len(history_id) - sources[0]["value"] += f' These are your historical observations: {placeholder}.' - - history_id = sorted(history_id) - print('history_idddddddd', step_id, history_id) - input_images = [rgb_list[i] for i in history_id] + cur_images - input_img_id = 0 - else: - assert action == 5 - sources = [{"from": "human", "value": ""}, {"from": "gpt", "value": ""}] - input_images += [look_down_image] - messages.append( - {'role': 'assistant', 'content': [{'type': 'text', 'text': llm_outputs}]} # noqa: F405 - ) - input_img_id = -1 - - prompt = random.choice(self.conjunctions) + DEFAULT_IMAGE_TOKEN - sources[0]["value"] += f" {prompt}." - print('sources', step_id, sources) - prompt_instruction = copy.deepcopy(sources[0]["value"]) - parts = split_and_clean(prompt_instruction) - - content = [] - for i in range(len(parts)): - if parts[i] == "": - content.append({"type": "image", "image": input_images[input_img_id]}) - input_img_id += 1 - else: - content.append({"type": "text", "text": parts[i]}) - - messages.append({'role': 'user', 'content': content}) - - print('step_id', step_id, 'messages:', messages) - - text = self.processor.apply_chat_template(messages, tokenize=False, add_generation_prompt=True) - - inputs = self.processor(text=[text], images=input_images, return_tensors="pt").to( - self.model.device - ) - - with torch.no_grad(): - output_ids = self.model.generate(**inputs, max_new_tokens=128, do_sample=False) - - llm_outputs = self.processor.tokenizer.decode( - output_ids[0][inputs.input_ids.shape[1] :], skip_special_tokens=True - ) - print('step_id:', step_id, 'output text:', llm_outputs) - - if bool(re.search(r'\d', llm_outputs)): - forward_action = 0 - coord = [int(c) for c in re.findall(r'\d+', llm_outputs)] - pixel_goal = [int(coord[1]), int(coord[0])] - - goal = self.pixel_to_gps(pixel_goal, depth / 1000, intrinsic_matrix, tf_camera_to_episodic) - print('before', goal, depth.shape) - goal = (transformation_matrix @ np.array([-goal[1], 0, -goal[0], 1]))[:3] - - if not env.sim.pathfinder.is_navigable(np.array(goal)): - goal = np.array(env.sim.pathfinder.snap_point(np.array(goal))) - - # look down --> horizontal - env.step(4) - env.step(4) - - # Forking logic based on mode - if self.args.mode == 'system2': - action = agent.get_next_action(goal) - if action == 0: - goal = None - output_ids = None - action = 2 # random action - print('conduct a random action 2') - observations = env.step(action) - step_id += 1 - messages = [] - continue - else: # dual-system logic - local_actions = [] - pixel_values = inputs.pixel_values - image_grid_thw = torch.cat([thw.unsqueeze(0) for thw in inputs.image_grid_thw], dim=0) - - with torch.no_grad(): - traj_latents = self.model.generate_latents(output_ids, pixel_values, image_grid_thw) - - # prepocess align with navdp - image_dp = ( - torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 - ) - pix_goal_image = copy.copy(image_dp) - images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) - depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) - pix_goal_depth = copy.copy(depth_dp) - depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) - - with torch.no_grad(): - dp_actions = self.model.generate_traj( - traj_latents, images_dp, depths_dp, use_async=True - ) - - random_choice = np.random.choice(dp_actions.shape[0]) - if self.args.continuous_traj: - action_list = traj_to_actions(dp_actions) - if len(action_list) < 8: - action_list += [0] * (8 - len(action_list)) - else: - action_list = chunk_token(dp_actions[random_choice]) - - local_actions = action_list - if len(local_actions) >= 4: - local_actions = local_actions[:4] - action = local_actions[0] - if action == 0: - goal = None - output_ids = None - action = 2 # random action - print('conduct a random action 2') - observations = env.step(action) - step_id += 1 - messages = [] - continue - - print('predicted goal', pixel_goal, goal, flush=True) - else: - action_seq = self.parse_actions(llm_outputs) - print('actions', action_seq, flush=True) - - if len(action_seq) != 0: - action = action_seq[0] - action_seq.pop(0) - elif goal is not None: - # Forking logic based on mode - if self.args.mode == 'system2': - action = agent.get_next_action(goal) - action = action.detach().cpu().numpy()[0] if isinstance(action, torch.Tensor) else action - action = action[0] if hasattr(action, "__len__") else action - else: # dual-system logic - if len(local_actions) == 0: - # navdp - local_actions = [] - image_dp = ( - torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 - ) - - images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) - depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) - - depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) - with torch.no_grad(): - dp_actions = self.model.generate_traj( - traj_latents, images_dp, depths_dp, use_async=True - ) - - random_choice = np.random.choice(dp_actions.shape[0]) - if self.args.continuous_traj: - action_list = traj_to_actions(dp_actions) - if len(action_list) < 8: - action_list += [0] * (8 - len(action_list)) - else: - action_list = chunk_token(dp_actions[random_choice]) - print("first action_list", action_list) - - local_actions = action_list - if len(local_actions) >= 4: - local_actions = local_actions[:4] - # if len(local_actions) >= 2: - # local_actions = local_actions[:2] - - print("local_actions", local_actions) - - action = local_actions.pop(0) - # navdp - else: - action = local_actions.pop(0) - - forward_action += 1 - print('forward_action', forward_action, flush=True) - if forward_action > 8: - goal = None - output_ids = None - messages = [] - step_id += 1 - forward_action = 0 - local_actions = [] - continue - if action == 0: - goal = None - output_ids = None - messages = [] - step_id += 1 - forward_action = 0 - local_actions = [] - continue - else: - action = 0 - - if info['top_down_map'] is not None: - if save_dot: - save_raw_image = self.dot_matrix_two_dimensional( - save_raw_image, save_img=False, save_path=f'test_{step_id}.jpg', pixel_goal=pixel_goal - ) - frame = observations_to_image({'rgb': np.asarray(save_raw_image)}, info) - vis_frames.append(frame) - - print("step_id", step_id, "action", action) - - # refactor: core - if action == 5: - env.step(action) - observations = env.step(action) - else: - observations = env.step(action) - step_id += 1 - messages = [] - - process_bar.update(1) - - metrics = env.get_metrics() - if self.save_video: - images_to_video( - vis_frames, - os.path.join(self.output_path, f'vis_{self.epoch}', f'{scene_id}'), - f'{episode_id:04d}', - fps=6, - quality=9, - ) - vis_frames.clear() - sucs.append(metrics['success']) - spls.append(metrics['spl']) - oss.append(metrics['oracle_success']) - nes.append(metrics["distance_to_goal"]) - print( - f"scene_episode {scene_id}_{episode_id:04d} success: {metrics['success']}, spl: {metrics['spl']}, os: {metrics['oracle_success']}, ne: {metrics['distance_to_goal']}" - ) - - result = { - "scene_id": scene_id, - "episode_id": episode_id, - "success": metrics["success"], - "spl": metrics["spl"], - "os": metrics['oracle_success'], - "ne": metrics["distance_to_goal"], - "steps": step_id, - "episode_instruction": episode_instruction, - } - - with open(os.path.join(self.output_path, 'result.json'), 'a') as f: - f.write(json.dumps(result) + "\n") - env.close() - return ( - torch.tensor(sucs).to(self.device), - torch.tensor(spls).to(self.device), - torch.tensor(oss).to(self.device), - torch.tensor(nes).to(self.device), - torch.tensor(len(sucs)).to(self.device), - ) - - def parse_actions(self, output): - action_patterns = '|'.join(re.escape(action) for action in self.actions2idx) - # import ipdb; ipdb.set_trace() - regex = re.compile(action_patterns) - matches = regex.findall(output) - actions = [self.actions2idx[match] for match in matches] - actions = itertools.chain.from_iterable(actions) - return list(actions) - - def preprocess_depth_image_v2( - self, depth_image, do_depth_scale=True, depth_scale=1000, target_height=None, target_width=None - ): - if target_height is None: - target_height = self.image_processor.crop_size['height'] # 384 - target_width = self.image_processor.crop_size['width'] # 384 - - resized_depth_image = depth_image.resize((target_width, target_height), Image.NEAREST) - - img = to_numpy_array(resized_depth_image) - if do_depth_scale: - img = img / depth_scale - - return img, (target_width, target_height) - - def get_intrinsic_matrix(self, sensor_cfg) -> np.ndarray: - width = sensor_cfg.width - height = sensor_cfg.height - fov = sensor_cfg.hfov - fx = (width / 2.0) / np.tan(np.deg2rad(fov / 2.0)) - fy = fx # Assuming square pixels (fx = fy) - cx = (width - 1.0) / 2.0 - cy = (height - 1.0) / 2.0 - - intrinsic_matrix = np.array( - [[fx, 0.0, cx, 0.0], [0.0, fy, cy, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]] - ) - return intrinsic_matrix - - def get_axis_align_matrix(self): - ma = np.array([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) - return ma - - def xyz_yaw_to_tf_matrix(self, xyz: np.ndarray, yaw: float) -> np.ndarray: - x, y, z = xyz - transformation_matrix = np.array( - [ - [np.cos(yaw), -np.sin(yaw), 0, x], - [np.sin(yaw), np.cos(yaw), 0, y], - [0, 0, 1, z], - [0, 0, 0, 1], - ] - ) - return transformation_matrix - - def xyz_pitch_to_tf_matrix(self, xyz: np.ndarray, pitch: float) -> np.ndarray: - """Converts a given position and pitch angle to a 4x4 transformation matrix. - - Args: - xyz (np.ndarray): A 3D vector representing the position. - pitch (float): The pitch angle in radians for y axis. - Returns: - np.ndarray: A 4x4 transformation matrix. - """ - - x, y, z = xyz - transformation_matrix = np.array( - [ - [np.cos(pitch), 0, np.sin(pitch), x], - [0, 1, 0, y], - [-np.sin(pitch), 0, np.cos(pitch), z], - [0, 0, 0, 1], - ] - ) - return transformation_matrix - - def xyz_yaw_pitch_to_tf_matrix(self, xyz: np.ndarray, yaw: float, pitch: float) -> np.ndarray: - """Converts a given position and yaw, pitch angles to a 4x4 transformation matrix. - - Args: - xyz (np.ndarray): A 3D vector representing the position. - yaw (float): The yaw angle in radians. - pitch (float): The pitch angle in radians for y axis. - Returns: - np.ndarray: A 4x4 transformation matrix. - """ - x, y, z = xyz - rot1 = self.xyz_yaw_to_tf_matrix(xyz, yaw)[:3, :3] - rot2 = self.xyz_pitch_to_tf_matrix(xyz, pitch)[:3, :3] - transformation_matrix = np.eye(4) - transformation_matrix[:3, :3] = rot1 @ rot2 - transformation_matrix[:3, 3] = xyz - return transformation_matrix - - def pixel_to_gps(self, pixel, depth, intrinsic, tf_camera_to_episodic): - ''' - Args: - pixel: (2,) - [u, v] pixel coordinates - depth: (H, W) - depth image where depth[v, u] gives depth in meters - intrinsic: (4, 4) - camera intrinsic matrix - tf_camera_to_episodic: (4, 4) - transformation from camera to episodic frame - Returns: - (x, y): (x, y) coordinates in the episodic frame - ''' - v, u = pixel - z = depth[v, u] - print("depthhhhhhhhhhhhhh", z) - - x = (u - intrinsic[0, 2]) * z / intrinsic[0, 0] - y = (v - intrinsic[1, 2]) * z / intrinsic[1, 1] - point_camera = np.array([x, y, z, 1.0]) - - # Transform to episodic frame - point_episodic = tf_camera_to_episodic @ point_camera - point_episodic = point_episodic[:3] / point_episodic[3] - - x = point_episodic[0] - y = point_episodic[1] - - return (x, y) # same as habitat gps - - def dot_matrix_two_dimensional( - self, - image_or_image_path, - save_path=None, - dots_size_w=8, - dots_size_h=8, - save_img=False, - font_path='fonts/arial.ttf', - pixel_goal=None, - ): - """ - takes an original image as input, save the processed image to save_path. Each dot is labeled with two-dimensional Cartesian coordinates (x,y). Suitable for single-image tasks. - control args: - 1. dots_size_w: the number of columns of the dots matrix - 2. dots_size_h: the number of rows of the dots matrix - """ - with open_image(image_or_image_path) as img: - if img.mode != 'RGB': - img = img.convert('RGB') - draw = ImageDraw.Draw(img, 'RGB') - - width, height = img.size - grid_size_w = dots_size_w + 1 - grid_size_h = dots_size_h + 1 - cell_width = width / grid_size_w - cell_height = height / grid_size_h - - font = ImageFont.truetype(font_path, width // 40) # Adjust font size if needed; default == width // 40 - - target_i = target_j = None - if pixel_goal is not None: - y_pixel, x_pixel = pixel_goal[0], pixel_goal[1] - # Validate pixel coordinates - if not (0 <= x_pixel < width and 0 <= y_pixel < height): - raise ValueError(f"pixel_goal {pixel_goal} exceeds image dimensions ({width}x{height})") - - # Convert to grid coordinates - target_i = round(x_pixel / cell_width) - target_j = round(y_pixel / cell_height) - - # Validate grid bounds - if not (1 <= target_i <= dots_size_w and 1 <= target_j <= dots_size_h): - raise ValueError( - f"pixel_goal {pixel_goal} maps to grid ({target_j},{target_i}), " - f"valid range is (1,1)-({dots_size_h},{dots_size_w})" - ) - - count = 0 - - for j in range(1, grid_size_h): - for i in range(1, grid_size_w): - x = int(i * cell_width) - y = int(j * cell_height) - - pixel_color = img.getpixel((x, y)) - # choose a more contrasting color from black and white - if pixel_color[0] + pixel_color[1] + pixel_color[2] >= 255 * 3 / 2: - opposite_color = (0, 0, 0) - else: - opposite_color = (255, 255, 255) - - if pixel_goal is not None and i == target_i and j == target_j: - opposite_color = (255, 0, 0) # Red for target - - circle_radius = width // 240 # Adjust dot size if needed; default == width // 240 - draw.ellipse( - [(x - circle_radius, y - circle_radius), (x + circle_radius, y + circle_radius)], - fill=opposite_color, - ) - - text_x, text_y = x + 3, y - count_w = count // dots_size_w - count_h = count % dots_size_w - label_str = f"({count_w+1},{count_h+1})" - draw.text((text_x, text_y), label_str, fill=opposite_color, font=font) - count += 1 - if save_img: - print(">>> dots overlaid image processed, stored in", save_path) - img.save(save_path) - return img diff --git a/internnav/internnav_habitat/habitat_vln_evaluator.py b/internnav/internnav_habitat/habitat_vln_evaluator.py index ba86d6d..9ed4c48 100644 --- a/internnav/internnav_habitat/habitat_vln_evaluator.py +++ b/internnav/internnav_habitat/habitat_vln_evaluator.py @@ -19,8 +19,6 @@ from transformers import AutoProcessor, Qwen2_5_VLForConditionalGeneration from transformers.image_utils import to_numpy_array -# Import for Habitat registry side effects — do not remove -import internnav.env.utils.habitat_extensions.measures # noqa: F401 from internnav.configs.evaluator import EvalCfg from internnav.evaluator import DistributedEvaluator, Evaluator from internnav.model.basemodel.internvla_n1.internvla_n1 import InternVLAN1ForCausalLM @@ -42,6 +40,9 @@ from habitat.tasks.nav.shortest_path_follower import ShortestPathFollower from habitat.utils.visualizations.utils import observations_to_image from habitat_baselines.config.default import get_config as get_habitat_config + + # Import for Habitat registry side effects — do not remove + import internnav.internnav_habitat.measures # noqa: F401 # isort: skip except Exception as e: print("Habitat Error:", e) print("Habitat Evaluation is not loaded.") @@ -90,7 +91,7 @@ def __init__(self, cfg: EvalCfg): cfg.env.env_settings['output_path'] = self.output_path # init agent and env - super().__init__(cfg) + super().__init__(cfg, init_agent=False) # ------------------------------------- model ------------------------------------------ self.model_args = argparse.Namespace(**cfg.agent.model_settings) @@ -449,7 +450,7 @@ def _run_local_eval(self, idx=0) -> None: # noqa: C901 output_ids = None action = 2 # random action print('conduct a random action 2') - observations = self.env.step(action) + observations, _, done, _ = self.env.step(action) step_id += 1 messages = [] continue @@ -493,7 +494,7 @@ def _run_local_eval(self, idx=0) -> None: # noqa: C901 output_ids = None action = 2 # random action print('conduct a random action 2') - observations = self.env.step(action) + observations, _, done, _ = self.env.step(action) step_id += 1 messages = [] continue diff --git a/internnav/internnav_habitat/habitat_vln_evaluator_clean.py b/internnav/internnav_habitat/habitat_vln_evaluator_new.py similarity index 100% rename from internnav/internnav_habitat/habitat_vln_evaluator_clean.py rename to internnav/internnav_habitat/habitat_vln_evaluator_new.py diff --git a/scripts/eval/bash/torchrun_eval.sh b/scripts/eval/bash/torchrun_eval.sh index ae3993c..00303c5 100644 --- a/scripts/eval/bash/torchrun_eval.sh +++ b/scripts/eval/bash/torchrun_eval.sh @@ -2,7 +2,7 @@ MID_RUN_NAME="InternVLA-N1" torchrun \ - --nproc_per_node=1 \ + --nproc_per_node=8 \ --master_port=2333 \ scripts/eval/eval.py \ --config scripts/eval/configs/habitat_cfg.py \ diff --git a/scripts/eval/configs/habitat_cfg.py b/scripts/eval/configs/habitat_cfg.py index 18a8680..33cf6b1 100644 --- a/scripts/eval/configs/habitat_cfg.py +++ b/scripts/eval/configs/habitat_cfg.py @@ -29,12 +29,12 @@ eval_type='habitat_vln', eval_settings={ # all current parse args - "local_rank": 0, # node rank - "output_path": "./logs/habitat/test_refactor_debug", # output directory for logs/results + "output_path": "./logs/habitat/test_refactor_0d00014", # output directory for logs/results "save_video": False, # whether to save videos "epoch": 0, # epoch number for logging "max_steps_per_episode": 500, # maximum steps per episode # distributed settings + "local_rank": 0, # node rank "world_size": 1, # number of distributed processes "rank": 0, # rank of current process "gpu": 0, # gpu id to use diff --git a/setup.cfg b/setup.cfg index 0bbee65..baadd6a 100644 --- a/setup.cfg +++ b/setup.cfg @@ -10,7 +10,7 @@ extra_standard_library = pkg_resources,setuptools known_first_party = internutopia, internutopia_extension, grevaluator, grbench, grmodel no_lines_before = STDLIB,LOCALFOLDER default_section = THIRDPARTY -skip_glob = internutopia/*, internutopia_extension/* +skip_glob = internutopia/*, internutopia_extension/*, internnav/scripts/eval/configs/* # ignore-words-list needs to be lowercase format. For example, if we want to From 2b0eb8b9125708be8d86d681cd1243c0f25f0ee8 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Wed, 12 Nov 2025 09:29:05 +0000 Subject: [PATCH 06/35] update new register name; tiny fix on style --- internnav/internnav_habitat/habitat_env.py | 2 +- .../internnav_habitat/habitat_n1_agent_temp.py | 3 ++- .../habitat_vln_evaluator_new.py | 2 +- scripts/eval/configs/comm_cfg.py | 16 ---------------- scripts/iros_challenge/start_eval_iros.sh | 2 +- 5 files changed, 5 insertions(+), 20 deletions(-) delete mode 100644 scripts/eval/configs/comm_cfg.py diff --git a/internnav/internnav_habitat/habitat_env.py b/internnav/internnav_habitat/habitat_env.py index 6376974..b680e94 100644 --- a/internnav/internnav_habitat/habitat_env.py +++ b/internnav/internnav_habitat/habitat_env.py @@ -38,7 +38,7 @@ def __init__(self, env_config: EnvCfg, task_config: TaskCfg): # generate episodes # self._env.episodes = self._env.episodes[0:1] # for debug self.episodes = self.generate_episodes() - print(self.episodes) + # print(self.episodes) def generate_episodes(self) -> List[Any]: """ diff --git a/internnav/internnav_habitat/habitat_n1_agent_temp.py b/internnav/internnav_habitat/habitat_n1_agent_temp.py index 0cea910..0d52524 100644 --- a/internnav/internnav_habitat/habitat_n1_agent_temp.py +++ b/internnav/internnav_habitat/habitat_n1_agent_temp.py @@ -21,7 +21,8 @@ DEFAULT_IMAGE_TOKEN = "" -class HabitatAgent: +@Agent.register("N1") +class HabitatAgent(Agent): def __init__(self, model, processor, args, device): self.model = model self.processor = processor diff --git a/internnav/internnav_habitat/habitat_vln_evaluator_new.py b/internnav/internnav_habitat/habitat_vln_evaluator_new.py index ff5e60b..2f65236 100644 --- a/internnav/internnav_habitat/habitat_vln_evaluator_new.py +++ b/internnav/internnav_habitat/habitat_vln_evaluator_new.py @@ -26,7 +26,7 @@ DEFAULT_IMAGE_TOKEN = "" -@Evaluator.register('habitat_vln') +@Evaluator.register('habitat_vlln') class HabitatVlnEvaluator(DistributedEvaluator): def __init__(self, cfg: EvalCfg): args = argparse.Namespace(**cfg.eval_settings) diff --git a/scripts/eval/configs/comm_cfg.py b/scripts/eval/configs/comm_cfg.py deleted file mode 100644 index 3c1b7bb..0000000 --- a/scripts/eval/configs/comm_cfg.py +++ /dev/null @@ -1,16 +0,0 @@ -from internnav.configs.agent import AgentCfg -from internnav.configs.evaluator import EnvCfg, EvalCfg, EvalDatasetCfg, TaskCfg - -eval_cfg = EvalCfg( - agent=AgentCfg( - server_port=8087, - model_name='cma', - ckpt_path='checkpoints/r2r/fine_tuned/cma_plus', - model_settings={}, - ), - env=EnvCfg['internutopia'], - task=TaskCfg['vln_pe'], - dataset=EvalDatasetCfg['mp3d'], - eval_type='internutopia_vln', - eval_settings={'save_to_json': False, 'vis_output': True}, -) diff --git a/scripts/iros_challenge/start_eval_iros.sh b/scripts/iros_challenge/start_eval_iros.sh index 335b614..5701241 100755 --- a/scripts/iros_challenge/start_eval_iros.sh +++ b/scripts/iros_challenge/start_eval_iros.sh @@ -40,7 +40,7 @@ mkdir -p logs SERVER_LOG="logs/${CONFIG_PREFIX}_server.log" EVAL_LOG="logs/${CONFIG_PREFIX}_eval.log" -processes=$(ps -ef | grep 'internnav/agent/utils/server.py' | grep -v grep | awk '{print $2}') +processes=$(ps -ef | grep 'scripts/eval/start_server.py' | grep -v grep | awk '{print $2}') if [ -n "$processes" ]; then for pid in $processes; do kill -9 $pid From b414ba3ddccd8f9fb5c1940748411accc24d4744 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Wed, 12 Nov 2025 09:47:09 +0000 Subject: [PATCH 07/35] latest tested --- .../{habitat_n1_agent_temp.py => habitat_n1_agent.py} | 0 .../{habitat_vln_evaluator_new.py => habitat_vlln_evaluator.py} | 0 internnav/internnav_habitat/utils.py | 0 scripts/eval/configs/habitat_cfg.py | 2 +- setup.cfg | 2 +- 5 files changed, 2 insertions(+), 2 deletions(-) rename internnav/internnav_habitat/{habitat_n1_agent_temp.py => habitat_n1_agent.py} (100%) rename internnav/internnav_habitat/{habitat_vln_evaluator_new.py => habitat_vlln_evaluator.py} (100%) delete mode 100644 internnav/internnav_habitat/utils.py diff --git a/internnav/internnav_habitat/habitat_n1_agent_temp.py b/internnav/internnav_habitat/habitat_n1_agent.py similarity index 100% rename from internnav/internnav_habitat/habitat_n1_agent_temp.py rename to internnav/internnav_habitat/habitat_n1_agent.py diff --git a/internnav/internnav_habitat/habitat_vln_evaluator_new.py b/internnav/internnav_habitat/habitat_vlln_evaluator.py similarity index 100% rename from internnav/internnav_habitat/habitat_vln_evaluator_new.py rename to internnav/internnav_habitat/habitat_vlln_evaluator.py diff --git a/internnav/internnav_habitat/utils.py b/internnav/internnav_habitat/utils.py deleted file mode 100644 index e69de29..0000000 diff --git a/scripts/eval/configs/habitat_cfg.py b/scripts/eval/configs/habitat_cfg.py index 33cf6b1..de96107 100644 --- a/scripts/eval/configs/habitat_cfg.py +++ b/scripts/eval/configs/habitat_cfg.py @@ -29,7 +29,7 @@ eval_type='habitat_vln', eval_settings={ # all current parse args - "output_path": "./logs/habitat/test_refactor_0d00014", # output directory for logs/results + "output_path": "./logs/habitat/test_refactor_7e25e72", # output directory for logs/results "save_video": False, # whether to save videos "epoch": 0, # epoch number for logging "max_steps_per_episode": 500, # maximum steps per episode diff --git a/setup.cfg b/setup.cfg index baadd6a..3acbb93 100644 --- a/setup.cfg +++ b/setup.cfg @@ -45,4 +45,4 @@ per-file-ignores=*/__init__.py:F401 ignore=E402,E501,W503,E203,D401,R504,R505,SIM102,SIM117,E711,E226 max-line-length = 120 max-complexity = 30 -exclude=_*,.vscode,.git,docs/**,**/test/**,**/lcmtypes/**,*.ipynb,internnav/internnav_habitat/habitat_n1_agent_temp.py +exclude=_*,.vscode,.git,docs/**,**/test/**,**/lcmtypes/**,*.ipynb,internnav/internnav_habitat/habitat_n1_agent.py From 99adf731eab7f88e85d89f895641d0ef90ea4ba0 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Wed, 12 Nov 2025 09:49:43 +0000 Subject: [PATCH 08/35] delete temp agent; rename default evaluator for habitat --- ...luator.py => habitat_default_evaluator.py} | 0 .../internnav_habitat/habitat_n1_agent.py | 751 ------------------ setup.cfg | 2 +- 3 files changed, 1 insertion(+), 752 deletions(-) rename internnav/internnav_habitat/{habitat_vlln_evaluator.py => habitat_default_evaluator.py} (100%) delete mode 100644 internnav/internnav_habitat/habitat_n1_agent.py diff --git a/internnav/internnav_habitat/habitat_vlln_evaluator.py b/internnav/internnav_habitat/habitat_default_evaluator.py similarity index 100% rename from internnav/internnav_habitat/habitat_vlln_evaluator.py rename to internnav/internnav_habitat/habitat_default_evaluator.py diff --git a/internnav/internnav_habitat/habitat_n1_agent.py b/internnav/internnav_habitat/habitat_n1_agent.py deleted file mode 100644 index 0d52524..0000000 --- a/internnav/internnav_habitat/habitat_n1_agent.py +++ /dev/null @@ -1,751 +0,0 @@ -import copy -import itertools -import os -import re -import sys -from pathlib import Path - -import numpy as np -import torch - -sys.path.append(str(Path(__file__).parent.parent.parent)) - -from collections import OrderedDict - -from PIL import Image -from transformers import AutoProcessor, Qwen2_5_VLForConditionalGeneration - -from internnav.model.basemodel.internvla_n1.internvla_n1 import InternVLAN1ForCausalLM -from internnav.model.utils.vln_utils import split_and_clean, traj_to_actions - -DEFAULT_IMAGE_TOKEN = "" - - -@Agent.register("N1") -class HabitatAgent(Agent): - def __init__(self, model, processor, args, device): - self.model = model - self.processor = processor - self.args = args - self.device = device - # ------------------------------------- model ------------------------------------------ - processor = AutoProcessor.from_pretrained(args.model_path) - processor.tokenizer.padding_side = 'left' - - device = torch.device(f"cuda:{self.local_rank}") - if args.mode == 'dual_system': - model = InternVLAN1ForCausalLM.from_pretrained( - args.model_path, - torch_dtype=torch.bfloat16, - attn_implementation="flash_attention_2", - device_map={"": device}, - ) - elif args.mode == 'system2': - model = Qwen2_5_VLForConditionalGeneration.from_pretrained( - args.model_path, - torch_dtype=torch.bfloat16, - attn_implementation="flash_attention_2", - device_map={"": device}, - ) - else: - raise ValueError(f"Invalid mode: {args.mode}") - - model.eval() - self.device = device - - self.model = model - self.processor = processor - - # refactor: this part used in three places - prompt = "You are an autonomous navigation assistant. Your task is to . Where should you go next to stay on track? Please output the next waypoint\'s coordinates in the image. Please output STOP when you have successfully completed the task." - answer = "" - self.conversation = [{"from": "human", "value": prompt}, {"from": "gpt", "value": answer}] - - self.conjunctions = [ - 'you can see ', - 'in front of you is ', - 'there is ', - 'you can spot ', - 'you are toward the ', - 'ahead of you is ', - 'in your sight is ', - ] - - self.actions2idx = OrderedDict( - { - 'STOP': [0], - "↑": [1], - "←": [2], - "→": [3], - "↓": [5], - } - ) - - self.objectnav_instructions = ["Search for the {target_object}."] - - self.num_frames = args.num_frames - self.num_future_steps = args.num_future_steps - self.num_history = args.num_history - - def reset(self, episode, env): - """Clear all per-episode state.""" - self.rgb_list = [] - self.action_seq = [] - self.output_ids = None - self.goal = None - self.messages = [] - self.local_actions = [] - self.forward_action = 0 - - # maybe store initial transforms you need for this ep: - self.initial_agent_state = env.get_agent_state() - self.initial_height = self.initial_agent_state.position[1] - - def act(self, observations, env, info): - """ - Pure policy step: - - given obs (rgb/depth/gps/compass) + optional env/info - - update internal state (goal, messages, local_actions, etc.) - - return a single action (int) - """ - # 1) unpack obs: rgb, depth, gps, compass, etc. - # 2) handle 'look down' case - # 3) maybe call LLM to get pixel goal or action_seq - # 4) maybe call diffusion policy to get local_actions - # 5) choose final `action` (0..5) - # 6) return `action` - return action - - def _run_local_eval(self, idx=0) -> None: # noqa: C901 - """ - Run local evaluation on this rank. - - Important: if resuming from previous results, need to read from / write to "self.output_path/progress.json". - For each episode, save the result dict in jsonl format to that file. - In Env, the episodes are already filtered by this file, tasks that have the same (scene_id, episode_id) are skipped. - - - Returns - ------- - dict[str, Tensor]: - { - "sucs": [N_local], - "spls": [N_local], - "oss": [N_local], - "nes": [N_local], - } - """ - # Create / get env - # self.env = self.env # HabitatEnv from DistributedEvaluator - - sucs, spls, oss, nes = [], [], [], [] - self.model.eval() - - # resume from previous results - # TODO: Current read write op is not distributed safe - if os.path.exists(os.path.join(self.output_path, 'progress.json')): - with open(os.path.join(self.output_path, 'progress.json'), 'r') as f: - for line in f.readlines(): - res = json.loads(line) - if "scene_id" not in res: - print("This evaluation has already finished!") - return ( - torch.tensor(sucs).to(self.device), - torch.tensor(spls).to(self.device), - torch.tensor(oss).to(self.device), - torch.tensor(nes).to(self.device), - torch.tensor(len(sucs)).to(self.device), - ) - if idx == 0: # noqa: F405 TODO this need to keep in evaluator - sucs.append(res['success']) - spls.append(res['spl']) - oss.append(res['os']) - nes.append(res['ne']) - - # Episode loop is now driven by env.reset() + env.is_running - process_bar = tqdm.tqdm(total=len(self.env.episodes), desc=f"Eval Epoch {self.epoch} Rank {idx}") - while self.env.is_running: - - # ------------ 1. Start of episode ------------ - observations = self.env.reset() - if not self.env.is_running or observations is None: - break - - # ---- episode meta (scene_id, episode_id, instruction) ---- - # we get it from the underlying habitat env - episode = self.env.get_current_episode() - scene_id = episode.scene_id.split('/')[-2] - episode_id = int(episode.episode_id) - episode_instruction = ( - episode.instruction.instruction_text if 'objectnav' not in self.config_path else episode.object_category - ) - print("episode start", episode_instruction) - - agent_state = self.env._env.sim.get_agent_state() - rotation = agent_state.rotation - translation = agent_state.position - rotation_matrix = quaternion.as_rotation_matrix(rotation) - transformation_matrix = np.eye(4) - transformation_matrix[:3, :3] = rotation_matrix - transformation_matrix[:3, 3] = translation - - agent = ShortestPathFollower(self.env._env.sim, 0.25, False) - - os.makedirs(os.path.join(self.output_path, f'check_sim_{self.epoch}'), exist_ok=True) - Image.fromarray(observations['rgb']).save( - os.path.join(self.output_path, f'check_sim_{self.epoch}', f'rgb_{idx}.jpg') - ) - - vis_frames = [] - step_id = 0 - - if self.save_video: - os.makedirs(os.path.join(self.output_path, f'vis_{self.epoch}', f'{scene_id}'), exist_ok=True) - initial_height = self.env._env.sim.get_agent_state().position[1] - - rgb_list = [] - action_seq = [] - output_ids = None - - goal = None - action = None - messages = [] - local_actions = [] - - done = False - - # ---------- 2. Episode step loop ----------- - while (not done) and (step_id <= self.max_steps_per_episode): - # refactor agent get action - rgb = observations["rgb"] - depth = observations["depth"] - x, y = observations["gps"] - camera_yaw = observations["compass"][0] - depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) - depth = depth * (self._max_depth - self._min_depth) + self._min_depth - depth = depth * 1000 - - agent_state = self.env._env.sim.get_agent_state() - height = agent_state.position[1] - initial_height - camera_position = np.array([x, -y, self._camera_height + height]) - tf_camera_to_episodic = ( - self.xyz_yaw_pitch_to_tf_matrix(camera_position, camera_yaw, np.deg2rad(30)) - @ self.get_axis_align_matrix() - ) - - image = Image.fromarray(rgb).convert('RGB') - save_raw_image = image.copy() - - save_dot = False - if action == 5: - look_down_image = image - save_raw_image = look_down_image.copy() - look_down_depth, resize_shape = self.preprocess_depth_image_v2( - Image.fromarray(depth.astype(np.uint16), mode='I;16'), - do_depth_scale=True, - depth_scale=1000, - target_height=224, - target_width=224, - ) - look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() - look_down_depth[look_down_depth > 5.0] = 5.0 - else: - image = image.resize((self.args.resize_w, self.args.resize_h)) - rgb_list.append(image) - - if self.args.mode == 'dual_system': - down_observations, _, done, _ = self.env.step(5) - down_observations, _, done, _ = self.env.step(5) - - look_down_image = Image.fromarray(down_observations["rgb"]).convert('RGB') - depth = down_observations["depth"] - depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) - depth = depth * (self._max_depth - self._min_depth) + self._min_depth - depth = depth * 1000 - look_down_depth, resize_shape = self.preprocess_depth_image_v2( - Image.fromarray(depth.astype(np.uint16), mode='I;16'), - do_depth_scale=True, - depth_scale=1000, - target_height=224, - target_width=224, - ) - look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() - look_down_depth[look_down_depth > 5.0] = 5.0 - - self.env.step(4) - self.env.step(4) - - info = self.env.get_metrics() - - if len(action_seq) == 0 and goal is None: - if action != 5: - sources = copy.deepcopy(self.conversation) - sources[0]["value"] = sources[0]["value"].replace( - '.', episode.instruction.instruction_text[:-1] - ) - cur_images = rgb_list[-1:] - if step_id == 0: - history_id = [] - else: - history_id = np.unique( - np.linspace(0, step_id - 1, self.num_history, dtype=np.int32) - ).tolist() - placeholder = (DEFAULT_IMAGE_TOKEN + '\n') * len(history_id) - sources[0]["value"] += f' These are your historical observations: {placeholder}.' - - history_id = sorted(history_id) - print('history_idddddddd', step_id, history_id) - input_images = [rgb_list[i] for i in history_id] + cur_images - input_img_id = 0 - else: - assert action == 5 - sources = [{"from": "human", "value": ""}, {"from": "gpt", "value": ""}] - input_images += [look_down_image] - # messages.append( - # {'role': 'assistant', 'content': [{'type': 'text', 'text': llm_outputs}]} # noqa: F405 - # ) - input_img_id = -1 - - prompt = random.choice(self.conjunctions) + DEFAULT_IMAGE_TOKEN - sources[0]["value"] += f" {prompt}." - print('sources', step_id, sources) - prompt_instruction = copy.deepcopy(sources[0]["value"]) - parts = split_and_clean(prompt_instruction) - - content = [] - for i in range(len(parts)): - if parts[i] == "": - content.append({"type": "image", "image": input_images[input_img_id]}) - input_img_id += 1 - else: - content.append({"type": "text", "text": parts[i]}) - - messages.append({'role': 'user', 'content': content}) - - print('step_id', step_id, 'messages:', messages) - - text = self.processor.apply_chat_template(messages, tokenize=False, add_generation_prompt=True) - - inputs = self.processor(text=[text], images=input_images, return_tensors="pt").to(self.model.device) - - with torch.no_grad(): - output_ids = self.model.generate(**inputs, max_new_tokens=128, do_sample=False) - - llm_outputs = self.processor.tokenizer.decode( - output_ids[0][inputs.input_ids.shape[1] :], skip_special_tokens=True - ) - print('step_id:', step_id, 'output text:', llm_outputs) - - if bool(re.search(r'\d', llm_outputs)): - forward_action = 0 - coord = [int(c) for c in re.findall(r'\d+', llm_outputs)] - pixel_goal = [int(coord[1]), int(coord[0])] - - intrinsic_matrix = self.get_intrinsic_matrix( - self.config.habitat.simulator.agents.main_agent.sim_sensors.rgb_sensor - ) - goal = self.pixel_to_gps(pixel_goal, depth / 1000, intrinsic_matrix, tf_camera_to_episodic) - print('before', goal, depth.shape) - goal = (transformation_matrix @ np.array([-goal[1], 0, -goal[0], 1]))[:3] - - if not self.env._env.sim.pathfinder.is_navigable(np.array(goal)): - goal = np.array(self.env._env.sim.pathfinder.snap_point(np.array(goal))) - - # look down --> horizontal - self.env.step(4) - self.env.step(4) - - # Forking logic based on mode - if self.args.mode == 'system2': - action = agent.get_next_action(goal) - if action == 0: - goal = None - output_ids = None - action = 2 # random action - print('conduct a random action 2') - observations = self.env.step(action) - step_id += 1 - messages = [] - continue - else: # dual-system logic - local_actions = [] - pixel_values = inputs.pixel_values - image_grid_thw = torch.cat([thw.unsqueeze(0) for thw in inputs.image_grid_thw], dim=0) - - with torch.no_grad(): - traj_latents = self.model.generate_latents(output_ids, pixel_values, image_grid_thw) - - # prepocess align with navdp - image_dp = ( - torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 - ) - pix_goal_image = copy.copy(image_dp) - images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) - depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) - pix_goal_depth = copy.copy(depth_dp) - depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) - - with torch.no_grad(): - dp_actions = self.model.generate_traj( - traj_latents, images_dp, depths_dp, use_async=True - ) - - random_choice = np.random.choice(dp_actions.shape[0]) - if self.args.continuous_traj: - action_list = traj_to_actions(dp_actions) - if len(action_list) < 8: - action_list += [0] * (8 - len(action_list)) - else: - action_list = chunk_token(dp_actions[random_choice]) - - local_actions = action_list - if len(local_actions) >= 4: - local_actions = local_actions[:4] - action = local_actions[0] - if action == 0: - goal = None - output_ids = None - action = 2 # random action - print('conduct a random action 2') - observations = self.env.step(action) - step_id += 1 - messages = [] - continue - - print('predicted goal', pixel_goal, goal, flush=True) - else: - action_seq = self.parse_actions(llm_outputs) - print('actions', action_seq, flush=True) - - if len(action_seq) != 0: - action = action_seq[0] - action_seq.pop(0) - elif goal is not None: - # Forking logic based on mode - if self.args.mode == 'system2': - action = agent.get_next_action(goal) - action = action.detach().cpu().numpy()[0] if isinstance(action, torch.Tensor) else action - action = action[0] if hasattr(action, "__len__") else action - else: # dual-system logic - if len(local_actions) == 0: - # navdp - local_actions = [] - image_dp = ( - torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) / 255 - ) - - images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0).to(self.device) - depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) - - depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0).to(self.device) - with torch.no_grad(): - dp_actions = self.model.generate_traj( - traj_latents, images_dp, depths_dp, use_async=True - ) - - random_choice = np.random.choice(dp_actions.shape[0]) - if self.args.continuous_traj: - action_list = traj_to_actions(dp_actions) - if len(action_list) < 8: - action_list += [0] * (8 - len(action_list)) - else: - action_list = chunk_token(dp_actions[random_choice]) - print("first action_list", action_list) - - local_actions = action_list - if len(local_actions) >= 4: - local_actions = local_actions[:4] - # if len(local_actions) >= 2: - # local_actions = local_actions[:2] - - print("local_actions", local_actions) - - action = local_actions.pop(0) - # navdp - else: - action = local_actions.pop(0) - - forward_action += 1 - print('forward_action', forward_action, flush=True) - if forward_action > 8: - goal = None - output_ids = None - messages = [] - step_id += 1 - forward_action = 0 - local_actions = [] - continue - if action == 0: - goal = None - output_ids = None - messages = [] - step_id += 1 - forward_action = 0 - local_actions = [] - continue - else: - action = 0 - - if info['top_down_map'] is not None: - if save_dot: - save_raw_image = self.dot_matrix_two_dimensional( - save_raw_image, save_img=False, save_path=f'test_{step_id}.jpg', pixel_goal=pixel_goal - ) - if self.save_video: - frame = observations_to_image({'rgb': np.asarray(save_raw_image)}, info) - vis_frames.append(frame) - - print("step_id", step_id, "action", action) - - # refactor: core - if action == 5: - self.env.step(action) - observations, _, done, _ = self.env.step(action) - else: - observations, _, done, _ = self.env.step(action) - step_id += 1 - messages = [] - - # ---------- 3. End of episode ----------- - # Update result and write progress to the output_path/progress.json - - process_bar.update(1) - - # After the episode finishes, collect metrics: - metrics = self.env.get_metrics() - - sucs.append(metrics['success']) - spls.append(metrics['spl']) - oss.append(metrics['oracle_success']) - nes.append(metrics["distance_to_goal"]) - - print( - f"scene_episode {scene_id}_{episode_id:04d} success: {metrics['success']}, " - f"spl: {metrics['spl']}, os: {metrics['oracle_success']}, " - f"ne: {metrics['distance_to_goal']}" - ) - - # Write per-episode result.json entry (still per-rank) - result = { - "scene_id": scene_id, - "episode_id": episode_id, - "success": metrics["success"], - "spl": metrics["spl"], - "os": metrics['oracle_success'], - "ne": metrics["distance_to_goal"], - "steps": step_id, - "episode_instruction": episode_instruction, - } - os.makedirs(self.output_path, exist_ok=True) - with open(os.path.join(self.output_path, 'progress.json'), 'a') as f: - f.write(json.dumps(result) + "\n") - - self.env.close() - - return { - "sucs": torch.tensor(sucs, device=self.device), - "spls": torch.tensor(spls, device=self.device), - "oss": torch.tensor(oss, device=self.device), - "nes": torch.tensor(nes, device=self.device), - } - - def parse_actions(self, output): - action_patterns = '|'.join(re.escape(action) for action in self.actions2idx) - # import ipdb; ipdb.set_trace() - regex = re.compile(action_patterns) - matches = regex.findall(output) - actions = [self.actions2idx[match] for match in matches] - actions = itertools.chain.from_iterable(actions) - return list(actions) - - def preprocess_depth_image_v2( - self, depth_image, do_depth_scale=True, depth_scale=1000, target_height=None, target_width=None - ): - if target_height is None: - target_height = self.image_processor.crop_size['height'] # 384 - target_width = self.image_processor.crop_size['width'] # 384 - - resized_depth_image = depth_image.resize((target_width, target_height), Image.NEAREST) - - img = to_numpy_array(resized_depth_image) - if do_depth_scale: - img = img / depth_scale - - return img, (target_width, target_height) - - def get_intrinsic_matrix(self, sensor_cfg) -> np.ndarray: - width = sensor_cfg.width - height = sensor_cfg.height - fov = sensor_cfg.hfov - fx = (width / 2.0) / np.tan(np.deg2rad(fov / 2.0)) - fy = fx # Assuming square pixels (fx = fy) - cx = (width - 1.0) / 2.0 - cy = (height - 1.0) / 2.0 - - intrinsic_matrix = np.array( - [[fx, 0.0, cx, 0.0], [0.0, fy, cy, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]] - ) - return intrinsic_matrix - - def get_axis_align_matrix(self): - ma = np.array([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) - return ma - - def xyz_yaw_to_tf_matrix(self, xyz: np.ndarray, yaw: float) -> np.ndarray: - x, y, z = xyz - transformation_matrix = np.array( - [ - [np.cos(yaw), -np.sin(yaw), 0, x], - [np.sin(yaw), np.cos(yaw), 0, y], - [0, 0, 1, z], - [0, 0, 0, 1], - ] - ) - return transformation_matrix - - def xyz_pitch_to_tf_matrix(self, xyz: np.ndarray, pitch: float) -> np.ndarray: - """Converts a given position and pitch angle to a 4x4 transformation matrix. - - Args: - xyz (np.ndarray): A 3D vector representing the position. - pitch (float): The pitch angle in radians for y axis. - Returns: - np.ndarray: A 4x4 transformation matrix. - """ - - x, y, z = xyz - transformation_matrix = np.array( - [ - [np.cos(pitch), 0, np.sin(pitch), x], - [0, 1, 0, y], - [-np.sin(pitch), 0, np.cos(pitch), z], - [0, 0, 0, 1], - ] - ) - return transformation_matrix - - def xyz_yaw_pitch_to_tf_matrix(self, xyz: np.ndarray, yaw: float, pitch: float) -> np.ndarray: - """Converts a given position and yaw, pitch angles to a 4x4 transformation matrix. - - Args: - xyz (np.ndarray): A 3D vector representing the position. - yaw (float): The yaw angle in radians. - pitch (float): The pitch angle in radians for y axis. - Returns: - np.ndarray: A 4x4 transformation matrix. - """ - x, y, z = xyz - rot1 = self.xyz_yaw_to_tf_matrix(xyz, yaw)[:3, :3] - rot2 = self.xyz_pitch_to_tf_matrix(xyz, pitch)[:3, :3] - transformation_matrix = np.eye(4) - transformation_matrix[:3, :3] = rot1 @ rot2 - transformation_matrix[:3, 3] = xyz - return transformation_matrix - - def pixel_to_gps(self, pixel, depth, intrinsic, tf_camera_to_episodic): - ''' - Args: - pixel: (2,) - [u, v] pixel coordinates - depth: (H, W) - depth image where depth[v, u] gives depth in meters - intrinsic: (4, 4) - camera intrinsic matrix - tf_camera_to_episodic: (4, 4) - transformation from camera to episodic frame - Returns: - (x, y): (x, y) coordinates in the episodic frame - ''' - v, u = pixel - z = depth[v, u] - print("depthhhhhhhhhhhhhh", z) - - x = (u - intrinsic[0, 2]) * z / intrinsic[0, 0] - y = (v - intrinsic[1, 2]) * z / intrinsic[1, 1] - point_camera = np.array([x, y, z, 1.0]) - - # Transform to episodic frame - point_episodic = tf_camera_to_episodic @ point_camera - point_episodic = point_episodic[:3] / point_episodic[3] - - x = point_episodic[0] - y = point_episodic[1] - - return (x, y) # same as habitat gps - - def dot_matrix_two_dimensional( - self, - image_or_image_path, - save_path=None, - dots_size_w=8, - dots_size_h=8, - save_img=False, - font_path='fonts/arial.ttf', - pixel_goal=None, - ): - """ - takes an original image as input, save the processed image to save_path. Each dot is labeled with two-dimensional Cartesian coordinates (x,y). Suitable for single-image tasks. - control args: - 1. dots_size_w: the number of columns of the dots matrix - 2. dots_size_h: the number of rows of the dots matrix - """ - with open_image(image_or_image_path) as img: - if img.mode != 'RGB': - img = img.convert('RGB') - draw = ImageDraw.Draw(img, 'RGB') - - width, height = img.size - grid_size_w = dots_size_w + 1 - grid_size_h = dots_size_h + 1 - cell_width = width / grid_size_w - cell_height = height / grid_size_h - - font = ImageFont.truetype(font_path, width // 40) # Adjust font size if needed; default == width // 40 - - target_i = target_j = None - if pixel_goal is not None: - y_pixel, x_pixel = pixel_goal[0], pixel_goal[1] - # Validate pixel coordinates - if not (0 <= x_pixel < width and 0 <= y_pixel < height): - raise ValueError(f"pixel_goal {pixel_goal} exceeds image dimensions ({width}x{height})") - - # Convert to grid coordinates - target_i = round(x_pixel / cell_width) - target_j = round(y_pixel / cell_height) - - # Validate grid bounds - if not (1 <= target_i <= dots_size_w and 1 <= target_j <= dots_size_h): - raise ValueError( - f"pixel_goal {pixel_goal} maps to grid ({target_j},{target_i}), " - f"valid range is (1,1)-({dots_size_h},{dots_size_w})" - ) - - count = 0 - - for j in range(1, grid_size_h): - for i in range(1, grid_size_w): - x = int(i * cell_width) - y = int(j * cell_height) - - pixel_color = img.getpixel((x, y)) - # choose a more contrasting color from black and white - if pixel_color[0] + pixel_color[1] + pixel_color[2] >= 255 * 3 / 2: - opposite_color = (0, 0, 0) - else: - opposite_color = (255, 255, 255) - - if pixel_goal is not None and i == target_i and j == target_j: - opposite_color = (255, 0, 0) # Red for target - - circle_radius = width // 240 # Adjust dot size if needed; default == width // 240 - draw.ellipse( - [(x - circle_radius, y - circle_radius), (x + circle_radius, y + circle_radius)], - fill=opposite_color, - ) - - text_x, text_y = x + 3, y - count_w = count // dots_size_w - count_h = count % dots_size_w - label_str = f"({count_w+1},{count_h+1})" - draw.text((text_x, text_y), label_str, fill=opposite_color, font=font) - count += 1 - if save_img: - print(">>> dots overlaid image processed, stored in", save_path) - img.save(save_path) - return img diff --git a/setup.cfg b/setup.cfg index 3acbb93..dd5d8f9 100644 --- a/setup.cfg +++ b/setup.cfg @@ -45,4 +45,4 @@ per-file-ignores=*/__init__.py:F401 ignore=E402,E501,W503,E203,D401,R504,R505,SIM102,SIM117,E711,E226 max-line-length = 120 max-complexity = 30 -exclude=_*,.vscode,.git,docs/**,**/test/**,**/lcmtypes/**,*.ipynb,internnav/internnav_habitat/habitat_n1_agent.py +exclude=_*,.vscode,.git,docs/**,**/test/**,**/lcmtypes/**,*.ipynb From 75b38a7fc7c70e7f1438949d679412ddbe9bc129 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Wed, 12 Nov 2025 09:51:15 +0000 Subject: [PATCH 09/35] update slurm bash --- scripts/eval/bash/eval_dual_system.sh | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/scripts/eval/bash/eval_dual_system.sh b/scripts/eval/bash/eval_dual_system.sh index ef4be1e..56e4b40 100755 --- a/scripts/eval/bash/eval_dual_system.sh +++ b/scripts/eval/bash/eval_dual_system.sh @@ -12,8 +12,6 @@ srun -p efm_t \ --ntasks-per-node=8 \ --cpus-per-task=16 \ --kill-on-bad-exit=1 \ - python scripts/eval/eval_habitat.py \ - --model_path checkpoints/${MID_RUN_NAME} \ - --predict_step_nums 32 \ - --continuous_traj \ - --output_path results/$MID_RUN_NAME/val_unseen_32traj_8steps \ + python scripts/eval/eval.py \ + --config scripts/eval/configs/habitat_cfg.py \ + > logs/${MID_RUN_NAME}_log.txt 2>&1 From 08bb9c33f4e8058945475e92185e91be140957c2 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Wed, 12 Nov 2025 10:03:53 +0000 Subject: [PATCH 10/35] update readme --- internnav/internnav_habitat/README.md | 135 ++++++++++++++++++++++++++ 1 file changed, 135 insertions(+) diff --git a/internnav/internnav_habitat/README.md b/internnav/internnav_habitat/README.md index 03779de..b7c5d73 100644 --- a/internnav/internnav_habitat/README.md +++ b/internnav/internnav_habitat/README.md @@ -1 +1,136 @@ # Habitat in InternNav + +This package adapts [Meta AI Habitat](https://aihabitat.org) environments and +metrics so they can be used from InternNav's evaluation framework. It provides +an environment wrapper, custom measurements, and evaluator implementations that +bridge Habitat simulations with InternNav agents and distributed evaluation +utilities. + +## Package structure + +``` +internnav_habitat/ +├── __init__.py +├── habitat_env.py +├── habitat_default_evaluator.py +├── habitat_vln_evaluator.py +├── measures.py +└── refactor_notes.md +``` + +* `__init__.py` re-exports the public entry points for the environment and the + VLN evaluator so they can be imported as + `from internnav.internnav_habitat import HabitatEnv`. +* `habitat_env.py` implements the `Env` subclass that wraps Habitat's + `Env` object. It bootstraps episodes, handles sharding across distributed + ranks, and adapts Habitat's observations to InternNav's expectations. +* `habitat_default_evaluator.py` contains a lightweight evaluator that runs a + conventional Habitat agent inside the InternNav evaluator loop. +* `habitat_vln_evaluator.py` is the task-specific evaluator used for Vision- + and-Language Navigation (VLN). It loads InternNav vision-language models, + orchestrates inference, and logs results during distributed evaluation. +* `measures.py` registers additional Habitat measurements (path length, + oracle metrics, step counts) that are required by the evaluators. + +The `refactor_notes.md` file captures design notes and TODOs collected during a +previous refactoring pass. + +## Habitat environment wrapper + +`HabitatEnv` is registered under the key `"habitat"` via the shared +`Env.register` decorator. When InternNav builds an environment from an +`EnvCfg`, the wrapper: + +1. Imports and instantiates the Habitat `Env` using the configuration object + provided in `env_settings['habitat_config']`. +2. Stores the distributed context (`local_rank`, `world_size`) and any output + directory override (`output_path`). +3. Pre-computes the episode list by grouping Habitat episodes by scene, + filtering completed episodes via `progress.json`, and sharding the remaining + work by rank. +4. Implements the standard reset/step/close/render accessors expected by the + InternNav `Env` base class while delegating to the underlying Habitat + simulator. + +This design keeps the Habitat-specific logic isolated from the rest of the +framework and ensures that distributed evaluation proceeds deterministically +across ranks. + +## Evaluation pipeline + +InternNav evaluators extend the shared `DistributedEvaluator` base class, which +handles distributed initialization, environment instantiation, metric +aggregation, and result logging. The Habitat integration provides two +implementations: + +### `HabitatVlnEvaluator` + +The VLN evaluator (`habitat_vln_evaluator.py`) is responsible for coordinating +model inference in Habitat scenes. + +* **Configuration:** During initialization the evaluator reads an `EvalCfg` + whose `env.env_settings['config_path']` points to a Habitat YAML file. The + config is loaded with Habitat's baseline utilities, sensor intrinsics are + cached, and custom measurements (`top_down_map`, `collisions`) are enabled. +* **Environment binding:** The Habitat configuration is injected back into the + `EnvCfg` so the shared `DistributedEvaluator` base class can create the + `HabitatEnv` wrapper with the correct settings. +* **Model loading:** Depending on `cfg.agent.model_settings.mode`, the evaluator + loads either the InternVLA dual-system model or a Qwen2.5-VL model using + Hugging Face Transformers. The processor is configured with left padding and + the model is moved to the rank-local GPU. +* **Episode loop:** + 1. `HabitatEnv.reset()` advances to the next episode and returns the first + observation. + 2. The evaluator reads episode metadata (scene, instruction) from Habitat, + constructs prompt messages, and collects RGB/depth history for the + language model. + 3. Visual inputs are prepared (resizing, optional look-down depth capture) and + depth maps are filtered through `filter_depth` to remove sensor noise. + 4. The evaluator queries the loaded model for the next action sequence, + translates model tokens to Habitat actions via `traj_to_actions`, and + steps the environment. + 5. Per-episode metrics (`success`, `SPL`, oracle success, navigation error) + are appended and checkpointed to `progress.json` for resumability. +* **Aggregation:** After all ranks finish, inherited utilities gather per-rank + tensors, compute global averages, and write `result.json` in + `output_path`. + +### `HabitatVlnEvaluator` (baseline) + +The default evaluator in `habitat_default_evaluator.py` offers a simpler loop +where a pre-built InternNav agent interacts with the Habitat environment. +InternNav's agent abstraction is reset with each new Habitat episode, and +per-step actions are produced via `agent.act()`. The evaluator records the same +metrics as the VLN evaluator, making it useful for baselines or sanity checks. + +## Custom Habitat measurements + +`measures.py` registers a suite of metrics with Habitat's registry so that they +are available in the Habitat configuration: + +* `PathLength`: cumulative Euclidean distance traveled by the agent. +* `OracleNavigationError`: minimum geodesic distance to the goal along the + trajectory. +* `OracleSuccess`: binary success metric derived from oracle navigation error + relative to a goal radius (default 3.0 meters). +* `OracleSPL`: best Success weighted by Path Length value observed during the + trajectory. +* `StepsTaken`: number of actions issued by the agent, including STOP. + +These metrics complement Habitat's built-in success and SPL scores, allowing +InternNav to report a richer set of statistics. + +## Extending the integration + +* **Adding evaluators:** Subclass `DistributedEvaluator`, supply + Habitat-specific initialization similar to `HabitatVlnEvaluator`, and + implement `eval_action` and `calc_metrics`. +* **Custom sensors or observations:** Augment the Habitat YAML configuration and + update `HabitatEnv` or the evaluator to consume the new observation keys. +* **Additional metrics:** Register new measures in `measures.py` and enable them + in the Habitat config via `config.habitat.task.measurements.update(...)`. + +By centralizing Habitat-specific logic in this package, InternNav can swap in +other simulators or extend Habitat support without touching the rest of the +training and evaluation stack. From cde84b3933f55ba2ac2ba71b07b2daf9ec020998 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Thu, 13 Nov 2025 03:49:13 +0000 Subject: [PATCH 11/35] fix init dist print --- internnav/evaluator/distributed_base.py | 11 ++--------- internnav/utils/dist.py | 9 +++++++-- 2 files changed, 9 insertions(+), 11 deletions(-) diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index 94bfc06..4327c8a 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -22,19 +22,12 @@ class DistributedEvaluator(Evaluator): def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True): # distributed setting - import socket - - print( - f"Rank {os.getenv('RANK')} / {os.getenv('WORLD_SIZE')} on {socket.gethostname()}:{os.getenv('MASTER_PORT')}" - ) - - self.output_path = cfg.eval_settings["output_path"] # TODO: unsafe for distribution - - init_distributed_mode() + init_distributed_mode(dist_url=cfg.eval_settings['dist_url'], port=cfg.eval_settings['port']) self.local_rank = get_rank() np.random.seed(self.local_rank) self.world_size = get_world_size() + self.output_path = cfg.eval_settings["output_path"] # TODO: unsafe for distribution # habitat env also need rank to split dataset cfg.env.env_settings['local_rank'] = get_rank() diff --git a/internnav/utils/dist.py b/internnav/utils/dist.py index 82c14a3..7a65599 100644 --- a/internnav/utils/dist.py +++ b/internnav/utils/dist.py @@ -190,7 +190,7 @@ def save_on_master(*args, **kwargs): torch.save(*args, **kwargs) -def init_distributed_mode(port=29529, backend="nccl", timeout_hours=2): +def init_distributed_mode(dist_url="env://", port=29529, backend="nccl", timeout_hours=2): # Fast-path: torchrun provides these if all(k in os.environ for k in ["RANK", "WORLD_SIZE", "LOCAL_RANK", "MASTER_ADDR", "MASTER_PORT"]): rank = int(os.environ["RANK"]) @@ -218,10 +218,15 @@ def init_distributed_mode(port=29529, backend="nccl", timeout_hours=2): setup_for_distributed(is_master=True) return + import socket + + print(f"Rank {os.getenv('RANK')} / {os.getenv('WORLD_SIZE')} on {socket.gethostname()}:{os.getenv('MASTER_PORT')}") + # Device selection must happen before NCCL init torch.cuda.set_device(local_rank) - dist.init_process_group(backend=backend, init_method="env://", timeout=datetime.timedelta(hours=timeout_hours)) + dist.init_process_group(backend=backend, init_method=dist_url, timeout=datetime.timedelta(hours=timeout_hours)) + dist.barrier() setup_for_distributed(dist.get_rank() == 0) From c89723d305a74815faba7273cd87e4ed7b08b77c Mon Sep 17 00:00:00 2001 From: wangyukai Date: Thu, 13 Nov 2025 07:20:25 +0000 Subject: [PATCH 12/35] fix eval config; fix local rank to rank --- internnav/evaluator/distributed_base.py | 6 +++--- internnav/internnav_habitat/habitat_env.py | 8 ++++---- .../internnav_habitat/habitat_vln_evaluator.py | 15 +++++++-------- internnav/utils/dist.py | 6 +++++- scripts/eval/configs/h1_cma_cfg.py | 3 ++- scripts/eval/configs/h1_internvla_n1_cfg.py | 2 ++ scripts/eval/configs/h1_rdp_cfg.py | 2 ++ scripts/eval/configs/h1_seq2seq_cfg.py | 2 ++ 8 files changed, 27 insertions(+), 17 deletions(-) diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index 4327c8a..c284edc 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -22,15 +22,15 @@ class DistributedEvaluator(Evaluator): def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True): # distributed setting - init_distributed_mode(dist_url=cfg.eval_settings['dist_url'], port=cfg.eval_settings['port']) + self.local_rank = init_distributed_mode(dist_url=cfg.eval_settings['dist_url'], port=cfg.eval_settings['port']) - self.local_rank = get_rank() + self.rank = get_rank() np.random.seed(self.local_rank) self.world_size = get_world_size() self.output_path = cfg.eval_settings["output_path"] # TODO: unsafe for distribution # habitat env also need rank to split dataset - cfg.env.env_settings['local_rank'] = get_rank() + cfg.env.env_settings['rank'] = get_rank() cfg.env.env_settings['world_size'] = get_world_size() self.eval_config = cfg diff --git a/internnav/internnav_habitat/habitat_env.py b/internnav/internnav_habitat/habitat_env.py index b680e94..1b0f3f4 100644 --- a/internnav/internnav_habitat/habitat_env.py +++ b/internnav/internnav_habitat/habitat_env.py @@ -12,7 +12,7 @@ def __init__(self, env_config: EnvCfg, task_config: TaskCfg): """ env_settings include: - habitat_config: loaded from get_habitat_config - - local_rank: int, rank index for sharding + - rank: int, rank index for sharding - world_size: int, total number of ranks """ try: @@ -27,7 +27,7 @@ def __init__(self, env_config: EnvCfg, task_config: TaskCfg): self.config = env_config.env_settings['habitat_config'] self._env = Env(self.config) - self.local_rank = env_config.env_settings.get('local_rank', 0) + self.rank = env_config.env_settings.get('rank', 0) self.world_size = env_config.env_settings.get('world_size', 1) self._current_episode_index: int = 0 self._last_obs: Optional[Dict[str, Any]] = None @@ -45,7 +45,7 @@ def generate_episodes(self) -> List[Any]: Generate list of episodes for the current split, already: - grouped by scene - filtered by done_res (the path is self.output_path/progress.json) - - sharded by (local_rank, world_size) + - sharded by (rank, world_size) """ all_episodes = [] @@ -71,7 +71,7 @@ def generate_episodes(self) -> List[Any]: scene_id = scene.split('/')[-2] # shard by rank index / world_size - for episode in per_scene_eps[self.local_rank :: self.world_size]: + for episode in per_scene_eps[self.rank :: self.world_size]: episode_id = int(episode.episode_id) if (scene_id, episode_id) in done_res: continue diff --git a/internnav/internnav_habitat/habitat_vln_evaluator.py b/internnav/internnav_habitat/habitat_vln_evaluator.py index 9ed4c48..9fdd015 100644 --- a/internnav/internnav_habitat/habitat_vln_evaluator.py +++ b/internnav/internnav_habitat/habitat_vln_evaluator.py @@ -44,8 +44,7 @@ # Import for Habitat registry side effects — do not remove import internnav.internnav_habitat.measures # noqa: F401 # isort: skip except Exception as e: - print("Habitat Error:", e) - print("Habitat Evaluation is not loaded.") + print(f"Warning: ({e}), Habitat Evaluation is not loaded in this runtime. Ignore this if not using Habitat.") DEFAULT_IMAGE_TOKEN = "" @@ -170,10 +169,10 @@ def eval_action(self): Returns dict[str, Tensor] on GPU (1D tensors of same length). """ # Old behavior was something like: - # sucs, spls, oss, nes, ep_num = self.eval_action(self.local_rank) + # sucs, spls, oss, nes, ep_num = self.eval_action(self.rank) # Now just implement the actual eval here and return dict. - sucs, spls, oss, nes, _ = self._run_local_eval(self.local_rank) + sucs, spls, oss, nes, _ = self._run_local_eval(self.rank) return { "sucs": sucs, # shape [N_local] @@ -202,7 +201,7 @@ def calc_metrics(self, global_metrics: dict) -> dict: # "length" will be filled by base class } - def _run_local_eval(self, idx=0) -> None: # noqa: C901 + def _run_local_eval(self) -> None: # noqa: C901 """ Run local evaluation on this rank. @@ -242,14 +241,14 @@ def _run_local_eval(self, idx=0) -> None: # noqa: C901 torch.tensor(nes).to(self.device), torch.tensor(len(sucs)).to(self.device), ) - if idx == 0: # noqa: F405 TODO this need to keep in evaluator + if self.rank == 0: # noqa: F405 TODO this need to keep in evaluator sucs.append(res['success']) spls.append(res['spl']) oss.append(res['os']) nes.append(res['ne']) # Episode loop is now driven by env.reset() + env.is_running - process_bar = tqdm.tqdm(total=len(self.env.episodes), desc=f"Eval Epoch {self.epoch} Rank {idx}") + process_bar = tqdm.tqdm(total=len(self.env.episodes), desc=f"Eval Epoch {self.epoch} Rank {self.rank}") while self.env.is_running: # ------------ 1. Start of episode ------------ @@ -280,7 +279,7 @@ def _run_local_eval(self, idx=0) -> None: # noqa: C901 # save first frame per rank to validate sim quality os.makedirs(os.path.join(self.output_path, f'check_sim_{self.epoch}'), exist_ok=True) Image.fromarray(observations['rgb']).save( - os.path.join(self.output_path, f'check_sim_{self.epoch}', f'rgb_{idx}.jpg') + os.path.join(self.output_path, f'check_sim_{self.epoch}', f'rgb_{self.rank}.jpg') ) vis_frames = [] diff --git a/internnav/utils/dist.py b/internnav/utils/dist.py index 7a65599..81634de 100644 --- a/internnav/utils/dist.py +++ b/internnav/utils/dist.py @@ -221,13 +221,17 @@ def init_distributed_mode(dist_url="env://", port=29529, backend="nccl", timeout import socket print(f"Rank {os.getenv('RANK')} / {os.getenv('WORLD_SIZE')} on {socket.gethostname()}:{os.getenv('MASTER_PORT')}") + print('| distributed init (rank {}): {}, gpu {}'.format(rank, dist_url, local_rank), flush=True) # Device selection must happen before NCCL init torch.cuda.set_device(local_rank) - dist.init_process_group(backend=backend, init_method=dist_url, timeout=datetime.timedelta(hours=timeout_hours)) + dist.init_process_group( + backend=backend, init_method=dist_url, world_size=world_size, rank=rank, timeout=datetime.timedelta(0, 7200) + ) dist.barrier() setup_for_distributed(dist.get_rank() == 0) + return local_rank def save_model(args, epoch, model_without_ddp, optimizer, checkpoint_path): diff --git a/scripts/eval/configs/h1_cma_cfg.py b/scripts/eval/configs/h1_cma_cfg.py index 6b27ee9..eae6a51 100644 --- a/scripts/eval/configs/h1_cma_cfg.py +++ b/scripts/eval/configs/h1_cma_cfg.py @@ -47,5 +47,6 @@ 'filter_stairs': False, }, ), - eval_settings={'save_to_json': False, 'vis_output': True}, + eval_type='vln_multi', + eval_settings={'save_to_json': True, 'vis_output': False}, ) diff --git a/scripts/eval/configs/h1_internvla_n1_cfg.py b/scripts/eval/configs/h1_internvla_n1_cfg.py index 90a801c..e6411e7 100644 --- a/scripts/eval/configs/h1_internvla_n1_cfg.py +++ b/scripts/eval/configs/h1_internvla_n1_cfg.py @@ -69,4 +69,6 @@ # 'selected_scans': ['8194nk5LbLH', 'pLe4wQe7qrG'], }, ), + eval_type='vln_multi', + eval_settings={'save_to_json': True, 'vis_output': False}, ) diff --git a/scripts/eval/configs/h1_rdp_cfg.py b/scripts/eval/configs/h1_rdp_cfg.py index a6380c8..a7e0254 100644 --- a/scripts/eval/configs/h1_rdp_cfg.py +++ b/scripts/eval/configs/h1_rdp_cfg.py @@ -45,4 +45,6 @@ 'filter_stairs': False, }, ), + eval_type='vln_multi', + eval_settings={'save_to_json': True, 'vis_output': False}, ) diff --git a/scripts/eval/configs/h1_seq2seq_cfg.py b/scripts/eval/configs/h1_seq2seq_cfg.py index 2934e8e..4fd9c19 100644 --- a/scripts/eval/configs/h1_seq2seq_cfg.py +++ b/scripts/eval/configs/h1_seq2seq_cfg.py @@ -45,4 +45,6 @@ 'filter_stairs': False, }, ), + eval_type='vln_multi', + eval_settings={'save_to_json': True, 'vis_output': False}, ) From 783627689df58c53f1600877f38c6afec0edf016 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Thu, 13 Nov 2025 07:45:33 +0000 Subject: [PATCH 13/35] update init distributed mode if condition --- internnav/evaluator/distributed_base.py | 2 +- internnav/utils/dist.py | 20 +++++++++++--------- 2 files changed, 12 insertions(+), 10 deletions(-) diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index c284edc..91eeb58 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -23,9 +23,9 @@ class DistributedEvaluator(Evaluator): def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True): # distributed setting self.local_rank = init_distributed_mode(dist_url=cfg.eval_settings['dist_url'], port=cfg.eval_settings['port']) + np.random.seed(self.local_rank) self.rank = get_rank() - np.random.seed(self.local_rank) self.world_size = get_world_size() self.output_path = cfg.eval_settings["output_path"] # TODO: unsafe for distribution diff --git a/internnav/utils/dist.py b/internnav/utils/dist.py index 81634de..1d68832 100644 --- a/internnav/utils/dist.py +++ b/internnav/utils/dist.py @@ -191,14 +191,8 @@ def save_on_master(*args, **kwargs): def init_distributed_mode(dist_url="env://", port=29529, backend="nccl", timeout_hours=2): - # Fast-path: torchrun provides these - if all(k in os.environ for k in ["RANK", "WORLD_SIZE", "LOCAL_RANK", "MASTER_ADDR", "MASTER_PORT"]): - rank = int(os.environ["RANK"]) - world_size = int(os.environ["WORLD_SIZE"]) - local_rank = int(os.environ["LOCAL_RANK"]) - # SLURM path: derive env then fall back to env:// - elif "SLURM_PROCID" in os.environ: + if "SLURM_PROCID" in os.environ: rank = int(os.environ["SLURM_PROCID"]) world_size = int(os.environ["SLURM_NTASKS"]) num_gpus = torch.cuda.device_count() @@ -206,13 +200,21 @@ def init_distributed_mode(dist_url="env://", port=29529, backend="nccl", timeout # pick first node as master nodelist = os.environ["SLURM_NODELIST"] + print(f'Node list: {nodelist}') master_addr = subprocess.getoutput(f"scontrol show hostname {nodelist} | head -n1") - os.environ.setdefault("MASTER_ADDR", master_addr) - os.environ.setdefault("MASTER_PORT", str(port)) + + os.environ["MASTER_ADDR"] = master_addr + os.environ["MASTER_PORT"] = str(port) os.environ["RANK"] = str(rank) os.environ["WORLD_SIZE"] = str(world_size) os.environ["LOCAL_RANK"] = str(local_rank) + # Fast-path: torchrun provides these + elif 'RANK' in os.environ and 'WORLD_SIZE' in os.environ: + rank = int(os.environ["RANK"]) + world_size = int(os.environ["WORLD_SIZE"]) + local_rank = int(os.environ["LOCAL_RANK"]) + else: print("Not using distributed mode") setup_for_distributed(is_master=True) From dac13e1bcf463a514e37c123d81915ae7b17eadd Mon Sep 17 00:00:00 2001 From: wangyukai Date: Thu, 13 Nov 2025 08:48:56 +0000 Subject: [PATCH 14/35] update dist for dlc --- internnav/utils/dist.py | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/internnav/utils/dist.py b/internnav/utils/dist.py index 1d68832..3f7f1d0 100644 --- a/internnav/utils/dist.py +++ b/internnav/utils/dist.py @@ -213,7 +213,14 @@ def init_distributed_mode(dist_url="env://", port=29529, backend="nccl", timeout elif 'RANK' in os.environ and 'WORLD_SIZE' in os.environ: rank = int(os.environ["RANK"]) world_size = int(os.environ["WORLD_SIZE"]) - local_rank = int(os.environ["LOCAL_RANK"]) + if "LOCAL_RANK" in os.environ: + local_rank = int(os.environ["LOCAL_RANK"]) + elif "RANK" in os.environ: + # fallback: assume per-node GPU count n + num_gpus = torch.cuda.device_count() + local_rank = rank % max(1, num_gpus) + else: + local_rank = 0 else: print("Not using distributed mode") From d8734c746d0a3158e3c6b859bb71168fd14f31ff Mon Sep 17 00:00:00 2001 From: wangyukai Date: Thu, 13 Nov 2025 10:06:20 +0000 Subject: [PATCH 15/35] fix bug in evaluator --- internnav/internnav_habitat/habitat_vln_evaluator.py | 3 +-- scripts/eval/configs/habitat_cfg.py | 6 +----- 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/internnav/internnav_habitat/habitat_vln_evaluator.py b/internnav/internnav_habitat/habitat_vln_evaluator.py index 9fdd015..0be81f4 100644 --- a/internnav/internnav_habitat/habitat_vln_evaluator.py +++ b/internnav/internnav_habitat/habitat_vln_evaluator.py @@ -153,7 +153,6 @@ def __init__(self, cfg: EvalCfg): self.num_future_steps = self.model_args.num_future_steps self.num_history = self.model_args.num_history - # ------------------------------------- old ------------------------------------------ self._camera_height = self.sim_sensors_config.rgb_sensor.position[1] self._min_depth = self.sim_sensors_config.depth_sensor.min_depth self._max_depth = self.sim_sensors_config.depth_sensor.max_depth @@ -172,7 +171,7 @@ def eval_action(self): # sucs, spls, oss, nes, ep_num = self.eval_action(self.rank) # Now just implement the actual eval here and return dict. - sucs, spls, oss, nes, _ = self._run_local_eval(self.rank) + sucs, spls, oss, nes, _ = self._run_local_eval() return { "sucs": sucs, # shape [N_local] diff --git a/scripts/eval/configs/habitat_cfg.py b/scripts/eval/configs/habitat_cfg.py index de96107..a079c0c 100644 --- a/scripts/eval/configs/habitat_cfg.py +++ b/scripts/eval/configs/habitat_cfg.py @@ -29,15 +29,11 @@ eval_type='habitat_vln', eval_settings={ # all current parse args - "output_path": "./logs/habitat/test_refactor_7e25e72", # output directory for logs/results + "output_path": "./logs/habitat/test", # output directory for logs/results "save_video": False, # whether to save videos "epoch": 0, # epoch number for logging "max_steps_per_episode": 500, # maximum steps per episode # distributed settings - "local_rank": 0, # node rank - "world_size": 1, # number of distributed processes - "rank": 0, # rank of current process - "gpu": 0, # gpu id to use "port": "2333", # communication port "dist_url": "env://", # url for distributed setup }, From bfe361637c83e74a715a14a2a05e07737ca78024 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Sat, 15 Nov 2025 04:34:07 +0000 Subject: [PATCH 16/35] update distributed vln multi, episode loader --- internnav/agent/internvla_n1_agent.py | 224 +++++++++++------- internnav/env/internutopia_env.py | 22 ++ .../env/utils/episode_loader/__init__.py | 2 + .../utils/episode_loader}/base.py | 21 +- .../utils/episode_loader/dataset_utils.py} | 122 +++++++++- .../utils/episode_loader/generate_episode.py} | 64 +++-- .../utils/episode_loader}/resumable.py | 13 +- internnav/evaluator/__init__.py | 8 +- internnav/evaluator/distributed_base.py | 25 +- internnav/evaluator/utils/common.py | 141 ----------- internnav/evaluator/utils/dataset.py | 129 ++-------- ....py => vln_multi_distributed_evaluator.py} | 76 +++--- internnav/projects/__init__.py | 0 internnav/utils/progress_log_multi_util.py | 1 + scripts/eval/bash/start_aliyun_dlc.sh | 87 +++++-- scripts/eval/bash/torchrun_eval.sh | 34 +-- scripts/eval/configs/h1_cma_cfg.py | 16 +- scripts/eval/configs/h1_internvla_n1_cfg.py | 12 +- scripts/eval/configs/h1_rdp_cfg.py | 20 +- scripts/eval/configs/h1_seq2seq_cfg.py | 20 +- scripts/eval/eval.py | 2 +- 21 files changed, 561 insertions(+), 478 deletions(-) create mode 100644 internnav/env/utils/episode_loader/__init__.py rename internnav/{projects/dataloader => env/utils/episode_loader}/base.py (67%) rename internnav/{projects/dataloader/data_reviser.py => env/utils/episode_loader/dataset_utils.py} (60%) rename internnav/{evaluator/utils/eval.py => env/utils/episode_loader/generate_episode.py} (52%) rename internnav/{projects/dataloader => env/utils/episode_loader}/resumable.py (89%) rename internnav/evaluator/{vln_multi_evaluator.py => vln_multi_distributed_evaluator.py} (89%) delete mode 100644 internnav/projects/__init__.py diff --git a/internnav/agent/internvla_n1_agent.py b/internnav/agent/internvla_n1_agent.py index 6e97e02..600b0c8 100644 --- a/internnav/agent/internvla_n1_agent.py +++ b/internnav/agent/internvla_n1_agent.py @@ -1,22 +1,21 @@ -import os import copy -from PIL import Image -import numpy as np -import imageio -import base64 -import pickle +import os import threading -import cv2 -from gym import spaces import time + +import cv2 +import imageio +import numpy as np import torch +from gym import spaces +from PIL import Image -from internnav.configs.agent import StepRequest, AgentCfg from internnav.agent.base import Agent +from internnav.configs.agent import AgentCfg from internnav.configs.model.base_encoders import ModelCfg from internnav.model import get_config, get_policy from internnav.model.utils.misc import set_random_seed -from internnav.model.utils.vln_utils import S2Input, S2Output, S1Input, S1Output +from internnav.model.utils.vln_utils import S1Input, S1Output, S2Input, S2Output @Agent.register('internvla_n1') @@ -27,58 +26,56 @@ class InternVLAN1Agent(Agent): shape=(256, 256, 1), dtype=np.float32, ) - + def __init__(self, config: AgentCfg): super().__init__(config) set_random_seed(0) vln_sensor_config = self.config.model_settings self._model_settings = ModelCfg(**vln_sensor_config) - env_num = getattr(self._model_settings, 'env_num', 1) - sim_num = getattr(self._model_settings, 'sim_num', 1) - self.device = torch.device(self._model_settings.device) + local_rank = getattr(self._model_settings, 'local_rank') + self.device = torch.device(local_rank) self.mode = getattr(self._model_settings, 'infer_mode', 'sync') self.sys2_max_forward_step = getattr(self._model_settings, 'sys2_max_forward_step', 8) - + policy = get_policy(self._model_settings.policy_name) policy_config = get_config(self._model_settings.policy_name) model_config = {'model': self._model_settings.model_dump()} self.policy = policy(config=policy_config(model_cfg=model_config)) self.policy.eval() - + self.camera_intrinsic = self.get_intrinsic_matrix( self._model_settings.width, self._model_settings.height, self._model_settings.hfov ) - + self.episode_step = 0 self.episode_idx = 0 self.look_down = False - - - ### for async dual sys + + # for async dual sys self.pixel_goal_rgb = None self.pixel_goal_depth = None self.dual_forward_step = 0 self.sys1_infer_times = 0 - + self.sys1_depth_threshold = 5.0 self.sys1_forward_step = 4 - + self.s1_input = S1Input() self.s2_input = S2Input() self.s2_output = S2Output() self.s1_output = S1Output() - + # Thread management self.s2_thread = None - + # Thread locks self.s2_input_lock = threading.Lock() self.s2_output_lock = threading.Lock() self.s2_agent_lock = threading.Lock() - + # Start S2 thread self._start_s2_thread() - + # vis debug self.vis_debug = vln_sensor_config['vis_debug'] if self.vis_debug: @@ -87,7 +84,7 @@ def __init__(self, config: AgentCfg): self.fps_writer = imageio.get_writer(f"{self.debug_path}/fps_{self.episode_idx}.mp4", fps=5) self.fps_writer2 = imageio.get_writer(f"{self.debug_path}/fps_{self.episode_idx}_dp.mp4", fps=5) self.output_pixel = None - + def reset(self, reset_index=None): '''reset_index: [0]''' if reset_index is not None: @@ -97,7 +94,7 @@ def reset(self, reset_index=None): self.fps_writer2.close() else: self.episode_idx = -1 - + self.episode_step = 0 self.s1_input = S1Input() with self.s2_input_lock: @@ -105,21 +102,21 @@ def reset(self, reset_index=None): with self.s2_output_lock: self.s2_output = S2Output() self.s1_output = S1Output() - - ### for async dual sys + + # for async dual sys self.pixel_goal_rgb = None self.pixel_goal_depth = None - self.dual_forward_step = 0 + self.dual_forward_step = 0 self.sys1_infer_times = 0 - + # Reset s2 agent with self.s2_agent_lock: self.policy.reset() - + if self.vis_debug: self.fps_writer = imageio.get_writer(f"{self.debug_path}/fps_{self.episode_idx}.mp4", fps=5) self.fps_writer2 = imageio.get_writer(f"{self.debug_path}/fps_{self.episode_idx}_dp.mp4", fps=5) - + def get_intrinsic_matrix(self, width, height, hfov) -> np.ndarray: width = width height = height @@ -129,14 +126,11 @@ def get_intrinsic_matrix(self, width, height, hfov) -> np.ndarray: cx = (width - 1.0) / 2.0 cy = (height - 1.0) / 2.0 - intrinsic_matrix = np.array([ - [fx, 0.0, cx, 0.0], - [ 0.0, fy, cy, 0.0], - [ 0.0, 0.0, 1.0, 0.0], - [ 0.0, 0.0, 0.0, 1.0] - ]) + intrinsic_matrix = np.array( + [[fx, 0.0, cx, 0.0], [0.0, fy, cy, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]] + ) return intrinsic_matrix - + def _start_s2_thread(self): def s2_thread_func(): while True: @@ -149,7 +143,7 @@ def s2_thread_func(): else: time.sleep(0.5) # Sleep briefly if inference is not needed continue - + # # Check if currently inferring # if self.mode == "sync": # if not self.s2_output.is_infering: @@ -158,12 +152,19 @@ def s2_thread_func(): # else: # time.sleep(0.5) # Sleep briefly if already inferring # continue - + # Execute inference success = True try: with self.s2_agent_lock: - current_s2_output = self.policy.s2_step(self.s2_input.rgb, self.s2_input.depth, self.s2_input.pose, self.s2_input.instruction, self.camera_intrinsic, self.s2_input.look_down) + current_s2_output = self.policy.s2_step( + self.s2_input.rgb, + self.s2_input.depth, + self.s2_input.pose, + self.s2_input.instruction, + self.camera_intrinsic, + self.s2_input.look_down, + ) except Exception as e: print(f"s2 infer error: {e}") self.s2_output.is_infering = False @@ -171,22 +172,29 @@ def s2_thread_func(): success = False if not success: try: - current_s2_output = self.policy.s2_step(self.s2_input.rgb, self.s2_input.depth, self.s2_input.pose, self.s2_input.instruction, self.camera_intrinsic, False) + current_s2_output = self.policy.s2_step( + self.s2_input.rgb, + self.s2_input.depth, + self.s2_input.pose, + self.s2_input.instruction, + self.camera_intrinsic, + False, + ) except Exception as e: print(f"s2 infer error: {e}") self.s2_output.is_infering = False self.policy.reset() self.s2_output.output_pixel = None - self.s2_output.output_action = [0] # finish the inference + self.s2_output.output_action = [0] # finish the inference self.s2_output.output_latent = None continue - - print(f"s2 infer finish!!") + + print("s2 infer finish!!") # Update output state with self.s2_output_lock: - print(f"get s2 output lock") + print("get s2 output lock") # S2 output - + self.s2_output.output_pixel = current_s2_output.output_pixel self.s2_output.output_action = current_s2_output.output_action self.s2_output.output_latent = current_s2_output.output_latent @@ -199,20 +207,20 @@ def s2_thread_func(): self.s2_thread = threading.Thread(target=s2_thread_func) self.s2_thread.daemon = True self.s2_thread.start() - + def should_infer_s2(self, mode="sync"): """Function: Enables the sys2 inference thread depending on the mode. mode: just support 2 modes: "sync" and "partial_async". "sync": Synchronous mode (navdp_version >= 0.0), Sys1 and Sys2 execute in a sequential inference chain. - "partial_async": Asynchronous mode (navdp_version > 0.0, e.g., 0.1), + "partial_async": Asynchronous mode (navdp_version > 0.0, e.g., 0.1), Sys2 performs a single inference, while Sys1 performs multiple inference cycles. """ if self.episode_step == 0: return True - + if self.s2_output.is_infering: return False - + # 1. Synchronous mode: infer S2 every frame to provide to S1 for execution if mode == "sync": if self.s2_output.output_action is None: @@ -223,23 +231,27 @@ def should_infer_s2(self, mode="sync"): if mode == "partial_async": if self.dual_forward_step >= self.sys2_max_forward_step: return True - if self.s2_output.output_action is None and self.s2_output.output_pixel is None and self.s2_output.output_latent is None: + if ( + self.s2_output.output_action is None + and self.s2_output.output_pixel is None + and self.s2_output.output_latent is None + ): # This normally only occurs when output is discrete action and discrete action has been fully executed return True return False raise ValueError("Invalid mode: {}".format(mode)) - + def step(self, obs): - mode = self.mode #'sync', 'partial_async' - - obs = obs[0] # do not support batch_env currently? + mode = self.mode # 'sync', 'partial_async' + + obs = obs[0] # do not support batch_env currently? rgb = obs['rgb'] depth = obs['depth'] instruction = obs['instruction'] pose = np.array([[1, 0, 0, 0], [0, 1, 0, 0], [0, 0, 1, 0], [0, 0, 0, 1]]) - + # S2 inference is done in a separate thread - if self.should_infer_s2(mode) or self.look_down: # The look down frame must be inferred + if self.should_infer_s2(mode) or self.look_down: # The look down frame must be inferred print(f"======== Infer S2 at step {self.episode_step}========") with self.s2_input_lock: self.s2_input.idx = self.episode_step @@ -249,8 +261,8 @@ def step(self, obs): self.s2_input.instruction = instruction self.s2_input.should_infer = True self.s2_input.look_down = self.look_down - self.s2_output.is_infering = True #for async - + self.s2_output.is_infering = True # for async + self.dual_forward_step = 0 else: # Even if this frame doesn't do s2 inference, rgb needs to be provided to ensure history is correct @@ -258,17 +270,17 @@ def step(self, obs): # S1 inference is done in the main thread while self.s2_output.is_infering: time.sleep(0.5) - + while not self.s2_output.validate(): time.sleep(0.2) - + output = {} # Simple branch: # 1. If S2 output is full discrete actions, don't execute S1 and return directly print('===============', self.s2_output.output_action, '=================') if self.s2_output.output_action is not None: output['action'] = [self.s2_output.output_action[0]] - + with self.s2_output_lock: self.s2_output.output_action = self.s2_output.output_action[1:] if self.s2_output.output_action == []: @@ -286,34 +298,53 @@ def step(self, obs): self.look_down = False if self.sys1_infer_times > 0: self.dual_forward_step += 1 - + # print('Output action:', output, self.dual_forward_step) - + else: self.look_down = False # 2. If output is in latent form, execute latent S1 if self.s2_output.output_latent is not None: self.output_pixel = copy.deepcopy(self.s2_output.output_pixel) print(self.output_pixel) - + if mode != 'sync': - processed_pixel_rgb = np.array(Image.fromarray(self.s2_output.rgb_memory).resize((224, 224))) / 255.0 - processed_pixel_depth = np.array(Image.fromarray(self.s2_output.depth_memory[:,:,0]).resize((224, 224))) * 10.0 + processed_pixel_rgb = ( + np.array(Image.fromarray(self.s2_output.rgb_memory).resize((224, 224))) / 255.0 + ) + processed_pixel_depth = ( + np.array(Image.fromarray(self.s2_output.depth_memory[:, :, 0]).resize((224, 224))) * 10.0 + ) processed_pixel_depth[processed_pixel_depth > self.sys1_depth_threshold] = self.sys1_depth_threshold - + processed_rgb = np.array(Image.fromarray(rgb).resize((224, 224))) / 255.0 - processed_depth = np.array(Image.fromarray(depth[:,:,0]).resize((224, 224))) * 10.0 # should be 0-10m + processed_depth = ( + np.array(Image.fromarray(depth[:, :, 0]).resize((224, 224))) * 10.0 + ) # should be 0-10m processed_depth[processed_depth > self.sys1_depth_threshold] = self.sys1_depth_threshold - - rgbs = torch.stack([torch.from_numpy(processed_pixel_rgb), torch.from_numpy(processed_rgb)]).unsqueeze(0).to(self.device) #[1, 2, 224, 224, 3] - depths = torch.stack([torch.from_numpy(processed_pixel_depth), torch.from_numpy(processed_depth)]).unsqueeze(0).unsqueeze(-1).to(self.device)#[1, 2, 224, 224, 1] - self.s1_output = self.policy.s1_step_latent(rgbs, depths, self.s2_output.output_latent, use_async=True) + + rgbs = ( + torch.stack([torch.from_numpy(processed_pixel_rgb), torch.from_numpy(processed_rgb)]) + .unsqueeze(0) + .to(self.device) + ) # [1, 2, 224, 224, 3] + depths = ( + torch.stack([torch.from_numpy(processed_pixel_depth), torch.from_numpy(processed_depth)]) + .unsqueeze(0) + .unsqueeze(-1) + .to(self.device) + ) # [1, 2, 224, 224, 1] + self.s1_output = self.policy.s1_step_latent( + rgbs, depths, self.s2_output.output_latent, use_async=True + ) else: - self.s1_output = self.policy.s1_step_latent(rgb, depth * 10000.0, self.s2_output.output_latent, use_async=False) - + self.s1_output = self.policy.s1_step_latent( + rgb, depth * 10000.0, self.s2_output.output_latent, use_async=False + ) + else: assert False, f"S2 output should be either action or latent, but got neither! {self.s2_output}" - + if self.s1_output.idx == []: output['action'] = [-1] else: @@ -325,9 +356,8 @@ def step(self, obs): self.s2_output.output_action = None else: self.s2_output.output_action = None - - - self.s2_output.output_pixel = None #TODO: now just for visulization + + self.s2_output.output_pixel = None # TODO: now just for visulization if mode == 'sync': self.s2_output.output_latent = None else: @@ -339,31 +369,41 @@ def step(self, obs): self.sys1_infer_times += 1 self.dual_forward_step += 1 - + if self.dual_forward_step > self.sys2_max_forward_step: print("!!!!!!!!!!!!") print("ERR: self.dual_forward_step ", self.dual_forward_step, " > ", self.sys2_max_forward_step) print("!!!!!!!!!!!!") - + print('Output discretized traj:', output['action'], self.dual_forward_step) - - # Visualization + + # Visualization if self.vis_debug: vis = rgb.copy() if 'action' in output: vis = cv2.putText(vis, str(output['action'][0]), (50, 50), cv2.FONT_HERSHEY_SIMPLEX, 1, (0, 255, 0), 2) if self.output_pixel is not None: pixel = self.output_pixel - vis = cv2.putText(vis, f"{pixel[1]}, {pixel[0]} ({self.s2_output.idx})", (50, 100), cv2.FONT_HERSHEY_SIMPLEX, 1, (0, 255, 0), 2) - + vis = cv2.putText( + vis, + f"{pixel[1]}, {pixel[0]} ({self.s2_output.idx})", + (50, 100), + cv2.FONT_HERSHEY_SIMPLEX, + 1, + (0, 255, 0), + 2, + ) + cv2.circle(vis, (pixel[1], pixel[0]), 5, (0, 255, 0), -1) self.output_pixel = None self.fps_writer.append_data(vis) - + if self.s1_output.vis_image is not None: - Image.fromarray(self.s1_output.vis_image).save(os.path.join("./vis_debug_pix/", f"ttttt_{self.episode_step}.png")) + Image.fromarray(self.s1_output.vis_image).save( + os.path.join("./vis_debug_pix/", f"ttttt_{self.episode_step}.png") + ) self.fps_writer2.append_data(self.s1_output.vis_image) - + self.episode_step += 1 if 'action' in output: return [{'action': output['action'], 'ideal_flag': True}] diff --git a/internnav/env/internutopia_env.py b/internnav/env/internutopia_env.py index ad7fcf1..ba7793f 100644 --- a/internnav/env/internutopia_env.py +++ b/internnav/env/internutopia_env.py @@ -1,7 +1,13 @@ +import os +import sys from typing import Any, Dict, List from internnav.configs.evaluator import EnvCfg, TaskCfg from internnav.env import base +from internnav.env.utils.episode_loader import ( + ResumablePathKeyEpisodeloader, + generate_vln_episode, +) @base.Env.register('internutopia') @@ -22,6 +28,22 @@ def __init__(self, env_config: EnvCfg, task_config: TaskCfg): super().__init__(env_config, task_config) env_settings = self.env_config.env_settings task_settings = self.task_config.task_settings + + # generate episodes + self.episode_loader = ResumablePathKeyEpisodeloader( + env_config.dataset.dataset_type, + **env_config.dataset.dataset_settings, + rank=env_settings['rank'], + world_size=env_settings['world_size'] + ) + self.episodes = generate_vln_episode(self.episode_loader, task_config) + if len(self.episodes) == 0: + sys.exit(0) + task_settings.update({'episodes': self.episodes}) + + # set visible device for isaac sim + os.environ["CUDA_VISIBLE_DEVICES"] = env_settings.get('local_rank', '0') + config = Config( simulator=SimConfig(**env_settings), env_num=task_settings['env_num'], diff --git a/internnav/env/utils/episode_loader/__init__.py b/internnav/env/utils/episode_loader/__init__.py new file mode 100644 index 0000000..b3d58ad --- /dev/null +++ b/internnav/env/utils/episode_loader/__init__.py @@ -0,0 +1,2 @@ +from .generate_episode import generate_vln_episode +from .resumable import ResumablePathKeyEpisodeloader diff --git a/internnav/projects/dataloader/base.py b/internnav/env/utils/episode_loader/base.py similarity index 67% rename from internnav/projects/dataloader/base.py rename to internnav/env/utils/episode_loader/base.py index d00a67b..ab18b61 100644 --- a/internnav/projects/dataloader/base.py +++ b/internnav/env/utils/episode_loader/base.py @@ -1,9 +1,7 @@ -from internnav.evaluator.utils.common import load_data +from .dataset_utils import load_data, revise_one_data, skip_list -from .data_reviser import revise_one_data, skip_list - -class BasePathKeyDataloader: +class BasePathKeyEpisodeloader: def __init__( self, dataset_type, @@ -13,7 +11,15 @@ def __init__( filter_same_trajectory, revise_data=True, filter_stairs=True, + rank=0, + world_size=1, ): + # current supported dataset types in InternUtopia + # only kujiale has special scene path + # others type should be considered the same as mp3d in loading + allowed = ('R2RVLN', 'mp3d', 'kujiale', 'grscene') + assert dataset_type in allowed, f"Unsupported dataset type: {dataset_type}. Allowed: {allowed}" + self.path_key_data = {} self.path_key_scan = {} self.path_key_split = {} @@ -25,14 +31,19 @@ def __init__( filter_same_trajectory=filter_same_trajectory, filter_stairs=filter_stairs, dataset_type=dataset_type, + rank=rank, + world_size=world_size, ) for scan, path_list in load_data_map.items(): for path in path_list: trajectory_id = path['trajectory_id'] - if revise_data: + + # tiny revision for R2R dataset in MP3D to fit vlnpe task + if dataset_type == 'mp3d' and revise_data: if trajectory_id in skip_list: continue path = revise_one_data(path) + episode_id = path['episode_id'] path_key = f'{trajectory_id}_{episode_id}' path['start_position'] += robot_offset diff --git a/internnav/projects/dataloader/data_reviser.py b/internnav/env/utils/episode_loader/dataset_utils.py similarity index 60% rename from internnav/projects/dataloader/data_reviser.py rename to internnav/env/utils/episode_loader/dataset_utils.py index d4841b4..12e5f46 100644 --- a/internnav/projects/dataloader/data_reviser.py +++ b/internnav/env/utils/episode_loader/dataset_utils.py @@ -1,3 +1,13 @@ +import copy +import gzip +import json +import os +from collections import defaultdict + +import numpy as np + +from internnav.utils.common_log_util import common_logger as log + fall_path_z_0_3 = [ 70, 121, @@ -322,8 +332,7 @@ 2306, ] -skip_list = [ -] +skip_list = [] fall_path_custom = { 6558: [-1, 0, 0], @@ -447,3 +456,112 @@ def revise_one_data(origin): origin['reference_path'][0][1] = origin['reference_path'][0][1] + amend_offset[1] origin['reference_path'][0][2] = origin['reference_path'][0][2] + amend_offset[2] return origin + + +def transform_rotation_z_90degrees(rotation): + z_rot_90 = [np.cos(np.pi / 4), 0, 0, np.sin(np.pi / 4)] # 90 degrees = pi/2 radians + w1, x1, y1, z1 = rotation + w2, x2, y2, z2 = z_rot_90 + revised_rotation = [ + w1 * w2 - x1 * x2 - y1 * y2 - z1 * z2, # w + w1 * x2 + x1 * w2 + y1 * z2 - z1 * y2, # x + w1 * y2 - x1 * z2 + y1 * w2 + z1 * x2, # y + w1 * z2 + x1 * y2 - y1 * x2 + z1 * w2, # z + ] + return revised_rotation + + +def has_stairs(item, height_threshold=0.3): + has_stairs = False + if 'stair' in item['instruction']['instruction_text']: + latest_height = item['reference_path'][0][-1] + for index in range(1, len(item['reference_path'])): + position = item['reference_path'][index] + if abs(position[-1] - latest_height) >= height_threshold: + has_stairs = True + break + else: + latest_height = position[-1] + return has_stairs + + +def different_height(item): + different_height = False + paths = item['reference_path'] + for path_idx in range(len(paths) - 1): + if abs(paths[path_idx + 1][2] - paths[path_idx][2]) > 0.3: + different_height = True + break + return different_height + + +def load_data( + dataset_root_dir, split, filter_same_trajectory=True, filter_stairs=True, dataset_type='mp3d', rank=0, world_size=1 +): + with gzip.open(os.path.join(dataset_root_dir, split, f"{split}.json.gz"), 'rt', encoding='utf-8') as f: + data = json.load(f)['episodes'][rank::world_size] + + if dataset_type == 'kujiale': + scenes = list(set([x['scan'] for x in data])) + else: + scenes = list(set([x['scene_id'] for x in data])) # e.g. 'mp3d/zsNo4HB9uLZ/zsNo4HB9uLZ.glb' + + scenes.sort() + new_data = {} + for scene in scenes: + if dataset_type == 'kujiale': + scene_data = [x for x in data if x['scan'] == scene] + scan = scene + else: + scene_data = [x for x in data if x['scene_id'] == scene] + scan = scene.split('/')[1] # e.g. 'zsNo4HB9uLZ' + new_scene_data = [] + for item in scene_data: + new_item = copy.deepcopy(item) + new_item['scan'] = scan + new_item['original_start_position'] = item['start_position'] + new_item['original_start_rotation'] = item['start_rotation'] + if dataset_type != 'kujiale': + x, z, y = item['start_position'] + new_item['start_position'] = [x, -y, z] + r1, r2, r3, r4 = item['start_rotation'] + new_item['start_rotation'] = transform_rotation_z_90degrees([-r4, r1, r3, -r2]) + new_item['reference_path'] = [[x, -y, z] for x, z, y in item['reference_path']] + new_scene_data.append(new_item) + + new_data[scan] = new_scene_data + + data = copy.deepcopy(new_data) + new_data = defaultdict(list) + + # filter_same_trajectory + if filter_same_trajectory: + total_count = 0 + remaining_count = 0 + trajectory_list = [] + for scan, data_item in data.items(): + for item in data_item: + total_count += 1 + if item['trajectory_id'] in trajectory_list: + continue + remaining_count += 1 + trajectory_list.append(item['trajectory_id']) + new_data[scan].append(item) + log.info(f'[split:{split}]filter_same_trajectory remain: [ {remaining_count} / {total_count} ]') + data = new_data + new_data = defaultdict(list) + + if filter_stairs: + total_count = 0 + remaining_count = 0 + for scan, data_item in data.items(): + for item in data_item: + total_count += 1 + if has_stairs(item) or different_height(item): + continue + remaining_count += 1 + new_data[scan].append(item) + log.info(f'[split:{split}]filter_stairs remain: [ {remaining_count} / {total_count} ]') + data = new_data + + return data diff --git a/internnav/evaluator/utils/eval.py b/internnav/env/utils/episode_loader/generate_episode.py similarity index 52% rename from internnav/evaluator/utils/eval.py rename to internnav/env/utils/episode_loader/generate_episode.py index 9e6c447..b244045 100644 --- a/internnav/evaluator/utils/eval.py +++ b/internnav/env/utils/episode_loader/generate_episode.py @@ -1,11 +1,43 @@ -from internnav.configs.evaluator import EvalCfg -from internnav.evaluator.utils.common import load_kujiale_scene_usd, load_scene_usd -from internnav.projects.dataloader.resumable import ResumablePathKeyDataloader +import os +from internnav.configs.evaluator import TaskCfg +from internnav.utils.common_log_util import common_logger as log -def generate_episode(dataloader: ResumablePathKeyDataloader, config: EvalCfg): - scene_data_dir = config.task.scene.scene_data_dir - scene_asset_path = config.task.scene.scene_asset_path +from .resumable import ResumablePathKeyEpisodeloader + + +def load_scene_usd(mp3d_data_dir, scan): + """Load scene USD based on the scan""" + from internutopia.core.util import is_in_container + + find_flag = False + for root, dirs, files in os.walk(os.path.join(mp3d_data_dir, scan)): + target_file_name = 'fixed_docker.usd' if is_in_container() else 'fixed.usd' + for file in files: + if file == target_file_name: + scene_usd_path = os.path.join(root, file) + find_flag = True + break + if find_flag: + break + if not find_flag: + log.error('Scene USD not found for scan %s', scan) + return None + return scene_usd_path + + +def load_kujiale_scene_usd(kujiale_iros_data_dir, scan): + """Load scene USD based on the scan""" + scene_usd_path = os.path.join(kujiale_iros_data_dir, scan, f'{scan}.usda') + if not os.path.exists(scene_usd_path): + log.error('Scene USD not found for scan %s', scan) + return None + return scene_usd_path + + +def generate_vln_episode(dataloader: ResumablePathKeyEpisodeloader, task: TaskCfg): + scene_data_dir = task.scene.scene_data_dir + scene_asset_path = task.scene.scene_asset_path eval_path_key_list = dataloader.resumed_path_key_list path_key_data = dataloader.path_key_data episodes = [] @@ -21,9 +53,9 @@ def generate_episode(dataloader: ResumablePathKeyDataloader, config: EvalCfg): from internnav.env.utils.internutopia_extension.configs.tasks import VLNEvalTaskCfg robot = H1RobotCfg( - **config.task.robot.robot_settings, - controllers=[ControllerCfg(**cfg.controller_settings) for cfg in config.task.robot.controllers], - sensors=[RepCameraCfg(**cfg.sensor_settings) for cfg in config.task.robot.sensors], + **task.robot.robot_settings, + controllers=[ControllerCfg(**cfg.controller_settings) for cfg in task.robot.controllers], + sensors=[RepCameraCfg(**cfg.sensor_settings) for cfg in task.robot.sensors], ) for path_key in eval_path_key_list: @@ -33,23 +65,23 @@ def generate_episode(dataloader: ResumablePathKeyDataloader, config: EvalCfg): data['path_key'] = path_key data['name'] = dataloader.task_name - if config.task.scene.scene_type == 'kujiale': + if task.scene.scene_type == 'kujiale': load_scene_func = load_kujiale_scene_usd scene_scale = (1, 1, 1) else: load_scene_func = load_scene_usd scene_scale = (1, 1, 1) - robot_flash = getattr(config.task, "robot_flash", False) - one_step_stand_still = getattr(config.task, "one_step_stand_still", False) - if config.task.metric.metric_setting['metric_config'].get('name', None) is None: - config.task.metric.metric_setting['metric_config']['name'] = 'default_eval_name' + robot_flash = getattr(task, "robot_flash", False) + one_step_stand_still = getattr(task, "one_step_stand_still", False) + if task.metric.metric_setting['metric_config'].get('name', None) is None: + task.metric.metric_setting['metric_config']['name'] = 'default_eval_name' episodes.append( VLNEvalTaskCfg( - **config.task.task_settings, + **task.task_settings, robot_flash=robot_flash, one_step_stand_still=one_step_stand_still, - metrics=[VLNPEMetricCfg(**config.task.metric.metric_setting['metric_config'])], + metrics=[VLNPEMetricCfg(**task.metric.metric_setting['metric_config'])], scene_asset_path=load_scene_func(scene_data_dir, dataloader.path_key_scan[path_key]) if scene_asset_path == '' else scene_asset_path, diff --git a/internnav/projects/dataloader/resumable.py b/internnav/env/utils/episode_loader/resumable.py similarity index 89% rename from internnav/projects/dataloader/resumable.py rename to internnav/env/utils/episode_loader/resumable.py index 73cdd6d..81dba8c 100644 --- a/internnav/projects/dataloader/resumable.py +++ b/internnav/env/utils/episode_loader/resumable.py @@ -3,11 +3,10 @@ from internnav.evaluator.utils.config import get_lmdb_path -from .base import BasePathKeyDataloader -from .data_reviser import skip_list +from .base import BasePathKeyEpisodeloader -class ResumablePathKeyDataloader(BasePathKeyDataloader): +class ResumablePathKeyEpisodeloader(BasePathKeyEpisodeloader): def __init__( self, dataset_type, @@ -19,6 +18,8 @@ def __init__( run_type, retry_list, filter_stairs, + rank=0, + world_size=1, ): # 加载所有数据 super().__init__( @@ -29,6 +30,8 @@ def __init__( filter_same_trajectory=filter_same_trajectory, revise_data=True, filter_stairs=filter_stairs, + rank=rank, + world_size=world_size, ) self.task_name = task_name self.run_type = run_type @@ -43,9 +46,7 @@ def __init__( filtered_target_path_key_list = [] for path_key in self.path_key_data.keys(): - trajectory_id = int(path_key.split('_')[0]) - if trajectory_id in skip_list: - continue + # trajectory_id = int(path_key.split('_')[0]) with database.begin() as txn: value = txn.get(path_key.encode()) if value is None: diff --git a/internnav/evaluator/__init__.py b/internnav/evaluator/__init__.py index 07a7208..b9929c8 100644 --- a/internnav/evaluator/__init__.py +++ b/internnav/evaluator/__init__.py @@ -1,8 +1,12 @@ from internnav.evaluator.base import Evaluator from internnav.evaluator.distributed_base import DistributedEvaluator -from internnav.evaluator.vln_multi_evaluator import VlnMultiEvaluator + +# from internnav.evaluator.vln_multi_evaluator import VlnMultiEvaluator +from internnav.evaluator.vln_multi_distributed_evaluator import ( + VlnMultiDistributedEvaluator, +) # register habitat import internnav.internnav_habitat # noqa: F401 # isort: skip -__all__ = ['Evaluator', 'VlnMultiEvaluator'] +__all__ = ['Evaluator', 'DistributedEvaluator'] diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index 91eeb58..fca3b9d 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -7,7 +7,13 @@ from internnav.configs.evaluator import EvalCfg from internnav.env import Env from internnav.evaluator import Evaluator -from internnav.utils.dist import dist, get_rank, get_world_size, init_distributed_mode +from internnav.utils.dist import ( + dist, + get_rank, + get_world_size, + init_distributed_mode, + is_dist_avail_and_initialized, +) class DistributedEvaluator(Evaluator): @@ -22,16 +28,23 @@ class DistributedEvaluator(Evaluator): def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True): # distributed setting - self.local_rank = init_distributed_mode(dist_url=cfg.eval_settings['dist_url'], port=cfg.eval_settings['port']) + if not cfg.eval_settings.get('use_agent_server', False): + self.local_rank = init_distributed_mode( + dist_url=cfg.eval_settings.get('dist_url', "env://"), port=cfg.eval_settings.get('port', 29529) + ) + else: + self.local_rank = 0 np.random.seed(self.local_rank) self.rank = get_rank() self.world_size = get_world_size() - self.output_path = cfg.eval_settings["output_path"] # TODO: unsafe for distribution + self.output_path = cfg.eval_settings.get("output_path") # TODO: unsafe for distribution # habitat env also need rank to split dataset cfg.env.env_settings['rank'] = get_rank() + cfg.env.env_settings['local_rank'] = self.local_rank cfg.env.env_settings['world_size'] = get_world_size() + cfg.env.dataset = cfg.dataset self.eval_config = cfg @@ -40,15 +53,17 @@ def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True) # -------- initialize agent config (either remote server or local agent) -------- if init_agent: - if cfg.remote_agent: + if cfg.eval_settings.get('use_agent_server', False): + assert not is_dist_avail_and_initialized(), "agent server requires single evaluator process." # set agent port based on rank from internnav.utils import AgentClient - cfg.agent.agent_settings['port'] = 8000 + get_rank() + print(f"[R{self.rank}] Connecting to agent server at port {cfg.agent.server_port}") self.agent = AgentClient(cfg.agent) else: from internnav.agent import Agent + cfg.agent.model_settings['local_rank'] = self.local_rank self.agent = Agent(cfg.agent) def eval(self): diff --git a/internnav/evaluator/utils/common.py b/internnav/evaluator/utils/common.py index f855014..1b811b9 100644 --- a/internnav/evaluator/utils/common.py +++ b/internnav/evaluator/utils/common.py @@ -1,9 +1,5 @@ -import copy -import gzip -import json import math import os -from collections import defaultdict import numpy as np from PIL import Image, ImageDraw @@ -133,143 +129,6 @@ def check_is_on_track( return True -def has_stairs(item, height_threshold=0.3): - has_stairs = False - if 'stair' in item['instruction']['instruction_text']: - latest_height = item['reference_path'][0][-1] - for index in range(1, len(item['reference_path'])): - position = item['reference_path'][index] - if abs(position[-1] - latest_height) >= height_threshold: - has_stairs = True - break - else: - latest_height = position[-1] - return has_stairs - - -def different_height(item): - different_height = False - paths = item['reference_path'] - for path_idx in range(len(paths) - 1): - if abs(paths[path_idx + 1][2] - paths[path_idx][2]) > 0.3: - different_height = True - break - return different_height - - -def transform_rotation_z_90degrees(rotation): - z_rot_90 = [np.cos(np.pi / 4), 0, 0, np.sin(np.pi / 4)] # 90 degrees = pi/2 radians - w1, x1, y1, z1 = rotation - w2, x2, y2, z2 = z_rot_90 - revised_rotation = [ - w1 * w2 - x1 * x2 - y1 * y2 - z1 * z2, # w - w1 * x2 + x1 * w2 + y1 * z2 - z1 * y2, # x - w1 * y2 - x1 * z2 + y1 * w2 + z1 * x2, # y - w1 * z2 + x1 * y2 - y1 * x2 + z1 * w2, # z - ] - return revised_rotation - - -def load_data(dataset_root_dir, split, filter_same_trajectory=True, filter_stairs=True, dataset_type='mp3d'): - with gzip.open(os.path.join(dataset_root_dir, split, f"{split}.json.gz"), 'rt', encoding='utf-8') as f: - data = json.load(f)['episodes'] - - if dataset_type == 'mp3d': - scenes = list(set([x['scene_id'] for x in data])) # e.g. 'mp3d/zsNo4HB9uLZ/zsNo4HB9uLZ.glb' - elif dataset_type == 'kujiale': - scenes = list(set([x['scan'] for x in data])) - else: - raise Exception(f"Unsupported dataset type {dataset_type}, please update cfg to contain valid dataset_type") - scenes.sort() - new_data = {} - for scene in scenes: - if dataset_type == 'mp3d': - scene_data = [x for x in data if x['scene_id'] == scene] - scan = scene.split('/')[1] # e.g. 'zsNo4HB9uLZ' - else: - scene_data = [x for x in data if x['scan'] == scene] - scan = scene - new_scene_data = [] - for item in scene_data: - new_item = copy.deepcopy(item) - new_item['scan'] = scan - new_item['original_start_position'] = item['start_position'] - new_item['original_start_rotation'] = item['start_rotation'] - if dataset_type == 'mp3d': - x, z, y = item['start_position'] - new_item['start_position'] = [x, -y, z] - r1, r2, r3, r4 = item['start_rotation'] - new_item['start_rotation'] = transform_rotation_z_90degrees([-r4, r1, r3, -r2]) - new_item['reference_path'] = [[x, -y, z] for x, z, y in item['reference_path']] - new_scene_data.append(new_item) - - new_data[scan] = new_scene_data - - data = copy.deepcopy(new_data) - new_data = defaultdict(list) - - # filter_same_trajectory - if filter_same_trajectory: - total_count = 0 - remaining_count = 0 - trajectory_list = [] - for scan, data_item in data.items(): - for item in data_item: - total_count += 1 - if item['trajectory_id'] in trajectory_list: - continue - remaining_count += 1 - trajectory_list.append(item['trajectory_id']) - new_data[scan].append(item) - log.info(f'[split:{split}]filter_same_trajectory remain: [ {remaining_count} / {total_count} ]') - data = new_data - new_data = defaultdict(list) - - if filter_stairs: - total_count = 0 - remaining_count = 0 - for scan, data_item in data.items(): - for item in data_item: - total_count += 1 - if has_stairs(item) or different_height(item): - continue - remaining_count += 1 - new_data[scan].append(item) - log.info(f'[split:{split}]filter_stairs remain: [ {remaining_count} / {total_count} ]') - data = new_data - - return data - - -def load_scene_usd(mp3d_data_dir, scan): - """Load scene USD based on the scan""" - from internutopia.core.util import is_in_container - - find_flag = False - for root, dirs, files in os.walk(os.path.join(mp3d_data_dir, scan)): - target_file_name = 'fixed_docker.usd' if is_in_container() else 'fixed.usd' - for file in files: - if file == target_file_name: - scene_usd_path = os.path.join(root, file) - find_flag = True - break - if find_flag: - break - if not find_flag: - log.error('Scene USD not found for scan %s', scan) - return None - return scene_usd_path - - -def load_kujiale_scene_usd(kujiale_iros_data_dir, scan): - """Load scene USD based on the scan""" - scene_usd_path = os.path.join(kujiale_iros_data_dir, scan, f'{scan}.usda') - if not os.path.exists(scene_usd_path): - log.error('Scene USD not found for scan %s', scan) - return None - return scene_usd_path - - def get_new_position_and_rotation(robot_position, robot_rotation, action): from omni.isaac.core.utils.rotations import ( euler_angles_to_quat, diff --git a/internnav/evaluator/utils/dataset.py b/internnav/evaluator/utils/dataset.py index c4f224c..7db38f4 100644 --- a/internnav/evaluator/utils/dataset.py +++ b/internnav/evaluator/utils/dataset.py @@ -1,112 +1,15 @@ -import os -import sys import json +import os import lmdb import msgpack_numpy from internnav import PROJECT_ROOT_PATH -from internnav.evaluator.utils.common import load_data -from internnav.evaluator.utils.config import get_lmdb_path, get_lmdb_prefix - from internnav.configs.evaluator import EvalDatasetCfg -from .config import Config - +from internnav.env.utils.episode_loader.dataset_utils import load_data +from internnav.evaluator.utils.config import get_lmdb_path -def split_data(dataset_cfg: EvalDatasetCfg): - if isinstance(dataset_cfg.dataset_settings, dict): - config = Config(**dataset_cfg.dataset_settings) - run_type = config.run_type - split_number = 1 # config.total_rank - run_type = run_type - name = config.task_name - split_data_types = config.split_data_types - base_data_dir = config.base_data_dir - filter_stairs = config.filter_stairs - - print(f'run_type:{run_type}') - print(f'name:{name}') - print(f'split_data_types:{split_data_types}') - prefix = get_lmdb_prefix(run_type) - if run_type == 'eval': - filter_same_trajectory = False - elif run_type == 'sample': - filter_same_trajectory = True - else: - print(f'unknown run_type:{run_type}') - sys.exit() - - lmdb_path = get_lmdb_path(name) - # get all data - path_key_map = {} - count = 0 - - dataset_type = dataset_cfg.dataset_type - for split_data_type in split_data_types: - data_map = load_data( - base_data_dir, - split_data_type, - filter_same_trajectory=filter_same_trajectory, - filter_stairs=filter_stairs, - dataset_type=dataset_type, - ) - for scan, path_list in data_map.items(): - path_key_list = [] - for path in path_list: - trajectory_id = path['trajectory_id'] - episode_id = path['episode_id'] - path_key = f'{trajectory_id}_{episode_id}' - path_key_list.append(path_key) - path_key_map[scan] = path_key_list - count += len(path_key_list) - - print(f'TOTAL:{count}') - - # split rank - rank_map = {} - split_length = count // split_number - index = -1 - for scan, path_key_list in path_key_map.items(): - for path_key in path_key_list: - index += 1 - rank = index // split_length - if rank >= split_number: - rank = split_number - 1 - rank_map[path_key] = rank - - ranked_data = {} - for i in range(split_number): - filtered_path_key_map = {} - for scan, path_key_list in path_key_map.items(): - filtered_list = [] - for path_key in path_key_list: - if rank_map[path_key] == i: - filtered_list.append(path_key) - if len(filtered_list) > 0: - filtered_path_key_map[scan] = filtered_list - ranked_data[i] = filtered_path_key_map - - for rank, path_key_map in ranked_data.items(): - count = 0 - for scan, path_key_list in path_key_map.items(): - count += len(path_key_list) - print(f'[rank:{rank}][scan:{scan}][count:{len(path_key_list)}]') - print(f'[rank:{rank}][count:{count}]') - - if not os.path.exists(lmdb_path): - os.makedirs(lmdb_path) - database = lmdb.open( - f'{lmdb_path}/sample_data.lmdb', - map_size=1 * 1024 * 1024 * 1024 * 1024, - max_dbs=0, - ) - with database.begin(write=True) as txn: - for rank, path_key_map in ranked_data.items(): - key = f'{prefix}_{rank}'.encode() - value = msgpack_numpy.packb(path_key_map, use_bin_type=True) - txn.put(key, value) - print(f'finish [key:{key}]') - database.close() +from .config import Config class ResultLogger: @@ -151,7 +54,7 @@ def get_split_map( def write_now_result_json(self): # create log file - log_content = [] + # log_content = [] self.database_read = lmdb.open( f'{self.lmdb_path}/sample_data.lmdb', map_size=1 * 1024 * 1024 * 1024 * 1024, @@ -209,23 +112,23 @@ def write_now_result_json(self): reason_map[ret_type] = reason_map[ret_type] + 1 if success > 0: reason_map['reach_goal'] = reason_map['reach_goal'] + 1 - + if count == 0: continue - json_data[split]={} - json_data[split]['TL']=round((total_TL / count),4) - json_data[split]['NE']=round((total_NE / count),4) + json_data[split] = {} + json_data[split]['TL'] = round((total_TL / count), 4) + json_data[split]['NE'] = round((total_NE / count), 4) if 'fall' not in reason_map: reason_map['fall'] = 0 - json_data[split]['FR']=round((reason_map['fall'] / count),4) + json_data[split]['FR'] = round((reason_map['fall'] / count), 4) if 'stuck' in reason_map: - json_data[split]['StR']=round((reason_map['stuck'] / count),4) + json_data[split]['StR'] = round((reason_map['stuck'] / count), 4) else: - json_data[split]['StR']=0 - json_data[split]['OS']=round((total_osr / count),4) - json_data[split]['SR']=round((total_success / count),4) - json_data[split]['SPL']=round((total_spl / count),4) - json_data[split]['Count']=count + json_data[split]['StR'] = 0 + json_data[split]['OS'] = round((total_osr / count), 4) + json_data[split]['SR'] = round((total_success / count), 4) + json_data[split]['SPL'] = round((total_spl / count), 4) + json_data[split]['Count'] = count # write log content to file with open(f'{self.dataset_type}_result.json', 'w') as f: diff --git a/internnav/evaluator/vln_multi_evaluator.py b/internnav/evaluator/vln_multi_distributed_evaluator.py similarity index 89% rename from internnav/evaluator/vln_multi_evaluator.py rename to internnav/evaluator/vln_multi_distributed_evaluator.py index e573c7a..8efb7c7 100644 --- a/internnav/evaluator/vln_multi_evaluator.py +++ b/internnav/evaluator/vln_multi_distributed_evaluator.py @@ -1,4 +1,3 @@ -import sys from enum import Enum from pathlib import Path from time import time @@ -7,14 +6,12 @@ import numpy as np from internnav.configs.evaluator import EvalCfg -from internnav.evaluator.base import Evaluator +from internnav.evaluator import DistributedEvaluator, Evaluator from internnav.evaluator.utils.common import set_seed_model from internnav.evaluator.utils.config import get_lmdb_path from internnav.evaluator.utils.data_collector import DataCollector -from internnav.evaluator.utils.dataset import ResultLogger, split_data -from internnav.evaluator.utils.eval import generate_episode +from internnav.evaluator.utils.dataset import ResultLogger from internnav.evaluator.utils.visualize_util import VisualizeUtil -from internnav.projects.dataloader.resumable import ResumablePathKeyDataloader from internnav.utils import common_log_util, progress_log_multi_util from internnav.utils.common_log_util import common_logger as log @@ -27,27 +24,14 @@ class runner_status_code(Enum): STOP = 4 -@Evaluator.register('vln_multi') -class VlnMultiEvaluator(Evaluator): +@Evaluator.register('vln_multi_distributed') +class VlnMultiDistributedEvaluator(DistributedEvaluator): def __init__(self, config: EvalCfg): self.task_name = config.task.task_name - if not Path(get_lmdb_path(self.task_name)).exists(): - split_data(config.dataset) self.result_logger = ResultLogger(config.dataset) - common_log_util.init(self.task_name) - self.dataloader = ResumablePathKeyDataloader(config.dataset.dataset_type, **config.dataset.dataset_settings) self.dataset_name = Path(config.dataset.dataset_settings['base_data_dir']).name - progress_log_multi_util.init(self.task_name, self.dataloader.size) - self.total_path_num = self.dataloader.size - progress_log_multi_util.progress_logger_multi.info( - f'start eval dataset: {self.task_name}, total_path: {self.dataloader.size}' # noqa: E501 - ) - # generate episode - episodes = generate_episode(self.dataloader, config) - if len(episodes) == 0: - log.info("No more episodes to evaluate. Episodes are saved in data/sample_episodes/") - sys.exit(0) - config.task.task_settings.update({'episodes': episodes}) + + # vec env settings self.env_num = config.task.task_settings['env_num'] self.proc_num = ( config.env.env_settings['distribution_config']['proc_num'] @@ -62,16 +46,25 @@ def __init__(self, config: EvalCfg): while self.proc_num > 1 and self.proc_num * self.env_num > self.total_path_num: self.proc_num -= 1 log.info(f'dataset size is too small! Change proc_num to {self.proc_num}.') - # update + + # update config config.task.task_settings['env_num'] = self.env_num if 'distribution_config' in config.env.env_settings: config.env.env_settings['distribution_config']['proc_num'] = self.proc_num config.agent.model_settings.update({'env_num': self.env_num, 'proc_num': self.proc_num}) self.robot_name = config.task.robot_name + super().__init__(config) set_seed_model(0) - self.data_collector = DataCollector(self.dataloader.lmdb_path) + + common_log_util.init(self.task_name) + self.total_path_num = len(self.env.episodes) + progress_log_multi_util.init(self.task_name, self.total_path_num) + progress_log_multi_util.progress_logger_multi.info( + f'start eval dataset: {self.task_name}, total_path: {self.total_path_num}' # noqa: E501 + ) + self.data_collector = DataCollector(get_lmdb_path(self.task_name)) self.robot_flash = config.task.robot_flash self.save_to_json = config.eval_settings['save_to_json'] self.vis_output = config.eval_settings['vis_output'] @@ -96,7 +89,7 @@ def warm_up(self): action=[{self.robot_name: {'stand_still': []}} for _ in range(self.env_num * self.proc_num)] ) if obs[0][self.robot_name]['finish_action']: - print('get_obs') + # print('get_obs') break return obs @@ -168,10 +161,10 @@ def env_step(self, action): self.runner_status[ np.logical_and(self.runner_status == runner_status_code.NORMAL, action == {'h1': {'stop': []}}) ] = runner_status_code.STOP - print(action) - t0 = time() + # print(action) + # t0 = time() obs, reward, terminated, truncated, info = self.env.step(action=action.tolist()) - print(f"inner one step time {time() - t0}") + # print(f"inner one step time {time() - t0}") obs = self._obs_remove_robot_name(obs) finish_status = np.logical_or( np.array([ob['finish_action'] for ob in obs]), @@ -184,14 +177,21 @@ def env_step(self, action): ) or np.logical_and.reduce(np.array(finish_status)): self.runner_status[self.runner_status == runner_status_code.STOP] = runner_status_code.NORMAL break - if __debug__ and np.logical_or.reduce(np.array(finish_status)): - print(f'finish_status: {finish_status}') + # if __debug__ and np.logical_or.reduce(np.array(finish_status)): + # print(f'finish_status: {finish_status}') end_time = time() duration = round(end_time - start_time, 2) log.info(f'env step time: {duration}s') return obs, terminated def terminate_ops(self, obs_ls, reset_infos, terminated_ls): + """ + 1. reset agent if finished warm up + 2. reset envs that are terminated + 3. start new trace log and visualize log + 4. return whether all envs are terminated + 5. return updated reset_infos + """ finish_warmup_ls = (self.runner_status == runner_status_code.WARM_UP) & [ob['finish_action'] for ob in obs_ls] if np.logical_or.reduce(finish_warmup_ls): self.agent.reset(np.where(finish_warmup_ls)[0].tolist()) @@ -249,7 +249,7 @@ def terminate_ops(self, obs_ls, reset_infos, terminated_ls): reset_infos = reset_infos.tolist() if np.logical_and.reduce(self.runner_status == runner_status_code.TERMINATED): - print('finished') + # print('finished') return True, reset_infos for reset_info in new_reset_infos: if reset_info is None: @@ -268,7 +268,7 @@ def terminate_ops(self, obs_ls, reset_infos, terminated_ls): def eval(self): print('--- VlnMultiEvaluator start ---') obs, reset_info = self.env.reset() - print('obs:', obs) + # print('obs:', obs) for info in reset_info: if info is None: continue @@ -293,10 +293,20 @@ def eval(self): self.runner_status[[info is None for info in reset_info]] = runner_status_code.TERMINATED while self.env.is_running(): - + start_time = time() + # get action from agent obs, action = self.get_action(obs, action) + log.info(f'get_action time: {round(time() - start_time, 2)}s') + + # step env + start_time = time() obs, terminated = self.env_step(action) + log.info(f'env_step time: {round(time() - start_time, 2)}s') + + # terminate ops + start_time = time() env_term, reset_info = self.terminate_ops(obs, reset_info, terminated) + log.info(f'terminate_ops time: {round(time() - start_time, 2)}s') if env_term: break diff --git a/internnav/projects/__init__.py b/internnav/projects/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/internnav/utils/progress_log_multi_util.py b/internnav/utils/progress_log_multi_util.py index c7c60b1..7ad3655 100644 --- a/internnav/utils/progress_log_multi_util.py +++ b/internnav/utils/progress_log_multi_util.py @@ -68,6 +68,7 @@ def init(dataset_name, path_count): formatter = logging.Formatter('[%(asctime)s][%(levelname)s] %(message)s') file_handler.setFormatter(formatter) progress_logger_multi.addHandler(file_handler) + progress_logger_multi.disabled = False INITED = True diff --git a/scripts/eval/bash/start_aliyun_dlc.sh b/scripts/eval/bash/start_aliyun_dlc.sh index 14d5e90..cb4efc6 100755 --- a/scripts/eval/bash/start_aliyun_dlc.sh +++ b/scripts/eval/bash/start_aliyun_dlc.sh @@ -1,26 +1,65 @@ #!/bin/bash + +# Activate conda automatically source /root/miniconda3/etc/profile.d/conda.sh -conda activate internutopia - -while [[ $# -gt 0 ]]; do - case $1 in - --config) - CONFIG="$2" - shift 2 - ;; - *) - echo "Unknown parameter: $1" - exit 1 - ;; - esac -done - -if [ "$RANK" -eq 0 ]; then - RAY_max_direct_call_object_size=104857600 ray start --head --port=6379 - sleep 20s - bash scripts/eval/start_eval_iros.sh - sleep inf -else - RAY_max_direct_call_object_size=104857600 ray start --address=${MASTER_ADDR}:6379 - sleep inf -fi + +mode="$1" +shift # remove first argument so only extra args left (--config ...) + +case "$mode" in + habitat) + echo "[run.sh] Starting HABITAT evaluation..." + + conda activate habitat + + python scripts/eval/eval.py \ + --config scripts/eval/configs/habitat_cfg.py \ + > logs/internvla_n1_log.txt 2>&1 + + ;; + + internutopia) + echo "[run.sh] Starting INTERNUTOPIA evaluation..." + + conda activate internutopia + + # -------- parse remaining arguments (e.g., --config xxx) -------- + while [[ $# -gt 0 ]]; do + case $1 in + --config) + CONFIG="$2" + shift 2 + ;; + *) + echo "Unknown parameter: $1" + exit 1 + ;; + esac + done + # ---------------------------------------------------------------- + + if [ "$RANK" -eq 0 ]; then + echo "[run.sh] Starting Ray head..." + RAY_max_direct_call_object_size=104857600 \ + ray start --head --port=6379 + + sleep 20s + + echo "[run.sh] Exec start_eval.sh..." + bash scripts/eval/bash/start_eval.sh + + sleep inf + else + echo "[run.sh] Starting Ray worker..." + RAY_max_direct_call_object_size=104857600 \ + ray start --address=${MASTER_ADDR}:6379 + + sleep inf + fi + ;; + + *) + echo "Usage: $0 {habitat|internutopia} [--config xxx]" + exit 1 + ;; +esac diff --git a/scripts/eval/bash/torchrun_eval.sh b/scripts/eval/bash/torchrun_eval.sh index 00303c5..df3ddfd 100644 --- a/scripts/eval/bash/torchrun_eval.sh +++ b/scripts/eval/bash/torchrun_eval.sh @@ -1,20 +1,26 @@ # use to run distributed eval with 4 gpus on single node -MID_RUN_NAME="InternVLA-N1" +while [[ $# -gt 0 ]]; do + case $1 in + --config) + CONFIG="$2" + shift 2 + ;; + *) + echo "Unknown argument: $1" + exit 1 + ;; + esac +done + +# Extract the prefix from the config filename +CONFIG_BASENAME=$(basename "$CONFIG" .py) +CONFIG_PREFIX=$(echo "$CONFIG_BASENAME" | sed 's/_cfg$//') +EVAL_LOG="logs/${CONFIG_PREFIX}_eval.log" + torchrun \ --nproc_per_node=8 \ --master_port=2333 \ scripts/eval/eval.py \ - --config scripts/eval/configs/habitat_cfg.py \ - > logs/${MID_RUN_NAME}_log.txt 2>&1 - -# CUDA_VISIBLE_DEVICES=6,7 -# MID_RUN_NAME="InternVLA-N1" -# torchrun \ -# --nproc_per_node=8 \ -# --master_port=29501 \ -# scripts/eval/eval_habitat.py \ -# --model_path checkpoints/InternVLA-N1 \ -# --continuous_traj \ -# --output_path logs/habitat/test_new_checkpoint2 \ -# > logs/${MID_RUN_NAME}_old_log1.txt 2>&1 + --config $CONFIG \ + > $EVAL_LOG 2>&1 diff --git a/scripts/eval/configs/h1_cma_cfg.py b/scripts/eval/configs/h1_cma_cfg.py index eae6a51..05fcb01 100644 --- a/scripts/eval/configs/h1_cma_cfg.py +++ b/scripts/eval/configs/h1_cma_cfg.py @@ -22,11 +22,11 @@ }, ), task=TaskCfg( - task_name='cma_plus_eval', + task_name='cma_plus_refactor_debug', task_settings={ - 'env_num': 2, + 'env_num': 1, 'use_distributed': False, - 'proc_num': 2, + 'proc_num': 8, }, scene=SceneCfg( scene_type='mp3d', @@ -44,9 +44,13 @@ dataset_settings={ 'base_data_dir': 'data/vln_pe/raw_data/r2r', 'split_data_types': ['val_unseen', 'val_seen'], - 'filter_stairs': False, + 'filter_stairs': True, }, ), - eval_type='vln_multi', - eval_settings={'save_to_json': True, 'vis_output': False}, + eval_type='vln_multi_distributed', + eval_settings={ + 'save_to_json': True, + 'vis_output': True, + 'use_agent_server': False, + }, ) diff --git a/scripts/eval/configs/h1_internvla_n1_cfg.py b/scripts/eval/configs/h1_internvla_n1_cfg.py index e6411e7..f367473 100644 --- a/scripts/eval/configs/h1_internvla_n1_cfg.py +++ b/scripts/eval/configs/h1_internvla_n1_cfg.py @@ -30,7 +30,7 @@ 'predict_step_nums': 32, 'continuous_traj': True, # debug - 'vis_debug': True, # If vis_debug=True, you can get visualization results + 'vis_debug': False, # If vis_debug=True, you can get visualization results 'vis_debug_path': './logs/test/vis_debug', }, ), @@ -64,11 +64,15 @@ dataset_settings={ 'base_data_dir': 'data/vln_pe/raw_data/r2r', 'split_data_types': ['val_unseen'], # 'val_seen' - 'filter_stairs': False, + 'filter_stairs': True, # 'selected_scans': ['zsNo4HB9uLZ'], # 'selected_scans': ['8194nk5LbLH', 'pLe4wQe7qrG'], }, ), - eval_type='vln_multi', - eval_settings={'save_to_json': True, 'vis_output': False}, + eval_type='vln_multi_distributed', + eval_settings={ + 'save_to_json': True, + 'vis_output': False, + 'use_agent_server': False, + }, ) diff --git a/scripts/eval/configs/h1_rdp_cfg.py b/scripts/eval/configs/h1_rdp_cfg.py index a7e0254..71b519b 100644 --- a/scripts/eval/configs/h1_rdp_cfg.py +++ b/scripts/eval/configs/h1_rdp_cfg.py @@ -22,11 +22,11 @@ }, ), task=TaskCfg( - task_name='rdp_eval', + task_name='cma_plus_refactor_debug', task_settings={ - 'env_num': 2, - 'use_distributed': True, - 'proc_num': 1, + 'env_num': 1, + 'use_distributed': False, + 'proc_num': 8, }, scene=SceneCfg( scene_type='mp3d', @@ -36,15 +36,21 @@ robot_usd_path='data/Embodiments/vln-pe/h1/h1_vln_pointcloud.usd', camera_resolution=[256, 256], # (W,H) camera_prim_path='torso_link/h1_pano_camera_0', + vlnce=False, # vlnpe by default + obstacle_detection=False, # whether allow flash across obstacle ), dataset=EvalDatasetCfg( dataset_type="mp3d", dataset_settings={ 'base_data_dir': 'data/vln_pe/raw_data/r2r', 'split_data_types': ['val_unseen', 'val_seen'], - 'filter_stairs': False, + 'filter_stairs': True, }, ), - eval_type='vln_multi', - eval_settings={'save_to_json': True, 'vis_output': False}, + eval_type='vln_multi_distributed', + eval_settings={ + 'save_to_json': True, + 'vis_output': True, + 'use_agent_server': True, + }, ) diff --git a/scripts/eval/configs/h1_seq2seq_cfg.py b/scripts/eval/configs/h1_seq2seq_cfg.py index 4fd9c19..0d2d9de 100644 --- a/scripts/eval/configs/h1_seq2seq_cfg.py +++ b/scripts/eval/configs/h1_seq2seq_cfg.py @@ -22,11 +22,11 @@ }, ), task=TaskCfg( - task_name='seq2seq_eval', + task_name='cma_plus_refactor_debug', task_settings={ - 'env_num': 2, - 'use_distributed': True, - 'proc_num': 1, + 'env_num': 1, + 'use_distributed': False, + 'proc_num': 8, }, scene=SceneCfg( scene_type='mp3d', @@ -36,15 +36,21 @@ robot_usd_path='data/Embodiments/vln-pe/h1/h1_vln_pointcloud.usd', camera_resolution=[256, 256], # (W,H) camera_prim_path='torso_link/h1_pano_camera_0', + vlnce=False, # vlnpe by default + obstacle_detection=False, # whether allow flash across obstacle ), dataset=EvalDatasetCfg( dataset_type="mp3d", dataset_settings={ 'base_data_dir': 'data/vln_pe/raw_data/r2r', 'split_data_types': ['val_unseen', 'val_seen'], - 'filter_stairs': False, + 'filter_stairs': True, }, ), - eval_type='vln_multi', - eval_settings={'save_to_json': True, 'vis_output': False}, + eval_type='vln_multi_distributed', + eval_settings={ + 'save_to_json': True, + 'vis_output': True, + 'use_agent_server': True, + }, ) diff --git a/scripts/eval/eval.py b/scripts/eval/eval.py index 79d0cda..55b4814 100644 --- a/scripts/eval/eval.py +++ b/scripts/eval/eval.py @@ -37,7 +37,7 @@ def main(): evaluator_cfg = load_eval_cfg(args.config, attr_name='eval_cfg') # fill in evaluator default config - if evaluator_cfg.eval_type == 'vln_multi': + if evaluator_cfg.eval_type == 'vln_multi_distributed': from internnav.configs.evaluator.vln_default_config import get_config evaluator_cfg = get_config(evaluator_cfg) From 43957f64ff2b88807f5923b02237ccb95bbe713e Mon Sep 17 00:00:00 2001 From: wangyukai Date: Mon, 17 Nov 2025 07:11:38 +0000 Subject: [PATCH 17/35] cma tested --- internnav/env/internutopia_env.py | 6 ++--- internnav/evaluator/distributed_base.py | 2 +- .../vln_multi_distributed_evaluator.py | 26 +++++++++++-------- internnav/utils/dist.py | 2 +- scripts/eval/configs/h1_cma_cfg.py | 2 +- 5 files changed, 21 insertions(+), 17 deletions(-) diff --git a/internnav/env/internutopia_env.py b/internnav/env/internutopia_env.py index ba7793f..453c374 100644 --- a/internnav/env/internutopia_env.py +++ b/internnav/env/internutopia_env.py @@ -31,8 +31,8 @@ def __init__(self, env_config: EnvCfg, task_config: TaskCfg): # generate episodes self.episode_loader = ResumablePathKeyEpisodeloader( - env_config.dataset.dataset_type, - **env_config.dataset.dataset_settings, + env_settings['dataset'].dataset_type, + **env_settings['dataset'].dataset_settings, rank=env_settings['rank'], world_size=env_settings['world_size'] ) @@ -42,7 +42,7 @@ def __init__(self, env_config: EnvCfg, task_config: TaskCfg): task_settings.update({'episodes': self.episodes}) # set visible device for isaac sim - os.environ["CUDA_VISIBLE_DEVICES"] = env_settings.get('local_rank', '0') + os.environ["CUDA_VISIBLE_DEVICES"] = str(env_settings.get('local_rank', 0)) config = Config( simulator=SimConfig(**env_settings), diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index fca3b9d..a50a477 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -44,7 +44,7 @@ def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True) cfg.env.env_settings['rank'] = get_rank() cfg.env.env_settings['local_rank'] = self.local_rank cfg.env.env_settings['world_size'] = get_world_size() - cfg.env.dataset = cfg.dataset + cfg.env.env_settings['dataset'] = cfg.dataset self.eval_config = cfg diff --git a/internnav/evaluator/vln_multi_distributed_evaluator.py b/internnav/evaluator/vln_multi_distributed_evaluator.py index 8efb7c7..776e06e 100644 --- a/internnav/evaluator/vln_multi_distributed_evaluator.py +++ b/internnav/evaluator/vln_multi_distributed_evaluator.py @@ -128,6 +128,7 @@ def _transform_action_batch(self, actions: List[Dict], flash=False): return transformed_actions def get_action(self, obs, action): + start_time = time() # process obs obs = np.array(obs) fake_obs_index = np.logical_or( @@ -143,6 +144,9 @@ def get_action(self, obs, action): # change warm_up action = np.array(action) action[self.runner_status == runner_status_code.WARM_UP] = {'h1': {'stand_still': []}} + end_time = time() + duration = round(end_time - start_time, 2) + log.info(f'[TIME] agent step time: {duration}s') return obs, action def _need_reset(self, terminated_ls): @@ -155,6 +159,7 @@ def _need_reset(self, terminated_ls): def env_step(self, action): start_time = time() + # stop_count = [0 for _ in range(self.env_num * self.sim_num)] while True: # stop action maybe also need 50 steps @@ -181,7 +186,7 @@ def env_step(self, action): # print(f'finish_status: {finish_status}') end_time = time() duration = round(end_time - start_time, 2) - log.info(f'env step time: {duration}s') + log.info(f'[TIME] env step time: {duration}s') return obs, terminated def terminate_ops(self, obs_ls, reset_infos, terminated_ls): @@ -192,6 +197,8 @@ def terminate_ops(self, obs_ls, reset_infos, terminated_ls): 4. return whether all envs are terminated 5. return updated reset_infos """ + start_time = time() + finish_warmup_ls = (self.runner_status == runner_status_code.WARM_UP) & [ob['finish_action'] for ob in obs_ls] if np.logical_or.reduce(finish_warmup_ls): self.agent.reset(np.where(finish_warmup_ls)[0].tolist()) @@ -263,6 +270,10 @@ def terminate_ops(self, obs_ls, reset_infos, terminated_ls): self.visualize_util.trace_start( trajectory_id=self.now_path_key(reset_info), reference_path=reset_info.data['reference_path'] ) + + end_time = time() + duration = round(end_time - start_time, 2) + log.info(f'[TIME] reset time: {duration}s') return False, reset_infos def eval(self): @@ -293,21 +304,14 @@ def eval(self): self.runner_status[[info is None for info in reset_info]] = runner_status_code.TERMINATED while self.env.is_running(): - start_time = time() # get action from agent obs, action = self.get_action(obs, action) - log.info(f'get_action time: {round(time() - start_time, 2)}s') - # step env - start_time = time() obs, terminated = self.env_step(action) - log.info(f'env_step time: {round(time() - start_time, 2)}s') - # terminate ops - start_time = time() - env_term, reset_info = self.terminate_ops(obs, reset_info, terminated) - log.info(f'terminate_ops time: {round(time() - start_time, 2)}s') - if env_term: + env_terminate, reset_info = self.terminate_ops(obs, reset_info, terminated) + + if env_terminate: break # save step obs diff --git a/internnav/utils/dist.py b/internnav/utils/dist.py index 3f7f1d0..0b7ac64 100644 --- a/internnav/utils/dist.py +++ b/internnav/utils/dist.py @@ -225,7 +225,7 @@ def init_distributed_mode(dist_url="env://", port=29529, backend="nccl", timeout else: print("Not using distributed mode") setup_for_distributed(is_master=True) - return + return 0 import socket diff --git a/scripts/eval/configs/h1_cma_cfg.py b/scripts/eval/configs/h1_cma_cfg.py index 05fcb01..c794d9e 100644 --- a/scripts/eval/configs/h1_cma_cfg.py +++ b/scripts/eval/configs/h1_cma_cfg.py @@ -51,6 +51,6 @@ eval_settings={ 'save_to_json': True, 'vis_output': True, - 'use_agent_server': False, + 'use_agent_server': True, }, ) From a9ca15dedd4ffa9452a015ec7e6780404d65dcc1 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Mon, 17 Nov 2025 11:03:41 +0000 Subject: [PATCH 18/35] cma tested; episode loader; torchrun; local agent tested; TODO fix isaac sim gpu setting --- internnav/env/utils/episode_loader/resumable.py | 9 +++++++-- internnav/evaluator/distributed_base.py | 3 +-- internnav/evaluator/utils/data_collector.py | 8 +++++++- .../evaluator/vln_multi_distributed_evaluator.py | 11 +++++++++-- scripts/eval/bash/torchrun_eval.sh | 2 ++ scripts/eval/configs/h1_cma_cfg.py | 4 ++-- scripts/eval/configs/h1_internvla_n1_cfg.py | 4 ++-- 7 files changed, 30 insertions(+), 11 deletions(-) diff --git a/internnav/env/utils/episode_loader/resumable.py b/internnav/env/utils/episode_loader/resumable.py index 81dba8c..bee3ac0 100644 --- a/internnav/env/utils/episode_loader/resumable.py +++ b/internnav/env/utils/episode_loader/resumable.py @@ -1,3 +1,5 @@ +import os + import lmdb import msgpack_numpy @@ -37,11 +39,14 @@ def __init__( self.run_type = run_type self.lmdb_path = get_lmdb_path(task_name) self.retry_list = retry_list + + if not os.path.exists(self.lmdb_path): + os.makedirs(self.lmdb_path) + database = lmdb.open( f'{self.lmdb_path}/sample_data.lmdb', map_size=1 * 1024 * 1024 * 1024 * 1024, - readonly=True, - lock=False, + lock=True, ) filtered_target_path_key_list = [] diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index a50a477..7f730e3 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -44,7 +44,6 @@ def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True) cfg.env.env_settings['rank'] = get_rank() cfg.env.env_settings['local_rank'] = self.local_rank cfg.env.env_settings['world_size'] = get_world_size() - cfg.env.env_settings['dataset'] = cfg.dataset self.eval_config = cfg @@ -64,7 +63,7 @@ def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True) from internnav.agent import Agent cfg.agent.model_settings['local_rank'] = self.local_rank - self.agent = Agent(cfg.agent) + self.agent = Agent.init(cfg.agent) def eval(self): """ diff --git a/internnav/evaluator/utils/data_collector.py b/internnav/evaluator/utils/data_collector.py index f721d82..99659b6 100644 --- a/internnav/evaluator/utils/data_collector.py +++ b/internnav/evaluator/utils/data_collector.py @@ -104,7 +104,12 @@ def save_sample_data(self, key, result, instruction): if result != 'success': finish_flag = 'fail' lmdb_file = os.path.join(self.lmdb_path, 'sample_data.lmdb') - database = lmdb.open(lmdb_file, map_size=1 * 1024 * 1024 * 1024 * 1024, max_dbs=0) + database = lmdb.open( + lmdb_file, + map_size=1 * 1024 * 1024 * 1024 * 1024, + max_dbs=0, + lock=True, + ) with database.begin(write=True) as txn: encode_key = key.encode() episode_datas = self.merge_data(self.episode_total_data, self.actions) @@ -129,6 +134,7 @@ def save_eval_result(self, key, result, info): f'{self.lmdb_path}/sample_data.lmdb', map_size=1 * 1024 * 1024 * 1024 * 1024, max_dbs=0, + lock=True, ) with database_write.begin(write=True) as txn: key_write = key.encode() diff --git a/internnav/evaluator/vln_multi_distributed_evaluator.py b/internnav/evaluator/vln_multi_distributed_evaluator.py index 776e06e..9cbb0bc 100644 --- a/internnav/evaluator/vln_multi_distributed_evaluator.py +++ b/internnav/evaluator/vln_multi_distributed_evaluator.py @@ -27,9 +27,12 @@ class runner_status_code(Enum): @Evaluator.register('vln_multi_distributed') class VlnMultiDistributedEvaluator(DistributedEvaluator): def __init__(self, config: EvalCfg): + start_time = time() + self.task_name = config.task.task_name self.result_logger = ResultLogger(config.dataset) self.dataset_name = Path(config.dataset.dataset_settings['base_data_dir']).name + config.env.env_settings['dataset'] = config.dataset # vec env settings self.env_num = config.task.task_settings['env_num'] @@ -70,6 +73,10 @@ def __init__(self, config: EvalCfg): self.vis_output = config.eval_settings['vis_output'] self.visualize_util = VisualizeUtil(self.task_name, fps=6) + end_time = time() + duration = round(end_time - start_time, 2) + log.info(f'[TIME] Env Init time: {duration}s') + @property def ignore_obs_attr(self): return [ @@ -186,7 +193,7 @@ def env_step(self, action): # print(f'finish_status: {finish_status}') end_time = time() duration = round(end_time - start_time, 2) - log.info(f'[TIME] env step time: {duration}s') + log.info(f'[TIME] Env Step time: {duration}s') return obs, terminated def terminate_ops(self, obs_ls, reset_infos, terminated_ls): @@ -273,7 +280,7 @@ def terminate_ops(self, obs_ls, reset_infos, terminated_ls): end_time = time() duration = round(end_time - start_time, 2) - log.info(f'[TIME] reset time: {duration}s') + log.info(f'[TIME] Env Reset time: {duration}s') return False, reset_infos def eval(self): diff --git a/scripts/eval/bash/torchrun_eval.sh b/scripts/eval/bash/torchrun_eval.sh index df3ddfd..463570c 100644 --- a/scripts/eval/bash/torchrun_eval.sh +++ b/scripts/eval/bash/torchrun_eval.sh @@ -1,5 +1,7 @@ # use to run distributed eval with 4 gpus on single node +CONFIG=scripts/eval/configs/h1_cma_cfg.py + while [[ $# -gt 0 ]]; do case $1 in --config) diff --git a/scripts/eval/configs/h1_cma_cfg.py b/scripts/eval/configs/h1_cma_cfg.py index c794d9e..331a0cb 100644 --- a/scripts/eval/configs/h1_cma_cfg.py +++ b/scripts/eval/configs/h1_cma_cfg.py @@ -22,7 +22,7 @@ }, ), task=TaskCfg( - task_name='cma_plus_refactor_debug', + task_name='cma_plus_refactor_debug_local_dist', task_settings={ 'env_num': 1, 'use_distributed': False, @@ -51,6 +51,6 @@ eval_settings={ 'save_to_json': True, 'vis_output': True, - 'use_agent_server': True, + 'use_agent_server': False, }, ) diff --git a/scripts/eval/configs/h1_internvla_n1_cfg.py b/scripts/eval/configs/h1_internvla_n1_cfg.py index f367473..e81ff52 100644 --- a/scripts/eval/configs/h1_internvla_n1_cfg.py +++ b/scripts/eval/configs/h1_internvla_n1_cfg.py @@ -45,7 +45,7 @@ task_name='test', task_settings={ 'env_num': 1, - 'use_distributed': False, # If the others setting in task_settings, please set use_distributed = False. + 'use_distributed': False, # flag for multi isaac sims, must be False because currently internvla-n1 agent unsupported batch observation 'proc_num': 1, }, scene=SceneCfg( @@ -73,6 +73,6 @@ eval_settings={ 'save_to_json': True, 'vis_output': False, - 'use_agent_server': False, + 'use_agent_server': False, # If use_agent_server=True, please start the agent server first. }, ) From 6e93ba032407e30b9521f9980845ddd04ab45e3e Mon Sep 17 00:00:00 2001 From: wangyukai Date: Mon, 17 Nov 2025 12:35:57 +0000 Subject: [PATCH 19/35] add vlnpe distributed script --- scripts/eval/bash/eval_vlnpe_distributed.sh | 25 +++++++++++++++++++++ 1 file changed, 25 insertions(+) create mode 100644 scripts/eval/bash/eval_vlnpe_distributed.sh diff --git a/scripts/eval/bash/eval_vlnpe_distributed.sh b/scripts/eval/bash/eval_vlnpe_distributed.sh new file mode 100644 index 0000000..14f15b8 --- /dev/null +++ b/scripts/eval/bash/eval_vlnpe_distributed.sh @@ -0,0 +1,25 @@ +#!/bin/bash +# vlnpe distributed scripts for dlc and slurm +# use this to run distributed eval with 1 gpus on single node +# set use_agent_server=False in config file to use local agent on single node + +source /root/miniconda3/etc/profile.d/conda.sh +conda activate internutopia + +CONFIG=scripts/eval/configs/h1_internvla_n1_cfg.py +while [[ $# -gt 0 ]]; do + case $1 in + --config) + CONFIG="$2" + shift 2 + ;; + *) + echo "Unknown argument: $1" + exit 1 + ;; + esac +done + +# use srun for slurm eval +python scripts/eval/eval.py \ + --config $CONFIG \ From b4af0cebbbcb7c4b660b020fd41ef2e6b33c1129 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Tue, 18 Nov 2025 06:55:26 +0000 Subject: [PATCH 20/35] add grscene; add new result write and resumble load data feature based on lmdb path + rank; remove TODOs and unused files --- .../env/utils/episode_loader/dataset_utils.py | 6 +- .../env/utils/episode_loader/resumable.py | 2 +- .../habitat_extensions/evaluator_single.py | 695 ------------------ .../utils/habitat_extensions/fonts/arial.ttf | Bin 311636 -> 0 bytes .../env/utils/habitat_extensions/maps.py | 370 ---------- .../env/utils/habitat_extensions/measures.py | 560 -------------- internnav/evaluator/utils/data_collector.py | 6 +- internnav/evaluator/utils/dataset.py | 95 +++ .../vln_multi_distributed_evaluator.py | 17 +- internnav/internnav_habitat/README.md | 2 - .../habitat_vln_evaluator.py | 3 +- internnav/internnav_habitat/refactor_notes.md | 66 -- scripts/eval/bash/start_eval.sh | 2 +- scripts/eval/bash/torchrun_eval.sh | 4 +- scripts/eval/configs/h1_internvla_n1_cfg.py | 2 +- scripts/eval/configs/h1_rdp_cfg.py | 10 +- scripts/eval/configs/habitat_cfg.py | 2 +- 17 files changed, 119 insertions(+), 1723 deletions(-) delete mode 100644 internnav/env/utils/habitat_extensions/evaluator_single.py delete mode 100644 internnav/env/utils/habitat_extensions/fonts/arial.ttf delete mode 100644 internnav/env/utils/habitat_extensions/maps.py delete mode 100644 internnav/env/utils/habitat_extensions/measures.py delete mode 100644 internnav/internnav_habitat/refactor_notes.md diff --git a/internnav/env/utils/episode_loader/dataset_utils.py b/internnav/env/utils/episode_loader/dataset_utils.py index 12e5f46..c85c2bb 100644 --- a/internnav/env/utils/episode_loader/dataset_utils.py +++ b/internnav/env/utils/episode_loader/dataset_utils.py @@ -501,7 +501,7 @@ def load_data( with gzip.open(os.path.join(dataset_root_dir, split, f"{split}.json.gz"), 'rt', encoding='utf-8') as f: data = json.load(f)['episodes'][rank::world_size] - if dataset_type == 'kujiale': + if dataset_type in ['kujiale', 'grscene']: scenes = list(set([x['scan'] for x in data])) else: scenes = list(set([x['scene_id'] for x in data])) # e.g. 'mp3d/zsNo4HB9uLZ/zsNo4HB9uLZ.glb' @@ -509,7 +509,7 @@ def load_data( scenes.sort() new_data = {} for scene in scenes: - if dataset_type == 'kujiale': + if dataset_type in ['kujiale', 'grscene']: scene_data = [x for x in data if x['scan'] == scene] scan = scene else: @@ -521,7 +521,7 @@ def load_data( new_item['scan'] = scan new_item['original_start_position'] = item['start_position'] new_item['original_start_rotation'] = item['start_rotation'] - if dataset_type != 'kujiale': + if dataset_type == 'mp3d': x, z, y = item['start_position'] new_item['start_position'] = [x, -y, z] r1, r2, r3, r4 = item['start_rotation'] diff --git a/internnav/env/utils/episode_loader/resumable.py b/internnav/env/utils/episode_loader/resumable.py index bee3ac0..eadb4f6 100644 --- a/internnav/env/utils/episode_loader/resumable.py +++ b/internnav/env/utils/episode_loader/resumable.py @@ -44,7 +44,7 @@ def __init__( os.makedirs(self.lmdb_path) database = lmdb.open( - f'{self.lmdb_path}/sample_data.lmdb', + f'{self.lmdb_path}/sample_data{rank}.lmdb', map_size=1 * 1024 * 1024 * 1024 * 1024, lock=True, ) diff --git a/internnav/env/utils/habitat_extensions/evaluator_single.py b/internnav/env/utils/habitat_extensions/evaluator_single.py deleted file mode 100644 index 24d95ea..0000000 --- a/internnav/env/utils/habitat_extensions/evaluator_single.py +++ /dev/null @@ -1,695 +0,0 @@ -import argparse -import copy -import itertools -import os -import random -import re -import sys -from collections import OrderedDict -from typing import Any - -import cv2 -import habitat -import numpy as np -import quaternion -import torch -from depth_camera_filtering import filter_depth -from habitat import Env -from habitat.config.default import get_agent_config -from habitat.config.default_structured_configs import ( - CollisionsMeasurementConfig, - FogOfWarConfig, - TopDownMapMeasurementConfig, -) -from habitat.utils.visualizations.utils import images_to_video, observations_to_image -from habitat_baselines.config.default import get_config as get_habitat_config -from omegaconf import OmegaConf -from PIL import Image -from transformers import AutoProcessor -from transformers.image_utils import to_numpy_array - -PROJECT_ROOT_PATH = os.path.dirname(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) -sys.path.append(PROJECT_ROOT_PATH) -print(f"PROJECT_ROOT_PATH {PROJECT_ROOT_PATH}") -from internnav.model.basemodel.internvla_n1.internvla_n1 import InternVLAN1ForCausalLM -from internnav.model.utils.vln_utils import ( - chunk_token, - split_and_clean, - traj_to_actions, -) -from internnav.utils.dist import get_rank, get_world_size, init_distributed_mode - -DEFAULT_IMAGE_TOKEN = "" - - -class VLNEvaluator: - def __init__( - self, - config_path: str, - split: str = "val_seen", - env_num: int = 1, - output_path: str = None, - model: Any = None, - processor: Any = None, - epoch: int = 0, - args: argparse.Namespace = None, - ): - self.args = args - self.device = torch.device('cuda') - self.split = split - self.env_num = env_num - self.save_video = args.save_video - self.output_path = output_path - self.epoch = epoch - self.config_path = config_path - self.config = get_habitat_config(config_path) - self.agent_config = get_agent_config(self.config.habitat.simulator) - self.sim_sensors_config = self.config.habitat.simulator.agents.main_agent.sim_sensors - - # for gradio evaluation - self.infer_data_ready = False - self.infer_scene_id = 0 - self.infer_episode_id = 0 - self.infer_success_cnt = -1 - self.infer_instruction = "" - self.infer_success = False - self.env = None - with habitat.config.read_write(self.config): - # self.config.habitat.task.measurements.success.success_distance=3.0 - self.config.habitat.dataset.split = self.split - self.config.habitat.task.measurements.update( - { - "top_down_map": TopDownMapMeasurementConfig( - map_padding=3, - map_resolution=1024, - draw_source=True, - draw_border=True, - draw_shortest_path=True, - draw_view_points=True, - draw_goal_positions=True, - draw_goal_aabbs=True, - fog_of_war=FogOfWarConfig( - draw=True, - visibility_dist=5.0, - fov=90, - ), - ), - "collisions": CollisionsMeasurementConfig(), - } - ) - - print(f"config = {type(self.config)}") - print(OmegaConf.to_yaml(self.config)) - - self._camera_height = self.sim_sensors_config.rgb_sensor.position[1] - self._min_depth = self.sim_sensors_config.depth_sensor.min_depth - self._max_depth = self.sim_sensors_config.depth_sensor.max_depth - - camera_fov_rad = np.deg2rad(self.sim_sensors_config.depth_sensor.hfov) - self._camera_fov = camera_fov_rad - self._fx = self._fy = self.sim_sensors_config.depth_sensor.width / (2 * np.tan(camera_fov_rad / 2)) - - self.model = model - self.processor = processor - - prompt = "You are an autonomous navigation assistant. Your task is to . Where should you go next to stay on track? Please output the next waypoint\'s coordinates in the image. Please output STOP when you have successfully completed the task." - answer = "" - self.conversation = [{"from": "human", "value": prompt}, {"from": "gpt", "value": answer}] - - self.conjunctions = [ - 'you can see ', - 'in front of you is ', - 'there is ', - 'you can spot ', - 'you are toward the ', - 'ahead of you is ', - 'in your sight is ', - ] - - self.actions2idx = OrderedDict( - { - 'STOP': [0], - "↑": [1], - "←": [2], - "→": [3], - "↓": [5], - } - ) - - self.num_frames = args.num_frames - self.num_future_steps = args.num_future_steps - self.num_history = args.num_history - - def preprocess_depth_image_v2( - self, depth_image, do_depth_scale=True, depth_scale=1000, target_height=None, target_width=None - ): - if target_height is None: - target_height = self.image_processor.crop_size['height'] # 384 - target_width = self.image_processor.crop_size['width'] # 384 - - resized_depth_image = depth_image.resize((target_width, target_height), Image.NEAREST) - - img = to_numpy_array(resized_depth_image) - if do_depth_scale: - img = img / depth_scale - - return img, (target_width, target_height) - - def get_intrinsic_matrix(self, sensor_cfg) -> np.ndarray: - width = sensor_cfg.width - height = sensor_cfg.height - fov = sensor_cfg.hfov - fx = (width / 2.0) / np.tan(np.deg2rad(fov / 2.0)) - fy = fx # Assuming square pixels (fx = fy) - cx = (width - 1.0) / 2.0 - cy = (height - 1.0) / 2.0 - - intrinsic_matrix = np.array( - [[fx, 0.0, cx, 0.0], [0.0, fy, cy, 0.0], [0.0, 0.0, 1.0, 0.0], [0.0, 0.0, 0.0, 1.0]] - ) - return intrinsic_matrix - - def preprocess_instrinsic(self, intrinsic, ori_size, target_size): # (V, 4, 4) (resize_shape) (h, w) - intrinsic = copy.deepcopy(intrinsic) - if len(intrinsic.shape) == 2: - intrinsic = intrinsic[None, :, :] # (1, 4, 4) or (B, 4, 4) - - intrinsic[:, 0] /= ori_size[0] / target_size[0] # width - intrinsic[:, 1] /= ori_size[1] / target_size[1] # height - - # for crop transform - intrinsic[:, 0, 2] -= (target_size[0] - target_size[1]) / 2 - - if intrinsic.shape[0] == 1: - intrinsic = intrinsic.squeeze(0) - - return intrinsic - - def get_axis_align_matrix(self): - ma = np.array([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) - return ma - - def xyz_yaw_to_tf_matrix(self, xyz: np.ndarray, yaw: float) -> np.ndarray: - x, y, z = xyz - transformation_matrix = np.array( - [ - [np.cos(yaw), -np.sin(yaw), 0, x], - [np.sin(yaw), np.cos(yaw), 0, y], - [0, 0, 1, z], - [0, 0, 0, 1], - ] - ) - return transformation_matrix - - def xyz_pitch_to_tf_matrix(self, xyz: np.ndarray, pitch: float) -> np.ndarray: - x, y, z = xyz - transformation_matrix = np.array( - [ - [np.cos(pitch), 0, np.sin(pitch), x], - [0, 1, 0, y], - [-np.sin(pitch), 0, np.cos(pitch), z], - [0, 0, 0, 1], - ] - ) - return transformation_matrix - - def xyz_yaw_pitch_to_tf_matrix(self, xyz: np.ndarray, yaw: float, pitch: float) -> np.ndarray: - """Converts a given position and yaw, pitch angles to a 4x4 transformation matrix. - - Args: - xyz (np.ndarray): A 3D vector representing the position. - yaw (float): The yaw angle in radians. - pitch (float): The pitch angle in radians for y axis. - Returns: - np.ndarray: A 4x4 transformation matrix. - """ - x, y, z = xyz - rot1 = self.xyz_yaw_to_tf_matrix(xyz, yaw)[:3, :3] - rot2 = self.xyz_pitch_to_tf_matrix(xyz, pitch)[:3, :3] - transformation_matrix = np.eye(4) - transformation_matrix[:3, :3] = rot1 @ rot2 - transformation_matrix[:3, 3] = xyz - return transformation_matrix - - def pixel_to_gps(self, pixel, depth, intrinsic, tf_camera_to_episodic): - ''' - Args: - pixel: (2,) - [u, v] pixel coordinates - depth: (H, W) - depth image where depth[v, u] gives depth in meters - intrinsic: (4, 4) - camera intrinsic matrix - tf_camera_to_episodic: (4, 4) - transformation from camera to episodic frame - Returns: - (x, y): (x, y) coordinates in the episodic frame - ''' - v, u = pixel - z = depth[v, u] - print("depthhhhhhhhhhhhhh", z) - - x = (u - intrinsic[0, 2]) * z / intrinsic[0, 0] - y = (v - intrinsic[1, 2]) * z / intrinsic[1, 1] - point_camera = np.array([x, y, z, 1.0]) - - # Transform to episodic frame - point_episodic = tf_camera_to_episodic @ point_camera - point_episodic = point_episodic[:3] / point_episodic[3] - - x = point_episodic[0] - y = point_episodic[1] - - return (x, y) # same as habitat gps - - def config_env(self) -> Env: - env = Env(config=self.config) - # env.episodes = env.episodes[0:1] - return env - - def run_single_eval(self): - - self.model.eval() - self.env = self.config_env() - self.scene_episode_dict = {} - for episode in self.env.episodes: - if episode.scene_id not in self.scene_episode_dict: - self.scene_episode_dict[episode.scene_id] = [] - self.scene_episode_dict[episode.scene_id].append(episode) - intrinsic_matrix = self.get_intrinsic_matrix( - self.config.habitat.simulator.agents.main_agent.sim_sensors.rgb_sensor - ) - sucs, spls, oss, nes = [], [], [], [] - - if True: # fixme - scenes_keys = list(sorted(self.scene_episode_dict.keys())) - - self.infer_success = False - self.infer_data_ready = False - print('---------------current infer scene:', scenes_keys[self.infer_scene_id]) - selected_scenes = ['17DRP5sb8fy', 'r1Q1Z4BcV1o', 'dhjEzFoUFzH'] - key_name = ( - 'data/scene_datasets/mp3d/' - + selected_scenes[self.infer_scene_id] - + '/' - + selected_scenes[self.infer_scene_id] - + '.glb' - ) - episodes = self.scene_episode_dict[key_name] - step_size = len(episodes) // 6 - # episode_id = 0 - - episode = episodes[self.infer_episode_id * step_size] - - episode_instruction = ( - self.infer_instruction - ) # episode.instruction.instruction_text if 'objectnav' not in self.config_path else episode.object_category - print("episode start", episode_instruction) - - # episode_id = int(episode.episode_id) - env = self.env - env.current_episode = episode - observations = env.reset() - - agent_state = env.sim.get_agent_state() - rotation = agent_state.rotation - translation = agent_state.position - rotation_matrix = quaternion.as_rotation_matrix(rotation) - transformation_matrix = np.eye(4) - transformation_matrix[:3, :3] = rotation_matrix - transformation_matrix[:3, 3] = translation - - # agent = ShortestPathFollower(env.sim, 0.25, False) - - os.makedirs(os.path.join(self.output_path, f'check_sim_{self.epoch}'), exist_ok=True) - - vis_frames = [] - step_id = 0 - - if self.save_video: - os.makedirs(self.output_path, exist_ok=True) - initial_height = env.sim.get_agent_state().position[1] - - rgb_list = [] - # depth_list = [] - action_seq = [] - # past_key_values = None - output_ids = None - - goal = None - action = None - # look_down_observations = None - # look_down_id_list = [] - messages = [] - # last_action = None - local_actions = [] - - # begin evaluation main loop - while not env.episode_over and step_id <= 70: - rgb = observations["rgb"] - depth = observations["depth"] - x, y = observations["gps"] - camera_yaw = observations["compass"][0] - depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) - depth = depth * (self._max_depth - self._min_depth) + self._min_depth - depth = depth * 1000 - - agent_state = env.sim.get_agent_state() - height = agent_state.position[1] - initial_height # Habitat GPS makes west negative, so flip y - camera_position = np.array([x, -y, self._camera_height + height]) - # robot_xy = camera_position[:2] - # tf_camera_to_episodic = self.xyz_yaw_to_tf_matrix(camera_position, camera_yaw) @ self.get_axis_align_matrix() - tf_camera_to_episodic = ( - self.xyz_yaw_pitch_to_tf_matrix(camera_position, camera_yaw, np.deg2rad(30)) - @ self.get_axis_align_matrix() - ) - - image = Image.fromarray(rgb).convert('RGB') # raw observation image - # image_size = image.size # 640*480 - save_raw_image = image.copy() - - if action == 5: - look_down_image = image # Image.fromarray(look_down_observations['rgb']).convert('RGB') - save_raw_image = look_down_image.copy() - - # rgb_list.append(look_down_image) - look_down_depth, resize_shape = self.preprocess_depth_image_v2( - Image.fromarray(depth.astype(np.uint16), mode='I;16'), - do_depth_scale=True, - depth_scale=1000, - target_height=224, - target_width=224, - ) - look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() # [H, W] - # depth clip to 5m - look_down_depth[look_down_depth > 5.0] = 5.0 - else: - image = image.resize((self.args.resize_w, self.args.resize_h)) - rgb_list.append(image) - - down_observations = env.step(5) - down_observations = env.step(5) - - look_down_image = Image.fromarray(down_observations["rgb"]).convert('RGB') - depth = down_observations["depth"] - depth = filter_depth(depth.reshape(depth.shape[:2]), blur_type=None) - depth = depth * (self._max_depth - self._min_depth) + self._min_depth - depth = depth * 1000 - look_down_depth, resize_shape = self.preprocess_depth_image_v2( - Image.fromarray(depth.astype(np.uint16), mode='I;16'), - do_depth_scale=True, - depth_scale=1000, - target_height=224, - target_width=224, - ) - look_down_depth = torch.as_tensor(np.ascontiguousarray(look_down_depth)).float() # [H, W] - # depth clip to 5m - look_down_depth[look_down_depth > 5.0] = 5.0 - - env.step(4) - env.step(4) - - info = env.get_metrics() - current_frame_infer_pixel = False - if len(action_seq) == 0 and goal is None: # 只有执行完一次输出的所有 action_seq 才能继续做模型推理 - if action != 5: - sources = copy.deepcopy(self.conversation) - if 'objectnav' in self.config_path: - sources[0]["value"] = sources[0]["value"].replace( - '.', - random.choice(self.objectnav_instructions).format( - target_object=episode.object_category.replace('_', ' ') - ), - ) - else: - sources[0]["value"] = sources[0]["value"].replace( - '.', episode_instruction[:-1] - ) - cur_images = rgb_list[-1:] # current observation - if step_id == 0: - history_id = [] - else: - history_id = np.unique( - np.linspace(0, step_id - 1, self.num_history, dtype=np.int32) - ).tolist() - placeholder = (DEFAULT_IMAGE_TOKEN + '\n') * len(history_id) - sources[0]["value"] += f' These are your historical observations: {placeholder}.' - - history_id = sorted(history_id) - print('history_idddddddd', step_id, history_id) - input_images = [rgb_list[i] for i in history_id] + cur_images - input_img_id = 0 - else: - assert action == 5 # last action is look down - sources = [{"from": "human", "value": ""}, {"from": "gpt", "value": ""}] - input_images += [look_down_image] - # messages.append({'role': 'assistant', 'content': [{'type': 'text', 'text': llm_outputs}]}) - input_img_id = -1 - - prompt = random.choice(self.conjunctions) + DEFAULT_IMAGE_TOKEN - sources[0]["value"] += f" {prompt}." - print('sources', step_id, sources) - prompt_instruction = copy.deepcopy(sources[0]["value"]) - parts = split_and_clean(prompt_instruction) - - content = [] - for i in range(len(parts)): - if parts[i] == "": - content.append({"type": "image", "image": input_images[input_img_id]}) - input_img_id += 1 - else: - content.append({"type": "text", "text": parts[i]}) - - messages.append({'role': 'user', 'content': content}) - - print('step_id', step_id, 'messages:', messages) - - text = self.processor.apply_chat_template(messages, tokenize=False, add_generation_prompt=True) - - inputs = self.processor(text=[text], images=input_images, return_tensors="pt").to(self.model.device) - - with torch.no_grad(): - output_ids = self.model.generate(**inputs, max_new_tokens=128, do_sample=False) - - llm_outputs = self.processor.tokenizer.decode( - output_ids[0][inputs.input_ids.shape[1] :], skip_special_tokens=True - ) - print('step_id:', step_id, 'output text:', llm_outputs) - - if bool(re.search(r'\d', llm_outputs)): # output pixel goal - current_frame_infer_pixel = True - forward_action = 0 - coord = [int(c) for c in re.findall(r'\d+', llm_outputs)] - pixel_goal = [int(coord[1]), int(coord[0])] # switch the goal o - - goal = self.pixel_to_gps(pixel_goal, depth / 1000, intrinsic_matrix, tf_camera_to_episodic) - print('before', goal, depth.shape) - goal = (transformation_matrix @ np.array([-goal[1], 0, -goal[0], 1]))[:3] - - if not env.sim.pathfinder.is_navigable(np.array(goal)): - goal = np.array(env.sim.pathfinder.snap_point(np.array(goal))) - - # look down --> horizontal - env.step(4) - env.step(4) - - # action = agent.get_next_action(goal) - local_actions = [] - pixel_values = inputs.pixel_values - image_grid_thw = torch.cat([thw.unsqueeze(0) for thw in inputs.image_grid_thw], dim=0) - - with torch.no_grad(): - traj_latents = self.model.generate_latents(output_ids, pixel_values, image_grid_thw) - - # image_dp = torch.tensor(np.array(look_down_image.resize((224, 224)))).to(torch.bfloat16) - # pix_goal_image = copy.copy(image_dp) - # images_dp = torch.stack([pix_goal_image, image_dp]).unsqueeze(0) - # depth_dp = look_down_depth.unsqueeze(-1).to(torch.bfloat16) - # pix_goal_depth = copy.copy(depth_dp) - # depths_dp = torch.stack([pix_goal_depth, depth_dp]).unsqueeze(0) - - with torch.no_grad(): - dp_actions = self.model.generate_traj(traj_latents) - - random_choice = np.random.choice(dp_actions.shape[0]) - if self.args.continuous_traj: - action_list = traj_to_actions(dp_actions) - if len(action_list) < 8: - action_list += [0] * (8 - len(action_list)) - else: - action_list = chunk_token(dp_actions[random_choice]) - print("first action_list", action_list) - local_actions = action_list - action = local_actions[0] - if action == 0: - goal = None - output_ids = None - action = 2 - print('conduct a random action 2') - observations = env.step(action) - step_id += 1 - messages = [] - continue - - print('predicted goal', pixel_goal, goal, flush=True) - else: - action_seq = self.parse_actions(llm_outputs) - print('actions', action_seq, flush=True) - - if len(action_seq) != 0: - action = action_seq[0] - action_seq.pop(0) - elif goal is not None: - if len(local_actions) != 0: - action = local_actions.pop(0) - else: - action = 0 - forward_action += 1 - print('forward_action', forward_action, flush=True) - if forward_action > 8: - goal = None - output_ids = None - messages = [] - step_id += 1 - forward_action = 0 - local_actions = [] - continue - if action == 0: - goal = None - output_ids = None - messages = [] - step_id += 1 - forward_action = 0 - local_actions = [] - continue - else: - action = 0 - - if info['top_down_map'] is not None: - frame = observations_to_image({'rgb': np.asarray(save_raw_image)}, info) - if current_frame_infer_pixel: - frame = cv2.putText( - frame, - f"{pixel_goal[1], pixel_goal[0]}", - (50, 80), - cv2.FONT_HERSHEY_SIMPLEX, - 1, - (255, 0, 0), - 2, - ) - frame = cv2.circle(frame, (pixel_goal[1], pixel_goal[0]), 5, (255, 0, 0), -1) - else: - output_str = str(action) - output_str = ( - output_str.replace('1', "Go forward").replace('2', 'Turn left').replace('3', 'Turn right') - ) - output_str = output_str.replace('5', 'Look down').replace('0', 'Stop!') - frame = cv2.putText(frame, output_str, (50, 80), cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 0, 0), 2) - vis_frames.append(frame) - if action == 5: - vis_frames.append(frame) - - print("step_id", step_id, "action", action) - - if action == 5: - env.step(action) - observations = env.step(action) - else: - observations = env.step(action) - step_id += 1 - messages = [] - - self.infer_success_cnt += 1 - - # metrics = env.get_metrics() - if self.save_video: - images_to_video(vis_frames, self.output_path, f"res_{self.infer_success_cnt}", fps=6, quality=9) - self.infer_success = True - vis_frames.clear() - - env.close() - return ( - torch.tensor(sucs).to(self.device), - torch.tensor(spls).to(self.device), - torch.tensor(oss).to(self.device), - torch.tensor(nes).to(self.device), - torch.tensor(len(sucs)).to(self.device), - ) - - def parse_actions(self, output): - action_patterns = '|'.join(re.escape(action) for action in self.actions2idx) - # import ipdb; ipdb.set_trace() - regex = re.compile(action_patterns) - matches = regex.findall(output) - actions = [self.actions2idx[match] for match in matches] - actions = itertools.chain.from_iterable(actions) - return list(actions) - - def preprocess_qwenvl(self, source): - prompt = random.choice(self.conjunctions) + DEFAULT_IMAGE_TOKEN - if len(source[0]["value"]) != 0: - source[0]["value"] += f" {prompt}." - else: - source[0]["value"] = f"{prompt}." # Please output the next waypoint\'s coordinates in the image." - return source - - -def eval(): - global local_rank - - parser = argparse.ArgumentParser() - parser.add_argument("--local_rank", default=0, type=int, help="node rank") - parser.add_argument("--model_path", type=str, default="") - parser.add_argument("--habitat_config_path", type=str, default='scripts/eval/configs/vln_r2r.yaml') - parser.add_argument("--eval_split", type=str, default='val_unseen') - parser.add_argument("--output_path", type=str, default='./exps_pix/val_unseen/debug_coord_wm') - parser.add_argument("--num_future_steps", type=int, default=4) - parser.add_argument("--num_frames", type=int, default=32) - parser.add_argument("--save_video", action="store_true", default=True) - parser.add_argument("--num_history", type=int, default=8) - parser.add_argument("--resize_w", type=int, default=384) - parser.add_argument("--resize_h", type=int, default=384) - parser.add_argument("--predict_step_nums", type=int, default=16) - parser.add_argument("--continuous_traj", action="store_true", default=False) - parser.add_argument("--max_new_tokens", type=int, default=1024) - - parser.add_argument('--world_size', default=1, type=int, help='number of distributed processes') - parser.add_argument('--rank', default=0, type=int, help='rank') - parser.add_argument('--gpu', default=0, type=int, help='gpu') - parser.add_argument('--port', default='2333') - parser.add_argument('--dist_url', default='env://', help='url used to set up distributed training') - parser.add_argument('--device', default='cuda', help='device to use for training / testing') - - args = parser.parse_args() - init_distributed_mode(args) - local_rank = args.local_rank - np.random.seed(local_rank) - # Load model and tokenizer - processor = AutoProcessor.from_pretrained(args.model_path) - processor.tokenizer.padding_side = 'left' - - device = torch.device(f"cuda:{local_rank}") - model = InternVLAN1ForCausalLM.from_pretrained( - args.model_path, torch_dtype=torch.bfloat16, attn_implementation="flash_attention_2", device_map={"": device} - ) - - # start the evaluation - evaluate(model, processor, args) - - -def evaluate(model, processor, args): - model.eval() - world_size = get_world_size() - evaluator = VLNEvaluator( - config_path=args.habitat_config_path, - split=args.eval_split, - env_num=world_size, - output_path=args.output_path, - model=model, - processor=processor, - epoch=0, - args=args, - ) - sucs, spls, oss, nes, ep_num = evaluator.eval_action(idx=get_rank()) - - -if __name__ == "__main__": - eval() - print('hello world!!') - sys.exit(0) diff --git a/internnav/env/utils/habitat_extensions/fonts/arial.ttf b/internnav/env/utils/habitat_extensions/fonts/arial.ttf deleted file mode 100644 index 886789b85b4b4e662519fcb7fe4d88ddf2205c5b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 311636 zcmeFa30zfG_cy-wKIaZhf;gcd97YEaXK_kV!8B(<12g3cS3#KqoO;Ztv<%J6(#*`% ztjwnCkfB+cnU$HDscD*1!()?~Poom||6Tjs3uyT~PyhFQ|NqbL{dg|lwdb|hUVH6z zhP&^91Q9g>(Wy8kZQzZEZfl%R`mY>yxh%UWc-7%=UCtnpZv9#nIOG}X6luZ_r6hv)l zG^RNK{c1=HZJtaPt24Ii9$k8U%giiThA$(C?nOuXNP!<%#=I`vy;X;{MdJ!2wS^KpWFg^Tg{> zVv}2;1)=lo`Zt-c;%erbJgVYWmH(`Y+Yk?GvPs2xwt||xrQ%piRNdrbPaJa;@{uQw zISM)MiDQmJzV^g1M@?_^#4$%rM|k3xqo#SDIOeG7bWa>})U1amjyY=P@We4k&A#=- zF-H+Edg7QPBhVAa92rwRam-PRRx0kx<7zQi#r=3JEgn*Ff0e&l#p|iK$ukJ?dM&o9 z{04{zw|Gaz8>%|TRJ;-5K`p*i@y06uXBBUXcs(pD)^jM=X=%#Voa?lVQ27xm9p>BX&kpJ`CBSI*i~OG3pn53%%7>^YAh}1Qaa6~Vsg?%a$sFM$)M+e zbjnrnAyh<#K$)kOLH&>_K?|l1z(mN=st&JfwXBtE2=q{! zdI>z!!Oa2Lom8M?oq{~({QrK|3~+QpOL>s7OpS$gV<24!TIR8ZQJ4pVhNI6igmFMR zMrY74^gU7O+=2Ss&Iv8DmZz(h%scT<8s*k(c}3`#$5V{DGp|{T?J`Bxo35mqRMRhO zmrL6KBf)KgN9v&nv%!-s#{p>)P;Sc3GoB5wg{FZ{RZ^QXXeb-%N*$D)7bfp~ra4_J zm3QV@H!LMp-LfVucGB*Qb`&jD>qDfJ}vI93~I;4O2YQ^1L%Y9s}!;?WR`eIcVvC zg>f$Hf#)R`d2BIkNxbfg)u_u*$51Pp^-#;fD-r9!P_nai@XWKVn0CedOzylY`P^Vy zBl}xk$p$`kt=rVFX^~Evp>)K)iKSuNWC_^%%(I25FP4M#VAk+j#+7FxmaFdgSSr@W z1n@J|Y?xlE);67V8}d!rP22X`zkxN%Yk)Oj%E-EByJPz+gr>aSj`eSz-FPkWN;X#$ z*EZL%_nc>z@*123+^+bTHphIkRa@_R^Y+d&SPG83N?12+Q#=~e;&`o1SLLjEQ)?^% zuOU;5+&6m}Q(`Z7maqu=aeajF? zS66#~eHN?rFkX-Bo#zRP*GzDk3Z7=4JYsWpO?$3AAJwi~^Q>Hex%Wz9u3uiOY?r1L zu_dzonyZhkl~-$~r#D{RrZ?cTr1xxO_Q}4_tAQ(5A+Hl&pX{%_-pPr&roZPE#Wu~o z^4ZE<&l5fNX#Bo3FK^^GT^kIAsHGRmn`eyBqf^=Np^t0ZXubm6i ztFR8tG4a|qy*KyDzJfK&*BCqk_Stnu!j^XRoU`BO^Ca`}dJ1p9>`7RgUO!>_N?zIC zYh?B}W^JBZuibh*wAV_mr74z<{knIC%#qacn~qs3!P$<_optXXy#BGaW)bX-y?rrc zV2$%kaPOw)Gv%sl-Ry^XotmrDyyhzQtX!{^de7fp8#33IImcIzsMbCPs_Q$i25V=I zHOxKoIfv)ht5fgw9@|?9>Ud?Y9a~*}d$rAT%~z{@MZ&ht_Am`?`HWEO2mYJc_eyH6 zNnWeG>X~Ql8Z%e#U#)F(eb!#F@~Zx;b?lunwo)S>Py{ViZmMw?i{ZoRjiO%bX?793!vLD1#P8 zr5VE=Wk#HlKExO{ablw3D9kaO`K8Y3xu}-t71Y3ZizbygigRby&2kzkC64KNg_F2# z9#q@L7+Ev{tcT`h=N9EVN)woSNnUoI!$@;XEzH3Hp{A}K`V|$HISW|rB{Pju2Q&yJ zmtBf+I0_Av&E)at zLFIV5o8!!OmX;QwJ06e&{HJE;8hIX8Jou@FPGfprS*}t;K~Yf-w`P?<>@o3(NAHsGW_-)RLKrhSGG=G-rteb6r;Abd(jKh#O>2#eA1?XFPk(5+%aKsrmVc zDp}Ee0Uk(W4sxcJLOqUrqqJ;hzO$|-*iuWm7iUR9UZJW{QZxl@9Z*H~RCHucU{0Q6 zQW2L=&xOv7TxWhUG*V73O85x}&(*2{jgGJJE@$ZU_uT zI%i-o1W)bzPE226S)!4NX1NZSLD2+WMrc`fg)nTL)7hMySO&1o zoV*feb{Xb*BJ^16A9)IkCc*YmMNM%{J4_9%cf!;%u!fjLSWz$$?|@pAdWC`^*QlbV zFh zD7dX7Cnt|>0#;d~JaPhOmnhw;6%Rq`3YDK%kjDc;C#v4`qLL}4rjaUhR+&Z9ajuv; zAwRD)m;1pynd&Zpq2jcHsVas(l<|5rWa{4Ak^>QL@c>yJoSJW6dtBnJP6fhev9U z7yOew@f3RJ*6^%*4^zI~@o zph+E*jHE7|yLIjs;Cqc#ca3aw_3~nB>lw9LhqzVci!Z*A%|{G3HzEKRZj*5l^fgdh zmWIn7^VXkl$a1vh+6L`)Z3nPb+orvM+uW;f;jTZ@zy3(S_V%*&0{!|U{p*kPYpsDF zAYOl@fBliZ_rauj`+fb9K0kE5{z$*>WAFd=OM~l=^v$#G^+)HlB(NdJmE|JtVj{2UvXv*9Yl0>NkLPt100g_-oZVHLr^Em&yEfVj=Ds@P&_XiPhL`%U{p+!BdG6e34~t zm$){E+9w)y>v(p|^3L5bb0@0LNZzrC{mmJq`*guZ->yj5@SVL`m%MO^|1B#@VVi?8-Ye6Bix9>*9?h9 zJENn~-RNobGE$5p<4$9(@vQMeq$RRJWaG%F$hgSF$n?l@kxL@iMad{@RA5waRHLY7 zQ4vwCqT-_lL^-0I(K0$HIx?1GWvqW}P;A54kl3);nAn8aPO&{>^JB|n=fuv7T@d?l z?CRJTVmHQai`^c(JNEt94`YwTeihdaFSNfbFB_M; zT<&?f*X2H!Q!Wp?oO$_<%kwWUx$Lf*@JH`IE>>5$tJJP)gH|cctr9Pb55y&CZVxnf zRHGWr&4K0?YES7xucwdD$LWjorTTJxjsB8esUOwPSzMOaEC(zXJerHNCR?-qQgau= z%fnY0{ze0%iD5u9ncXH_Sv4phBgb-LanV2RWDSn#^>RxJFDhY z-CdPeh5hrN-%50re+7Z#^ju)cnOjcJIsN;Yb*HBz^(wFks5pJcnW?8HpPG4k+vf?V z7oJ*oYU#uPjvDbZhNZ9$=gnjN2=Y)MXBK1Vi6Wva9InnV%yA!QW zM4bpd(eQ*ge*XBk$Il)A^7vV9b$rk99mn4|j$V$xef;U;FCR}m-uHN)<1xphjz=C3 zZ??19rDkV>-oRe}H*C+?p0KU3J#JfWd(5`X_MYuU+iKgB_%+4X)?SteETm=g+7(#0 zbr1O!Ht7T2L!~chyiZ>pT8=mNSD`jkEB~u}%no+wYxq5eK2#s6XCa(Wx1K%@ITKCP z&958R@yic=xIWU%)A^SM|K*{_={(=+&||!@zY2BVzslu2eee|}8a+jGXs$MnmeN;r zFD<0`^aOTjuf?w~DxlVT=wZ4*KhgvAD9xi?bb@}Mm9(DzMHlHOT0<|;yR?U1#KYul zS_Egk7cTuBdXM(g`?QZfpnqa-!$07!V51;d}TZ4CD z71Am=`rGh5e+hOf@E)9L*iUc{`~7am3FRMj2kiV+T1|J-Y$~U_=o|Wuwu+_VQ6YsU zbYY>(R3(;)$Ha2+IQ>D@!YXX|jfPvS5KoAe;z_Xze%wd+3P0g5)`+L*7y4DK6;F$2 z#Is_ZcuuSr&x;qti{d5tESK0IHi}L38yyxEV!qfcUJ+ZwtD;f_h_}%?LF-Sc|rR~JFFekKGV)< zUus`#-)lc;Kgu8FMforJll)o!B7c>?$=~HAd0AFzzM7xrkF$%wpw{Y7>(A)V>g)99 z^!57l`V0DtIIFy@yYvnEMx2>9>#yir^jC47*{W~Dd3wA4y8ec~L*J>tsqfO?(s%1` z>wENf^mq05^u7A~`ab;weZT&pen9_7Kd67KAJPx&NAyo{mO7??svp-+=%48)^;7z3 z{fvHA|6Kn<|5E=-|EGRV|62b>|5pD_|6V_@|Da#cf7CDP|I&Zbe-@vMFZ5sZU-jSg z-}OuSW!gX+WrgTOuh15HOMFS2Xfy4myXj53558!aHc}g|jnGDEqqUp03@uGdr=P_? z38T)>Z|nCI8#5Rb=JCQ|I&Vf_q75Z$08&mjJgL3HQi#h*?oNd`~&I*2GtL4(6CYC zCLv9mg@!c`k1!&mqGMv?TC{A{IzFLIV%v7@J9O;Sxl2;lZrywIyrEa`eaLVcT4Gj&tIq+`P$C@(T)!if=0^Et@)R z`iz;k|6|r2v+pdw>+XBz%)R%%dG}Y$U+}=f2NylG_~A#EEPZs@W6K|3@x;m}SFK+2 z)Y_+?d3N1%>z~(Nc=4r|T^lxT+Wg9vS1Y$}du{vcZ|vCl=B~GPzrE+3ci-Fl{=N_P ze|UgCI{5LS!$&?jdhFBVCq6rQ>iV_g^=rrL*N)e(9j{+IUcYv{e(iYu+VT3eBcA8{ z7uSxS%fx(yb%6UO5<79#i2G~HIXsTTvk0Ht0p$561Gu;M+e74^2s{IPM-+g&x&d{Q(RZJ|M13a`^~10D`(s=KV~B3rOElOQC<9Is4MCkD$Qx2kG!)|;f&28d z)d(bk=k6oAw;qrMfd9Sd>plZO`o1;5X`*?MecogMrpGwvS09i42)xW4zQo-am@V_ z1BjknM6~K6(du%%kplg%IZw2<3(?b%=NZ&{7P@=(H==bDiJn8<^_z*F$M|22BYGKa zHXbC}^e)lnLf{ReSIUUCpiN~50At>YHrs{+mB3F#uMGwu|Lc%z2l(!62TUM(a{aQK}7pI5gk|$d_nY4 zO8{g2Xb;grv_Ci$K)(ke)5iud4p;~veJB`62Nn|@ZV22>bR-v8OY{l)`y>N^K93^* z=y{@Jw*y}heR>d2;&uZV$B6_0b8uo6(PtrevIkzLF^1D8iOwK>7JYnw! z5Ph|j=${LSz78Y$=3b)jFplqw0hE3J4bgem7bQ!W< zhQ2OCKbOI;3i_+M2`C4)166pI>PzIF2J9grqJSB|3&153vOh2n*a`fCcaY!>7usnO zmRTfhDJ1M@<6EiTeINoBlBicqBFGmg16Gizk2jq(*bY>YXxI~&1#H9nUP6Frz!xMM z>%e&uP0+r{ZW1BEz*yiJU>9%_s3y@g96?Lk1$eYLN1~+;WC6=bv_ibqeiE%A zOMD8jn?%B3U^|I6BLTE)gYhM%16xS6MZI0#bVRx%bNFW6O&l#|j8K+6iMEjXJ0Ob1zng-ouK*y&Q+-LS zEd%BNj{xBH^lV@ufN?wx9Y6C7iFMG`x^^U<%OJ5H@;rZ%#ET^)URp%L6-HtM`rnX4 zViRQFj6OHtMB)|b>D9YQR9Z=Fg`I3&Mgp!-yk1UX2f`iTxAOprU66ZsGZJt22N2(b zG3;3ipx<{U0@FymHx|ezv3CuL_gy4DK>9=I;Xpcxk9L#z*dG{2;&3vFBin&Xc=gmO z0A-)*Ktmt~K)X-D2j?I08F-)k6sRU~3i6*`LE_9%5@*5dEXMHp1rlGtCci}gU!mWB zLbh{|`P}UQ+JF59@D+(~kcV@T_!j#37JYwQy5T8;%6%W*?)olf6c;c!pebzBz~Vo;?hPEmn%qAq23>m zt$HlpDAkK3-u5B!4Tuy+NJ@m-0AMFcy$g^Jyi3xuh@>?PNC%b!dr8_l0Y8znw*)eP z1;BRTJCZ)A>x;NA%KcE!4}ARAlJrj|8PFY=OtK!{Ayls?FbmiRRFMos-$AEI2KOh~ z;28kC8lp|Z86+EhL$a{}Yy>WlY!VKPB^j~+*i5o1@|u;C3~dd(Kr$?sWOJm$7XrIT zMu0c2qh(|qP)suFb^!U&dq~Fg1u(8y@QkyQY=N+4GhjE#R^Z+GUXt->lYnuyL3x`B zl5NkCY!?h*4DB$^_Gr@~i)6=%Bs&cUz`qmv>$D&EjU@cL?6L;HSiAf}G6`czx(O%) zRs!z=7fE)7d|lDLE82HO`|jY|J&|M&q+)^ksQ#Dm%?pv^3l-GO$q8Q?S9 z1?(hw=Mj>3wIq3W1^{{QfgJbrCpiZ^=U^`8qWxU7zb}U5ylo`!p9b7ZvSJR&`H*qJ zWB@Weu$JV5?EvWN!77rA9s!W|P%%(WaxwTX2LFeVei-Q`=wr!fl1pC#-XQrHWO%GA z$;UC?$Dz{|F949?34~7|d@>!#A-U>qU@^(n2Lb4A^+l3vB*~{B!&A`RQ_F$%B=HVI z`OHlupA7*Je{L4Z_0=Sw2VM*&`4akmX(Gv&!Pk{Ya>HKWQ<58hBe@B6wpfA2KpfD8 z|70<+9oPq)AbAvg zjCUd9JB7iX--v&Uw6ZL?u0LFg;d{1lvPLur17w80F{GZJOHUcN` zI!W|#67rseyeH=X7}v?8Bu`=PP9*@NfpTCya0sX-dAcPq5|{-%0~`P@kvtOv3hr4$%xq z0SbX-z%JlBlK*TBBmOUQztG1|3rYTry1ziCU#dv{IvW75-$F?K-i72P=%@Hcfe`V>U9AYkrs&l15qAWNm@`CFd0C+eh`oWfJc3dr9Sus`vTno)Coo( z4O#=`z)z$#8~`A%kpxiQ2yGfezQ#R)X}}6#A8?VhCLzF00Ay)`ybz2%WF7$doAw3J zwkhg08worDK;F=1z-V9*fHq+Spk3GmU@?Hc!_Jb{9DO#2jLmZZ@M#X&!XalkbQ-=K zfbJron+S|Qq8LCP?h&;J^ldZ*k^#tSpbw*pw8#ViydswYdw^d^i;4pvOVqu^Rcmz@x=r(prLlOVnuv`QpK&O%!Q~=)YZK(%PeL#}d*y zjUlb`BGS4*A4w?dT1i?r$kro+w4Ug{*I3eeqmSfsr1klYw0<$9rDTzox`yyxRy>1j zX%j*`Z?#%277(k=#(y=3jSs7cwfN%*4(kTVn&EUo;{*hX6YhoHz}vDJq-4I6@`v|3Od(xZch<1KtBX%%O;wF<++Rv8>kE!ME? zY77t`!D9I9{vtT7mxxdFOZ01FwZ_K9#wChG{}%o&L^lyDL}F56Qg95igos~Wyxt{ zY4|81db!o7TiBQ4))3JxF$s-gSW*!m7R*xfXYSf1ySv543E|($J$EgCmh46sJcIt+ zRjgMNf~F=$1Sf`x9}^SP zs!_|SXkon_U(r>3yW_U+rFV_ zpBUFZCQh_y>6ergkkmLSCaJSu!`JQL?o%-_Nddbt6wzME z$1-}3O)5n0uff9qSAk7N;#UkJD8b)9LNsW+Yu7Fz_Huq$U;`Xnn_2iV3B!m{k?WyG z0+->i0}X{RM5wOPe?>yC%uMjMMYfL+(Tpo=a4J3&$DgxVl7D;DVJ^&`YH8h`g=mF? zS;fcKug~zZWkceFg)#+e4&!R>E%t;K(l z;^`aK{MR3IebmxkwqD(MLDYV*m(BADOA1TE`tp31?&eQy9M|U(^Fugz<=F5^WPQ{* zP^6KjGAx>g-FbpSEZ_Oqseb6cjruv`_C>XRMH2`e{dYKwiL(nGF2s8xr5;dhJh&Q9Ah=)=$&@e@tQz+u$ z6z2Y&A`~^KIpUEN0UCujME_3FpubTJMS{js6lfgiuhfE~L0eJ`Xe){XZLMfLwQ&DJ z3Dgp_jiQOv8u7Li4~nl5G*Zztx(V@g z8sz>SZ#fzQI$F`2X(-|uG|c@S-Uv4wbPVYCbPJ6@d@QAb-b(49;}jiFquk$87L5jV z(9NI|K)=C0(oE1C8UyO2TR~6h-mAL&OVc0`l=5 zNzfuiiz&zbPwXmnf|k%E&{9S5g97(g*kzgrI*lfSP6z!GyG^Hn&ZGj++o=%rABxVR zBE;{YV$j)ioBIpwLuFb{rJ#3F8R*?K75lgEp=qFV6rD@c-Dk0@b_VEuG!t|l-41#` z{lk5RDrgqye7XZU3qa3cm+frOg>)zAgLD_@BGA*=HG4PcV!8+PVVdJUMUN=Dgytf? zl3iEsDNMYZ0%cr$M*UGoafPeT~*3zMYbT+uIR zAL3uq2cTcke$ao?0r!6Fhi3XUeFXXq9dv(yUDO|gey8a7bO`bDbi}<6`?Nm+y`boi zbQJN6bPV)g^eO01ivCO|-0#yb^cm={bQ1J8(7o81d=UImp&tM@piu;9 zTVNP49(WLV60lOBC#MMEoxl#@0$`-8<#S8D3E6QIK z<)xxLPL#)r@)%KWh@|978M$#F78Zh36>RFm>qkj3~2m({K)>Hnr|;rW3n&DC#pnzJ-QwVH)0|Q-F>MdJAUs7MQ#Rc7dS1f$_jj z;0M4BSW!C)<9JZfK+v{8Z(uxdC-4JcRpR^rQ6v?CvWPD$!P@B|r{Pt@A`SkIT3+02<922p~ z6F#`{_vR6mV%f&H*CP5f5|2{24yzO0C{Dy8>`J97-I>DdoZpGU zRds7v*N7MQs;YOPVEM*~*&J+%xFhVwh$&&Jz-bnYD@7_fFk)ofn1})3ml8H1BDoYi zw?y;~8yC^jtks#@Y>8+G5#r5gYY5vaOm!L^t{9F=sua1&3AUxS4BIeU7h4Bgf-TY( zVQX#+wKcQ{+k@=&?EZFNyWMWJ>voAp^bITBr<3Ce6WGui#DNtCEl5}KAb1$TZU&U3 zuuD8hb~Vrj$w6s-#UR(tY#KDdaQ%`NT`7D=jB#0_`wCa^AR3h3*VQ$CP^Ha1(v=iH z$YmRTOU4Ev7G@&XCFfNNO3$biZqAw;>I&|cu@xJz>(6~4l*5*DAIQw4kjB$`hx88a zRli&Rl)oTZDl;o3zV-;IjmC$>H+L-^l$POI-#pXRfg|qbnS)#prx{~2w&Dl#7gAHU z;hhkN|SRWr%PZwNoLupKE%7z#a)M;W+sj5@j#Hd?mZ!GG>f}l?0a@wov>}_1m zbzHp^o3Joc2?s$H(Tu`Wl`zpvRZ)^}P*vJ`s@z{w<$l$ZW=f;#FaaBEX7I2HIE^}W z6#4I?&c5;SVpEUI?6IlN=+vy}R40(-nm;W!#8p1QFg9doa)IH};<6^-P3#CAPFH5M zGsTr1onmb0q1s(lJeG@lM5k<^v8m}98^$I(Q#STU?vWbpNXguEqgb?s=kuA_(tw4iTg_8zHUsuQT0X2#)oHYuv6d6ewaTFH%UKV*lSj3 zWM<#SLB+k4@%D%enH{C>hU7hz3tQ9Wb_dWu43_lOML zCf0e1f{tnZBExINJC8S38&oW$bSuQ;;dcc4- zoQ`%N!%-(A%Vi*||CM!I2Dfvd=!%-js5$Yfn#pF(H=>c(a5=d!78j67JMi{={}5_VQBs0^YBS@Hfk(K(K> z87|EM9;vSS@#r_j)#UasLTZy>j@5Es-O^C4A~ht>;K~&h_ZhBLBQol=4UJ?DnVH~$ zwlcPVRz-hwy#O;ch`pps&dtnliMi+!OFmYO${e5Rk7BbX8!n&dzR|fAld~{2%_>|p za%SYlX3dhf;*o5#RHGt2BRbO6J2X1ekrK9{Aytf=xv6Qg(e%oaHVGSo>YIw)P%qFE z@eimQaYE^4nTo0E92+#UMzextj2?(J>N2wNtD2D+(HK)#CeE%@k=+#&fFo0&l`97` zlIQa2msJteo%1n7;j+XAMH>}AV~q{^nYfVcq{h@-!r_g(;^SSd zTeFGS`e9BXV=tBN+$LdKrHqa)4#JfUyK@>2-8wS6w}tv6BYA@7S0>X0BwXbqGR(9= z6GAsqa$9&knZ+eLy(NuCaY?ziq^5aRG%R^DUujSymp!iLFEFTagVfyaF46ek6g$oG zL21#0;Ixd?iY$-S4obfwWtOu-p*NIyVy*`LGPF>MJdVjwO_iFy%UcDGEW_WW$Kubb zj5?>%W`|X(9AWf#1!WB|X{K*vq-V|ir$&|T3*1Ttwaq-kaCMLO2x^M$>TyN-3i13a zv_a``ITAj%qQduzGMJhvpWi^nBcq|whsqp&h#@rRQ^S4L*2D;X+7Njg@M%FYb+ zB(JC#>S>gTgRQeoLVx(oii-ZxM*oVe3P+{8d_uGl6kV}Z?vlGIic{h3Ov9;kZ<`c1cp8p{>ku{r^+)cAx}_tr8M(`y!9mVbTcnmuuo(-_C-7(2D_(XN5(1r9!kQ_k3uRI zUC#&nuLSUdmDP3GAv^ zj`s-(_ayAB(Xf+dI%LqXljH-jQ^te4lm00}#4N2JxIE={xp$*h7Vt>Lm(OKLm zBQ0ayL-4(IWArftTpz#3d#(Ed_VgssK#XTI?H4<>>ObzP?hU=+ z|94|IPB)YkVPC*IbO3v`-jqcae@h2TvgLMsYu}LCW1q^+*uSuuz7oI6+4$V4?a}+Y z`(mfjTzn4)ZDXgv8N8vZtr#XoPpDO>Q4tPk5%Ia~C&$ajvwMu=NPF5b{|AKusW7~c4GK%A3(WV)P!_hsd3w`s5Ieep@tOZ9s!_gdy# z&sAqs@2>u+`d4=c_r2JYGYk7p9>Scg#K^W{zrrzmPSIIm!5hx%;bVwMF-rUcpV{I8 zyzz|Rakd$~91v&4*SO*NSzMO5kHZ_lLisIT_(aPRJimBEu8<$%b3lG4f7hC5QCd9S z^wbk?k1B#x_i2mpc||*;H^V!z+|Y9e%TmjemUWirExY)AjkddS2f456sXto(ak84K z=T$GQ-dMdEds!M`4smaSXLvm!y#t@gnD3>qxR>c;>_-g2473)##9(Mc!&)rQ`8Vtd)3g*FP;|E$>^t zwEE(GllNLHtv}+PxtDFYZG`Ps+k>_(wnO$TSm#^Vz49t7u;vh_@s_hx?G;)mJL*mG zfNVePc|87o$`A=lmFvVjd5736V=ObQJ!B6tlrF$AKZ5sSK8bgk_0WchK_ZPN%l0Ni zYeRiKVm#e6^9yaqiV*C&`G#J?p1NL^*Qi4O1TV(z?OuSLMUAjG zFba}Qz~hiFFv|1jVSu)iI#v&r8{GXh{QpABDeQ%N)*T`6-~QbB*kQMwp0-)YVT;F) z3e~jpoO zNUue^9k@qL;yU29)QY`e$X|i-Y~-y(n1S?a#K)ptJ5Sul_5jX{qsa%bBEJ>*%m;YP zEwneOi(cwJgRx|S=S{%9=wmp-{=gvAX@IaVaG!XG=81RQYfz4m?m_?eaXygZ2?v1B zT$J}lyBOr%gLpH@!H=>6fk>dGe1W>jhO`}FTa5o^bKDsFJCq9<*B~^qzCun*xLaBjg8EpbsVieLZIR62Djh z@a&uQbP~8h&!M463+Oz}vYD218W^Hb>i$Dtf$vPPvlL~wTbE)SInXz}jKm&Q`5m>f z#?qazuN3gV3s?!B=afCzwCZjIQp6x?iBqSO)T&D8SC4tF7FI+k;oE#}3!jhO`EC9)Mm? zBh-OLEQ1%y&e-k%lkBl+gGlBHxe5^Wg)AGqydm2}@E-0BQQlvl!geoy zQ%#7qr+-T~vJ7ay24#c1A>vCRGp~oGaum%&xEywT5BRP?{625UxTKh@!b1^_hvp@dKvuOLo`9ZKq*=)O0={? z9>#+)y5zSs(heVpxg3V{V^@XCkhjcsSWLF;#5kXa4?0XwK(Dvyhh>z07(Ziq-u<-& zKQOmEFK4UxpF)&#of?RpW?c>$b<3E?-^s7r_P>qGBbMjkGoN>VV>#@0V?2v_P1wE_ z?Eu3YB7Y-L4z#w%i)HpHqS7{sg78J$Pe755echI1O44`278}9OV=W+ml;sS*j(vdc z*AKgoiE=z%J52Z58j%C%szB}w-_+g1VEzb;>)6p1Hs`gWt3$87ULC>~)_QCz0-+V_ zZ@&j$AY}Xk{0uvK3O31oC9!`7|D}k}1K4-KUfq|#%e2q;=xOB5_u8j7WV_=vb(MYk zd+qUBp*pv~zoQ-d_(;fczjyqY1HnEHeWbyT?}D6Lz4fmS>$ItV<2hd-b(o^>6C zkZ}`aJj-$d@WYtzo84|}fA_Q2&F*ztuzQ`g1L8*ki~CuOdj`wG`mkiUs}b_~v=zpp z&ZTBP`FYQymX1`w`rvYut<*2lBdFgFaUP$K^<}!#avAduAIN#U4%HfjJ~8eodKPrP zoEAV2O||>59+3}>Wu2(GAPV900^-fICGdHCPI`du(T?MKf!lVZ`s#eqn{I~e@2R{} z@Ijdsd6t`LjrCjVppSyD-AOr+VJu|X!SaA-l6@)#*c-u59H#cTK3r{SM82rEO6ee( zo<;qos_hiq!a*0dY_h>-hoTPiTdmq8Q?N%L>~FHo_P7>d`(j;yr?nA{M0+30xAde1 zcX?Ptt8L}9+Bynrt`V)XB-7JqH;QFJJH8IONnb*@V13PlZ<+_6!`DlLEMwf4wdXOO z8Sv|XRt|f89=}^DhYqKp9_z>SvG-wo!?pDkhcME*1m}Fdo>+ow!FWowPN4^ohqsbb zOY}P*d2_IS+hOhAkM_KF_!@!G_x;G{w!JYY^Po2$UN5#}YG5r_*8`+vKp)({_BE~6 zZlZax<39E!(BoWcgY$)e?S%vFO{ny2#2E`rsJtMvu87ov=nj?Nkq*lBnjh?z&!JoO zyC_c|O&zrMcwSMT+UOr)t^Q7rYk@Rg-%F3{m9&7gZ3A}*8}l6jlr*X$5`*B$HnjN7r374 zW3&5a4bTTr8`X~6dZ1)wdH+IYIS4;Kx(Ra%c{zTCypXjjLBCap;fZ zewFY9gxs-aSUp1GE*@BgjT`-NZ!#0#^58Wt)L(oFaL9O(2B>fY;v;a5?<{5kiF#*x z6}SuW1cYw@FPmvxyLHALTxXgK-ftq@#Piq|=aB1hXmE(NcoUzW|E^5`tMxIzcLKLEAN@Qv z^4L&4afG5^OQR8v)~3=72GVVi&h+Y2`~+KLtfPlje$D)u`LGo{Vxt>s=he)=I(_xL z{-?CuL{Ha+*ABd)burCh=y=+}xH@frkLEC}Z=(#jI;}s8cK;4zsI|6S*&=@Sjk;H* zt;2B61Y`{SYcs`b0r)MbNq>m73~*c3K7bz30kw9qe&uG$W7L#)hW`e<`sOvrdW8(C zy?1`R^WqJ?^&wxfz8@HabH#pYhcFFcA8+WjA+Nvira5GPQP<9uFM)5lqE79as9hUa zE2_Q62i2|re^VT5XD{#$u;>5uxcJEo`v`phK-Lqu4(W~S$iui!xdqS4=nwdks*jH~*gtue_JFTy<~zpVGKy$%dQ}2)7}e<-K?K+o5+p|3ipt z$1CoMz4QN{LX1P*i~Kn>@AGlbbQafrF0b5I_j9c@=Cisk^il3Va82pY*U@|}%h%5u zU&DGr@L6kK$D&`NhIsy>LdfNVbRb_l<61Qp;cA5QtQPgmU=-xa!Z|VprXPYU^#s4h zcD!Om>Q<|-P3pRC)pSi$uc1)HjQiQ~ehI79Zj%-pD0Y=0X|wy<>^A)OCyN!Waezwv z`w_bt2NPe;1Zz7sT%aoFdk*}s66uX2`YA9k&&!{!5FEOu~_c!vfzN0Hsn z*NR$bZn4^>74@xFi0=oPxO*v41;X-BJO}{uBMdj-LepdcKCRDazc@u#>d ziJ*7&u~~i80C|uWX~UaCFal2z%c-R19A94y&TjQXp!uo;Y3PZgtP{JBkHyCq+X69U zXbOU}_&j7p(U4y-!tV@G0f%^f2nvt~-rPc3{QZ0&I$MDqUk~{pfws&-j*|`lwzkegQt7Ir9dZuEUP-3KdPW*)+VU1r#P|9zGn=EIwSr z0wH{SIG-z9%(|YMKAf`Rh7DH`x^CfrlcNrki=u3!nkgFQkZnjE=A3F8Clqh!O}8>I z@T(5R($1%qD-Ijm>@^QehRp(bGz+NBiiL>2u%vXRj5;#H)*(F(9w)=!-^YhhQ->EK z;N!#XSYy08q*@A`#$rNyo+Xs4$>JraRtyvF8Yw=^%xg-0?E*-6twQ0~*vIB$yFxig zU?f*({W+}`uW9O6(wd=rB1(8zR_%xTG(S9IZye_7se{3Kb%Bt(w(7pv9|n_GJWV~> zvG(vr@(>^RN=?V2wL`10GWbfY1J7Z`{qY}hu)_?Kfb|5MG*dQS>g+4wJiyY%=B!yY z&P9%9v-n_Qb!Khj7QDJ}prUG3rxP2$>IdeEsfU}u>~j?i%ooDwKH%rA>km%;em2yC zTyR=aSp$02{dlpmm1(?YASfG_dDt|pX^RG?7WSgZgwKHfknIB%u&g+sMPBac3XaO7 zQr!optOkN&2+0dlg>VacfIt4}A6{${0DB(2Eng2V=3RRSLGIuY^;&@??zxveQv>=dmHB7FLu>n;zQN&the$WuPj1iJF%`FMKxV zYacN0T3^W*9uj?l6Z|3f%2v)JHNiST6z4n>0Rg_g3?8*Qu)r~V)fReElW6)%ei;~Z z<%12%T-Dsh$45$tXLgH-8ii(NUR&&ImO#R5l}Y~)Uu@sM+7V(jS7-e>&9?WKhq*p# zDU0u224={8njcPkd^B_XqgM?m}vU&%dt zRAT4x@dX|Hu&E?8R}o0b3%bTv!Yja6svM}zBfQ#^Y-gWq2@J6D2f9&b(!c8~?E!qC zX+S-HcHLl!HDJdjo5c=;R$ZC`Vusa+Q#?REtPtKaCN5+-?dC9030mU8u|LxSeE5U3 zjte~;7`={v1ZVN}^EEvHTm+mcrk2lzm;%iQUYKo@-4X)$DUL#;NT4dmG;6&8TrRQ7 zISUaxc(B^hiOtssz7m-MEFx4@$5-+sBh$|xz7k^dr1Ow)`r}?K0rjrDu2jAf6KsJ6 z;L4UA2Phj0VvvT<{Ol`LQc0s&+S!V^F4t7`>i9|v-i&1)lKFTJ9m>b$gn2&k^<0g^ z;VWZOHl;ig?jrmx5FY|@(G`bc`salYbN)96&f9h+5c@Lkxt=coS<4KsfE@DNv9ILY z5k|dwetryPe|)CEYX%vYIRR_6^K~aI0rQTQXrwBcgvV4T$rl9{tT(?v2omUT&OR?G2!@Ld+%m!; z;SU}92iCKr7Mf!m8oL#^KfIq6;_!51;rYY&U?^y69(Ij;*06dZJg(g=7Isp8ob87X zdd5<>LyLUUfm_z?7LNJb{Veb)cK9KyDnU&-bkyRm?Q*DFa$4H*v`dC90=t4WicIFi@y1 zz*5-am(EasWm0H3v~pY&I1CBg0Fc4sDkSI@v_(tsLWWDBSTrlOt$&B0_rc`8+zEgU znjVFO!+eH{iN^#n6?EBp9K+y=VpKunz$A^{CbY(Q!hMM>lCPk35@kpdk5U&QGt^`f zwEbb@=c9`FT#6e5lrYo6oz%2(Q5202af12)Ezk2A;5iU;uGKDUJ|-6aLfW6GkptCt-lTksJnA^XN=Pcu*8;3ebA*){9}$uS3>6T1#K+2bfR!Kw)KH0u z6r@)Y{Zllo{Cp&rtYal9{Q*{PoUEg0{3zfD8)_LpMueK7R*?v${gImBgqR;v7_6r| z|E8JDW;Vxg{sj)hn+#24Aqm5b4y^PMGI|m#snkiJc0m&80+kLymU*56)!KK!NihgTH|8vz-EkXFC-V^L&~=Lx?;l ztc(PF@L$K&lmSajVk$H6#2k}-9xOsW4Fwc~*Jm7xsrQmGVxS}$PiXM?p6`z6SP9(QfR#8*&_k9ra=6ULO4`Ra1waX@No3#Ih?R7f zuG&xtjbz*d%#4qmCnb)U41@wDft4JDS`a~!n@@)%CXtJ<5`2!C6FH-iSb&vuTl5vU zX0qOdiPXo+1O#hpYF`%NF}^Z{h|~mFSfCRdu`)Q2^cQaetfa!xaFECVlQ<4?6)8zR zDUlcp!3-_*%ea(84i`!?i3WsJkamFt0xgO8SVz)!!K_dm(ZwVW0rw(N{A&V@ zfJ9u9gOA%2k>s!lfwdZ%B^ zC5~DZD6>(H4)zs}cVg_B0!-_z?kE-z^)`a7Nl+Iw9^+g}hAt-WMp^=3V1knij zVSS6lgAqx$g=UNHqV>>qmyU3$Ofp9N2~fZlF$i>MyBL?^;cM0C6cs z<|q_N#1Tnoao-aW>s7*HIqATt81J9*=>*#a9^I0}DMdmZ6?BrHMiY`COE=&IAufo5 zj{s1|scX=+=*tXxIR*;|Om}3ENTZDbap(!qCeksH6H`3eHl->;8V!c2gX3f}n&Aex z1)sq|o|7a&;&=sZn}RtCdI4?*rJRK4q==YDV1FcZci0A65OGNGur_XdZhA@pNF z3T{MQj@ajRAP6ki0Fp=ol;MPrU1(0C8yYo6A8e~6EK@#Qnew?5102dIv=X?JR!NMu z7-)j(MSTDl@nb|7k#Nx{#pod1Q;_2+3K>-Tbm!mmOvX9N30y{~lfrw8^AtWGz zOn6k5Y72uuAE9dcwTJ`<&rbGP&w#?SoeL>dF(aNam!KwRV&mo`7|mz#K7RyULNPtW zataS=4`r@Nx;GV^ip#LZlMG5N6r3YA!*?4RB7+*j2%_*nrbLE} z8m9!LU|-{S0q`jDu{58Nc#+4~SHKk-02J3IGFWqkXaaV`WEK%g!T^3kM+bjE><5Yn zJT40E>dRla3TAS0)X4xJ=$~ouum)?4CPFDCF;>=%o?liSzL}*k=F2Ms(3@uGQt-&})H3ap)jN>$NKvzvyFx+v+v?wIGNL=w3 zj6f3+MuFt`EMXfqDTAd6t$Bv2^>m;}V2b0DyRT?s2;H{j*8fL2cHnw&wEfgqUQ zQ1cA#fm@&{FgAEul@uPuq7%`xG#&XmI<~2_1ek%54bwcv35*P+0Vop61gmQXKj}1o zORE)e0&i3fKufa}WL%6iP)LnW!-g^^gS;5jG{u5q6zprqxGh<1 zd_?f&Y8rlUanJ;DBA8Fa2+bj2sQ|YAGA-lL*8j?( zX)dnen)C6e_%B`=gkivo+#sGVnn8cyNL|G!Csw$`O zI4r@VWRi&>3el7UF)Pj`B(T21;p>jDM)Gk!NofH$;S?FtCk&<#X>2n?K4an()ll%2 z>T```!6XO%wk%zi0WtWeE&x$9snH6SkOV~_E|>)s$Y>x3L{PiIMKd5CQwR?EawE|x z#3=)LLlQGsrZ+W3h#3-jq|rsFwn_~mC~8tsWh|ut2_#G|=uP|t%z%mfCS`=VdHZt1~>#PXijjxTn(zoB`}ddoPdx_F6zgKFd}6_ z9!k>?gg~Ju{UE?nc)IiNc_!m?=IPl^PbCtvKvpkkN6{F~LeUtN7f(`5fl8eOY8S#p zj9!j{ZL2B;Vj*&8_+9V6fsGi5BEhS*mRWQIx9b*CHAm zJe|~YN`b<&ac&*@Vvo8X_ly%^1e%s|;!g8gEcy?eO>hC>9~~6a>FOj_t2qS#3X_zGt7Qe8>pNtme7>?A91$Qv z;R-=gRR=KP1UUi9x`269GbKO)GDrf^p*fa-T(}$^9R;jFnt@3>>vs`|NkCcyT>1+D zq_E(IF&Ug1Qw2;a;BFi-3hH*-SSwI1I zOPrwT5PGGw3^PI2;mPwh#6mb=#V_Mj(f{u|TS4h$E6@ zkV2k_z|7-&4t3&%m?EhDDWX$KPzE~U0?}i#;Fy{ea~1MPW4#^KHmE^l%}8mw>LY-p zU~n6XtYLx?Wl6`EYyrD~Q9gsVfV>I$7K4{7^pkZA%zkKdpot|aiimq? zvZRU<+EKDB&6E{K#i&S$f{Z(4M8Eejqw08&LDwO7@;EI(=fy}cbqJ;cmv*uW(Rb3p zlnfgoh6gXkpsPXTg`kH$^ckdD9^xplGOdA301CA}?ns#v7{!zqg%j%p}qH2?8COPt=$nBf^MO63pX>q;B3sa zc|Vy{C0|(}IZzVm;U_9Dk)oIal{yL3E`Ux>*LgG{&wHL>Q1HheBGQ~FXwbVv+>5kx zYG1Nk@Q~OOkg+ov%xE}Aq6K;SZ&MHz0p&zJBEK5`!Og^;LmCvGEmzp-8?teR5Xl?H z<|aEcjnRB=p1336mPt%y2A-H>vJYuIkT$_l0cQowLq!WI3p^lZX!v5_`<~d0VX})l zuri6EXe(sBxPzaYn42@fK zX-Y_l98^pm_9LK(rf9~xGD6Y}0T#?ICmks?DN)w6EMOuVBsc>{S_%LGa7ni7bteK+WImyZm}(#%<0u3=(GcT=hZ@L9 zK~5Gmzy&ryMqm|9KZdBKG(yRQlBP5@nrP^dKIM!o3h7){ATPKYW(;6BsQ+c0oFxae z@p6u?Lu3~OUE}0v%1+9ulnk1Dd<02oao-aW{^A|hriD0^TrnQdNtB|BsA1qeP2u8- zn6(W#;c4U*7@8sI!BLwihMCq)9lVJC)38Br;wK|%;3x!etVly16fyZ>a>c$VXa*@) zhGK~tad0kcNoX*Dq^dZmxr7_w7PyIy$Z-r?(Xx;&g)~5g9&7=O!jWnK3EnVCSOQ(!z}flORZJW6FCb0Q;Q zrskv+hK-*Ony!eqEwPe-m0t*0J|IBHJ?WByt|w@c*U82F7?FZN$U|wGu6f>c(gFoV zqGKDKe^dW+^Hk7DCuTQh+Pt4k>R8W$sex<@ibRitQh5mCkOguQanb>nk zgRRe&E0SHb6btW@p6*bS(+|8<3Zwblybl2D{1R{tl^J+qj>*2ItjnE1EU?c>PlbzV z2RtA_&!*WVz)&6cWSIQe#0W~mY~X4z{A3g|=bw_JX|+v}^O^<(QY|A1OmPfLvwZf# zVHK?dBNp%!C?vrgCdM78EmB&9v}Qm6fC&XS3r@0(pihxe!tyZ+@zZ`$r24=NWSV&p zlDB~RaH3($usB(+s-_j7kt!1%R^F453r0sUa8xD>lZ+L2oPnd;;?J{5euCj<-N}Fy zRY(}%PYrm0qY&w2OG*+R8W4KZkdq}tHE07(EGegH`mrPeq>`bu3W-g&Y{+OT zr(xp3hh52wIRh;Olu=1+J9nq#$>G96F>9I-*+tPbv9^_VQy>xWED>=;k|tT?{n?Q! z2!~ciPs;ItPNEc5Oim`vyrBtkP0B-HP38^qNT(s_!BLxNmXon;6I_Y@Gm@I-7}TLE z`pGeqn!=+IAm_>w;1LouR9jgx%s6HQQ*$K)tt=Mvj)DeLHA&Yz#eh(WQ9+Zaia!U} zvYzE?C>En415knN$tyZ_H#pwH&1_qNT>$z5%*F)&t|dcx7rA^nSm$vnCv^+y4)#I{t4p*Qm>SOZ~?0qPzdrFa1>>mvW4+e zShff&VJyq)z)Fm=m%z%RuA8Q=+GbMHWyiF2+tf8vFP_3m8ow!8I`FZQkdLqu^C4j+ zuGUSPhT_B#!_yGJKp;n0nUOIv3&6^P?VETM(R6&Q%o0{Y-vd?_blooGWaJ94G6t-~ zEeI?9>5Oh`+cvuEG_2Gi)g(xk(F3e>U01f{qz;ps2?El(gk9C74PYWAr%l;SCFERSr6fVEm7xAehDBIu=~>y-@tjnt;3^mZnl9_Q zhkjFV58T4UT!zD5&d%y)0c|S*D>WZ04O~tTXG0{j9Tm`H;YbE@Vltk!eXQgQC4=ZY z={O%N6&X@#oKqDbo}j8gO=$lD3{(`iek6#`gR;|Z9!ut()3GZa&xQYV4hg|HGcy-cB8c3lb+tdyYzP_S*1a7Y{W za%gL@AZh$K)Nu!WwPC5a5oN72u1u#(okE>u@+4eB%dADE~Sa*d4 zq-hn)%2rAma$$i6Oc2vxZC5nBWP>wsbX#b)ke~2S9ht$&X$g|al8$CbmZs}ClFQ|w zAto)^Q5?{nu~bWSP#DM3SXuK@7-&rwYQwl_azXEgsNG zloFkkB42e3DQ>BiLe@xD9r6a$QcXv-bJQSKHpgc@*GB-ufgql9OzKd>usklaT*_mmK=5zCe zl>xU*VwAb=i8b=p#0QI>(7cd;!Z?A{tMWxl7j+TC7t>0hwY%UyhG|@!X8@6cVN_hq zZlXmG&d?kkIB*tp+NSGzo@*DpjOH38uizGt^4x~w(%@DM7-%6@afF;&s!Uh%DsGYm z#9>9r!qu)Vmgkwc2X5inPTtA6wOXO#dJWIOqK##^xRY#UsiQIY zN?_Gu$@X+Dj{^c`*i5Qggnt_IGmX)FZXR!xqylc4 z#8hVBi8Utskj6FN81I5ywGDvuAR-LLujt3mGG4R|@4^8L2|9o%39@j%EusiB*^k(Fv(4T`d@#jr)Te z(t?AlbA@stxT`OJ5yPJ<1RADoi{Jddoi5lOh<6+utyZgc+0NvA2(m39 zXXk9-KW*%k&Dlc1E+9ieCIR?eZ`sen$Rl<1@s`8Fn- zRL*YK%WkG!Adj?QyQp@R+9X%5$>nM(MJ?tQAZ1qy9(Abe<*LPu=V*4yvJD7ofJe*< zwyj%cp^RfzIX7h$Ae$Pq?V6J<&lX(~w=wvrr$`x~sX1VU6SXe_O$Ijsn zs*}g%HU?kSu+2&pa;H(UU~~f@XHt!dts0iDv}g0{eHLu+JPnp@Y{<-RN_K&Gm>%7f zXqz?^1k1=n$k)jBHjQt(VvSP}75@QyfRb;8T*n!~ zES0zt5;UKbQhtmmi$KUjX|n9-dZj6w6tb`sp6+Pn1s85+bh~|ew$oFBP;wP|CR|lh z=`5_tsWg?x`FKZrRO%#<{tf8Vt5wsa(CgJ|6vz%uj-EcCP%dXOjzbb2J%35ht>a-l zU?(gGc$_5*1pqke2EJ5ECP7jHl&7egel1eL!P7}Srxg0_Z24mCLp85ns8P7WE76^^#+j!bE?ldDv^lH_!2WpuoowaRrz zRAl_cbWY3yk08dNz*=|4MJ_DRSXLq7l7-2|vrsq#N4KrjYJf|q8?f~F&P^AroRulN z1rVRj;ur)vx90K%s|*iXfs-!bKQ?a06cv)dR{4awn6fe$ID)K77n6lZ@yivLawu|YDM>w^0eqd&5}V8h$E5;AcZ^; zK^26{SSidWF6u;d5~ZM%rxf{asbFOaZg;wt%XCZR3szc!pa(}SQm8eQTBC}8Uqt_v z`9h&y_B#~wVWYwqvbvjsnFUH_3MLQQnvPwrrO*YnLenXum96<+Gn=P5$tf1vUb&pb zJuoK9xqP)yDYR#%rVHg>+08m~7B&>u)w3`(I4(q)x|y}7>bbIQS24rLHuRWOtM2NS zYiiwo$?vgAM9Yy9?>egGaZubjnjSq)&O!h-U;!u*HfFR27Bc|q)XW%0l$qB&(nLHI z?)dpQSXi>ef`APT0u~`c8rtqjC)(92Pm?^&C)KncBg!KX@=zL6H9)IAquLbmSvt1S z`Bv658Q<-0%(Qu56stLnuo7}#I-kWXn5Oc0g<=X+>LgIJ5VqIrjzeKEXf!C0L`@D) zAHbAktF;=(WwRVddOGBAa5X)LNq03=NX}U*$MFJRt)@~SDuF7esG5E)(!s&a#GXSM zXnwX_vF?@4LbI?L2<=8=^Pw}-7|rMA>8bR9TP87;8F*ri$$ql{Fd*+z{t4p*Qm-So z!2?+xc!l`{d4Q!=Fd4)2-&DtJD`6;h%FqO~JUwK1N}Hr76Y}1mTm}La8a2Twd#zfd z+(4>U?qk-)Ok#R4p*Wr=c<3O9YXLbt*%7i%&30h5m-D!~Tx-;VyCNg9!cjKQqfYj8 z>?qm7)KniZ(GPOwoZ7U9Cqe3+LP5$SbJ6qq<#MCn^N=e8`Nt_G0V|H<2^o1F_*gE} zZ2<^?ODunqX@{JbDLVz5uX!a9pU>k+tJQ*rD3qNVJZLR@WsmS58;|pVRkds_+wf{K zm0RMp(d2ety+mXv`{Lwri40-@w>zHFym-Lv~>8$BwZN0x(A^J`_jTZeds&uEoY56?o(lauglFQ~i3p7kuWdqEy7ywMJ{*aD$9_U)7@Rx-+m@BUi zQb{S|KsldZtkqhJgFJGB15!#Z-^f>; zTE1As;ZCQMZ{-ExAv|cU!+REstm0gLEpi)@y*1vl^2TV#l8)w(%Mm_l}GOSf2Q)T+>E zYW-59QLJKApp(m$=}NOU-*5M-jV+CQA*U7dHCX+u;#5ALLzg)n*t%yr<%Z`?=fKRE zUIlJ`CT}@;*Ie8>HR&{eOUsdpSjZXK60etvJWY=!UWKlocRl5*~Hr+5REfjr3j4yfCV*Ar=dy8X<3ybm6I<8 z9+d^r(Gt(H&=jI7318$kb zD0AHtYjkT9A1r#-@|1tVIE_3NozwcYqE)njSC~(LqtM}}!G8?1a%-1?W!$V(MlHM% zVAm9^$ogxvegw{{)hat$txl&^pX(^aR%OtcYt13mX)QNfb+nFG!J=-lf>q&)AQXiK ze}T8CR0=bYx3K13!_}?MTqn3IGFE)?AxQeMgV-q7XJ=Pn5n2gy)(V|LMYYV{s9x7= z$WX6TR$8sOm2DN|5`+r=&pwTXfhe5DuAk$W??^v0jiml~$ou zsnu{~I2=~yDoU%^fyZKWtJ11;P#RzTWeP;aPfbb191u}5tEFlsm#-9Ont%w= z9Y{r-C{yc0gs04kJEc%w*upA)KB=6m_*{y`Di=@L(|d!wZ-rbpkZ7fDSLq_rCCB?Q zq9#J8BZ`!+mdFs^-)a{rG;4HhqocQLa3OKqMps$cm}&FArgiHsy(0_I7n(IZIxkRp zibXL6Ds>WQbqupXVE{Fc!ujVfEKs01k6hV<1 zWH#HZQ90$Qz<0YG2cpuToTqA1C3qn?xS7~lNe>Ldt!}+*2Du0$OAh9&I(wEiZ7d6TO?@$uQ08&img(s)CK=B%s zMcrxxtHLmcRi$lorB&4$m3eRj*7~P$b+^CR5AKMJ$O;!E{g_N?_EdW?*lk($-HY=O z#Tw1Z{MNeRI*TjqwlQ6A)Z2~5?rwK+_pSzVLDsKSW;rY*SE~&?tqls{=(dZCi~W9I z!}Bcbt|4`+?TXrO%vQRM>1iC@wryKuv7vRVefUP*>NdKKe!EYbhSbm-R=?3lhQ8Ie zy49A}aw*-ev@7++QL_O9-7F-vi*{GZSI_HD12bClGo(|Wvm3N_pAQGL+Ou!xa5y#F zs#b@CLW_5n&6eY|98d(}h@>t^Ax}h51>w-jFoQLufKH+mRn#a&e)s%rMd~(ouPnB; z-Sgy;wi+!|dmFV$cgwcy;?|)=E!OU1a4+>|(V^|u?CiFoHrp&Tq+Wpz`_r=+73kzvXJK~G-TAUD%d`Cp`iEEiy3s}t>Q`F9ZQV@ro!Cr3+LAREZAi6z=owY z>Rz>_WLwip6-I)VVmGH6^-{TB_2*PMH&UuNF@-sD4#S8t>$z#2^4iS?#C_yb>ZN*< z_`o!s9NxO5_h3Y5yCIl0HQLWT%>AJB}6GWxS7~< zNW+?Xwp_{G_l{@BXUrwlZQH10ezC)7J~vO#jR)K^iBaadC)OBuCw{g`oV^3w?~&2Faw5MTg)&hS~o+TNyl9mu1OJ4f3G+ed@B(P00u-@{y2ZDUcl(QcdVwyZSeU39J6FxvGk=w(-RJGgo< z+CB>IiHrb0xFG4r1;p7_Z)s`2>$dlAhYhCP?$o#JXd5|ie15NIb#S2DZtouqw(sBD zMlM-y*K2(q3(1W}+mKzHfuq}Q-@bh`8X5kxaip=hZF$h>O{t@Hzcy%hIyka(=g#)_ zwlQdo;6dx4J!p@5BigiORKp#$N60X8NA938XU^p)-J9x7wYM*K+Ld0R-)?x9?Qf88 zynNK@cDmgyb6b8Hx76K#5ggF!z@-;#-8$W$Z8WwnRk~vKJg1w@cC(-e#1TmYkV2k_ zpbEmt4Q0@5wB>+Kq7+p$C`Eq%mVQkhwD+ICy{GNpLLOy3=TVCSfh4(-kLhdZ|#{Z6GVw>pgq+M?0u)GJu2X-#k0F1OmP?Ss|UXn<$8UUBiR z&irW5AGC&pJ>Ai$)5oYlC(q4q8!inl*t>jQe{}Jv-I?|}?O_!UwsaQS?N+-{t?g)Z znkzfzFz0M-wcD5^@h181m3Fz-t{3+oTp;>Rx;zGtYd|V)bk%%!R&7+P-L9JLOwY8c zQ|*R7r>dnD6*F~p8gt|#L`%wS7H3V$o9)cB{CsMw+VWLB+xCiB>Y!B;+1ISsamJqB zy4Bc<#8z^$A0wJaAmpL+49?c;D|-q}3iGpcY@?&M<8k3;rf=`xm}&FAZEx)r=?$84 zSyJX_@dmm=XogF)-rzyPhl`nf41#qbET9s)CO4Ehy+jYIu(e*AC zJV|`PLmCCbP6H1-l*{w8R8FfK_^n$d2}JRrT%u}HC1fQyxS7~kJ{XxpU{{COb2Y(R^;69)b?IWfG&zbx*9ZYdGJ zORLLE3(HHd+`2Txwe?=E*K7BB&RkE`X4E~ncrMqrd#&vdo3Q5I$JI;AtINSnk+IjK z<-8#2#}&l++2M{IhjO{zp&;jcYx#nnRV?nhXgGBH-Cl2@*E_Vdw0h{$9&)K_uhm)- zdbwP?-LuskD1-ws_Uh^?lv^|B`i3Y(J$0!)Y#GbFrPflf-^Y zTk0+KmQf#UdTP(<<(7NPz17}wZaKHqUa%KRlpeN*t={T+^S$~)dDLqcuRPQy-@a_Q zKkN^O+ZO@S=k8X9hh7PXN%&Q-xp?Q!+0kI8y>mx>C>37r4GV=~0Th8aB54VmeeqXM10u=ujAJC-iKvenWM(cvseCPZN7MD9SJJF}bnKl+2_V4aZwR)}Up)0l#eJ5Qhr{;3@T(>eaFiL~I zG1F*bKFrV0&Ot%w&5UVI)vFg6Gc(O5EO+BEL`%wSSNk^Q&Ckzu{d@+bl6m3-7+|Zg zIFYSJfwp_nWji}}+B=b?`DCZ!$B4EdEHCRirRO@cv#r+dOUg48w)E-PMu!JF61eItkP+WH-6sg4tOLS6#JtF9mR@ z@4EF)nZkMJS!Ta)nWU%B%qUplDwhd6Z5Y+3rndB{obDj-s4Uf1K%`JLsS=779NbLo zIiz7gK3lHLp`-go`_7n4X7=pa*jz8YkI{T?-d1gu7~+&ind_cdW8c<^2N;kCb_ARi zunra9Egsm~pXyHmuiCx#QhTYh)Y*wUGR&2KvYWwtRUQrxt|)jUXOSM9IVDHCE~e|@ z>sD4)S67zyuDaco;r`XVD|=U0wyv&R0RY9d&0%3U><)+70nA}t{bF1_D0JQ7>@GYN zgXQBzT)ncocQv>xG7g9II9QPMV=|?c`b+1ZeffoHflyX&Gswo=)1aA_&G zI2aC=hQljYR`y=`sv&ae`e1f;SpuwdyF*tm;0zqiynFZV1zb8<09bcJeWklJYp)KM zXIF-ci#WP}|Ni0LfxFUOg$J!G!<8ZMpEg5%m>m{YhpWTA!_~rSVWqn@yR}N`rP-y~ z!QKlOhcM7>A9TxazOqZc``XpT(c);dYum10#+^61@(MUez^{Abq20UZm$&q~yU&{* zDW!w?QK>X4fg%t`B&~o}c#yC<#9|qFv@*fyMFa%JNEo$I7A6>gwV$Mg=-~>-d7@^H&bNYTv=- z)vH#A3-jg0;YxcroL<~Hz>Lyu&t5dUFn8fa+g9g#yD`I*dtKepU-|Ok^z2}^e&sbg z*ZVBkR0~d_;12s!y^&cRZ83Z8_Go057UmbAAPjmtv919Davx^hcH74;3?s^%t#8Rv z-qOOtz|Uv)+k-{o1FR6%HPuwRw{20*~Vb?Cxr1TJHXJ=o2 zxYnaE-a^MVIy}&+;X*29qZ?kiG1KP#e17-VI(;pn+0=~j7848ARGwRmi{ zRvd|=g9m3jN?7Vi;qZJ<`{%(w%>CA%v2O||*_~^TzwqyCAA9;~qV-kbheGf2X-zZl z_$I@=__K$KmAUBA7k@S`R_k;4_Io_aL|FQ)eEK=OofZy8rJ~`Gn zVJ`XiY&bFsv13k}W39}!Uo?rtCbgP)qInoihQ=eJPK*$-lDx1$VYb6In+lN^?)mZE z-KSfBH~Vxa{19vW^rvh8D~O3s?ZtnN9E?80I82V69p5&U9cDxLm!NFuQsGhMQTIE_ zcif+4V{AynKgWkvCW&t(GWf>^k-?Y4MF;)wt4=B#R!z=}NhX(zNlq$-H&U4-zCo7cOtXR)weSLz7OJS>FeAn*QtT-Ejq#8^ zV}_Se7>B+=!Qgd8RT8)I_#{s_w3RVG#u*>uD*RYl*vEg45Ap9Pq(0^(KZg6F@g9*D z@(jxy4SoKh{QYmB;dZ!r>{;>IliTCeUKoCe*IO`XNAU!jQd*cnd|R~Le6RS_ZEce_ z{v!k%A~f;g!`B*0X}+fv<_k(MOrfWh!Ue4mE-8gDp4}?E{?hxubN<@DvNM<7dnvo+ z(vM&Iz@P4B^|k+g>Ajb%ef!dPu#3Cb{@7x_d=GogJ?sN(`zhSBcF#R)m#|-6yCk%Y zy#{=B-ixh>65Gx+m|14Xet%rK!DAzx>3)CaWrYKU3ug}ZuMS@^bA9+-g(EZX>EBkk zY33t+arWqofB$HD0Vc-s-1N~Ge>k4bm*%cc3>$i8kk=cXLYmPs1MnN84GNvk_c8-~ zNMO*(6b2Ea8#@~M?QdKdWuwPf_p#7#GfwD%hm71a&7tmfk zr$VfsP2)?*9cIkj#QZrJ|7a*PPDa~D-YVWGhQ!C%k1#QII2N`=_eF1v-i1#ZTMOU$ zkk1K+_Z&NZ?J;6nVuE!K-q`4mqw9|!W40Z~@#7zmM%rA(~d&`7NxM&kKE*UKkIaTX^-%FE^D#RvO)!03=;TUG4Ml(EN!gdAf;v>Yp? zu%{%j*T_!g*lq#Qbgi9ZIweFro5`_y6p@&gbBr2C#8A(X^Sh9CZe|ZFbA1SH=$=xs z$`+}AdR^+CFxz9-jp`UWhG}C97#(#3X_ICa4#`W#%XKvMhXXfvi#J$t)lB%y-VgN95%)+o^bY&&PUs!Xd-Tv9#`~Sn{n}Uc(EGhR@}WCY z?{`Cgn*Vk!^tAqmPUtcF+iK{I{m1ms8;z@ap{r)tOL~X;p_lb8%Z2vn%TB0cFXTd1 zr<@NlSOsad@qe{=wLh!jRmXh(u~ZA+hig^qB0E?27Q<=h)@%7;LO6;DsZ~WTpKJvboKk&d6SA61zPu~7F```YN|wSVk_fhX^ku1-CbH~5 z-1C3!x$KFX-(6cOfnU~M{sj9omVfRCCw~6t2k*G|@!wy|tr2sdD*vi+W-2r#hVa=+ zmXVW0LF#j17TbrJ&xK#bAARws4~t^x0Cs-%upsz5&pym?{?5OQ@rGgOfWYS<3VcOg zr;#{x6P-$lk>>CWUbWT(ylP_T1fg(osdoL%Ph7U=&(>bf{*e90C%$>_9hd#(&rkf| zxwZdyEdeUW;VVM_H(JSLZXKVWX45H$b?^r;_@ER%&K{4Y*$}>OgOAQI_#ZSw#s{rp zQ4@DpWPI_9%cRvvJe*)t_?rd#k4lwQzZHuz=`TRcxo6Bpzrc(oWsb3|x1nW8yxVh} z7ST+Y0exskaKv(J5L63~#$ms$0&vtqk+L$0~ z{r=z^PhWUxcL7}Z^tB(V?y+9;N|d{uJsP??^k(4W^w@e^=xyQ99(GSC#Fm(l9eo=z zSdq7Vm}>UyVev=I%${Rt<7)x!^95~tsLmdJcdQBY=(%~Q9$C?n8@_7Ic2n>jN>}k>mFrB^l&!Gj3pfI!ln@sq{zkg6&2th_0=hcOehuKj0bK$Rr zL*aKaEQDh4FY=|rKW0Kd#`wP-8pGoWDn*ykbI8C%3eNr}Ptk3$C-e8>ec zKFyC9HrM9Uh@M7$s76kpb)9~v1UA4!f2 zrMXU$W$-6Uq2%2;=?LiyV|-3(E)M}T#N6$XZ0Rcsh^}o?S5np4!`Cv08Q(g`B0hK! z-;$;oL6-p{{yd?GH1kV%q^cN?9k}M1``-EBb<0;j^ZD<;`=j5y|ArgxzyDWnIR9|y z88*T$edY3p)?WO<+S=M5J@AP~+0U$f{9k{{zJa~^xi{WQW91*vfj>vzrI@dc^I_8c zu8G_jx-0a_MC2{$NJz_z>`ZhFZ4=sQ&=Q>}n~#p8p{SL9j2*EbfWl6!acvXrLYNANM4-EG zBXA;(^DuL`St!v5^yk5az0l7e-u}$RAOD{-*G1m5^@iM6cYW`2s@n)-IgYw{?0443 z621eBznxHG2e_jz9)B3$-KU-B#`u&l_B=J}(GbPgx?%@BkIs57zOsG5!vIBmH1zm5 z6T%C{c|5rRbv_66cjo&~Q~WeDbBrk6M)6Z!8oU7;P=WZ~OUN&9jL*4aFDU1SV|*nt zbil)3Bp}AUAH=PRRqzMQ2e9)mW4{$&sx;yeDvwI@3mf;hM7P8qkA5rmc>Ftw@4E5x zG6ypk^VejqvPhzE`toaDlfbp9{U_+VI5#t%OHjQ=m@zBjo zo)MuzWu!;8g)R@hHFRSr5_&9Dh7^9+*Mq@Ml68~dh31{nwqqv()ySWACc+a**}z3& z0pfrm1I^{_2M<=XLUn*1p9n()!ht{xK>+`{7=K|9GAh6Isek>_C*SkFPqW`te)bp7 zJiq$IKm5%@-UAP8A6@a}uRirpue;{gKYfStXMg>Z2VU{zCw}|(*UVz1T=L?NB05G& zlRdcJacRpO(YC?9yt*5$b0scgS`Z`hfS%BSd>k6- zj~}M&)fob`r)S7B^1`-lm_&|Yv>f}k_-%PXe5%={fWb1JisEZgJGooA$WG}}>77pa zBK=L`)#{b{JGghNw{mx=A9TLJrK0&Tsn>W{hQr@ou_zZ)&2K+6Mg<;cO{UIpP>=Dk zl88x~v=w^8xCSbtAd{1iT%LbxK9o0UBfJ5#C_8-6 zdWIzpn?c3Xr_gHpDEn*ceMo99dXX^ec+;PP(2vk?Q904?&p?U*tD*zJt?ac2Ax02p zL0bW44NmU*6DeUE&8ZYK&}}YxICsxAH-7Cm-`l%DmD5L#-g@;L?^GWy{N$^@^1W+b zcjf!;Ui|F(^@xw+H?39&;HQ|JJ8 zp7Up@6f75GEqVh+XzsmfLlSnEi->}2UPPCJL3^*1BciqAc) z^Y=ku=Y_Gxt`qgB5MiGo_5rGm^F*F>xk#3vyYM$!U=q`35|d?2(F}pufJw}|^YRny zJR`98U{DPo$q$$ZYgQbRK=r`yYoC16`yPJa&P(r{y8k1gzdrHkzFR)}B%8SI!^i*R1bdTs z$A_N!%}+hJZ<`+aKVMmU=b^Rd|Kd9zeej1Qwe3OAX~4WJ(_r_lqh3y6bL{0Tj3-mx z7&)VXWjkg*%8W96RY3zW35BMQI8Y(~341_dr;<1yM7f5OW(#;$u zk&R|4Vjn`ggKQjHABkpAn$TG?unnEXNa6q~oyF@M6C{j&;YLi-s#aVG92@^G5-|DM(_*af3ksP#D$#@ z8^Iq;AHfm;HOW4IiVlZtA#o)6znOjL`^!V&ZP>h(y%EBr1t9VvpY*V6M|+MR+bcd# z(imw5GdJ_e!w*ZLYvj0wl$B|N`6cun|`JJ*iw?hD@xzwiJ1VB|j^xbvPhdF|&% z|KHC_2C<6 zAsbW?;8F7!Ep)7FB#-)p_{s+nf*m5{Szj}u9sk&R`6T|L*cZk{%1Fi1;GzO4rkb9r z--KmQ7VG0-K#8vt5eE(Cb+)dbr=M5-QRaVjqR9^XUgo{*4Uy{-*QVc|c?WmB@ge38 z_Rh$yiJQ~6WNzg?Z2WiW+lpKSr#$H9ZQA7XGqh>tG2{Pm?A7xb#xogw#Grj&n>|H| zcjQ}1HhDDk`mxwNB8*|q@4#AvXQxBLQTC(X=$c1<52`cHKUhAZO$7P8Hr7Jg-LofE zn!r9r62iKGATJ!Ap~}&uwazibHIVGCWv)GVkUeGiIw=V-Foh`-D<`a9;f<`rUj4Q= z{pedy{^XiB-}d3P=l}Yz*Pj3AYj3^g4IlX6>t28R;(2%PzxhiKyzj;@hMoE+uDyK3<=G>h>pI#M;`Ecl`l-@f&V=|K(TQcFPMd?zwy4@7(mhFMnyG%hH(ifQnxY zw1!91IZOc+2@}BcekapR;7{(@`RRCydeo%;OwM4L~*O_xMxI!(9xq!^gUQ!=UGBAc};dfA_~U=zL9L0}-d@&T+$^ zJn1igLT4-W^s+V;g_2GcG@e_uFVM%OSL&CRUKf6o{$~62rR(kYdUx6%@;;^CZ$DxG zME_C#`Mk2Ee^!4$4=>iQjD>16@0Ku_%tAhvpYrzcm(wJRC(hL<`^<#_BtJ|<9`AC$(U$BK@qeytf#v-uXK(1jzd9=mn6YI96YY9K04ftK| zvx7ngQ-p8Ah!Z~e^wTeV5yqTQV8!z9%`+bu&m2j=KmF_J-%9^94Wk}gO$|~nOI?z> zD)mU}f8wv5@ppJsW_*PIm*XSp--Ymb;kXnXMSL=D#@b3OK8mD<>BZvk2pe?RdP+V|jNkBmR z7tz|fRoc3*v_(ZLN-d=-Wb*yaeUpIx`+Z*n^WL2|^WMC7@44rm^E=x@;ji*Q`9;Ab zOwn!Yr8a;Gib+yM>PUPDUbqeKmhZF0%4_I zju{*kuZ~)8dlA+;3{^z1$(KF-+fK%-Y%2M=Mc?A_Ut{DALv)~?0|X8`_E*(2+#wFQ1`8>HSJI?&J^0qKsm?ZpLpCl(;i9j-$ zsok|OdU&P7G}iEJ~l=u7N6Z+KBCA8tI;0u2HojuI$J36Y<3p)buHw^=Eq>ezQ3bk zKv@yKZxIT``(cHwX4T=zlMHwsHs?-g+E_pV(?hX73f$*t3zVe8pvQ)m!_bv-@)rRl z+=fJpC_v4buuTZA zkWVWsazo`1<(mgRFs^xP>z3~pPrARhpnXGrXRpKN`ZYQ%r+lB5+w+K-|LY2 zAbloen-6DM@=>WX-z35FVWDmjRNI%j$V71;vqCVj>K%Gz|n4Wz4VgfrI&70j6G)U=o z%odYgN`Hm01i%Lc-X~HTCLu|z{G&Me<0m@rec*lekGqEz#4442KMrHhWrv7U*d2Q> zzjX~s{da&jeTk8BbIsGcSCBC#!wIjKML$}(=5&3bEXSIW zC;WNWOmSYG2!WN9D*k*&^b4q!5Gw35v8pf4YZF%HZ4mBJo{%24@0B|2zq20{4(I(d z5A}=k+ z!6?zuB}Jgh$+_`S;H>ws$QvM+viH2dzo z+t}a(AF*BopRYXd%g6pUZNcZOxBOKU`+a-z1$OD5K7)Ph&}+Rn-~M3s+uNSaetFAt zwA$Ve-ZKRh?L^;wrk5w;Y_Mujr`wh96ja=@g~d6XY~e&@LF!WIuK;5Wb(RHQlt$cN_pZqm#DIqBudkhHHH$@S|CkE8xl6p8ayMU_?A6h`=mh!XRd2O5?O zWSZ~>BvVuhCYi^9O-PL;SwM3q;g162HAQX14}~Zc4nwd<`9#oXDp`@k{Hp-m3{uab1%xi`O>4=>|+;JJk`J7&@UhP z{NKoQ#DoXI8IGVIt-?m#Z&LE9LX#lLG|e?jzEx0x{_NNDT%IcP`O>I_mavP+$SYg^ z>pr7-`_t)a8#vV3iQQeSGROaeHSI-FMwnopW&43o!ThV(zDySC1gS zsb8E?%%-be=8=kugrp}ZrUVQFb$^1o5DqBF!7c%ru`re{P8C6h#d8(U;BYoUA-UC; zC>&G!1I{q{>Wkd7K)4sT6|>^JbV6eqSDCeNdS-4UFp0;wS~v$K|5&(4VgUH0#y$f= z#(UzIc#(|=1U*D9L}Gp<8I(-6v@7LL$J1&`P8X&^_PnHk+L%dv+2>7|@vcBgC0Wc0 z%J#Xj$+skvLXm_G_qPItldo5S$+8A8umo_Vl*oMY}Isb>Q;kfE$^3+qK8e78{;qore}L*~_NC_YPaq zaq*sC^M|a{l4wO8s^4$JOqwXz-PjHgy!$pQ4X_8mhvsyX6>LRYKkaY zRm|W7yg$g&z*js-JFqLD!>MLGwgmAYvoBUVMtyE-X#=7wT8-I4L#g4S!vABH%aI>n zJwbkFaGZd#*x3?xmH+@d!@kfi4{Q#>9@M?`f%Rgja^ncY1@|6qs0RXs!;mmCFfhRX zy3$>U?L!B|9}gVpG%5Q!9}%bgI81Es9D`nX9uw+%^nxV3zKe+h)JEKO`+&2!@wmOR z%Ge_t4?kW~YU~TS>+}BhynN$*D8l!^N?cV5WrMO!0j)wYTHC;Q$-?Jbhn1$=9v0E9 zay}}1BcrIAwvqvb?u<9+hR`7Hz#GP*O-FPNWm{VkUY3A+Ta$N&SN5_r#u5ffLxTCL zo2Pt~TSi8Ec6UF?QCG_%Ly{pK7*p_Q2Di^0f@sm~UyTRhz;=4zHuJ)nBj=SIXnx@r zFTBAvhqhilc*(WWcc;R8UY+*|@kK~|%6UZ5EUV{B1vRy*rLI`3HucwrYm=na(z}v* zx%R&FJ{BR8#rV=#qO6r~Q687SQWZ^R)$%(sd8;4NEuLhRl%NfShIU&m9Jsm;wd1{- z+sm}iOIBgOzugm{iX_VkMMJ@7yu)-dL25U_X;2Ym zCYr6PplXt6h2FkLtka$FRoJX-SN1E1;21ngrDN83 z1hG8|v7Myq_Xac@04BXT)^2lCe;w0IX>APKr>K_k@^H)47F;3uU6K5wbaeKQfT@OOQLa=X1Xw2w74ZB zkm5kp&yo!P&F(u6i0?6T=iTBjx`fUX$1wd%#dkZOK6RJ)`Bz!QKyY253{;~C3v?S3 z!2uOPCDdw<_^9qQiOmOYT1x77Vn)l$pS|!)nauBszpS#bv}3D zuf*r;kGuKAbzxe5-tA9gcpc)%DTCh-Bus_?@?>h*zu$H6;C^z?gFibTEuq_4DsJZd z$i%l2-^zTe@GVB@JH3!NmdJ$)ESR(!Bi~-PMyzoy34)fPFyn;p^*C|+G@O7Eny1Ri zH;PRXm;)l23fYVvoUX|mbSdpwaiZWsUrp5QIq8M}5T3`ltUv~i%<*#2I=UQGZ9EJN zh269VXLb6E>emUPQ}u~aRbFmeZTmgC(l*jI(kYe7DSI!+WNE6r+P`65tnoS-Nd9C^?B4)d&0-!xJjkNWgL%>_RleLas zN$wP|yQbDrQNx?NdgEx$@SkahW{){aSUT2b76|sQVM#2|tdP0yVnu9f-#{2X08Du{ zJ8@ffva;{wcejmbx>q{&<1qQPlhyK}lQbD&+Ee0~DHe9k4i8o#L(Wh`wg9)l9nn!7 zO`M1GT+2O;>OYe{G_M(|*H1p8(Q}g>BJ?u6&dHB@95LPmhubBJSzmvp$zdM!1 zfL$+Nhrwz)*+zQnOi2A7D{l!7L|MG5H$|KbwM40iUR0J{vJVxRqw-_H-Hw+X5(Vt4SS*^yZiY!v-`IGp5?v!A&ai~^0q%@ z-xXhF3)p=JvJZdsX?F9j-?J(Ill^!0O;*LC?acbi>}Q6qFL#2v?eNdusrQ=gp6?S! zyGHw_x~BSMs|_|khY$>r$||UyvFL*ZF+4-cz)?PR52EUysXL8p%E}7 z2k?v5m>ef<%oq0+n#z>k!AyFfQXi~KpR1f39GPxWCKOIiU#46oU8$^<)+!r?d!&bi zC#1K9w*#LEp9Mb)MPf=uC{qS1a*J|%=#KQ;X*m@rOIHPI(<4J8V?*OZ3rD9Xs*~Ll z{8M66@+QV7B_9=-9YrzxV(g#FqWz^9vQ|c61 zlmaD^xg;G5z)T11GNOp|Mo^H4-6@G`QNGy{Nqa-2QhB>67Y##VM&lT#Tr>>IrG}1T zmZk~bQDP)f)>bB#CDY(eDAEh+wQ}mUhD(1=y<>869;aRoSmkuuV6EV;biLww#aInt zJ^@>XNAThl#eoz9qVLf|iNxYu^jmhdIZm0QfqfM9_T!JEbQ*RtNL+k4=fsQ5VDk(UFXx@~xR~i@@vnWaqB7 zB;gRq%8y`CFdCjcU4L!&M5?eq)?QFt1^e$`+w+R6;Gx6!@TTBnwaIA2y(r$9zX@AVQ$9cr@h0_HIC*ek6MN~6!+AN-^ zn2ZE86KunFn-a2E0>MZ)A5ORX4QFzMfF=w091ejF9BO{r@oNaXh8sH?C%90C#v#3c zp3G#Tr#H1EiWU~N6-h+}q5pPX8yxOGtwDvP4Ezk*$*I%f!y!-&7Zh^yJ41Hc+Hy#Q z49F)r(ULD2q^Ta&lS@;yFmUfbP1T*XPFJ1VQ-?#%Y!R0d91!Ot;aWG=BoAH=Jyz?2 zXzwbBEhTx5UE7uONnmdTd zMZaD=Q<^C+k(SDGs<>LJjSZGYn$OJ}8XrJD{SN0H{(M6`(0eD-o@hE^ zNyGk#d~*?xT+uHr%*N!h_g)dbIVwg|0ekQK;uK3M0SG_Gb;C-P-`kR(ACUMumjUk8 zVnATDYXP(sgx9U{4{mm;B8T0opg>Q4R5hDqNi?xkQ2~wtjEwe<;ELje^;mn3287-m z(BqPoizQeSo52<$qRRxhVY}`{62X9^;HPoNqbzBml$Fx5?Qn<_&^WH!=}M)M3Oo}_ zV}^dsKSBfDheZ#KoG}c}ept)H{c-?b%b3HUIasK;W#lwu5A$Y*Y@C_n^h6+IJRP@+ zK!}2e2Pa^@0Wb8{Kn-iH@S#fRa>NX|POv$9W?ff9-~tPT>fL ztFt&l4O~&(efMe66xc3>BX=Hd`JA){W4Y&v4G>I(&?s*biDyf>gmG;-Ry*5W6T{4_g+FD5|Z96V)6fIKuX1GE;Plp*Y8_UEBj9E_&9rN%Q|NNQffT4^Z8vD9pLd$K<)))82U(KXXm_PJqiQ( zND>`@A&aUoQ7Qiz-dS(BD=X3G4IotV&nqfdSeZ~FrL=NeU)v1Z&FamT4YvKZW59%L zO*S}!SXD9SQf6TY*M{zl)43HEXQQ5GLREZ#bpaeEM8zkHiUmLQWkQ2CI$LG4MTn4a z9WSYEQdyh2LB)Gmg6*PSQhR~O){C3q#6m~h38hI9`$7ZV0IcemqCgA1sogpQ3kqqW zizvE=ULkU$!9o%VABCNmKqbPIj2r|x6R;23iwFGTA3LFpLo9;EiN9ui ztprMEf39>QTmZ33wCX^QY-vuyJj`{-N+u5K{QaNUHGSd*z1iBAI{|*4e79}k6<5fm z06~d42!eSz$rkKGJzXlK-KCy%s8;CjuJ!Z}jTDBvM|y^bCJU3?lRc9{uDjH`oVkwF zD_txS&iJd8D%%ich;6k0eC2%GRR1hxmTkU&sj}2|mEWoO39aw|%yWu-94R3#MlHy> zXKig1h@=cmz+^_}Yp}Uk><*{X=0mnZ#Kj{o%$~0Lc0~v!Xm9hlX|GT5L*)ccC?=TT zV{j2yR5jlpLe29K>ZM!qQBDs8Gh`1$13c-b%szoC> zP^6;nFl3|VZ^Sjo!o~@xQjD!1FCDHz<8~(!Fn@-_d)S&ChG5VV36JRngwPoYcZS9e zojv699+{vULLhknOq3WYe?eUx!_`$9&y)X+lj$;6HRzD za)&f1Acccvrzs!@QaEs=-KHx#zC=W^xCI2^H3-7%0k+_U_W+DXCNpFAXRrF*r$vzg z8Vi2)r^doq@6TV%UixhIwPJJ7mwg3uwc*Z5OE*{^yzw>1imjEo&3Aho9U6 z>Y*7s64c`rcj={AjlwKo6-zy(-T|ye8lVoa46xTZsy#Jc&EqB5*h3qH_HxV^;wj&s zi6QHk;0rQGm}zr4yWA?Kbe+7QY3iOCv1|>W|P2? z;3qDkmJ1?Y)N+JPfI1U41i`@t<$`At+6HaECc(*Y&#nt{%x90TnL2b=lj}{Fguw0# zbS)vEYW#sDF`vxX<3zJ9q0hocTaLD%!O50TSE5*Bd!zCb5~X+u{5hROmGvqo&hDK- zq%Sp7W(xvB$yC=ZCUAk)O89iRmXRxJMe;bnIOg7sccAPAcQT9S+wbeB)`K2X&PJhfI^Uh*s^YDYtsr*u32^u}JbjJlq%Uo*)@PzR(?L z$YE?G+Tf%2+C$uK@*WaXf#y*StjYsYSIe|=hdh_fHO;ktVv>o7Osd&pGFeQL1%;L2 zw~#<#QVm$PWU>I)Issb~j=~Deuy8Sx&1zy0g_w1Z7}hOFtph?5RL34Mq+4v3^K`8Z zX3RZomyWtvwuB&^*NC7~TE2GaFewXQm^mw(m5WE*L!Zk=By~a(3hlN#a#Y1lR3r%@ z^vu|S6OyF_QBuU@!2%H?l~J*{Da7h{>qc^Ta$z%idl2j^24>Zv+AKDCU)OQO5gq68 z99;5bTw}6uI|v8~Wb?_6Fc~;Nce%f$`}6?1#eto#ea(_hL(iGcVt?&?MqD6`$qu{v z>LnZ4wo~n$zobz@#V&a}I2N3_c6h*v_UleW-i~0y)e#m+Q>~Wn<;`J3FfFs@+psd_ zBd=5gT!%Uh$E~QIc|t}XGemS~vWoJ9uy~bd><8G?6HLaMBx@zsSQVoU2LHWw>~Z(+ z>0UaDQRv4@zd?jIvX$gS+2lG<5hy}@77E02*`(zgY zP;@KxWOHRT5?;Wu*3ZmIf2sIw(}+`lkRzvFX_mHjNKecf_0&_R%ome2W=*zL459zb z!Z1A}OBp7*6jMepdq8Do)6=q&!c5?l0v?E%Oq}whdf!}#Y& zM9AA3b}QltTFv7&{_y@r8mZH<^ylhDj6oe1@VW~k8Z5<|p}8%WM8pb$iKlo=D?Ygiy?20UrGmlD+=KiB_$7?!LC?pvK?9oZ%Czt3*Xwr(^P^QY-A?v&O* zuQmx6!f733=g0HFa+elMp(u)&qzW_DL;stt2Sxae3vggZ3M_Si{E>8t_z`P0tIx3t zA<3R+*CS9nbK>}k;uka$&GO^ykIDg@GXp7p z1_Z-ZqV5FBj@i?WH-xS0s777Y#F`M?B*CQ|{6}CeWH`7HjXmP{ooqFNR%Wz|VR_MB zR?Z{Mj~gyy$bZ3ayoCcM@M^4Nf4uFBf8ZxWgm;eWIwHs9vxO3&M(nNkve+$UVSA*k z)LvEwlas$DT30r*ti|3^HqYK#Hlyz?_SL2L1n!MIX7`s6Y(&}--~?nppw=Vd$4hpH zpDlSQ{AS6Y{2!O7Ljnwe=f@!gK;5G1JpPDGKrsw%q&3)NjCPYY&X>M>Ftz$Y5Q8-*q>S zukXx!_8B2ChY@#gggWz&V4zQ{fFc+T< z03!ewIzJ`ZDoi76&H-;k@~gm?r21KV=WTm#_>vLT^FO$lRSv!Bx)pibLzf=B`KHI4 zT$W(LbFtt>FI_gRVnOTN2h({sOc?gWsT z*!t)vSU7)p%}>Ay5Dxr);JXIu0i@MULLe0)ApGYZzeFj7>kEsJ%A(TUzp?_E*IWpH zFGglVA_OB=g7tp1WAToQwk^`L-~Hyf`C`?C+m=81@UrDk!d>ED>l@d9x8icR&yvOTbaXeR_W=@ z{OQd=9MOiw3R^PLXWn@0Wez+dju-g~T6n&K;T9W<#|C=`2giHI2WNO^1n(8^mF}@W zbb`lZoSB%QfE5~qIkX{YbK5r7#gw82T13mGlGvvgpbL{ zn7`;vGmD!W;2`gyFPTy69$U^{&HbWPFXeDF@~|D7hzd6!Y#UyM;bY)en;N7Pk)g8_u?;ae(Iz6w(xaR zZhHKomGjoIRl#T8WO+<`l8M)EdmuXhk{AE{&H=1%qA(0&_9ZcI(031fn~Jv4J*uEC;3OxA583PQ$BEC@IXfRK9J?VujV z`)~LxMdN$@92y<>QcuzIh+p{B++~(&h#KKNmCs3z^Jz2k1`$E>VdKk^nXf+PaDG+O z88fYA5#nRIXBSO6_*Os%fb;87=)-uOo@eCQkgUddosN&eoa2!$xp^iHnEldqZ!eqo z)(tc6C~xmfJh^Q7!&|Sq;(^uouRXbC6O(QkH%N5AH_`L@t1rC#!Rs&4n2iP(&Br|R zW6Z|u!MG6fLkDV6S}YT+v!(gUWtQ1i74Q+|4&yy>SU-u`5hh_)mx@LM|b|oc3U_DL}}o6o@%DxHcn#$R$T( znpxNw{>Sjk9>5(p6;Ei^{6HM+&Y)7#(Az@E~X#6Aa0JFu}NQD2>#aJh3G+rt>fi z(-0XslFuPqVEvg~8ie}JMMg?lf>KG5$Ed<*tb2+XCVZb6smC$9SQ4l|7Ex*XzFyz# z{SrA(eILEe9PHE)ZRe_)Ydb#>$JquzL4rDZtn2nWWKgs^!N^ILVmu*}< zcHbNv+Maj3v-6c!+pa@+7-Un_G|lNb~R!zv2PFW56fZdkCI5dDo?db zHfKy@elg?o%92UYHX+AamsgjADH#Ecw}UNFC-xh_B~v{Ui&t$BSXifN64vdQCOPG{ zge$fvX@?`dxFp3V4qv)_MEST5$!NUsIs9RG<42ykK-dxrKgae7N#O+3xFCLd7QkPH zvg<&e1-g3_;0me2&~uI=c#*qH`w)X{F`HCKNG_N{1-Ho=W$;qrNkTDC7L)Q&N%4AE zl3-9Fdy1d3f$ZG0$s4(0`MJ}g11ioN^5&b;J!==uuNpSVbDuVB#zkvS&B2T~Cp%91 z3NwP@r!UiISgne$mo?=(*E-Z^vgD!6oHgz1Rak57?;B+u=9_4qY@KWUQTvzQ(WkIi z@!5rE7oS_aq1WbK=Kd(d)X-~~by#v}>G{d?OIyt|lQT3#JEgLN6Yj5#(%*OO%|g1vy)zR1iER(^m#tqi<1ah#Xr(vLB=GW)~L|MS(|k6d&0)~Bw#V(a9{xKzcgDK*>Iu=NM(QA|NQGOzWgF-Wj7+Ei()o>3>swsgzpEoL~08cuTyfhG*sGWm-(SO zsA)kJP^V9VMa3CY%svF3q%3-6|Eewv+izh3^sqP~00sttsf2HRG(i9qe672w;}C*} zPPD)Yj30#uCQTKKkA?)_`kvGev=Cs!-=BbQB^qP7i7QyuziNBnSU_AD*c{j%=nBXI z(Fde}CbtXsa174_-2EVA5F`dhlo#CqHS{2#rG{7ucX%A_b{_lDkOz?{2)_d~7C$bG z^$*7|_GlCYgDGFPgx}rX^3bn4FAyKN@v8CbuIYRhbMht( z6h4B~XBOVjr(62d6Es>jSTTlQN%wH&jU1xwtr5c$A2o>$aV#s8;R$|LJ z8$L5Q8ybdf6OB`ZY#<15torlbg9|;kZRWCzlBz|E#NtI69*d4%xv8V0L;m}lZ=Uqa z>60ITt#>_$?3#7_nLWbW`cNQ3%0RhNS*<8RRZ+|`;<6R5!0c8LP&cv{TFvx?R+BmA zc5VPi2hxp9P$^B@U}bS@gSF8rLCg42uOUjX8m_xsQLu8I(hBJX+6RIVu~q3gkfaN= zU=4eHPbKMrdS*43Q=l6FLnEWjBB5an=>&Kx!vV-J)l^pA=u!ctAiTw)x}0g%g*>1Z zhdGKs6`}}A7>TIq8k+Ci&S}P!U)_cjj>{zCYq*LB&YqK$_b#m-GP*biw-P*Mgx<}XkaQI(YcGy z1nF{3^q3M}jvyav_Y@PNe5?a|54;y}AjuEtD{;gm14TB~ScYRLOueWDrT&Jd|k|m)Igv`peqHioI3Snf@=pH z0x(B5Kmf9)1Th6&Q2-{@h?zq%6#e+z=Oa$ZB{BCoB@0jxG1s{|A#l}1K#B0bB!|yA zbF3+84p~_t`XE~xMS-67+<|xsUmZZDl)Vf4kdZbR!>-m#e4DfV*heFL(6Ukz5iv+^ zrO-V<|AeG!mR@LcRP|CRHckx@E=4cs z&Y(a+``eN2obRiujeXyK#@?uJuwPGMxpBhXc$4y}A~#}lOp)TsLbzUcDX4frIbID0 zPgmlM-Ve!Ulfd>v%>*iVn%k3xpX2r%49I~9##kHj7;+VJ8LZnKqpOSSHMne!cL`(V zpYkpY)nbk}Lkc67Mepd3IQb0#dkyP1)=*O#GE*V@9YuQ?euY5njRvOFd-@owy(%Ri zmJeJ068tQoysex_h(R?`XbD9VFwzy~$4q__Da_1Nh{$j4V2W)>ZBB_P@G(bf12Q(q z^muOW)(AxmFddP#+eZYA_sDul?Aa|6QM)-CgII_)6rUMBr=-2*v>4W++d`=g$V<#G z7wx%RlwS_-ztP=vxhP*Hqg?UE(X6pJM}h8`Cg8n+{6+WRdI3SKEKIS30_NUkL5w3| zN+Z@QI>#7|Gv^=YxI%!>Ke|e8SdQyHE+q41gmRE#u);;DJ?x71pL1Xu7sPrV?hdxW zkemVa;Y}yEOahxB;TaM%pTwB1WL)iDsNo=x_SxJ~=CS*`7wVkqg7Ni}^bBh^HpX(z z<>)gP?guI!nYaAT__eRz|9E@hw6hofs$=r3bFZ(H(;LTLaM9#_+je&ri}zh}LEXlO zI`0&BUU5a!J-2nfPjiK2uFpX)0d|eDtI=vYWx7}^}#9@-z0L&z53 z5AeBp0*P3SnRj{$o+)q{Q}DFF1<@QMYY1Eh#z#Nl`MCf$Hpo*3@%cs@ZYbfnE?Co< ze+X`ac!5zq3iDNNa04c{MN>61!qHr5pc_%<)I7OCrl3%;Q`l{3lyfL9A6R3EZ+vjs z$1@&ia%ml9^G7UsR8HTyZRo-=71wkw5m#TjV9@Qack-z5A;1obF^YB}%;xV#1ryLK zOw&jBB!g$`5q$|A3iA&{BH;#%NP*mq@df+1e#GEf|x{ZmKZl zXh90>)1%1&)}vsxg!j<0Wf`xGw_K!LWRYoYqAz-R5rD(`QH~;oS7P#u~ zYd*~$-MjO~)jQi)-MCZqvf_2ivw!J)FaE+-mbG;qg`@CVtYc2CrWLFc@_SOymRsvCN?D0x?o*&RB%+ZS)FQ|7MvEHr_Q&v zx)ucINB1ZG?E5(MapceWhkb|h4<))1fkHXs%J{40Iv4!$TvJ@1S^u7wby?jGfIkGC zn*xB&1xL8(pvGL9uFZfwT~6>JOz`1^-1a$gZlbR>K9G1%d_0$#l*W=vb~J=&9MKD@ zv$dtnTPaq0QiAZG5%X@KoO9zGP|l&^9-#aL=f)gUH-K{P!3q`$QfA>efO2-G8=t|5 z0hIq7CWlr;^O2@wH%jj9W~y-Oq%7DdR)TbJB>!?<=*EZYZl8P8!FkI*y=uz(KJG`B zU-87FOPB1(wkp55W!$*6U3YECo?LToUFS*Zp*LQ7?d{iIeU}it5!qJh5XR6Y#8`iQ zomI?;WubxMXmN$j)ZlLjj}C9h-<+>hd8?ug`9r)zq5!<3GrcpTGxFQ=-!i@J`P}rS z?W>ThR4lM%5RX%B8z~O6O%Yqg_iZ1B{ucN${CV`0=tLeyUjzuN!{h@ZCpdzRN~F_t z9dt66Q+LjAwmIc|4n!cKCBXw6hyWAF;j2y#L^wGRfumSRX(*imTKR}oa5;p3y@5K~ zxzzo?@zo-lW`v_+%P|NupI~N=mz%?R`9DP;{sXq!d7RX+pA8Ih*CP)%$H6&X1i0ZR zsA{jWJ16`m`|V|azV^3^9_&m$dBu`Pwk=<_1qOU|;8@m&nKx%|cx2s=gQch5c;m(2 zz4gxTXoXvap?Mjj;uc=f2bO!8OJ;>~l{{D;FVB&e$|j3jwWt=m*KM&2sCHoGQ$o-z zB^!_%q#)sCUa`Raf7k4LWWDco_ZgZ!obmZObcRI1X*d^wWC;0VJ;S>#2b}F-F{y_j z(QCWARdiJ_Ei_G?W|^i|c;tn+O1>>cTjVkbFG7nSxe znxZvZXQgMAEG=A$z=dCGzqZ|8a%ZoNeIL>uvu!DUsH8pp+jIaXY(o+)=x!8tH;TF& z{5!-#_;;wmze5fF9ctu3+0Z@twNupMlueT(iL_s~_Q{Ko5vU;Ci#k6ZZU{GqF9>f7 zzZo_;!}0KC;ZMVIJiIWbcFk2uE#3H@K0p(a9YaBlDMPc0=s;Z#V%Q;@l?a8FAIcq4TDlS5p|v^J+zvgRY)7Wz(c5 zX`U8!eJ7SFcO#E2vUO;n!NN4*97~1$Re--iTEHnZALnQ{pN#a)HejkOo|&CRQiH9zT-|2I70duKk_}NG#nww z(vZn$?MI78pWy>Tsxx+3S+Uvx>Yl`GqK?eb@+od`b4!wVl5l z(^?PvBteZ1bt(H<}N0@0Se+erdN7=RT(cUQoR8i^9HQ2tGLlkLS-No z3X(bz;krtYYbikwF>T=PIcJj~*HSoa&-Ig_k9q;`b7*joE1YiLm|FD8kzau{iUpYAJ7m-~KyVFiy>6EMqiim8B z3U<|PK!C`@WVpNLteVK=2T%cy10)e~NKk6H`t9jk8eP^7tNYS%z$sf?pApDg~-+RSs`My%T{RUBEpZhi4{+QKKR?&_;kZ(lIX1QXmLFDk_T23IRJ9z_;plNC8TRF6wQ zu~BnOjau`d!KTb*YQ|9|RGaJ6fsP^4aFcExqmH%?b`E!s@=SG}=b4Yp_7{6rn65N0 zRri|qId^;hWjbjovARoy5__?u#98bq_YDwgJeRAh)w`rSZI808;#MmhWrW?PeU9G) z?|$EML_XsD!gJj8qa|kL@ufDtb@8o(Z=HPW$&qbTb2w#>;8x85#GNSzsc{aoWM{S% zto-ljHN>UtpuRF{Fgx>kQKr_N)-vw%<@2;@?n~TPyKix8ZcPR)(r_39Lt^cj;WFh& z++hUi!B-RijMX38s1Cy(h0&N5czmnSQ8X7KZufMJM)ZsaGRsJPj^=bEUUZw0YRB#I zWMBb=F~)&$PT3tkWZqB#?qoC-j^!%F*5qaivICnvvg&l(9Cm(t9`JF>4o6eRg9u%R zp!rU?>}&=SQMK76`yTcvA`cohcA0h^`I(CobPKB2T;{$GX{G6%)upf*94AJK4)*9S zcEWoCiz3{c!(&j)F9f*;|7nu7g#L3}O>Wjf*2moYFT!ffh+m)=xkJ-y^!E7p$sGu_ zNQloNg*L;>(RHvx=<7@%PT>&uKj$G);MEl^JLry*&w!^-Aujq;?(J zVNMuFJvd4!JNMFsc0&}zwZW|p?lkwMEAA8qh?J}wztnSael9H4lhCd%{1Y-49J5oGCXTY67fAeuE!hX!97y3#71YI-S=37 zT>04EP1R@Z-j?ln_Oa4;!C>w^?0!|ewDYdl-Vo=U{6M^V*QqzbX`EPx{sB(oVjtz! zA-|JZP00HMX9YVb(#a)qXF1Zw5KU5w;pj6?4|BqWoJ=5kQ@D1D^A7nA6=^1&`<4Bs z{pQ!47N;JljYwXL-yU&QvpVbbY@Jmt_e_$T&CS-yjyu_1+FjOX#67m(TVHj&?)pG_ z+ww>Ihpx{wPxs_P{Ef%$4A~)A;CB#zLoFwdzdp?XXZHD-eRJxogo&PTkb z9}zNe@JAF4rxa|OIcN$t-O@|}FObXo*VK@8NGe8h-<8?B|FWe|tXHc2-Rx~_&Bq_q zWxo_lSoVkEeb1>pnYDHPfsJa;w&1yv@G$uXG!kL|&e2Go=5tC`DHe8mOjeUu_rTvm zwwI#lZ&TSeBpy?QpL`mN&7j2N- z*AuXZJjK>xTd}>rt-rn6aktxA;wkZt2sC?|z0LksPph}pzrwWKzQTQ_?@IqF`z`LZ zp0(baeRpYFtVgRd)=-%U{ggkeNw=Md*gIEaLMZr=bAjKFS+ z=Abo@S+L#!{<3tiH?4G+Ul=`Kv^*R|p|*>4i|F#X5^7!nU1aBEon?Mv11y3n?VT zq+Mtiu$mv&Eqpc4I5fmeIXkczDyC;em{L*D?YPcuV?g;fBY4N5J7zfA9LF3A_w@%1 z2rt^Df_5!qC>Ya-x|dzBwDDvmLfGkAnk2SC-U>O}HEO>vsy~cS6B^u30s-n>pFu_Z zj5}A-V1s)gk}8*q48S|hcrb}w$Z~*i+dW-I@2S+6cz56#>P6~G{zX&<;}KT0!hN#S z$zy_y-H~SynWqM#XOVEWGf1Bx96V4f!U`=$0;d@Z!iG$RM%YmQ%A~(Ud}zt!Y@;-* z^M%V+%wvDQT~bZAU*0+WD$Bhz&b6pQdo{fN%7m-*F~gm##Dgdjkv8U#)lro~Vw0*s zaX=_7E3?H@2`?D28@xB3cslBFr<8DAG?kX>l&8yz>(Wn`m0f_Gk)qI=S!hHT!SfDQ zMF1oCPhNQFG}7#N**C+wM7_fndCwL-$m3kozY@AM9PE&L-6(oO3LG5*o*|+hckP%9 z5eshVH)23~;(++vAy&_%mP=>K>Yxka11{>NpC1+z7mg8UiH*0gvDN3#Im@NpH~JUZ zABWCg+Plwh-hDAOr2l=c;Klc|xwkaI+|7jN;1|=3rL_iZJRpkQH9>_0 z;HL*~R>2{>--ee--us`jI)WuT8zB*6JR9si`G?VL0Por2$ z8;HKO*S#o{O80QON71!E>rwJ)A4>R%laYkO zZi}Gj!@)&HqJJuzfLgGWgy!r)48}&tE?>DX}tjhC@9r#v#|Jb}5p{vWtif{Uhm==mK_-0`pI~(;KDt18$ zmBhe4F^M6WwF(|Zh6=Gua0Zw-2wIfp(}BqNY_mq7bDOKHd#-i7=UN{kj>0U2bwsIk zK`OBcb2GSTzF0~QN{gzi@%zG@>{QArj&qRj1mFIM{R$kaKnEt)H_^ATuT@tgx@o=L7RKwTySQbdn-Gi%@ay=RPl1MgU(}4vD}GjdZ?$Dl{)Bb z=U#dq`gJ6Rpeyi9bf%NI0wp*%3-7W=5l%mP2P2y#cc|sY$vnb@4n@17;$_ioQL!<~ z_?ru&8<3Di-jltOUp;(AZ_y7>h#P-Ko<)uKaYe3=e}_KqW%O}j_dRuYa2%PE(ZSDb zOR$7Qz1zZj*T~GluQDKam78&uFk-El;E&l*Rag{b-51Lkz00H0lmmFaAw~}g|3L3X zb%$6!uwkG$FosSQ*}%PGfzd6C`2GI;tii&MxwAIaep@Tn#xy#sw&$#t|9I9r0@At) z{q?lCsg5P;`qnM1Ypatt)NQWYUU#VOSe;U*_o=87>duPA28rzKo~x10Kx1Rv#fv@n zzK&n7SchLgy{>7d2@C7n>W|e+^|6a^JCfMYbA^_lJpJQ6S9q6SVSt`5j)V=(G+`va z%t$>PsTxV(&UGW#j}%9u_U}QAr^tq%aY4}d>3cfbbHxvZkMWH8MB&as@j>FCm_g%% zdQJtI<5`-rmr=A0&ZA@&pmO0w!6(%0VE8fkKKOiy-;0&UL|2S`8|$Kd-`I6ADFy-h zuH8hru^inKn9h5f#})9A9g!PZq;KIPdnkDBFD;Z9KI}xD`KN@eDKLOvAr` z;yeLnqi`?)!*Zk;WK*d7%x7H57|BAMfA1Mr8vLrjIftU-3W|=isn`zS$w&CyR?fTt zMzrf&+{xTC&VT0}K?vv?pfF@)8N`^@a{`S&@=u6$3O%)P-|Jo%gg6RVF*QMVuENTU z2xZaQb5f3ixgU>06g-ZP^1G141fjYeD{#8|yWM;vSjep48+(Nk$cqI%-c2=m$6y5`CM&YM?n`G3s`>d@gZVrH)o|v>sV2%6!g<3u zJ$m|dgKB<${yV}U{AvQ~MvPd%rWg}qals6FN%WiwGVi%x>Nn$l*YPvUbc7-2>wy53 zT*g@2kz-&&zI-Vsn$skYfj)f=>OhYocfd1{5R68?XI6HPd^F!0pcP|%n1$Vi#)@(J8q|Bn{jTHJ$boHVSBeZs9ZSF^0sgXPvwW!u36?ED@Q|_L zQY-S?$T9+2E|qj~1F|!mZCeO&g^Ofd(}R?2?8$$M>j(9`qzP$(01DiY$ssXPDk}CK z61}bOV7F&4#m_&tncb0{xA`QNEm3Hbwu(v#C0zL?mbwaAlQ zbDeWTbCXv%m&BIk-CX)u@^f~?c_jLM;)mq-h3*mIQF$X1bHj7<=9Za8Sw<&Xo%0hb zoR0_(yB{lktn71#HZ*^ZGCN<&Q{%8o!6NH)g_5XW6An8tNf?s=l15RzAYv~|#^FzC zgT1L3c^S|sGfVM&K}wpUp~7&)j{kea=?Fy#!$~iUB*h+kxHw`qIW&7D96<8%$MpfI zcM}Q=$;!f5z#KySoD|dG=V>Z3M|u?(d4LupFB=EdJ=}gC_cQ7cNZtC(Kx7pL+k(n1UL=2Oa=8%~>8)Hyo3;`5T z>ToLCh5&YGQxruB-4(itnQJ6|A6v@?W)FMEU(h&c{M;wc8nwJ`+U$z5O!STX^70W| z1`nOF+Wpc!NzXl3Z{PKIAa5JzUiM3=^jE!lO*$|;5H20?aB)ag8cb?M=Beu6t~;yY zR|_xhcW_zD?>eGa+_HZ5WtgGkvg2ew#$_TKhT4>-6x5X$OZDavgU@NGt1T~1d2E^u?qD%_HH#I)KiRAIj>n*`6~oi0K6-Y> zJiX%V`qD;d8j*7gru)x!vU*{_(9%XgX5rC`9yJDq$8Pb0xje@quXj&DTcqLfv^2EA ze-2`k-*B)7sy}J2#p#sc%)s*+p4rLVoq^IC!Zn~fyJ4E~LBR+W(~O|6tlt&8vUSdq zqO-GK{c72$D_V!w{r=%+|Kxwx-`YHFQPF@O@2eR;cx2harp8&%EqMNrSUGBBRrQlM z4<0wPPoD=?4~zVwb?&gr%;?9bUcC0)8NZGXSu&{Yxt))BubeTnzN*)dyJqyRZyUX+ zsZaS?YnvwDH~x8cI6b>Bs@u;yzki=;0~%^;FKDE7W&t}W&XryRUyl>gFkW|9Os`Xf zo+vD{O+qIT|3*E#pK|U68|Sue+}JvIqxgr`U;U~TZMqhNr{#EXXD8}N+8eb-Yonvl ziFC`%xsQD%FxILk%@#+YY8LFaLe09^&3-V-)jC~j#4U$i?N`#EAhihi7={Bd0xw7c zh~_AHY=Qb03CwNuH)VpMe{AEk@Bib7xMIWOpW^5J+NV#w@Yz#8Ofx<7!!)|5yOE=G z3+S;wyG37R?H%piFkqNA%stfGIAB_zc}4U3EF54Rsisq@61OW=T%2-wd_8-YCm0Gx zl8JbJo+VlUev(cV6{2Pxl5_bS{>=Yj@4dsLD)aZ@^E~IwoaucsHPezzdLac!2;?9| zIw(aEBPc~FN>Q)_Dk6f4Aoc=SS<9*fFrY3LL`6||b=_SXtY1`g#j?wyNM?BN&vPar zvVQmXzSs3$*Za>K$jmd7nNyzfc|P^ND=MpO;FvR+%D7zD!&qaimMSZXi_+0ZJ|JtY zmO3c%wNV2~@PpQ#lBGIode~o9i0z?Lv-u-$Lgk7^8&ZWRJf@@(Fb$K#P^1D${we-> z{-u5eyKCQVQUe%Ji{PX#+IH9WYDew}<=`F`DYuk3O@N){ z=tA(UnKGt5Iu3l8^}clD2_83;98mWTyjx`hA3^p)VI*B`7|z zy0B6pzB;)m{qDObzIW|Yy9>__=J}_ssMPjuSp0|Tduyll8Zjr~pY&*PN#y**g_CBl zkiUBFwRul1sGGB~C76gO`cLdRa^|YtH_RH+I^=@Ey-ULV7Bn_C7ms=7%v8V0%RcEy zqKFVqF~dR35vLTFdP*9*PV0G(XI8jwYql>J(3{ld7t#dyY;pXJT$*N#c8i`PK#Tfz2i> z2n){JEXjT7DLt-w2R~1$VtLyXFixWk_eH!+uwjx-it_W?l<+ACD4e&|7V59BDFEmI z42qT%O$P$q>f~TUxPY8>m@Je}goT&sLMW!$07$O+G#waLAE^byn)?B%wy1B~Q{+f< z?5KHZOOY`hF6vj%r-A{zIVr^%$jAa_v_dLc%|$I0%xiZgS-y-1zcrYYA_hF@d14}O z3=^aChvo-uaow=ti488$NsC!q=pmX+sI63Di9HaKG!Q7D*+S^XLNt>vkstX3o3-cl z?A^O|W$%9DEjH^9>$C4a{urxx=pk0|=DYqNme>HpiYp-VSdi`~F!K<&a*{@#xQ1*`xKa~CRV~?@&haP6t4;}kjuBe>X zGI5#76RMfNe(9a*X!bGo=D^;CjZye*yU(d6R;MM_VMg5>zBl$L=FTSj_L>hcvp&Ym z`g7ffJstB*iFW=(Tk?iN%$+CNYC!Y-Jf9+!BN%+1<{DiHV2!zjOA5a)R0`LbYB92! zRf4&6yj(6{C;fVU(B#`(^*)YwUR!d7(m)fVm{04P7|pqf(dR!V#)&yWx(I#&xdCMa z=7Y#|8duk=sEow{-FVW-*OfKIrCvpN_^siuFR6{Qp6T9k>9^*9KI;ED2QUf#Pcy(P zl%7sZ;Vun_Hs}B2*pIt1_Ufu{iJ6H>m&JS*_(h+Y}jmg1eU{jnnQYo zC*&G=iY&_^|KGN=DxeBrgKj>YIeY{{{>YIdxiT36CVf{@k0yKarn~@U+%&)D$75kg6k&Vn8M)(RyUv#O&C3+U}NOrUcJ&EwQHZVKj%WVs+ZYh#mj-!?E$|q z;A)`-IJnhrb}*aEJ8BtYOgfSP$CRL8K;vX~m%c8_VMz?}v_IQ2O~O3ZaKq5Qo5}le8wl8&s}} z%m!HX^bhKic!FT>_Bs~=bmo4jcbQz^#bgk_buuOee%bf0tavs1C7X6dHpPo~Eq|4T zv-e%jK4lxT1K5k3n12&7#cs;}V-t-7Lm=~3q46R6Uvsjc9eAe>f-wbrF3O~S6jV!S z9MJ@D4Dz_4qWCb0yiOR^nDsGW?t)7Xo7-briOC4C!zHHGfHgEpvX`*^K`CjoI)Qx% zB1RjSn#ekbM@j6y zN=w)e?9(ZrH4H)Z3}TZctUSt{&izn_qI=QdIt(G{rr0W7U(%=OO`$^6Mhx(EE7u)<1Z_1nK*wcGnRLB^v~>hgN50FHAM2*_sOjDDfU=)A|J~M z1z_y)*9?aYKS&WoWop<%+R{=uJ&K&N3xR@^+}qg{8I&GcJgDS!^V!MM)8ndUInSZ-4K)(m6Al%e^95<`lIS5A^9$rGdF6BCn@icc>+ zt8zA*$*-tc#jh_~Rs5j&FbgWO)$0Sbs{&rCO5}l8B4v%DWPQl#?@XBRC>NJtUUMm$ z#x!PSCFvq1KU!R)q^eJ}E8>8^sX?g;K0(CWn?rI1Jz32_FSKsqmDOpH_MA(e{!ap$ zUof1)tE|^HQ1UcY)!?mgqL$UViI3UEdT4=E+Amld{34e+0Tf(7+3U2M5Ftd+jg)zv zCXW*4$sg5{Azc@v2G>YVM$(h&a$vBVb5BrGuv8EyC!g+T+kA~t085r29c8NrO^*m~ zPbB9gkUdzh0BIvSr41AkwOE8UiOM!l7~m3R{stKEwy{eAl1lk})6{1s#7eehpWD82 z-h_+s>bz67utBdce^WW<=E)ytKhJa3$<3M2$o}J}e#D}N`WMFSUOHv*eSgnx*isxD z|H8P}ZhwE>=j_~Vr|uiplZZerIcvaq{F9ECT0%)y&+^{GJi3Q1GsF}h7(pn)_KtQ+ zVW=ovlY^A-uY$LcJ_kiE+|usi83`@S6Su@)jj}MAHk05Y9@L62owc2bk4%i-A^KK8Y@I7 z6t(5mv6LqdoPO!@yvjI8KNE3Q?LjMML94=F7H3IgL7Y{2YvNMelpohsMqOKgAwfz) zPvPHy9tejb+179?!U7A5c-^$d(}$coo}}O?NmBBZy|AI3(kQLU%uTX%5kD$lSGT69DMUwN2{7GbP zo`ny|{H)DfGwxu3;$&mAu=E6bBBAifa4W z{xjF1Be-ZG1+k9wfH?Cr=2vmSBjvX`vNGp%t^Aiw?4B*z*Rn6S{rK2PSGrOQF6FD0 z+?6Vv$yQ7ZY?>MrpeLVW(i6rf09*V#u33XCVa#SZq3ACRxN37kRxM3(Gf2r8LRfL( zzX;p(izdS9W?VI0b0!!*6bid?Pq=>9kudF--LIap2Kq1K>Xl$egUmXP%WvgwAbV~b z0_uIXWM_1|@ffx-irp(0Vh0RMUu(SzO@O>}mU}KYE%MxGy53{D#J4>LN#6g|demo;G z(b4E)^ZJL*pdp2)M3zSQGm)1f{JqG2q#rnu7;UG#EpZw&bYe)+pesOwP!vStXK_Bf z^Sw||(DHWVg@j*h6OE5t%G5vqila@MEF|MgC=Decj;Jv06>j=FRmBM~qoqPxw5G z$HYpLp<$V<;l*sff3F#L=BmT&HLTj+;KJPtZ%ITdmgZ=qFXfB;m&KO*6##}8Svi4_f+`N(b5U zMA|*GcA1mGSDzr?Ma2a^n+szs7bcB~$wMTg0wD{6DwN7&v_V!rPPu&G)YuT{rr#H)Z!{ zTRz6*Q{pAS_u{rW|{zm z{<>$Or3f32oH7voVjpP!l9Ww6klNmrrb!LjNYN)=tTsjpCS=tr<odZA0G^H3l)nAJl zRcNaD z_+oa#3+t8Q2Rbg5Z=_#3+wnqPqn;{NNRMc~I#VGK-Rw?tprS0#r`QTzrP$E!0&x4+ zoAXQ4?fgM4QCL`DsRGW5`S*e1P_g%kQc#;qi&CLPW!2lsdm$&wt4HB_4#Si_e7KXS zW26f&Go66|ou5PKE``M<;i%ig4Ux1A${21ej+WLkx4~O0m4wr^l84HBp*uoX5jBz5 zc)ie6X!;62r-;+Q^9gD=n66z)i>|R0^Ech*(#Yh>+Tjhw1*HMEJ76wynNIIHrv8+= z;*utxJI`DsZ{gm%r}ytaprpF7(3f9Oc7Aro@d25ivVXf^z`%yep71D^je-+_OV#`v z{tm{z0NURwxDaC2bYYn_?Ws&AdF2j%6}J8OwvfNLC66K3tR0trmDUhqjwOZpg$HYn z#(JlYCXy^U^VT}HwC<%kKBaD69oOo{0D{1OkiJw52j|S%d&xLG0xD$8VUkG*aUH_M zL0JaEU2q~{XCZ@C7f6&3h-^@ytD#?d;lEhN6uP32mfx@Xbhu@RtWLaTUU9>Fu^!@*Kv& zH3j{fQxh-k+wamJ`Yx|6VHJ)%h}Cpy)2K!mqg<-w2l$I(l?S8&ZPg*>c@Z6Bl#DDc z+0Y+h$>@`qzf_+2eF$;;r6_cEmYQb!@d<5&H1z`#oA|>Rz(#M%}(Et%$=_8wF z3)ei?zIsjjb8AkUI(_t*Y10kwzwyk|Z|r({%Ny4(xMuOfh1Xqi39Y3i;D>nCunz{` zM6IaN*%%%q4|5I+4=$R>Cb(y^8Sbmt72!*YR)&_Poqaf~BKP4Ct<)@+=k>|sM=>Z( z-X>3Zai3y-WAV{qUffjHBuSo_&tFW}&Y@mpSkSi0tX11${o?axIZxV6>%*VDQ2%oir8RA;m4xJAhi2xP#@}@F12W z9TAqp{MI6Pj0t_Qur3kE0~r;pgd&L3p2+uwgISmjZl5PW6848Vjc1&*o>lK+W42s3 z=ZuCaY)J<5{KWG+tp) zOSGC)ebETR0LLjs1BXmfCO9TI#}>_0&v#6BPAj<7bxHaLm#47(`0;H-=;4X>rAl^E za?p55tD<^7sjsUq@7p&pxM%d%str}Vs;agrdV3(6Xo?mWC)B}Fb8S=tqy_-gfWQfQ z1hchgk*BV2QB^Ok%0kDgqG5`V22IBZ;0@_KI2R*iJ%8VIPo?SBG&QT#>e#o_WdfCYF{)IP=s?FC1 z54}H|z1mxL>$PVrn$4mQtle-pRqRexk2v+*1>@`CN0hEP{w((4^Ce`MNag$$?RZf3 z8&UwTEeZ{m#)YPZO#Tpy0DPE_FG&Kk!)HJ_iaYA@rv}SI?ITG zXPVD;pOaphQm&U)+E=<(MwGAFH{oBTU%0X-`H}RI{Ew8fN7}=WD)M^wJ;}%ACz8rl zk;{{pr=BQKW+i79fU41@%yG{MUzlDfDabiW4dTO`N;*^-u1Gb8l}Dsq;lJ@Ooytht zfY8v`;9}*9)S`lQuG>?}H1mc23u70gR;3IcIaQ$bLKY5}!bz7C*~iYS9h~5^k_F+E zQWEEt@D|G@sD*wnU==6?8b0wiN;YsH717C-N(ba{g~S z%lS#87d|T8P{3z&(*cbf4!tU%o(W0&d-VrZQNxwwE%*5A=~-*AyXtSP+)(*Lr7Tq@ zDwkI7uT(1Ig+7T+>EHVA8bfx72fIwq?|LtG3!q@>fd-ubeP=+V$BFZk|8p zhEs1IIPk)itdiNwo*n%5o;#+qZ!+6k-hO*TV;RKb1KF|4XxOH*l#*6xy>5!LtKv7s z`0V&qF+RmLJH}gMt#Lj)cDjp?@C?uAO`d@+9?!Sh6vbEU_bcwwpfg2QzLrEOY_n|i zo#UUACRiPINFkhrKTD+AJ;7(;S}#J`3)`O7|c& z8Jp!Ml~o@ggERAGHA?lKjf%e);P0wzw7w-ZDZLHm-f|Oi%M8Y5q8oq9V!bB$w|_(3 zKGKSN%N#&y@&PD`)vnB!J!*!JJ+nfqH z^K6i8B28%l+oUupMnrh3w^8IrE&_yTKGa+ec2+5@$|2(!px~jbk|V$pMEM43qQbQX z`vM-GrpG%zhZ}7Z+lGh+lg1t2tV~l!!cw|H>!TQbV8H-P8i&OsD{2d1Xi<})A`KH- z{|JK-bRl2mnsPN<~<(A1!EB+|6A85)8+Mx%*^&4!T4d|7fn85yJW?3N%(bq+9O z7Bz|lJ>mgIqFzv#dU^vXd%67y)t4&BW|i=;>>F9v?i8l!?dr&%r^}g1+MOM5(p6U> z>#8r9zLU}x?VR(CjG4`n3dvy%Me~CaOGP6gIMa+KkGCLAQoyW}bi3u@~0Or@36mE>miiGE@LnGQT#p&|2Uq&nrx&ipndit5u0R9bnE% zIg8vp>IggCNcxGTqDA2}lK4Xnyr-cd)H6DW4>k-64USIW6GGGZ^w1*1qUdtN@@PC_ ziFhKVzDmVvv3jhfN~KbmC}`&!o-0nwODs)r=;m#kQCUQ9q1wAi4kp0bv*Ee&#Jup* zFbA?yTbqxe3W;yng32Rf@$;-7DuEKLUt3{8fs0#44Qyog1uDkL?Y15qVP}(%^x8CHR@4YP55Oa%qr^xJH*+KNWTm2J8Ck)TQ9>Z+3 z4AKG(Dd-3+jxazmK`Bxr0wUg|SyuKO8^bSQW3uzJLkzQj`AUAh zqY>A$TpA+plmCkAvP#R~xB-e+NX|C{^`f19{aoZ#P6JUoGb{*$(+^>pbBWTP0V@^aCH zl$5IB7!iggD?nAYS3IK9N?x0NnYFB2%uIJ>UuTVXaaXoCdxO1^?X5r4+`kF;@I~$( zmTIU#=H@)v1EfWj?jdNfTDoq6uGmO)UAX$(h0?QDkh_VaxQT~t#SE1$nWuNBd&*66sk;+p=#-okO~=(y#bWoDfRjh2X-HO*38*;2_TSF%bV zMeCI(s9vL)aLw_r)Sd8h1f)WCmo~;1^2H*FNTH&Hl$bSPEmYi!{hVD;IZ{{XE0`y-JY1s$)!MyaZ@~IFsCY=Jmv`qYm=a%gquKMK#8z^K;Wej zMwIZH=RP4&qYmp~{eZx-rB7&8q$3Av0%HO^0oDi}C`$XsxrfytV8q8rQzV`M=>(+B zk~B+4)0o&g0X-Tx7QrT&fnF>43JyZY7f?|@X(FUTe*l~tA}ygJ^4Q)joR`AnBz2l1 z%MhY^;y`O_x72}7mK!~D02^d3WuTMs21A`w=eo3H@`xzO|Cs$8>_$UbEdxrGES-M*pgI7)h=f!nHL&}%3)B8H ztbAbJz=GlF;bj9Whu03QKf`c_X>7sd^yIR!mFJr-a7-zjlb%yHwbFZb?YMe=dfucE zug$9~=#y?LtE=o+TU(DL-x9#L7TFu>s-w61Hu$*DCznSpby38&)FLp~MWu)f!4q;m zq+>DJTCJ66zOWXl^8u+?SU&Iw_yjWPJ|Am=eFJyH<{AxdC!NR+4L#I@#)qA*srQ6g zCf=dZL_^O6LE~Q{(1OOd_^^QSeM@*K@Xn9V(Fnf>Hx|h~taWcYU!rNrLL>O;Kt?AB zbaM1`C>O&!n6dyF3DJR!CFC42igNyaM%H2+4IGqE&y)NVG*dEw>+AXfC=|WIZk!Qf zs+*@m_fvFgQ{7@9f~c;G%!)K6N!ICh^csLPI1zMPNH{PIx}QS+(}>+y{5^YU;rDA- z?yb|_yy_F?;vGN8ZOf;wPHZXvN89obI*y%s_HEa+Z(VlA+L3Z4A8uQ}=(5M2o;nR! zy3+5Mb=k#dwqAss$@d?9dG6fsBW*L;t{vwt{^0f9d(V5xedm1-BNE!d_9%1tB+RE6 zGJzV1Ei!@qIV31Hb#)Q7({R-hW2B;7%=WBVL%OTP_LwB`y|8Ad?}@MFh&fx4phd~& zZhXgtPvR?F8Y};cpOy30{#84BJ%A|r_v-gvzE9ofX46ehn+K9vt4SoLyaG! zReR^EOVrgsN@m{PzGjEr)(kKsEfB7EEM#hLQ!`YQW?5bhy(JXvtSb;I2h1BpUnxfj zEvbdlhTw+M_aoOK3eDj^@J9*1Pg;OtWl(bJKX6OIzC-Z_4J&9?PqdluPue!jQWh1Kd3(Fb({vvnYZ{yDDJLqHB;ONW>KmIK zUFJY%G1C*!C&p+s3?0b9NXi_}W*hpe*dFMILVD^h`$8B`%@Vq-7}_mkvqW!+*q6Xz zpsvzk8ITDtzgPXe%Fj~gsK}wf zWWjwR`>2_jde3D`*lO@sQ3v={9826H=0t+#gpJDJI$;`sl0Y}t$__|0EpU?vv||cD zxf3H#x6^&J`~TJ$;|z1;uUTI)vX^M-_tpPV`LpV)D*va6-DcWo;uo8)HSzJL>42?+ z)rRrP4NpuAkGO0wuja-=492f6lb|thnfe7{6sY&5&PhtM)Z49-ullXNrF~@-Ye8Pj z`Dl^mHfO7;nMwxR`R_EdhUnu_gjbC8s!nQthOruuKY{{sKjUNAJO(VWi+Hnikx{wG z+H5wOFVYNS47VCK7!vFh!`*>pyJOarkIS13O;ukhvYJHK~eQ$Rc2a5Q1we; zFe8)-D_A((ZZPG7yQZA!k2iE5Kv$zjjhRE`510vN?ZNChbF-JT8yd4uLis=6a7(6F zrVoFOzjh}e(Y5`>VaS@HxfQYvwloAhQ(0lZsp8v)vKm`-Lzb)n?@~A-i%#z#=LIewBCN>BbQr_9lo`m5*$(INglC5?~AS1$g(4&S3n6r(_ z$or4AH5zS4597GU51^uFERI_({h@6JN5%}`&_K9?n&JIzW_LXh1I063t8Z(0j%a;l zc~zB^4kXYFg!1xYJ{1Asv0F^5i&zmFo8!(Hp0p}Q9PZy(x$KLD%yyUAs5tTyg~f_B z9Z$u8U1x>4VXdsH3iK#K1T|HC=!0h0ht0^NXsoWoc3p=RLPcU2S}bpJg^UVRGwCI=A_e? z`@JKb%fFa1=)8BD*kvQ;EHCTf^Dk$EZ#na{9n&F8&X$Jo3Sl9RAinAEKsf{Z^gGRh zWJqirkHOtVreYpvNBKg@@Ml^DAU}*w06y)b3Y~*a&?2vgVL3~kzga)_mpFLm zvFWfl?)2!c`GS6fM)2S)6I4IepCP0pt z%TW(fvS2zI!+s00Ng|Q3mLCj-qETR9{{T|}ZufkFosZXqkO?(3-$v>lUVo#NTA}Q% z&)=DUJYPnw)2)_gfL&PP@pzwi`+R;aSB$+DTOH*c5q>5bq;ZPIKZSaVcPO*9>rcq0 zC0aoX9a;{>uF{izbWIVOgr2G;_6sx*v?60d*CT~(J5t|BAg>`>gmOU|2TekuUx?VK z14&J)Lv=+Ypiv4Q!E3I`5eVv&iyY~G0t_aJDPvkcw_(GI+oq0-HdM3@eCHiD0o+~k zy{pcDU{l~O^RUYXt?HQGjmira9s2!Zz2D(}Eu&tSEv8^FAbEX0OxAKa*XJ|{ScVdH zy%q|Ac!aDk^imMn@p$a&@}TH)y#7Y35M3VJ35pas7>;!7aWf`S}q0OH<8&NVD%F8A|wA_s_R zl$&-mr-UY;Pc9wXsahZj;2r%hI0k?G|=h_Cos2 zKFSts^g`m6%bu|bT z4regQ*9e`B(TTciLQsS#T88^1#l1@pB3(@=?A?{kERnWyt|`hd3Z?x;r#BCdOJn+tjI$vF z(HeFNTD_9xajBsIMRS#KFL4|3~C`C=!-b%6FB zmG6{O|6l%O_%Gkm_{8fno3iKLf6dYjH?3W|VcqEdeG=srspfvkN`A`yOP6ju@or_R z554Q4&#t=d*PrcaG#~v*x#sn)+g{oA`i|G`npN3+?_Dj`RV^J0#CyB9zjo*B%D(s9 z-LJZ;-@5;N>o+{UAA+c27BGRFe6D-Fo1lT=<)z(Y~ZvJ)wG_ zwUNKs+5P-Fl8rdO(8x<5FrnqMInc;Y-OL%BufTPs{nDWYqxIsYFF#T5Ab0%+$M+7t z0ZGLuEo*0vtpf1K+x@~Y5p>kDlkac17mH)om*#{i|6lZUwvjdIlS7)yTS*ZZ!bN(lMl@9-u!+#P!eQ`|Pr++ha;#pE* z4*$!Q7pk8Z-xud`SqwgahH@9A<2arC?GM>*d>g1&T#6+T0N@NpUgs^~o=^V#0QRbW zHt4b-Pq5nR$K-zx)G7UJK%L5c7ieGj_QvC18B*d}5sINPWGnFPaxKDwn$1x^I>_R| z>L6bdTpi>=Kqx`y51u##!1u&zIr%6bilY>7W(+V@-8&J<(}A#+^)GLTY(xEs+c%`R zd?KMJoqU7=?0Q@W5X)E|VTCQpW9yOgs9!){=P|`X!(~gm@o-Zzy(Gwlf(A9M`Iy6BjBjuCBSb9j&k^Xf7O2*!o1bU5F z7l?%1ySGpxJ#Dq9m|cr1Qlm6f^BIh=eO&-*x!{CEEP(%;`UjLTKWBI{at zl|O8F96I@(n)?O^(}0bS!dPoSYI3%i0Bf_^+k!-mEn3J1Y)eq+F0x+Z8tJ}2ut-`G z4DC-+)d)h6M-Cj;2^JCL|MJ_8%mLxE5PEHeFAv48vcHI@eR5u{$1>?TZdbPhHd+9A;rWn11fm2C-6b+0;#@9SGiKxIvh6Z_5XQ;FJmt@0%BvUj>(>+XbPE>rE(`|YwqdAGdyC&}m<%nkfU1z;zW{iT?srCiQ}5|6 z1^Ap{aeLuF&gb)#x7Mx0cdL}G{Axox;_AcO#zO^!UZB}r$`bGmg9Jj7OwU7eP$4eX zYfg>5sC=7HLk`ee-P=D{4(sc1I5aYoA*gN|5LYvj3d!VU;#Shdb)vF@^DCWqFIjrG z^Ge6q!KaNiv|qja`o#kW^rvh80;SBm3@dT%KrKV96TFCU#=WKJflHXVq*d!W?ic%% z$M^5Y^n6fR!YzhF!k0Tia~PL-M#>{?%cMC$;aobB2^~I+38D+b&CX>aatmUFdb8QT zOlB>I>Z;2#kuBzB&XMrCZP_Y~6mR2e!6W!RG!f@JdEd?@LOwWq=&)I{h7O-Kq6H8| z{VK{^3{694%^opw*6h*MnpRnsH5oqwyzzClTbC z#nxnf#JI>alJWcCE$!EqcZP_0XDA^79`a_m?+zWNTMzWA)3I|fH+qpxW-#Td0J6`JSi`J=KKOb_}bH{Eq#BIRm+`*PI)H zCMX%34GWwKQ$B%R!4^m%)4c7VGZh|M${#(9;yW_zkSwIHGpatX!*A2&-@O0UlCR#? ztI+jIbS6EQoxm@Yf=HtUdBNYX|0e8Skp-Y<17HFKK!SUsXifO zdezAVaveMWqPPG4(qG>(1Ru{HWXLFjPf=3J4Lh)c+BCn!Op0Ar?64)din2Y1vJdrn z=75=l9@)&Sz|?YRg*G_U;UP6y6rKR-=s2fp`qThVpk+E}AMJ<>^6_@P94gl!hXCIB zWs3za7&MNEa2*-hASVtihr7UgM}W;ewF#tQ@B@{6l^E% z)hfNJ4T%f#ikIx~*^k?ebmLZ8vHt4D0ZINQvsi&DDDG7PbCkGCP1y&%VU%6)CR-_{ zO?QmOFFJc}j>c6ad|HtR4T@G1d7bbHoy!=FW15>{jS|B3?}6)llughUb>2F}>zA#a zx8MEV$#&K69I+Dp-h25~cfs}7UfXuV4Q;&NMGsuWKg;a6`2LGCrPy!JhL80hY8oD2 z(tuQHA1h(gB;ee#A9}DJc^=y6>rd>nVwV>@cmkPmg8m(89VQ8VXCA)e7vE{)a~JPHMd{FrF`Bo+}GKLdLNt4L~1 z6Z!#_iPFyjEEM<`yOJAV%vO_NhHo*`j5Z#H3eZ!HTLHjkMg&zc=0{^uZgc{}1l*^_ zP&gP4gk@t~jU-u~2MY2Yp8x=Kcl&5_vVyBI!L{&DdrRhJzD> zGI*+Vc&Nf;iP>!jczi*=R0L*Sso0XA&r+^LJ}Y#j^NB4izf&O;bvRVlS(g_8aste4 zi4;LSwL1VXLjzL1nW)6j3#eHA--a}NSotK=vfupW`07^1Uuin?l)|3%*+UiIpNmqI zW!FCb^mR+y3_E((%$PAYdu#TxO!nhfmVC+#EE+5rdRm_)=U;eM$Ad4u_0}I>+4U~u ziHK|o`$ms!-ONV9t_Tt$tjicCMA%;?d*K^;eC-uTMm@fEGg%k#8Mqnfg>Q}RkMWo@ zMdC5mCF%fNOLFG{$hr(>p;HP=8?`)F*ynV`93M%ca7>XuLe8Vfmj(rw&fF{-G>T|^ zL#*${@h(dOfrhFmh)>x6opr7sh*rMNrDw;c zk#QZXEnLTq>c)DyF;f{0q|lp-2q6&$eicdQ$+K^_o7jXojP4I0M)2TYr1IK^eJ z4-{2oy6J@FBDN#JjDtKB1_9*B&v2&$KfHo`nc3q{8haT zR8Zz+tQR8o$l7OYBj8qdU%{GK<7L@5Sko2R-3W!=&H9KYYrH)By7+VUHK;SvZ2l?x z#PBw5a}4}!sH>6jt0L`5kAYD-nk`%)06*zZPx>kz- ziz>($2EPb=5$uowxXi+#psd=1Ay0S*KNlR_@ojE?9VjT_saCpBSbPXe>NUZ7 zr38@Sls3UWY5sulIqk!bTU-# zj2ed%nR!rkdgbMe>#qCDfyJT>F}c>4DDQLXgdu0x{0>vzX~UcQ^lk~PF1`A)TdzBH zz{GJ6ti5TSywTa57aP^97U^dfvF7rk`iiE&tZ}o)^qSz!n?A60_)vHysfSleN`Y}IM;ww2g2#$-)G--M zYBU&855jr$&}ORw=Ds-j4x5lw5|30zS|V~}WN;@s5P-*037#ENDSFLXR))DC$!14! zWCx#$iIcB+{iUfUKx@yeFeo;ADe%nSf-ibtTlpFA*tm`mj2)@ecs`6+3i$*m^a}fh zx|G6Qb>FeJQTiCj zJF?fX+poCbf?L1*jXuBUO7>AUFy|g-WNP*(dOC@julIB%u&Dd6x~@`mx50Oy$S50C9x0MCBz> zHaR*s%Ed!;P4GpU{E``u<>+Ql9GLyAp}xKm*ap>o8mH9&mh;)oRduyA2Na>Xd8pZ;Q2#$4(k-$Zz~8 zc4(MxX{Y8>W5{hV$EG zU1UGlLsrvBDZizA)V|yVXmR^Phm@=L4GJO-9n=jcANMUDT-+Ppc~ch^`4Ca z&LF1~(jsZbkkF5iZ6wtQF{1f!ImBF+3f3`#J!*OZw*3TVpdXpPn>KBdr)OGuZ}_D8 zWM6yb$n8q?Q`x4cvOnH_gnTF$B1W@a4ZtEP6F!l@aR-|$RZxtotkZdt6N*x0u>*b( z5J$}`+fc^K9AL^JY9k!w6!0~EgBhQe2;x(f{w5tjrxLT#OVzB}TX6vbk=0!$jqbg9 z7N5M;NL*8TJnf_7Z^L?`xDL2pPKxWm9f|0ei0i1_+!@z7JButL!91n=nLc4-fm)W( z@>sl%y;S!@9S7=2U1f+2s@g949lG8Yu=zYI*nD(v(Uy@fRS(3uDj3qnomEuhzYBmNe>W74vYOsDBX%G6chDM~zD(t+x7;rJ^ z^6XM3&E zLUUXieEgs?59=lbpVT64(b(vi!qvrc3zQpsI#?EKwD%15j5ZYwvkwXkjtnh2%YK&c z4F3f1U*w1K3ZPHK%Il>MWRsa1<`2}##<@lwH&z>4jFXM)jRxZy1D^~CSOhbxZmq#+E*5LK zSgc%&hkRVHi$(oAT1IlOSOkg$-i66X)|y3Fe|Y_!unf`oSv!SXBrc0)S!$6jmxK#F z0+ZAeq{ZxskyP*qOV1l%Q`3rO}h zLm)%=k|vHEJW9$VjBUu>`OO(B1}G=ZoNPiE3k$&I0J#a^S%R}~fTc(1_8zkQ0<04? z21>A8fmErp+SaUjZ2GPxe_lB2gX^Z;QJs1J$%Ts^*>vS)8jALL>9c9LS{xoA}gYTM{%5fG#O2sv4_-(XY6y|5qm z@~gYm)RAl|6f5Cx>~zQ`Fz#^XwV5v{##7hoAz7yLjgb@@sDEDicTNhu+svAyGD)H4 zE-56Kk&b7wQ;aslj;?cjCa;GK$sbzpmBT`E=;!zhaoCXL zq0jd&7N74e1PFZ=J{!YX!aof)mi*Jwk63?|nxDrY3P5Ira(Lb0{MtwEjl3) zFjL_Bk)>0y&c4Gsvj`t#y;jq+cx-%Z@pT2LuMihL)UVpJg{y z+6#i*2txaGA{5O-z;1wsl1nCQC_0cLVJST%PmNkFi6IWFh017TuCX4Vs41wkhQhY6 zwJ0i<3AoJ;YXNd3N5wLUie(bDl4}HiBb++X_)f2;i<;?9@Q1Ioe!}Mz)uL0POQTBk zlKkIVF2aHA0dxzHbyfNTEf#Rqlp;8ggZS!lBzIdaSR>f&2;wqJvu30VYCbI#u~AxKBwqm&Bm%-fAwQBx~MTGCf4&1u|_{bCa5G8gW2rX*t@ZPF?mXCX^fA-&WhT;9boc9O|HJcQF_@e zn~Qc?{cQW7_fGro*<2^WQhGL*bTTX7K50L$LP)w8i2NXhAQf^9k0j~tfW}%TbPY;o zKxU0}I&=-eMP}yn=nl=ll8mR|Q*CNKu5q;f`Qy{rB&nHnij$PBt$?E-T?;I9YPUoy zYd11JaM4jPjO$k+TO$I7Cwp>1)F?dC7Kud_Z ztR`pJV|OHM*1}vAlVB`GI5SJK1TCdAc$xD*!!;Ljlm8hThAtHdkYf}<#8IP#Kv+RP zfh`iULBhj{oLhZg>0JI;@JT;^WAB(VY8!j;%muITKPiXy?w!9XJu-Ceq+?#>N&o99 z+}#Se2*-)Lb4Y*IKm*MzNC|jO2vcOQXk5~$3+Y%`J_tAOYJI$L;9!P9N2rBs3|G%dMlF zr^2i|$)k);L65lR6O>+g25GtI54;EAn9Ii{1G>9VBr$kjr|4U=vI=#7pJd@m&Spq^rf(@GX6f-G`ktF6Mg=eg3kuG2ba$L`{n69aPk@Vi8Bf*U5 zc%QQMI7dqJBGQ~lB=`>rmXIevFv+}&i53<>H|9i&H=Qo-?o;XSxV!XbkS~%wBFfWO zL$)d9;`=9r4AFJs+#AvFPl)oPn$K%`J`t+e^;Szt^zt7M8Sm*VA%$zGl&-%OM8-~2=%p_IyGw)+5NL6Hz z@|FVjeZlbpKDl6Z0WZMGXP`Oh(3$G~~-IO)9lOw)50h>=*g zDQ{*D+%YjkE~#H#&qvo!uIKf6!gTAF!k~Zm0JAtLeL=>sh_O z^XoZ@E_M<~oSMvw$_}gzRq{xC+Uy>aV+ZSjxeKmavvs<~W10?N9t*Ry^X>3ccuqr7 z!E{TdYTyU~aupH4c7E|zqk+6{?F@(usN$%GC_;M+Qxg=!LOqfQ@ta84; zIY9xe&iH;-Pm+Oq1V?T2ZUbsTmyCfN0pSmPLUaE3=V3dmpQ9j`GHPeE@KX1?WRhP#mw zmSl?NPbRAidL(6uf$=1k48o2u=f&F5H?~kj3kOjQ1XvrO;cU~Y<>Z=RBpeKB;V@HO z=5nXSm=~2%CR8xgm6B5HNoshCZ0tC4Ys`a?Q2b3ND%%fY7ZUG~U`FHc76L;=LwDAo zLDE|QwtcGwNj$5d+rXn;WJ9P4^;VR6@8C5k9q9S&E_7OMw<5C-a`+H=)>;8tB?@^( z$BBI_w{219k&q@8RtG(j+;w%Lz_+z1pc{Cw^y=J5K!VLDP?$x(l5X3JyTT)y&zn=R zY+2jZt={sI*xTEOj;fffZd~u`H~m3A^(Lmy$=-ZZ=C+X);cP>D``{~6gUT+!TB(6P zu|rrYy~H}-$DCMgf~6LWw%wgETM^D=MiQ+ylU7t*Zz4f&!g6|wq^eL1Fm?sU|H&y@ zZIM#a4_et=!yMGW-=Zp0*c9Uwbsn3iEKrxSrHV-k1pQDPtoDe_Vf7`!Q&XuGGVHS0 zT(P^Vbqw~2#xx!-jQGmKeq$1bf7q6SH??M4Fuy3^8-#>+9f|{uBU=b>0Sz568x6vG z5X2n^g|Q+&LnDR8VV(6%0&aS!fIzZ!?`Wr4j`Coj>K_nxIL&VY8YX5x5mcZtq6m#X zMrhD5p~RWOuids)`F|NQJ}9@-y~S94%vJ)%sShPc z2A4K9*FT-BbZbZ6(A6yq%7YCJId|4`=uv+JJmV1Vk>^n26*Ec~otyI4TLi~BW{&lx5Sv0wx8uoI zMdavow3GRDKb5vXdiKzd*2Qq!>G_H#1Y_=YDId-_?9ut|9F2WF9ZSy)BPkATUhL|} zaAj0~@Gfa&PeUVvZdLEX?lDnp11B_cToCOZ(B*%XD|WN=J6ug{D;tgJqPAyeim!RP zrH$$PmN>KUYU*eHh}GcCk*(}qQSNZuExy;S+(F#Cezujk-d1tFABnS7Vb^iOAw}6Z z)lUAs^SF~ck?g%u90P?NT`6mNvO1F<#yakeb!U*S)1tr>hkj}>xfnJA1~5A%VK7KS z;TEDlw+DRFDf$V3QtS#Dv1afY9r6SX`V90u4G~4aJiuP*gb_wVPtZr>s7M7tLx-P5 z;}#dX-Sa8NIFRjcE(UXk;I5?k)Y9Xl7oQLsJctwF3zXq?g5vh ztS)FRa+|zK=Cs(8l3zh9z|r!kuB7C!;lXFfOR^xt19hi(C`UdA#kpF&1m`0Ws86bp z_woV0l3o;~B+5*m0ttZJb#_B`QFiaA*|yu>V6FrESzh+w$A8K0f1eNJdl2NkFWZ`Z zJo{vJ%BO77rei?<>VtI2AZyHilwJBH6ct$-fBY?@-S8!}kC2pLR1-iN8*B}( z248)!Inop#C=XPJx~HV(rIz_u#@44cq;{r$Ncp5xZ<&|+(}8rfB-Yz_filxSJup2w zGqy;%+<3Wtk!yvr!gqb(`sj+7w^3#ZugMw?0r8$SX=#f$=9$NrBG>pqNw%27X0L_a zYG#^wjCqQAo_VR+U`|Nzz;@_{;1Vc67Ds*>I{9I($qC_ZD5J?~2vgaTWSC;$2|Ua* ztT${h>@@sfPz_;h`mU6gl3l49JUx?oDP>5J{%do2>hsbL;p;-J(>J>5=`hhz@tRP9 zMB|`lr-LVuvJgsk4LJts5EdQ=p312SWOIHwQqbYW6~ihvgy-)W~(*WMaq@z@WDs-0q3Dm}%R@hL;ER8X^{^b}dEQPRBZ zHrl`KBA?1$L@UxR^4VJKqwU;YpX|~}2|NJ06WCei(>e@;4!InAvhGC(w{@Vgl?DMW za~cJs>;Xc2u`!wAZi2-ENOMs)q;>h;_Q8Dy_h~E78=L+4jl=)mbM*rQ)olAUcigh% zsz>it(w`uCZSk6E=X}H}piG)ra{BoNzV~+R{OB)xcD<1sfeOfBFH#zoYuEJgurn=Z z*~U9Buv}ofEN&bW8WtHAA8$O%Y$*1Z#C!RB#|QZhy8&#M*BES!*2N}8Z}Hv`zgynq zY4?2S|0wiH^uzd9wy*Mjvi+3jnQfeFnQEKjnwmE^I5#>aw%BW)Y@BQvV;kcdlQ%hd zR&-3vWR(4KxqG&4mdoJfQa+89!L7PEpd;_u4Cnwn0XRjvQeK6^Z6?*YH8-E+p6y=Z zUhP&4Zj(cUc#|BkMYW`eo4|JuzyTzZenYsyXbD%aNhH8^&oljTixmTlcV5zl6&BUk zn3!a8nGz=1)FbIbH3N+-Sj{oAfFs6s<3L&~wP}=5!cXfBsBP31`<|l()rLJ1U878q z&MrZV7j@O{y6RTwUyZE`@QA&K&@<{<>PUfxItB+w>jJ{4oKKq(a%jN*0kO%ECJG>6 zZ#T#9@8x9Xy=i~`!yVbL_y7B6X57|#^z^n>S3JM@hT9)8>{vVFwq>8cjMT*cVcI7Q zMu^&fU&o%uKY8J;7v4FDEn7MdQM;*FbA{4DtyerfIej(1+J7Tk#ji6hbFT8=n73Kk z?0i*u#pzfI0J&sixMymidbw+hVOw&SVRsTdb%8wUGzTgy^74FA3+5GAjA)$9^K3g& z3u+5dmd)k@6=vQ&T6xGCGXmp05M@$cz^Em(aH>9$h`MOpq(A}?c1r_F;PJFuBTv0< zszgQcSyVuc#iOI6JX&9*cP;g5ZS{O~CWwBi_zcnvzg@c+-b7v={TYxYBKCw;q^1e? zf%>qQ|3p)$yucnI_JX=v`TwHrJ>a9N(!cS0Zkyg`GBe3!GU?(}LR_*%9aFnX~%cwRpv@A79zOXWI*Pf0AC9 zTs6A9M-}wO+q&O)%c>dA{(jlZeJi)#0mpj6xR>7mMIG>T$ca8VW@OvGiXqHou(uai{sxxFW1aqJ>eOE^dI$oe~ z5ES$bIw+jtD+3fh;_@Dazw<>f3TL!TV#9&*Sb3IQEz3?gb7*q%aErVLUXAcRCT+?)pn*Odai69{fIfhNBZKe;CU=VPBB z04MvsK4W&TdU5y0d!Bnl&fB^qekJ}@{3oaa9+t+Ofu(a}nfEhC9hP-ud2qbMa-mr3*&9$Gl?wLXWY#1U z&hU8vg&#CzwZd=Q@f^pOcn_d(QENr?aEcL;bc18!De=5$(2)3S4`5uIeW#ibB-C4s zj;WIWsq&6JV_a6o0Rr||7ri*ws+j`_}>Xw zLM3X*lVb6)kdPI!7!V8sE%}h@`3XdV?7`4w_DhF;GATOh`l&^nGX){-I})0!AJsKaV(y9kQcMzLXQ>An^zosMj*+ z;vkQM;`r2zM?_Tkzh!7(UsR2W&K3NQz0hK3M_J?uuvd@FFB^p zW(E}o2Y({_Hl-+05d`GQ0-&J4^V4$~z<$bp|2L0^r;XZNyJXxKwJ#lvzY1)#-OFEI z-Mg%f-09)&@y{RnDO=n=b#AZQuWVWH_jmH(!Ly9@V8S_;Ti?(B#hhQGun z!9?^u^irUy?iE>u1fO3DwG2R|s{nGADoJ9hNyeH+U`LEyv6t-pnJZgZsq;^LLz=LR zX*EK-(oEl(zIwC#Onl19mGStB65vvnTDcw@CFvqO-fwpv7=ft?S%i2am8 zlJSE?pt#8|K(891rIyLvD3eSC3zC4O&?+NvoXG_O9!@-83An z*wMY9WyORU@u}>dVckbfj^76=l{9=~+=izp7p@n^u&LU#N_kLdV%mhz8vDkZHw<4t z^1%@gk2I?xbG8yq2?eu#(d@LM?9$Zk!5dP0cj{enlQcvgFHQH1k4`8aH*mhZ*t4*5 z@y&}yu8}v}H+$|%S(CA$Q}w_*ky-K?+kV@dws*4M%*{`=-ZU)Jo3mfs_wtRQ7X3T+ z+s{0jr-e6UHFh+#50{pfwF?V^tD_U&zhpIx*^jv44y_B#idtsI1(usanU*e{mDW?0 zsfOIItNQ2rM^|;}mvf|d`+ifqbu{J{8F);R!AK&6jBi>ANm7Gh>@CjrVORShqr<7U zv@1JUUM_HlE1@M{)#lOZLQ4xy6@p`L+0Xu#K;Y=lm#c}T>cxI!&LQGMWPr~vUiccg zzh|6ZJHO$8*Cb!T|KC)^knaG4;#`#b%E3S5Yg~l?y1mE4qmW8mepe>?4FO5{JiP}{ zxl&~Ez$dF+KG>Cqr?|2)YEg0(NCv<4fx@_wG{hLc4?ao3`_qOYECuVG!GvJM#hYzpb z_296cOIJ&otaXt!)$Vt*y~Y*Or}XWR-8x>=e&|gR<=~22Utr}d{%&aEpnF*5%>!Gv z%gO0`)A~MZ{?xm2mC@M0XrlP`?e}G-#GX|gvGZ*gjjCMOIlewNJ0q`1QKEgz*{w6X zwC>y*V3O&r7xeGPBX|c0j~Mny(*-963xb*9Z4Hep8_xvaarQ&sPM!Lxoh~1lJi7mi zgSXy%Seib6%-9Ljk8ZiQxK-{0G`@DkE2YUwC%WE4-sUMOeqUZbMgi*DanJp^t)usD zIXZp9*fH~^N7o!4dh5Xz{YFo^a-DLxZ|6>Qee?U%wYV(1ydC5|nxJ|buef|f?Sw0& z>8P?*F|YEL(erVaFY#^~Oe9=icw^+o^M38NGMq!0t=0e7m&!z?FMP>qknEABmw>g?0$P+*1enOc z{E_5xK=kDCf79 zva{?6+x4;Bbp~sxoqa{QKRbSwl+xO45oBn`uM}+s&>__E4>=q zCf@#4#hi8X`wm?7@Z|DiWO11z97g_$GklJ-2vfDr7IUt#!UX%rAxiNLv~_{y7K?1B z_&)3-uPFvK7vA(1i)=ukOsdUfHUqs&6SITu5%< zNBhOO-}J^ziy1the|ddTi&BTVmlbBWsT7qPi;1;~nvlVg5G9q@ue4A;5mRb#$d00;7Z`f- z-)L9;XiaRJ>E(-k@SC_SwhjBCM>yw`ZPcY4j!ml(kJMaUsYc(nCebgb4_wZO3F#jwBXx^S6YnMBDCcY5 ztEs11hU(;fm^>G~h>-0=vKTL@c@Mv}MHA)QuilCA!_TF5QU(a(UR29)Hu`O5jm+v_ zU`uMmHN5ut>iSOd?Ys|(2NG?;Q_(-2vf_5m3v3vgas}&r&Mn`8Tc{--ej2spH5M&Z-!k`#x{jRYkeCTr-kS%qpe?exkkK!%GH6V&|J?fUgkZ3>X0y-1F@n_|t z8k9+JjCe18JYU}lts$x;IFrsKG(!59sT{r<$It9zokMw3h$_^3s8y#55yi#mtwfwD z4Z7MO7P1qu#WjYWS6-{(H;`{frPSw~xA`3sbV=|x=S@x*>4?sA(szkg6Ipm`r0=da zuoGxag6l9II3Mvd^_HN;W#}LJkUG^|ZIA}VSJ%WAqan^3wnRE|^-esgK88^{^(dX& z$SvULB)gbi=5ztW=sZ9)BoyQ16-a{0`H+1aFG%nrXKh_hNIH+<8fT+HYjHi7F3R=t?YQTa*T6)aPjy+6XeXX4U#A2gqv$$LvYG_VFrE_}(%4SU zPkJ|Uj^dRk2fcA|wKIe!Ch)x=lF7PAux=Az3WX6~$!j)0_KF@D#?NKTCX zq%6@#bN#DHiNc38JzA6Gp)07JU>!aNiSw0D^kE3zZybjbwKH)Sou0Tz=YC9pxLUv0 z)i`e^TS8P7`Tefmsgsj)NPU(IDl6N~D74=Iw6 zsl=~I7D)2zuj^>W1;3(lqWO)arU#%Gk(?yDtWz8FmiCm!+nlV_y1PvV@K=FI^h9;bmXCRQ{4amn@-Ue4RX- z&iLnV|4kiqU7}_~&!zOYq}lt@CG^L?_+P#kDjL4~f2MYl){BMZ!YW~%unET6ZNmM+ zLx}wO4M3`&6KaH7VW04d@S5<3@V4--@V@Y&@UieYy!O8mz7@VlCZV5%UxcedgWg~5 zK=*53)JNBTN5^n{;;(=A`@j4Czqu~=ntReQ)tCP-Uc?{&s(t={aV}l|@6MmJWXWax z=PYrBm#;j@5AYQo^D=em)t&zz&m@Lxtg$`~3^`7}pME=D#(kQaqTl+zI48l1%^6QG z(|dv+6F+heZG3Aw>(}S~yKDa4`GU|IFrIfRCm>n6z-HH7=q2yQdxafXmpvvt2_KQ&!i&Po!U5rT!t25j;VAN4eIR^< z=sWWB{8~6GoD=>|GAr8$xSXaJ3F5NsYhDN<0=r%N%J${{(|09hepHr!&CBpF&Qows zyKBBzaGZ&kp{%KH56aosy#7^v|Lu9oiDYkGDQG1B66#g{f60=oSxrZrV;Xtva^ny6 z4qUT*qM`Jed4CGm|*_4g%g-cr=j_}QGQMHuhG8bA6DjDv7Wy{+Cwv$2eac=X;1w?dVxvszl)(ke2so1 z&BoAxym+t0mqE8LhP~!hWfSZHFuUMTd<%}Xo36~mB`kvIuy>UW^c(OjBFb}DhA10i zMX@5f4!^ysOxJ%?UyXH)byTKbnTMKwbscjt^XZ&$-*F^oi9B)Y%;WRp@xA-v@%hJRR=qIp#QpbwH0}lI%ADhK@EsHP&HZpr z-_d(U-+$u7{rEuL)u6y&={TMe8WyQ=$c&}q1EIod>3BS4@ccU}2hX1`9j`AE>*f!x zyn_yLeoI`rTc$Oq3-f#OT3k%dIMf;gZ)w7+P~K8r6?<*ghx5^hy-b|{;mnaW<376o zfse*Y*4q!tD#T$p+`iaKM1VR|0g0y zr9=(=zO2cLk)kv!Bk&qlWIdy+x-GsbehL3Jvia~;FtT~0;;)}R4G*A-)2CTQtWz{A zv$!}jE6UC$OR;;e8?a+X|BANTZW*^#RB`PlHV;>t*gVwr3$8*9f1w)K1pV6NmC^WJ zIa{{mj2S;3f4{cS& zwkCri7mEuRkXb&%J5+KCA!~>Iu6C?hKS*o)PTV<+WtGNH_X_8UNCo+#X9-L15dV7I z)@glb?HCyUtc0cC(9IIx!v>me=pH{)%yK3?GD^&ee|Y?O{5UH*ew?*Zhs0|P6*sa_ zS^V^v-eaq}|L)QFpWCw3o*k_58g`T8x-RkWN?3UC6H~iS-8qC%Svmp8`$a&G=#mNC!aH<)MHU)X!`+d9R2v3;G`)>T*UTz_TbrpxO;h<_j*UwC@a z8}W0@^Twjn3vvIM@hi$Ybuc{qDDK$rF-YiA+Ah@NQ)zFSv3$?3ZZ99o`Avtr;}33s zVB=-FH7ohN|1dT=_H7{2tO@F1XKbQF>>fkh);;SlZ$bk;Wo^?WDgH}YZ11m{0g2WT zEU3!w!v|SF1LWjZ49vLx%yw7TXQ{1bo{QmT3udeMrw)&Q;ZM$zZ<>r3;(U>tSNA~J8=(pvSD{(*gPAf*- z4~{jNnecL_-JRr3XlICab9D2i0Y4_~n0fhm`QW=0zudcikMYU!nv}oHoIa?o9t3~_^9h1%gW9w`NK?Sc*&f{=ik1wq{oc~a~^$k z#_(}16yqbeFZfNDlH6fC4|FNWK&udyAg@5HLTDX082^%1Pk&=8$c!qE%b5G*!cgmi z?K5t>sY_mF=gJw=?;E!4i9VeI^WXn$S7DENooC+HzvJB5od(`JX~Y|kzQ1M)YS-ZR zassuxh{kvbRAk^cAwPf7G<@ZKqk2EReo$KUrUj{wOxQVJe*ga6f0)$&)ZQ(n-52c4 zetqsokD`{`hR>zXl}e!ZV@H6t(7-Ry2smUIyxbEVMKomJ#$W{d(C% zd-wSEGeEq-BWi#=M&60Ys6#-BlI}w!6`TtQYmB?;!e5tmIg_3&C^Y)(Ue@g7hBcEw zu!NM?5L87$d-y9$e4<#2cCQC+Lx8utFK>50_9fc=gyxXM5WMNR;nk~T3CIUF+&3Njx^^J`$L*wmrzprkHi9RSPM#q@TP?dAPpSwV0o0k5nprCHHy~)sGE;uUPK$V1UJ-?U6I37J z@XyE)79)gaaM=l=QU_>X7@>K30NDl$T?H?X@XF(wd` zbYFG&eh$|Pp(LEi6prqbcqU%92>9rb19L&)rOc(0cUZ)*ja zLWD(a)q)&h5pk_&ZOY1`yQ6ovU0G%frKeY9S)6!Gh=a;-H{vL|i1aRH&wUm4l zz$VQOdj=fm=3`Vk!2!FFlj8T7jwb+`wkurR68rYQ(_AfEhHn$nFQ>jB z*jw5AQaWz3WHR zccByy?3q`N9^LcS(LcO;_uY4I-FP=L#E62U;jcjR`cOa|ys%Wu7|?l_UF6whV%esPi3!cpL}Wwlfkj~f_X;pusKaL6kV0+GO$z^=faz@dN| z*qQ$f;E>@`L-}6dM?eTI@F0khCt_6Rp$;AF&dx?>=XG*|KAv{T4K2|C-x^9|?xR_< ztjvHN@MNwGpX0^FGsiAj@FY+|yG@xnXVkO-m&Qd?z2OXppZ)fG_V(!=D`$*~|ME@z zmf?k&y&u1M&ho#E6APcIZr3F%nA-A1dgdn0A3GtW`+K1Ka{a%r6yVE%@%4X|2%C8o z`<*yQx)XY?ZtWTrZzJ6qZ^Pb4Elt1i{S;VEQIm)>*sAzZ)=odKZ~Q1OZKlOvqr;2S zZfnxof32%iOJ}iX#fj1`uKm)Lx&s9m2)cixrp~5K-nMP>y&V@+u@E1)J(mMVoX~m(NiD7Qv^P0RDm)7)B^D z$?9ot((9+#k{jjiq^7kbKfJNk0xr`&acS>OiCl zrz7R_;BB-zn0P%R>YHwgd+PD*M7N#^x}DOWiSkSs93UDRnIIZH6R+Qp)mZ}fj1gPFV{eFb}q2KRQ;R5c*%HEx(_7w()+S@%!=q$ty5Z|1`zs620~M>3Q_} zKjV?y;32WFpolOIkRLqxI7F`*@sY{_j?ePFnL1xWpR5rAM_Nv~aP zfxW97p_t9mid(w#QVR<5T6J=lruK1nOC9PM>7L-2>b92UmqokfcZ*i$S4MBi9~U*M zZ46t1Rw)((1`1B8xRh=6#kQ; zEQhOmi;%~x9u!By4b!USm`rS$D5j@`(n{dAoEr|eji682bGz~h+v2^B4*V4zPSEtMAx2FJhC@VK7B|_R=3ZQ@R zo<%jKz~xsRlEPhl>3em^Ybo!ioJ?s*kuy>%QU;_*DZw_S2bh_I=m6x0YiU4NCP>KS z5q(F|wm)-6!E+s=ld*O?J{Nsy*i+(%m>xWL9*zxSb6~B4t z&Xtd1Yk1zQJ98`ZXIz<-`t;Z>FK=RbIXQdqqn9=+z_dJp1|k#4%4m z^6I%?ptKSPvlo&Q!w!27IMSXR2%Ll0fpPSlNPQCL7vX%8YCeUBOZ%Hnr&$6P809JG zT-a}6>H#4LpW7mjuQVEDE=(A*8(AkMkKd?@US<))K>on;FN}159-}NeJVxt&u}U*J zB6hpUf$R$8U`vjJl-6Aj0y1%cU!DcSLtSWM)On_=Xs|jc27x+NrCB_RJL2K~iBNtU zbBXJ)+@u%l$saw%bUluB=yVh=X&z!BPgNiiWRc*&;Mm}-piGfOdhZv)Rp$({!t*2U zw!@Juk@=MasKXNxK0MfesQPN7v zOB)>Q5TMHYQ*$+cX?f|MwDW1=th8Ned(s-x_@#nv>~AnO*8XY32g%wk3a{PRG~`h`v?8$=#~9RW|1?>9 z)7i(+mxZ(gzjN5+jQB27LD06jMTA$o<4hqLim9xh|d3zT7c+e{jcjfr1c$L z=1&^9OgV4`N}-5d?3=|9s3pP6?kjCbfF~Il(73oc88{y>2!V{itUz^OCtvTJ416!2 zLPk|fMt}*+nBY}YJZ4jOyTeK#+OnMDQM*T6%mr-V6znae^w6tU5hItxm1Zi^g4lCr`%( zzHNt$5Q8}?3e2s1ZabVDbzZ-b5L~=XoC_b9$Ky94CYADcd0DPjC>y~X#)vE8?qn!2 zwsrNitTmbq9;4li#5%G=%0NioIuU-Iqyc4V7Q1Q=c^r+2zA~F9`oip^4naN~5|_x= z6BR2&nTz9~#a{{lbaA=ZfN!=SzZp_>IUTt+#I;`0x|000b0m8^pXls>F2pxb{}Fnp z2jdxu=ytBTY_YQpMB)vwOZK48Xz+QBlsKmALd|M%16@CjSzTtBJRsIqAmow&nv!-J zM1=#Ssr!U(-^>mo!~|bolaP!&>}kD>bV&)&3+f_IB0CxFVw9I*s-vxqZ)U&u$)Qv4 z#`|TJW>&PWn|EKYMAov)2Y1*j*UO`>?mDuEbdUR>tq$TiMP&Xnupb#jg^>OtOGMa> z$M6DEBIBEKywB-0rXrZti_yp5z$c= zHu8X=BFvSBFXlzP0NvrQT3`CgFR^YCb`oS0T!wSis3B^sw(V2iQV!X^R=+l#vR#pX zR&5ow5%O?liabSmKz&*@C~BGThj6KgK$v>-`;O zQ+jq7i8@yx(fJ%Q5|I@IpGb;hN67%gh_SQaZ{Mc4Jwq%P!rn1b3!%BgiME6?b{kx4 z>)5kr5%u!gm+{Az%X#sEY)^cCY`mDUC_XaL^K#2(2vt9_!F-)!K@T!yYe0t^d52Sf z1N(6#dx4)l0NtswA7La(*~~ zt&MdH>%dFja9p{Y^t1Vj(Y}ufnIUGqK1gSlfo4y_a$E&lRJu^FjqYS9wN#{BZ<*qm zp0Ze)r_M3VOW7nnBv}mk2#k|#F_lFe( z^8#Vb6}Fl}=|)Es5$nD@6UTf2KOW~Z916M_8U@NM4z-pz%gf{EP0TbDDPtq)T(8A? zN7rk4A+a>laU$>y1+($Rksh{3=jb4Te4X81tty7cuA>QB-L-9)&=h#^g9oe_>4C=GTCo(g;&RD7Z1 zuK#hLcFSwrk2s!pJnMedp{Q;pG{?QcQSDMNid0ibcKFQBP^!V7g7|r_6lCtUp&`ZR3 z%y-Hs`}&6worYS zCuy8=Of&UE=zeW!bigk6IlCR`Dq*(yxPG z77(^-5n}*oHeI<)+Evm*r~!7OR1tu53A>7prABrp{l1^#zJ%`O6$fUI&7PHAoxKI& zpOnp2WKC8&9o&Zi zi}O~C-rc)nKdg>z0&xW^(5XB?77N1$At+Gyv-5b;MQtPs(MWYfbh1K(k*8XfLW`=V z98Hywl1%X#OG!kU_`A`hy6iTyY$8j8K{kdRB^C-!CTWaRzN*EV<q2Bm_&1`Q*Fg*YV4*Pvkp2m=I|PNGqbLcK0X!hETVV+d#(<2B*e!Z11>187G7 z41eH8-E<^4j{<+KX)G6lQXFaQ41!BbqO&Q=5rzW12&W3b7=&C!DsfX%Hil&>tx21q zi@}PZuOt#ER`;w~vwC%1UETA~=W3B?YOgL+=ORVqYUWMgip76e{n3!?3_G1Y=dGtv zuH!@5F=BM2s*l+dNxns2xxj}&{Y#pvalVcKMXOUCgX&}92k>nKd9ex7N2?rMDg<-+ zb-_mSq>jVL@1(xbc&AVJow&WV@fJzB;PX?C;IulQqsiW?-F58`lacJu>;IJ3--7JhjmG_C`y#2hVPV>f5g>(r zLZE6e2{Ylb_)sMaE3_2J;4tFRo zBe_CF;UBt{CWEgOGOWa)`1ZV(K{H(>gGDk1W{6`mW@S`oNEuZ*zC1Tq9yrz-Epii} zYrLQ<5BP@g^f(NgZWhBgx)wnv@1t8p%nap2d+~tos_X>bl=DK<1~x|m(H9yNz<#c3 zb_qgs5%mx4q68~p96>zbe4$FYX04Yax@b|s9gTQN1R#u;mdNubj9VCr|McVGUN7GM zdEMdu=L0vkyb)PayDXT{0~uga*+6MP{Y$SM82u)5Oa1F#d_5koBbl-)ezW``)&jX~ z&dXMqqD%9scT6y#!A6);3Ji|(ng*OQvo8qxl)1aP?+C398CtpvBO>xK8I|s4M|MEX zby~t9kHru%YQ|XrO%c1>Y?$D(fS%}lFq;y71aou9?v<~Ra*)H#X*q6M&Vd~gT1gIH zSL0a6EJPupmE?Fy%HSBv2nmxM-k1E?#+8#Cb|{DC^yh8&kufd*e7-msV{Dyov zKQ-5%Tq#gNUn%(c-TWN60^eTL^%6hVOMq~N+u+-TUgAfJ?uh@G{}iA}`seZNqs^q& zxqo3rLs&Lt=ZUtZu1zfCseie4La+p+W?pOYXh#-rxVbd;F<(PU`?0w1J8ItKad)H| zmz-GkVyC*)+bTzHF0M--%D{hU|Zn|Ue*e#314oJZb*%TB6gPz?1 zUPZL#7pFsW;1cGVG~_P}Xw9pU18_~b&0$8;=HPIPW=Nc-%}d(hxi-__3HY*;ru45QPI|=Zru(HO zB_jBF1I$80u`aO-FKhhVRRX<)tG! z$@kA)-rN0%dBDwA7w}ae?GYQTVmV?m;H?IX+e)#wFkzpZPvnBHRs+vKWQ8L()ca2}3Hi=^aTmU)OS*U0FDZ)h&zE2_$ElPvgcgA4DZa;SSPjm& zjrZ(b%)t%|?<6W~DGLKDJ9WBV5{35Hg+kZMLgm29^OaJxa#m$^rBo@2k?X6k7pt#l z*9%c>T9+X~9o1ZhY$;liJg^&{;if?YE35kqD6Q1Sj>TL1_N7AQ*vie7$13H`s7tJ@ zZeLMaNrTi>)Vj2?x**DrYV%vrXLW6Mj((hx#g8>dIE-q10h|i_-^$Q_rU|J5=NCi+ z{>LqGZytY>#BbSfJR@uaz(plI#x43YiraMV6$LNyvqRBuw!MS%p=+z}@X@j>aX#iv z+Rv3(|6J_n;-gUmAR1OS98u2k`tM25@Lkl8-6N?q*tTb()GXaFr}>J87v=H1{>KvM z1MOF@zbHLS^*3d!!3n|vX*gR8=`IO5$&BmDPN_38U?BZ=GW~Z988EQiCE!Dt7Z1EA z4W}#?|0FrOiW||k0A-#3?Y^`iL;;R;w7lN$WLxW`@m z9<+NFG=c%R`jWf>(d*hf+{N!e=X(tNd~6#etEcn1^i%(W{?n!3-H?7^p-{)>gleSM zos?g&Jdpf*F$BSXTGwDW)%ClQmZrep^vYX}T{-F}k9;)a%MKta6-t zyPjdSX%~^&d9BpziijRT2x$&jG;DU{rf{SZHL$8oJRP^eY?RKjk?YX=c(rj@;Ju9n1rKX`|K3*bt)?> zVSPr6(~GKlzAj&Sxah`~cdvR9{M7Il`CaiHWeoTUSu`22^m#UwuH5Y`kx4}dtjQ41 z%I|L9PCS^_a7OM3iCoU2+7U~RM=l6-bXT^XQ8cdg+7`yo!zVL8YkM~HN~RLbWb;gG zO=4+TSvZ_g7%6GnHZyZf^+?KdH5tqwZ1>DvI+TB~ z-@dXJ<CVgY7tMN z)AS8C+mIs%KxN#S8@3AC4#&PY0kHr&03NDX@8spvTUluiOc{;-Y2^N$!eB6tf0J3= zPrG^2v)#JS@3?hT?=AQDcydek!;ud@kaM42=4YnYfBQ>nt!?|Xd3S}_u=qQv;>7J+ zR;2_B+CN!Q)VgZ-tPi$l%-cSq-{CJ_do^wLJ@<|3xMuql+Ho1t@TI&&?#Zz>pU?*G zm05TH2ziiwq;rICkbjyy*8D|}H)Rz#^II20_9LZadTNV; zl>Cx{)YOhVpaykIx4+)Dw6s<0b{*sQ zEbm^{v0HcaM;3A(uHgNV1q`VhgnsNM&7a{t=@p{`rsPd*xj65RmK*cdv@~4PF}`LU z6AEPpTD9t!o!v+8oQ~0s6@ZZK*jA$qhb`D4*xl^t1t2|U29zTa!0Czdcmw^I$ubZy z;N?jYeNkV9Pg?F{V|+7xB7gJU14qnTY6Fd(*&Wrm+Vak{+jctJ73Ai3EhwW7O^bFZ zD9rC!5KSGxJ9I#QXF+O~xu6({4k#g_U$*Dl#w*?eCoH6*kEcfLzeIQWh2zZ}tSbTW zMClPp@HFpe=NZVMWM3yUA~q&#CB*w?-A)qf*Ih5nN#sQ2eVT1(*S4&b%c1g;2$1nP z14P(=&k`@6v+%~UB?mN!s-8SzZn%>DhlsBa?jQnANAlOzF0X!zcP@4tRAze&N;$tK&~Z=Z=^#ZRo7x zg3U7)FP=>7f<$I~E_+ODFVge;g{XmsadbbF#cpUvgW zALE$mSdL9{+3}o>&J8*Intz~Q^83?W%8_cB5pxk%qYMV4i_=*~oy+5O13vSXS{Gab zb)j$r356)Txv7bj_$%dbg0^zcAdlD9yGNGxEVfsII zEhbQa5&lXrH1#7*t$aRka~KOC@&5ON|BpPy@DqV^@oF*mLY6cuF(Ev&V(pVO*8BX6 z2?2)5?1cj{4{vThA?PE#O<8h;>k|Sr&eO3^*`bD+(2F~2KJ_}obfh2Ii41O< zuMMZ6OpL8Ho1{;5jo8(}d4Z=ILh?d#QNyIDuZ4K(rFMTyco`n5nRnY=d4pR_BdvBC z_B}%IOY#VPG_$dvU~}3cNYg_ZSHq&Kqo<#+Tz71c#P(jLz;W3lOf{dj1ieUGo?LjH zx!4(4iq3e|1%UTKgKSgmZ)ASHX~o6tN7)%0mfZC~ML$bX;Zw`)?zZx6J^S5mohSG0 zD$?5FOZi!G0M>*lh_Z%?(D0r7C-HSe(Ghl#1&ELB-Sk%=1C`r;9`Ym5MgCMHDZRGqt6IGaQ0(i`-JRKnrvoJxs4zyl>x zBl-gydGHVOSZ8cjoY=iv`6~YXA^cHm;4P($g#Fh5i;SB+x0l%|t_WLYNSvh?^l%z{ zLk@^=3LyjC1hVQOD<9q!{vP!fdnXwuo5p(AOFJD~yhoL{)I;9$UaL_V&W4Huy^}3_ zygylgvi)Q?$yV7W+a(7!J&~2~GpA@Vn-DBxwb_lT!C*z%s9JSx;1VUI0sweKwt8^} zmJ@V$qgk?*ak|$FF451;{Q-Z|kB_D{x{`_3*p~pUDf8Wt7BUBRm+nOJ~phR2j)p$2? z1iSC>ZFg;YkOks@#cHA9DfIrw=zT&M`Ce;pCG1zx@tI9jl`z~o4A_GTgPvyOEf$Qn zLH0pgK*6&PYld}z^?mC}t76scu2L(}7pa6wcY+z*l1AS8jE0$rf)H`C1*hF)x z3j&V`ZMlUG+Xd*sRND9#@_26olU4%&JC1dW9p*mlb0fTs?{)*vmv~L!4oSj6mLfRW zh8IVYv`kO~ACL@ub$8)RVYCqafaM(T2uk9n??*wE)@iKo=+UkoppS@f_sBW*k4lC0 zA4#h(ALA6;9j|ykZrd$Co}|^&pw%}ztys|k!G$MmjXi`Wn#oewv-c9Hf&K0u#U0rvPuK3%n7n7*#0yiJ;a}Zhm3Kj!h()>p8iz@$}`Gv z5l|_~L|iK++Nkhw#XEjOWSqKL71h*%u4GV|?0PU>Q+NCO;EU3J5Y!}*-lNM@41l>9C6N2}zh&Xfsqb9dq@oR(nc z!c3UU=|zsioY+W>cjYjghGWY(rDMMpM748qS;1xzUzl|kyDE!Z?ZE5i{U(T@RYyiBB)iT}oc)D-Br3vk+q{A02xfil<@ zzJ@aGIaRo~AR+{bHhlX+;OQR(zE3Lfs>c9VXE`8!K^{@~v$2Udjb3S-2_ct>I667t zhIS4K0$3GMAo28x=f2V-@w`&QQ}EXLpT_JZc5SHQFuTk?#qV*XyV89g|Bd!u?q1#- z1H+VIhM|_hjuEbr?kZoUe}nr$@m|>vkXnGQf0mXiCexFo4oVxeCB#B!gPhrdL>2CI z>;P4E1@{ESYV3XT^d;Ec;Vj3u*TG;vLe7KVXlDtd4kd0$$MMg60zl!C){eME&s}1s zc>+FA*eVjt6xAv4J)i{PdQqP^gbakjOG4{(qFFMv2@&ZWMl5~euiv>Smu))T2qQN^ zxqq9Zghbx3|CpmBz78Drzho(Sh!1cs3xO(e5E*2g?7h84Q%6be1P7*XYu)}*c*A|G z*-?;#c$4T2KYdag$fTb>(ORM)x4@e_PcAUFG)LX?WHwoyZ23~92wO=t8cZetORFZV zPA+OKtst2c5t$bbCP97D1nIC;x(Hs0x-8l=VuPP$go#?O5ann@P0(3N>FQw z-0&uVRAUHO;Jzmc_Cbz8Td-6(YYS3`jkV1}4h!mW8;t`yjRV^l+aB8?n{2~!H=voU zra>A4T}1PK_A-)?STGYxg9eD3fd)$7AjCD1(1*(*0SN)nuUUL>M7ZGKvp)2+8((s% zm?by7_;jEUdRn40$-9CK7yRQJ+Qpcyj|W<-U`TND8X%J)na@@6`O!!dB=_0lB|GNC zb@bL}j~|m^h$cg$)nt_qHe7(#a)I&LkQ?Hv;J~bzOj*GWM!YcczkD&+0sJ(an2P^F z?3BPy703#RY@jhHy%>A<2bMWRyJ0j7osR9hT1sp(L+Tgrv1;DjEv%-#7SLXelAmVD zCt<-zhcTf}>%P;qGff=EZniCQ&r4k!sL57GDFaP2mGP$eCMDO@$KA)*GvwkzEb1D7X<)y& zK(pCBd6wP|a=e8TF5jM|8Nsg70LQVO%?t&2*iZ$?P7d)$p1j-%6NO(iHw|E?rv_Ho zso4=^UKT^B`sMUsp41zjc{&)(g&bcLIt!5k2dWiuR$|&AmO^YS`SMU`gf2TMO$Tg@ z?J{#*NQqO@R(AWG3a0%s9E%8E!jTUeREac=Y4KybSk8OzGDl7P7}H{JvGG@rzJH00 ziye6r+_5{(ZhM<`-uHC;txw`xNm)?zI5jMbJ>OW*ulB3mV(y4DJSH)x78714Syo z+Dp-7SAS6g#w~4R>VC8`2O&q#^7&hLYUe-m9d{>|x}wnCnegLDQV_H9nJ8a0P)ZJX zvGY|!Mdx@byc`-A4&)gtHCsGvs2kjD^+4Y0jVlQ9cE#vGM1-g!Dv#DXltcI|KhDK^ zM{J1W_Yr(9Hw%B!ISJ z83m)v5Vj#5q(DQ_i3(!HaYx3sKt2bd834)0&_uw zCjmt-Oz+@VC_%!UD$>exGZ|^*BG<;Rz9>cGZ`_!fR!Um!tJBM}Od z7jpssy#@arsx3VDp*14B&FnRq%%}kF;vzGe1<`1xv>68x3vJ?VH<;7tK!KwO&$}Zi z#khgejM9ZkQj-HWnLHY2gTkiipzxo`JqN@l-)$l^J|w5u{=@jHwrQEI;59_|wypYuWxh%#vKOK`gew$oiV22Xp@b?U zG@4Ty4@!)fSR|2@MeYRs9}a++*%Lw;-ZV7JV~L9x3u1lJ?n$?QLS6=?o+z)_uKa}O zdlWQ9woW`BkZW)&Y&Xh}gT@x&Q?2vQCRQ$$n?#>{ul%HZLX;6OU`j#ajXbfHsh!wS zsxbAE%u}SPrUlXh(|+lI>7sbqWJLI-h&dh!Rl&kkAea-B;2Psa-dcpXP@Kv|t(<-r zx$-WC%_gW-$W3NK%z`Lm@esC%@IOV!CcdHY1q(8)d==q7r)_F&hO<_r+PhfAvs*hm zCw2*;&454sI)fHAN`pdPBn^M|9LmM!%Ve}KSjJeHys-WpyAZcZov;3bos4Iq?_)p2 z>UO^)Mp^s~;=+W7EGPtw9~|?2X-+YCqMF156MwkR3M-&INfb5Gvd4TV$s}y^r=2EHD{J8my`J&liRH~dF50rCJ1u}`- zXmCYTxWir5*~0Bku^?Hrx4pE1;AakCRZr}WG-l&J5wM$5WdVaM5n+x5JAj*<%u{7?9o>V ze&pBDCx67Pe#1Ra$(n_cMeBQABI5vMQvML}I2%6xJbet3DwLDYol^lf<_NCkhfkb5 z{6Am45nF#azBm4%axgyc@2|VzW%r`(PmHm-@o}+QbG#Efq9Vm1geMbj0kt0@Jr6q$ zBNJNQaCw+=vu&hzuy2@uSU}hKEdQ;(mlFP08s7i4`bNuv=IWa{p}xT?^6#`ZK8&3n zW}iAHgJt~xptkWu@nh4OkRC}F)1MDxxHPVUb)~JzNN|nPM*9=LQr0kd{wqc8mj9%r z{bvOYV@bw@U&eh+Fn_|+?QTS!hJ_ZougO1UBUa1^6@~Abk(~D7E7#~X!fVid0z+O{b^Mf#4;7Xyj&=`Q4X<8^Y+n`VwZBw5HO z?KnR_6(!_QUn2;e$%_x6x4I8Y!t2Iopdj1Av;%?xV;Np%+_q=Q$}NpTQDq}Q9Sp6F;qARWy*E21Ii?1u zrccOQXjv3ol)k~TDR{rl*22nq77WjQ#`ru|u1>SP^cCB?Hc>F-Oh(j<%@=YO9V!xw z(n5xukjKD07SV3=`B)&Q!aRW1w&GyTl%LZYA)w+ACrLCyfkNSs=A|5hPK0hboe`(x zY|}b}=N7|4ipHAAV`JcKkLxg-z)zXhEg~FJ@y>I#;@d=g8uAz;nHVJ!lg0k6nhgWY z7kWm)b65*wyPm6)B+K*-d`d0|FH@R0Fm2>QW&ws$-&!*es-2jfsLXqxjKDOYfQX$ja1pvD3<$XI@+S?S{2a zcwC=6`fU6sX+ibEajVBIxGz5A`Nvm2w`}s01pX)l!8PB)|IElzYd3@ANe#3(kaAPx zG6uPOwL$Lh-#g0^H1hCa>-R#K5$#RhzUJ#&rWA8?GP<~Ei5rLf^6Rcve!|XxZ zIf~JY)F?=~EjOq_1Hun;jRv<1w*Vhu@+NW{_{|J3YVdF4JQN8(U(!?M3Q)jK8O|GI z&A|46=WwFHp*pI~Tg-|^iR&8)W=a)nPFSjAx?F#;m6|my{@wxlty!uz9?pHsHPhs~H9eW}k zY(D1Y4B-bYVhjd?)8#wVwd!x>X99*)sjD>Foyi*a8KlZ zW=^Md7b?M1>;)hKWCPr6iZzdwhjd#5HdxlI$it=%fdyHQjYHu(jU&5RxdGT}&0sUp zJ;aqAVJ%=vPMX^SBBybyahgc{i^&`8pB5o5PD5NSyzSE}(gviBNn4(_IZaJ#5dp*M zbMLumA>3XQWh@d4tMG=vI;ed3N5OTRYoX&J>nw7&g+&g-h)gG7(EQc_1rge1eka}; z|0%w0`of1-ja%@@>^4uA_n&e9j=pT@5Am@IP(Wheo>_3a*n5 zX$W3*r5JMMGP#HRsq>WdH##a*37bus zH1*gyo=ymR_K+N#^tib?ilNgZhD{T3Evsp6l-i!pP|B3;KioQe&NeT%N&03p(a`vLdW z+}t*#==L6+gLF%sZs^f5UJ}jMtvvFttvuirqzSKpf=q^-4Rst|K#wYKz&$K%1VyLm z!Q`-BH;XF2j%eitYtXo{ngE8O7)>U4H9&-4)&^0Z8gf;j2xHp@*$j#9l7SWym@Z71E=&`! zdWBg*Mj}R8QsLjPnx9kfl>w%6(cn}EsVSmVj4aJ^}uYeQku+E4*Z&+}a>bu^B>z2MLa9xL@ zrm$)wlMS}7SwsBe-?NR6{$9-ay_8!2jqGMm133h`h)HW zxl!of(w39KXX6ZRjmgN^oFQf$5C;ndT++i|uq{QO=!O^W=0S2F6GOCdCMF>i1BR#o zEgYFtVSXT)@69anaTMgl%xushgJJY8M=D6d%#`G9Pi$j_+g88%$n1j)X7&E;K*tF`jr_}?BIwm+y znyOAWjdM)*sRN}k${5o?#~7c|!CB^Rhiv7&oITt>=6Ua@qVjV0rjcbCRxMLYWW zkvHFcbp(?4o`0FakaZtM{0VeB1I*G3-5cv^WnV_)R$$S3lr8OFRw zyU2}^`H{7<0{m7im>g0l)8KKtZDBl0AjifX1#EoV8y22=PCFEIK1bm^j6doS6yPCA z6R(XWU8&lfL`WZf-;oH3vYHb%QovvsdM3ToWCFi_Xj@^Kh#B@!cZB(58?Hd0ahvQW zjixyX!Q_a;YvOZ?w?wXWaJL?Hl~g!EN*&0B@SMTcLS|d(t(LQ99sP0D;Y~|=eEHk1 zLy9^Uj=gQbvM)bn!&%N^Idot4<)?42Ey=xpZl4W%>`z)NJC%1xi`KvJcZAu3vU~-L zInpEiL+j8@>IV0fO2dP$``l`VZ=gKVaH~AkFjrn|IK(j!8hn;nzCAt>x~CFySj>Wo zeOx|20sD^@HWu#ZVo4>cVD7n~`H3>vR0m}&&_FRYVbh&YP?t163Fi#UEXy9tAxncr zvGn&bF;@UkQ6s()0L!SV1ile|z+w%Td$@*)6BAtOVa*VXyiHmp6a#F?LWb}^u0T>u zD|8q_MVZa*XmBBJ1jYeP*VkYc5w2HcYV*oO_L%sd@x0hzl#9g*BaHoKi%&_lw71-0RG*f9Yuu|GupAZNR^B%L z!Sb>3lJtwoVz4-De%Kv5DD5n&!hmOEBv%iMU@&88sp8EjAZ7;PtR`AFT5S5%h8zXh z{gzG8$1l~AW^t~b$L&r#Ih+`^(?KLH2$NF-wqXh{}_{JrodtuQ7TjKblmPxGW@Dgu1GKftb zT3Zf@chb=S^}c^tJcueoP&T;dNQg^Kgd)dy>@^BHU^ohZE+gEK5EDX?(6P{|kR0lt z9tqD3S7R^xR9G2^!WL|5|1GS*-V0wkoi&?yw(wV`-wI+{5(ac0t<1?TLiu#B6LmBv zo>if>RJN$L_@VW6s~#+??f2cE>el>WQ)|%n!nOw|8KkG`ha1N2*dbbDSB|}NzahSY zEtk99`vd~Im~eB$UlnK>LJk|E^%C-0gd=$!!ac)UUZpb1U6o#$FGLuc<*W&8$f?OYpO+%!VN*eM^$e*!BT%s|mWYr7;)kGRrV#!8$nb|Xz2Nr;VKb4k z!z4zh-2MCnCFu0~6J6&>MQ41zi6Fc=CD?~{-* zJWjr>R4M^H5A0p}D&dJbe}3WK>RYv0xwW~owQ<$kcR%|1v!`zvce?g}phEBas^-M_ zJD0I`@uQ2k-1^a;uUN16w@4%MOZl40A%K7=qOz7{*R`#6 zVHMYkVq*o9$^Z8}=S~uo{qOsI-}@mB=iZq+bMJZ1dCKo;s)2k!RbrbrE>pVUyoaHi z%8_thiDT0BjAJS{B25@|zD&O=W>HC|l!97pzx*@$q`+<_{ zjP!OEX24~1mHahAZso7tz^JJkg=+IZK%e53$#`uA7Ao*yu?P3Wl_av2ZqLu~VD>IE zRt@hmq1|F4uxihG+;_gDGS+*)j*o43zyc`}3A5)p`i1&6x>o8)deFhx-{L#oV=Iow zQ)&^so+$^_e)1ph^F=fic38AN6{!HfeFcFW%y_@yLPZ3PFb}}s1J)cc_`+o1$=R4r zWeN)5dS3*MUdD|;(;`5NRjxPrt8hm8n=m-U-^pjlh{S+GN_apY=E2t+Sx-9^4hUu) z^a3#l-I)*N+N)vrY%>ReQZ@~iBP~c2noERYcGQ}SpgD{kFJV`(zY=xC`@^A+zY7+? zwudv1DrrJ@qa~VGI4D64PS1Y&&ACMT)=v>=_s?lpq)#~cw!79pdEdWwKU_r5}y5hw_ z&49~Ppn^xVB4V$IpnfvNY&Z%s2q-M*tyVxCJO~IAd;^jal%YzO$<$f-z&=FFw}6%J zwI)B0mayd_6H)fENJJJT(jh~2nQ&Y!$tYnNq7%2PC8ere8`r+u-S)hgIBx6Zxm50f z+-mo2V!&H_MP2`=PRTv{=C>YgW@vndIVn0!r%e_ZChN~N) zwzLgdXLS72_=*4T{vgzA)PBj{+1}WTs^abV*wF*KDFtDWSU1EGeM0!mU}Q>26jxNZ zy~QcD5HSRC3jHb$IUykmnbjAT(+())SYMbnm`?~!tE?B&i?Pme{D~R%fjbv64m=-p zC@d(cU>$~JH3pV`4y4@{U@fM$%9kl1jGbk40b}e)E*fM8qsK=)RByZ}Ah2nyu04ppmQ|yzU4?GFBpJxZQKH`|CVumUvFNNcr0?(6T0Kj z=RGc(JboS+rAjds_7_2uh>{k^nl;r9PdY4$(`k1ks78x@Zbt-kfVUiqV3fn+qOiy@ zW_%ol&wvCI%Zaj7#PJ7aDM`sF!&uR%zo5bj(gu0fiwRXg zhEz8~l>~hmKYPbX`(l2`17fWh$kH~}0J<3QOj;Ef{J{1a25lQzO=|&!pPy=0_Ve04 z%V_Hzm;scYz;W965cDZ9!eXt+QGuGq*}{srv!K5y((sbB$NDQNqu64Hbp221hiYx0 zVz`rVW%?j7^lzUox$VX6?SF0m5_O?NJH&avo!4^mL+^Y+1RMI7#Y^5gR=u}<5*?{? z4t-vJ$ysAB?F~MMNF3Y6pjBK9G`;8O7m+kdI>L}fv}HWOpht~E6d|dEB~a9pf#>IS zX==IH)N(~=&T#fskc~#nq;UK>&lm=Km>w9sDI*(QT)P=1nl1a!siTvK(xj3;)-(4W6}ix9{|Ne zl+^0Wb8!*8f5jK$cl2K}{odTacjRIuqlQdeu;=;Q@5H>NE6$ui0*ZJgNvQi+LLF;q z8#RznKIkOCvr&{mOub5}#^+oeUl@LS9Fpur{@mMQD#E>3D@lYD9a>4WnKO=w zfr8xIOa{Edk5H2N-aTI3X;W2uv92R&g6dQ4CBqgrGKV+ec%Rvi_LG}kCvLDZj5&e9 zbWe7pOzmj=v(&v3hO;e$;db|a;JQyBzR#uFGdh>4gthcBZ!HWcT9TuO+Ds0ZwmcB* z9x%}!NSy@qlP>oQ<_V%$o@fqNF`@V{9%X=)Ory{mSLb3o)V62I`G{z% zZxL-Z^rvx{;CzT$)=_m<@d0PvYeuUadT}D*)3Aa3#Xbju$HSz+eT_tRF4PGufu_~T zP!Qg*p4k;JS*1ReDXc@Hf{qo6Q$R zW;I_EncsYCMH`bWFnGGCI$_FQ^wJRkB0Qx zp0S=y*{W1RFUeMADpLgsEvXryNK8w+`}FFm4H}T?Cz^_zK&MS5B||C-GLG7<>TvY` zaziDJH8|!CQCIX6{d!lTHv$sADwkBMl~0H{8`DdHUG#<=+;6fbYI0i&ykmMYO8V>} z84p2b8M$V7AlC@akhKO=fD+WaMD+a`F)Ontqh`SDm_7tQqWP(!Hw z1mQZI7b&Z<0AHg4La^~K{-L!K8HFRe_FSELgEmDw981c%xL#)Eov$$6&?8GZBVlj2S^Ols-f zXRtYO+|p}ApZ(uYx%!enO}=G{=lickpKEU%J@vTe-o3|-a-TiC4F4WCehp#Kp zAm)afk*w40jt44=fYu{FgTpeBoPm@lGOkw?tpRv3(q2(Y&J|L1FxZEb6KwWOsVJRL z6|YE45f#d2QHv5~)Xt5uBE&uM{_NuBYyny|cJ>mvTNKL3>cJ7(RMd-t2%WN}a5^WMB?)+I|GNnd`_fKYk z_SMQ=v(ryswGC;}%=wKB_^VS4GF>%pVNW2WfdaxlLAE4Djp_h9xjU8<^%V?ck`D&| z-pE?YKv$UNb zqZP!4McKV;HP5qa+rEYT`tc%tF#`0j{_#>v+cYw)MILQwkr(H+NW@i=7THyei))sW zb_zaRBAn(i*Cnq^sV;kwy_dbF?83xi`whkRLE%Bs0Y#b(73-s6)CLKob)mxzk^q28 zqP<}hP4cH#e&{tB9npd zm|97wV=<7kjDehG3?w(i;0LA?2C_6U2GVGw0Z(_yz|zj?CcXc_-r3-F$UC8$RN#iq z-;vEmrGA+INsogJPdkj?(LB?psQWLx?%o|&%{Ue8?2K79m&MMGKWEsD*NQ%0e}DF( z86Zmg?|$`M7th-A%c9EN#Iqil*G`40l@R#S3haiE^3}Se!wYOZKhmY)3Ch?R zR{*P#Yn2Byml#-mq$vA=nbCnwbSYQihL#_~Z`)gt9gpRRq8-@v!i+^6DuLD3O4w1r)qXXBjh7iwzycT@c%%1`H(8xLaJuJIEiXsBpOq zHvBD|?l(D7lciO@quYdE( zvIl#QzYp>m8_n2Z>_pe&1n?@mIU-Xc0wtqMW|h2BvZutzMyuo1scexRnwNBX!t>I_ zeLZ5P=W-NXyTzR>R+=?23k5`O5hy-TSm6&5TlYt3jsOuIFry@~{r+YYKJm*UM_>63 z{}bZb^{yCUiPAp7;DDK;i)^gVBjd!T25gf#2y2hcKwb7{kKk6-|G?M9Ih$L4nC{;@IFmU|Gs{;f~G^?L5w4SU{y z!f-wLq(8T7@9x|SfoqQv6&c+_kA;Sri5xJ(K>q9X%+-Gu((u?yUW{jaOeJNeV;( zJ(&pwD>X;^kx4ZRAlTE$&i~2_EfOmXopk~reNPglZjNhmGY)0pVPM!eU%*?703`T1Z3J_}E682>+LRyF=_wEoM)8B(Yk{S16?2BeJcdmU9X4Egn znOQS9GdK&SP*w(!5R6^xwV_j^-{C1<>Rahsi(XT{|L61bC2woY&ujUKI$##kM7dac zDy}hT*MV>ma71b#DyOU-&+ca;`k9D+CZeB(wx5aUN5(zKhe!;(awI=9YCr8(zh8{z zN^}}n^naRvCM4$j8@@jbJ~4~w%QPE-D5fU9g22-<+DxXwSDH=hf*#wuW}LL5Zp4uM zfLQ_Y0&)=?MhNBzd173(`cR}BIV58sbV_F2qMk-fdD$#3Me=Mc=JG(7@fN!r!3tZ1 zR+Ei`#h8QA9b>TFEc%ImB$EJp_hwv(nBv8XI^VOdMLz zPO`;Z`xK-WBK(PX9Q}dD-5IfWIM|rbBjF0a1DJY5$4h{Ad&r39eIN_K6H787BDo$6r=P`Nj`p zcFx0!btw@gA?nQ#%@2IAi1~6CClC%o0$J8nz~DW$;xPD2Ue0`AR3pllPjjImB0V^JO> z7iKJj!h~kQn1cBQMuBi=T&z=KvLzqj0m(rOq^}ACsf5#j!CqGv*vm67i2yPnF)ELF z)3%phDd}WP=%HYR*Wm})tK-FI_w-i+20#JnPh3EpAw#7IOG>)1Ua~bG-hp6;Gv59r z_k8=SJ3xmArrxtT*QPh`AS36-+`X$h9+-E{gx{8GNyHjsr9J=|c7XV?5>=izV_8rl z8g(O21FSeuVUN+WgOrwB6N7I#j|_wDW*IG2JD@=;xYUf#k1vg{K^p?$$+&r*AcZ?+ zx9s6ca+&GKZ_z@<;2WMNcS|g975;RELL-%Ec!3@^vY`r}6G%x|$BW$U1@86sJN$$D!*Dx<{T`}pNZPJT6=ecRCI+O?Qm~qCua?;0-N5sJd z<26*QuQ9eO%67m={8CkUi14(5*LtlbHj`s%!vH%_iC`(7%&N*RzMr6P&=7I6PDgEpk zt0y>yMocrLaTg0_%v_^IW1CfDUXQasm_@XWH5TR>?Q#I)n)Z%B4@X`*uyy6y;Q@Ug z26F9S0Nfs|&3cOmhqzB#s3o0WMBsDX)I9)mEu9LKVk^Zt)v32Lxvj071lp*ug~OSOPM9 zDc7XPC<1?#mU1DZAM&gzh+YTePKDwTw z=lq_ctUS*7P;t(OigT1_ob#dLT-zs(;%Vrm!kS2&1ODR8aW!5mlMv)=pau^)rMvXx zYJj{fHk$R9Z>>`fFTqT802>H?44wxZvU4 z_YKpJ-8koOB6RJxKWuw-mM9WcPxMpoUb6hY^;cZ|knz5H-l>Vxwk<#V?A$-U-}2?c z)xsx6iw8uxr)|uGukYEq`MD2Co+749+mFaizminSL_gGjKml)csKXH`1AY>yE-UjV zs});8wciyjN6kt+vcag60rrlz>xM8^6_Vb2;Pij@GFqVN@#5RD|r&l!&W%DMYZ5C~@K?Vhf^)Tue`-M3EPL)L9&uCM`?my@SXv_;KbuaV#OWH&ueZTd6w(Bt+|rc z?H8PO>_tm=?z>}-cJ%bQ@8}hEizb~gyCS)G;%zspzex;JYi9_>akg$I zEy_X>rk8h^E>h3RorDay$Uqg1 zu>%+(kW)B|mB38_D$4@c}> zwVbQnU8`ZZRf8g`?!91H+mp*CJ#}N`dUY@|q<@`j7QJ(?iD!_Q{A2r%Kd9~CrX#^U zin-W(XmnO3!poE z0It1kGyKoL!Isr0bgYg-5tt?L|G;t(ThqO#S_S4YAz}$P*Q#B z+Zj2Ek&r@oe1 zKJIkHfHxey;HLW{1vyg{sGQUCx>E$I#um+YUg=p_WH^#yup^|1f+b37Olop!R%&g^c!fHa z6f5o}e%Iw((bW_}3}33OBrcM04ENfLhbP>jK#35B>qYmH)Qbg1d0GE(KfuZ)Y3cJrpiFCXqCCbAkDb410q(mlGoKi|7*^~%lw_{PjLaGM+HnlV2k&XM_v& zg%~efr*p$PSOxn?t;R8PRh_W`o#ni4BMFXAe8)Ky7_`YaK%L_NbIBvG9SyyS=#cL?E)4}IJWY!D26KIe8ss3HQz_U$(rAx z(8doB^#g78N!RLn)O}V#{(&isY&;r=y(@ETr4JTv@#<=cki!zTe5}{Bif?zc=Da(= zf8W%4{`iiTZF`q2I-Y;DYOGMFfE;$^ZRG&?FGuQi`B<&yMdV|>8uVHUzFZ`ZGDjX| zG~1f(#~R1Rm&I*fTaDfe4O(l`C)g(1F1250zt!d%sgJbXrQcL-w9TMH7{|61m$yl<~eoOzCIpGlHopD(fnefy~ zX9J44%p+^VZWL6{Lby*fY4cp(fw{r;o*$#tma&l_EVzcpk4<0gv3xY zR_HLG$!K*RUm=p-vJu`A*hGJp>Wm6}kvEmKURAh+_!!0$X<904TKN1It)!n~Afo~? zuslJkPU{+44MdX4I|V_Eqqyh-hs&bUyJ|9^zA~~lvOQvp0HL56CdCeeSETL}LO3Lj z8N0{Xe=!Jx!51w4FpxSo2C_gX273@fi60#uniQHDnibj|GD2HDo=Et&vOz78pev=3 ze7o3DmH;He;SbpLRSv?rH41`cZO2%@%mDXvLs^ z8Rs;gJbFOi0M${@ZfgH(^Mz+PZjJZ57F4(%$kBJCPl`nw?S(Emt9#80U6@s$y216l zOADzfJA6kTO+)?Kq2hS$ILGnM(;R0yuM|tP1&$@oSHy1Z6~}Jp_l`p-VdqS$Dd)xN z#m+^}W#TSvnd2_!{o+xrRczHZI-V0RYdakwl+qSRw;*yw zQO(imc45ssQB{iS3lsCCDW-E6d@q5+JU?~WRm}~K>PAB{a8=dm5Sn3gqnJ$ducgPgH?_zbgG4^5oLG7b_+P#NUp~_k|6-pFKyuk^xLwg}7!sKr(a5k2 zmR%3vI4=4Ntu?pv-rV2Uf-C+}I~im=z3mZge%pN7Nn|;G2pYN-L<7GO3|ey=(Uwew_IX4JJ{mXx=IScTxJi_`BZ3?o@4kw&&7f0}kB2B>F6S(bPhi-GNj zmG#rI7C#d z9%R$Nf1EsJSdKr+Z7(=@TJXf-EMR8hKPY>TT_P%I;^-`|2@DQN|2;~+;^71^f4uSx z3b9*sz?K-rl9k1?bH7tfJM(3D45#fsP2!R4%Fb0N!4%A6CuVdciQwoG+{9IWHl0|i zB%#^#lz|Y7w4trJQcNQ8jkcL2g^?>=!q(3z9QQB=TIoJM1`rMMRbVY%Mf0iLiH1a| zd2c!=p~esjwX(fz-zrW==?zt!zE02bV&nZui;Wi_g&4_I$P5*q_!0xG#{BeR@S|Bl zJJw(jLqQ#vF~(YBJ0h7em~5=X0fsA4rL_~6r>Es41bBvdrBFs3)=7mnDYt5UZWUYC z+D)`RxKAQi=|C(6P??drb8W{1Sua9$+Xm#{OgSSYAnK74j`01)bmMq!f_H4_l)`bD zai!xb#`Zd`&)E9u+H~*Pp{a$_GrunVb;Y!*b9$ZK=bZXWv&M?!@@wNUIx1+TLtOpr$mIt2k*rxVs0y5CKVlVyAv9Yy% z$=aeimw;k99kHSkgdl)TMSW}7Rq-%q*RoEJiaQi|BFF02tplz;aohV}K0fH;Q(OCA zal%7~K6rY}!n*ZWp7raymdv{NlJ<$W&6@k0OXtnJ9)&UuvpM(tR|j*u%E#oq;@d%k zL{4jV>=f&0?qQ+al3|!5&_;7+CR0i1i0)a18JT6v04(9vFPNiMWBySEDOce{qWw`On(gi zulgZ{QRMXuilUg)M#2iDQU#BZoHMKD$ondOYL#V9OD;RH7&!4jpAra7&QhET4e`VpPa)agI%3XZS> zc+txT;pr8@tPxO)6fI;c>Qt=iNYCfc2wJQhEpc3H`oeMN+}GOr;L=MrAFWrsxNz?2 z{lz~aXdbJdx9&X5#tp!Q-sd&+TQf_!^0T~J24!bQbIsY694z4=_r6?OcCyPly*gHS zoK@6~xB#sUe1d9SF&OqE6B%dPC63lt=D85VUCWl5oswRt#?mYV(%GC(i03w#K&Oc7 ze!;RC1DWc90gOqAG9J(mVX%*X2m^B8Fathh0d_`>vBubqic2Vk{fe>2&;y7u?hDpC z%b0K24E)eKxkU3C08nSv0Jyjn$OeA~ciE5(oRlf187%Y`D13hirQ0g>l0gyb=k=}s%=G?~V)D`PE$?O;zA`B_y;qqrocb)T&ulFK)hP#$r$9)eNfZp;18@mh)p=D$|#t_ z5|?FF;@ywFeeaD|azk=&i+8s@wshVjZ$K6P<+jB)u7?FEPML7(1ZX$cfk&aP2u42S ztY*w`+F`4X$29|`=Bs@^%@r=klfZ5ueWa6Nzr*{L-+(inLamm%RKH71=E$M#E*+_? zX!U?RJm|&D>!B2XAl(Es8>}tEoWp$K4d^eJ7z|Kch-OA`Wo^OE0Wm6R_{olgFPgp$ z>6N$|$1+Y3141ep4zm{^$}u`YVpVirS;X zO|sOQ%dSdc{3CdyvjszE<7wuJ)3C6rwvW(*Y)JS4>42__%^V3(HXV z0VUY!*xNpyL7%UY!ajn$(;CRHwitDDRs&rRBWn3FbD~QZ^~qt$GaZxA z)#Q}uDalEx@#$YXW_r%{ofSPRIWzU^^k)5K{cZhi|GUw*WA7&4NWGT+RR7q2Q2){R zxBp=DQ1biKx9L)~Iv5NqkwTkYv4vd)gsB zi`a$#WM=-{R>zj(CD6G#I*rXvx8{*n2bJQ@tCyH&+JJfQJ6C6r?~xYP8N&gNCgH|9 zvJZf)Qb`@P5@~LNN&;H8z~a_-68pB@yXBHYZ~ke&|D9It%qwqM_S<=PFT!R!cJKa$ zd!Nbe%k348f8}~=54^nT-9K-8b=NLXIE}scGWK2w-P|)~1v(o!>OIGL#yd{+yza4I z;uhr&kLt2H9L%9)R~53eOvFFJnnHpZdWE3R6gpseJgI85Xo*yZY`~lVJ|geQ8D^y? zzqt^(4t13-m(d-Z{e)vOXZelKTB%?c&Pdn*gF~j&V0oQdt*S;9IjiF36fUum>wDc) z2tKwixfh%*uhKHWlux}D|#>Gmy) z|M(~3c;cSgt3DCMR|KQ2bFY1D`P5@3jl+IrpDEQdQs6VCT0Y8d*jZ&JD)E#u)UpOy zc&;%hBd@7lRpDEx{yZsvs1}GmGfGwrK$Qnn^~$;%+(X?)|Il&aOVih-u`Ob;g2ITO z64<~Qi>vF^*U@svt0Q8?YcJ2b;sm+dGk|=HvX%UUmF#*6RM9>nw<=yc0kHr>RRMOo z;H(9R1z0x-L})bx7|scZ?Pysxs*-**L4a80{z`RL<;u#nl^vCOr3-~O^(-kI^dmGd zd3R;`>$C8W<1Bm0@t)jN7+8BLE0k;|`$~2XzG75Gx6oqvIsxVX)a!zh>@}#g$?y#^ zUNXL$sRm&U?J3j%DyytR4gyyKqP>N3?670t13zQGcLFvNd5@YqTiSs-&yfXq9I4^L` z^ZX_>H+)rSd1z_EA6X*Xn@8P2M`>TXi6WRQsf|t0%{lzTi!=2F(DK~z!l2ziG!P2^ ztI_hvo%ZrH(2mB!0=3-7)f~|-1}qk`6~fiW)f{~Q?jQ=FpK-6SHj|A;_|`#M9|sTt z`BiqChUiV&NO|QRQd`D27zHIes;fSw!(~F%YG*Pu}dEwiS z-$--Z47BZWM%zwf^bK<^nz(+?34H7X4F>T(dxL3k+g-2`L$uKD$vsA-?{32|wzRgMo&g{oqeC7j_E4!PpP}QYWy4F)%Zjk(< zD=^s0SI`-$`@qfwd2nn6Eg8stBFj@VI_r3{x{f-Yo@|0!MI|_33@u!c)k=zEf@dLt zUVyf-i3r^XVevt zcrd)e;*f=Z!VDYY_&YO78c>)EF!{qZVKp4~#LJ;X%h(_cB1?L0Z~ak^oehnNfeKvx6D(PRnbMAb>3ALrNtBhh^GTAN}L&m)^tFpVLa_|F+dj z&)f2bI^)5c7POL60Mic#LEEoJpL+D!Bx|50kgQ3GVl$+9BA%?H!7UE=_02)=e&}H{0TzUq<7J+OLif1E-SFErD&mn6fFt<`UH!X1ZPa~ zhluPLSd*TB?=^!KM|+T4f7qn|XVG$)T(Km|;o=0%KZvtY$)2*xZbGD$g~!#x7| zCaL#Iu>qMvT#Y^TEIFngCOL}pk^`S%T%NrD3gtMG_aEghrT4$I&>jAT5U4xd&HKM7 z_p0=X!Taw+<5JaUuZH#LQYerOh$FTL1~QTs0~sNS!G2_BfXz%ozRBeXWJYr>3-Com z#n+O{QC(6*ZO~`g4Fq2$c#E6eKsbv4C@?S#zGnu8!4D=9#c+yYbT?Dk%~W=a4kWZm zk6QHS9yRu0N)I%)q@*Q(9zyD>k#0OV^&%@u$;-+`Ou@Miab zBWVEjbe9x_3ezGHiKUfdA4VAuMyX&jt;C~vDe|Y&qQs3Cj!=S0#F>)7D<~-%Ylx+N)4{1DhKMa=Vom5JBRt zK?iz-@j0+m5#5k=Dp?iU6w*mBT^JAp;{lcH58>Ug=@sY*4!sXuWwqlWoG%r}$s(n8GtRuW z$zgiY!P?>9roN`c)#m`x=;~`5Qy#M*RqwId>b3W)sRrC+aMBPt6uC`6{P06DHc=6a zRV46Q-J^5Zw;!F##^c#Uy5aTCad}_FAQb0LRn$h^-*72*U*3(HLtbmAElZ~Fj#+V)ki2+^P1^Q(H*B!!-tWrP~D!x8V%$S zt4#d1y$MgyL^8Ox?@w;Kvm}^&C@vDij|jUQ4@}^1=R0(iKb#{Uik?<@V%em8^1i~} zqZ-4q+P=BJq#OE{<5RuF@8tW@Y{6mE5w0wdUsB$;A&pUOS$W^rt9z8y@?^<(BNYXh zD^01zTwQ{>LjQ4~En`{(Q++;~sZBPbpUoEBf>}za&u#Si{9~O_jiw|}ILRq4hx%`# zF`LtgE;KYVEpvEg`k{&%)3qOQwazESQ};KpjI3F*p1r@Ct?JdQs=RNkB3CZP+>a;e zRfUHNSN3a2ryFX^Fb#92O`C#yPB-9|@z!DYjK&7a3>1k%1&>IfFFZ96=zi}}qHrPT zi;HmEr5WegkbkakZg_4@s5zvD%uH#0$n0H%m*!*YL!oRrKM2}}e}_r{MCi^(0goD3 zgV4Ieo<}s4(Z+~o<$^uJGcBJj#+(O8_Xv-bJG5-tv}OIeKN(_ub4##~8nKTe+h`Xl zU>$h%V6hP{i(l`)RJ!ks7dy8=nz7N}<(8mNRJXARdlfjOwszRZ*!|tmWo8`DKzCB5U|9XS=!{_FR_j_(P z_Hm?JKa7tc&Mx=7THMha&*R^KP7R1^12)qstgjb0=boQ74P5_vJZ*8u6zC;Y8?>o5 zbp>YoIn!+zwz)9e1rlHALF#G(*cV)X42puabVT7&ar2G2lOLWo?O_G<*Y6RJ7(+q- z40F-e0ALYRHF#}P8hw@5cr;JVY*33kKpp@%!;x}Y$1g60bf~+S<{pP(4u2|t2bP)fd4(W4r_t9e+}ZG4N@#hrcJBM!A&HT z%e1T1TaaA@-`ob}pwPag57N#h?d~!)rd_oXiXB#r{vj&GjFg|7DzsmB{~Q*U{vj3? zKKE+J7vh%yO*AEiE}3YEt-i2M%P5=GKPh_PKsz)?0t=}X!K+ImM)c6 z7-j%G#Gao4#YK10`RpWZz>>8|J*q>Msj}Ms#;}G=th}JMtVb{8$LRV!9giLU9WH#6 zW_^c-`J;3@`ih6EdWl#z0Tw`C!O{j_0Sp9_Ca#7qgdR9bf$342gwdpHcE#SLbKyPQ zjnsSVq8jYd&AWE((#GxD)%FmOf1#WUCHQ#EWK{Xoyfo>k@C*=x)WMFy&Vio6(c$7m zb%f(Y=LpY<(XrZT&eJ@<(k^#g5V_vDFfu>-kmoJs@6iH>+9O;Q9ilcz7dV$hAN0Hv zby9t0MRmF`m1vdV5@^;Tq8{PYT{db+9t^l$Hh&+ht^2fJa}1)AvBXeKmD~1AuJNY7-%%1Yl6RLR5pK|E-`=go@gIO-0v$x(uuLb^eq1np_!~&-V z&I)`GFckeDl7J6-@z?7*=(iggd^$oJqbMMK6CPbFaaEv24;`z2ZpHgvf`2x6anoLX zv-+}v+E&=_=s6_SdWd?sgzAW(R(xKzw&ZRX`tq6g-#lK#PaD_Yb$jfb z<(MDX7usIz3cGTW8PHt9IEWO7jNrQJc!n?7(8i$6ln!|g{8)j9S!pLqI^lfA+I?AZ zAn_+~Kmz0-9U{hXr=;P7XxiQlPqja(ZPKo4n+JY{olLc9O;E*$^>nS7?x)r3$7#pu zr)j6@=je9dK_z4lx_q943MvX_U^jBiGGJf62OP_ANMc^557?Tb_%k7P&~fZN0bLld z(+wk7;dmtuCkv=?S0=g6aHnr+y$hAMKx>hVdu`u^>`zrM`%;8;FXcL)7H@2!S4Z%-fstWbFm%$}8Alr&y1lj|d z#cd(p+R@R0t$dh56Q9+yKfa6a5y~X2+7B=aD`QXxC7OwX#VDTy4~F2kR)S<9YZ;#} z&TnyC0>qNc59a zn2}v7Pb4=!C_)BzEUFKDy8ib!k3IM4H`hP+)fBaP?$syx+OE)jWfyFJjQ0KY9Uo$a z4Tkmjd$UJPTAY`fmr}J*I8+wWs0ZPB@p*CGIGA*&eZq&87KCfwj{pH6f9U(U!nX#V zA0N`4WP$ves6hVX3+n+A0D|ZYsQfA)vL8qAr^Xc>{>)w0)gui_9;O(EhLhDe?ufqYYDA4(TTZfzhW35A)YY6^k_7aj!P7AU9 zT{yDwomIJM+Ctu`6E{@52D?;kOUHgi$2^7YK5SH*;yI{dge}NB^&2xzkphJH;1$px zUNf}l4dQ+X3&W2gA(woT7Q?IUI{;}9y!Z4VeqIu~>dyJ1r-(g0?ukohEYnl54|89& zRcrUHzWL|~?rKcOez1y0C9cdi8;&=QcTO-SIL8IYMQlBdUe3YBVB|fl0B2i)n9vmv zOe_3$0WX8%X{LVL33~ z7$6c9pTt07z8J{1(~z?-txqT! z=uUw(fosSC!&ErMTthvKYtZ6iuECT-T_edWv^?|B2ewUNej#~>D3OdM}aX6wq^#0K^^)rogjp-q$5@7ehNRP)KhnUZxjS_UfXdE>tK!1}RvLDxO$LM4bu($9N=|-(yqJat&*BaVw67M6sL+n?|Y3 z-`&4;RLu()T>AK!_V>k<_@v>p?rt3U%&8uAy4d>Jua;c4|La`um7;O&y=Q-%`!IKr zxMwit=dRqeE?MXMAM+S`2;wo_W!<4;jBRo^s7)+cW|(C<;yTLxHQ{={p<d z7dPTK18|bKbrLjRk)P2v7L`pgT|sVx%xAftLQU}L;9rAUkR}iEp5b(wKB!rpTbU-N zq;ob%n%^s;h7{BEjx3gKM2w&oaGix7=+XF3VMEmBJ>CH zNe=jcL@sY0Sf-d1Dh~$3PU#M9pDBX>y!x$Wvp!h)&)ipkyM6JpC3h~qX{qYViT-oZ zo#^f#ZWpy}PyX$L)!X0vn08dM;~s4TbeW)XlbOCIC>%5ND&DxL}uL6&3UP zl|~1ju<(}FXZDNor|MQNnW8PoeSE3sy5#lOi6sp?b04?Gw7<_>OfFXCf{y*V0ZE%t zR+~hu8U=uOQ3~~s!sXNj7HKzVm$;i+FoaU&vjE_G;Pg^22K^b`?pSDwXs9~9GJvQl5 zcus}t^W-C%xFSHbYa%XPz3o#mAh$jD!LzgbOu6mRfA6^O)RQqAkwGUeyjfQpa$lnA zYDeysVfQpY``lxH3-6eRIk|!IW0RouFR_Nb%7e1Q^)G0VIyG^+K21GGJ4e4*y-@#D zJE)-sLj*qH8h?NHaCMk|2An4Wq0dk}0o1njsEW_&KplKC6=|s#&~u7%`mQB#U5gr+ z-j^fINI0<*_QM{__|;~0l6twStI!IZn=xa43mzCiMk2x|_pv}|qHwR4eRa(9aavIO zZW#Pn*{Tr~<8s?y7RqSTRrIHlqTDxlnjY%1_OEI#_@(gWcICb~w{0Ju(gnG74)4^v zHdE9z%ahJu07bQhKF4QR4;&w$qeVgl` z-4*n>ZHVT94znMQD|d}s1ybSy`T)z0*ExYsJ9*1i*VRDN0$p3k7$*7F+|GtCfDTR= zQw9!%IOAu7`_1lC?O_4~_z@c#wR2oX$@JfR*siP5_Kk0g%8{l^&pthA?r)FD-7|Zo zc2%xN<7F4DB@TWop8N+qA!-#u_eur|Nbk}BJxSFIiWfU|ans+Kg|sKpeF-FTb4C*G zKg4yxSs(eHH8arZ`%N@UsOGG0RbPVM5LZ837mI=2e##mP2H&y~je(2>VCz8ki~-Cc zMUYE0 zYQpjpU7lp?5p?-(c68O93&hdwPaU=Pp7WMNl|T3+SU2$6t-m2KBs`>`ws?4Ccyb&%m!6rP1|4jAdaiqp=Qn{13oc1tZ!9ie zoG$cfsO@&J&>gdv*q~GXU~;-`jG0dfzdAB@dr2&Vrgb|vl=(CzQ$k{}H1J(}zkb+J z#5*AXdF|0b9Z^8ULvh3pv2;K=Dbo6BL)la+m8%9dQK8#{(^o~eCu{{Ltyz}bc-6eM zr~0b5mq%yhzJG0N`(-{o`&jPZ=S*KFigN45o-t*FXU4+0n;#W_%3bt+?wySr#2Dmt zlf7Tn@q>N~WJxjdWltCp9T7V-dbWSA-w>aGcn6DIA(uUI&|`PGltc#n6{^1-ZEoq6 z7O9<|(6kG?JphVR=6nqjPF&#(;#TFF!$8sy14+XGDM+%-nk6&ICc~q1NH)y@xk(U& zP?tmnaheWk_%s9=e(R@q64)*)%2$=t4>_*>w9A5fKmQVSQl754XXE7T+}})0E(r}8 zqfQO2C>ry|Uy1T}Ej?3hzijICV`)diLeNeJ{Rz_@y-`JDV>`0cAOe#BP`Lk!hCpjz zCd>4UozWAhK<&Jtc))W(Mt}^XXooUGdZtWRgf&TlE86ML=3cVE6$V&-{<|*Q|I+W) zSQ_q6e^=VmcwV*Zc}Hzf|JQz&SjJBtmwu9e7I3b5zgWz(oHRWe)`(4Q5>vIufS7~x z!}15r62{U#bIPub_~?S%<*e_j_p5CdZTgx8ijE@mx?x>9iI|10$(U+?4Cs3sp&HhA zQCTM34ZaS=*EF#U-0z<^jHZVd-J->FzYu>s z@tC&hdUko+EOl4=j!{Qzwzf|%z|vJa2yB|jevN=Kial(b?2iTfu7HhPqOCOu4?<&y z7uI=cFG_TX1`-Youv&+m_$TNs5{AJn!b%F{u;YU4Q?iwD2m=w9{q@9YOvrh^#-t zb<6p>UZzKk@h|nOOZ{u1ep4`+2mU+jYY1qxzNNZlb_4php@KT28Wk$diCw)lhv;M( zo0m#eRQy7S_-6H8`NKc^yizGYkA->rKL;u!9#{J!Sq#Y$$c4m!5gMhhz!-7A9$&rE zw?_oweo87;SN97QU7^+Y*7xZ81w0#yUc&a{%mKofG2>KF0P?q&xfklOdMDns37h>5lcRVjn+LWT$JxJ|*_kDui(6p_bY zyzfh|>lw|HtIGWuN=w@%$B4g+^NBtzBaNY;D|x^$v)W~t*#grmM)wh}K7C>_Om69B z^?f_-Y_7w6fLo62 z11zQsN|ab8c6n?~?CF@1rY3i>nDKvi4pw$K2NCafMCTw$Y~mUJ*+r-@Ak+f=hMa<^ zmxez_b_^n#O+q17@DMu+TS8rq!hT*j3WGC#m0KOJh)chEydw5fx8eD--gx)-YmUmj zZ+Y7(ri#|Ft7_>gXhRY+e_Zng~EK%83^_3QZF z0Jo55sZ_ZUiO%Ke@-bqH&d5h^xpyB1abt?(V2+Pj<$6^!=IBDz~b8$O=}G7AdR93_LPHLliXug2MSg1objOzq9h=K~b1c zjNOosN7NB$3IiigQVLp=1SMte07V(~s>0s;x#Y%<3OykuZZhO^;E5pWt%XVa*YcWR z1|F6B;QK!-Rga5O3gm>{j=L|NTso^%Q%X}_JFW)h^4qYQuFv}|q=d(>r3WgFkBbtL z)MSUyU=xXKrG!pGUm!_cQb3ZLguk`7q+F)^kytzK=Z_XenmeA9_n$3}`fyRI^A4=v zC!`pkhcOR1czeebM1<8oE>LImgM7i!?VIqUfx@MQFwH;PR2Wq?d=HeB&L<(AKsyY} ztrAJIq^9TL_^sn`aM#W(KY4k?gS^b&L+Ogq73!plB^4_ww2BJf z|DVWj&;Pf`FUnzCc<um~O$XzUWq9QL2)}CJUF8 z5bEmf5kfVbI9vzD^N6+Iz9CsvkB*RFavQS@wq~(9(ESkHENhlk)Mw3PVSN^Ck<@ev z&thQ3Ob7Ui0K>C2fSVbi?WttkjL=#M9jwa3iT$D?XV?OEz~-#7^to#I`k^99pq9Of z603!p+6C7Jf!215LHG&(>n|!M^iGHSAA7L%8BuWPspbcMHw6K1**InyEFoN(M{-du zZb`$x4ib<%_oh*~KOjywnWdO#d=N9$h3fWJ-ZaBM$8{-S*(|K8`j7Z7NkB%Id3WPOGc`2PkmOe?fu!NGDhq3e3KWFDYCokA7ofWpHQS zP5WQbU~BzKPJ3i%IOK{}9zEp_)rA@ETV7V%_lO{|dQJF>Yery(%lp!Yh%Z}6Dmc|f zi&LH5af4F5Nfd@iN`PN|X>y9cQdsD8{$d!?R*6SRUQGZD+hrD7iElxc6Y)Fc1xTzx zW}#Zfvs`8#bxeJkS=We{qI7*nnV3}uT=@^1$_nFQs3p*jKgjDrG-Jd=Ei@3{`2@aG zN{r0o0-bWdL?M3=Q2CkYz|E-LaJoLqTjrTHeRqXlj=Y?FC-P3xcE9_6&#K6(pP3GlVFV-ASTv9`>an+UP8y!xaR|98MIFPlj?|9A9H3t-8VQ!M@e z2nWomwPj_s2uqb~$if6csV$QF;_8k+D21k9tn9J2hpO}_O@tuYknq-B_XH>bJYpy$ zTu2$Um2^+Ud%w?NN${z^wjMpPBZNo%x9}vm(lA@?|AKizfCM`Qp`C;e*T)blGP#Sv zOO;cUbmQn)ajf+lBk>%h_1o3E6lD4->C?>D_|vV{Z#{|MDr*%cDhsei;&j(5rDX(!bhDTN zgy7?(-{?~jmyuLnHOpqGvmF;WHN#)vs7%yrBbAZj^yEy(wT^`em$U{UAU-h%vt5{k zBT|Ne!u91>ATJO{qB?aSM}fKz`cSCd@Auha;RuIkyv7s>g2yNr;)A{I71POLVhbjrgbC7OL9p3Vx zpeUsQXG^zm(5VOqwXD3WpM2_K1cc`8yl$4=lkkt7hnP^yxWjyPyoWgda>I$W=519q zbiQj+xMu7-?x2ar+e6l z3((nJqmS6FLogLwzsV@Y#|=Y;w5i^U&fhK7fiLhMMW}ZjDmCz95t{`;IIJds>I?j_ z>MxoCUtnHP^l(lX8h&MCWn;WCZjak5%ZFcG`{<*!t5(tL)wzAf`HN~Fd6*6!ex!Dh zoMZ7v%$-Y_gib_wusIH>uMY8%ItOW~k2>ti9Eb5J+-i6WCspSs4u@7+)uUcBvDCE( z^hfPA1d3BC9N#n+3$n2&JtOelUfCZM1A>onUyO@ZHi|#KUAs7UV3;^*ajpKxH)|Ij znqqvkuokq;odjBz@%>zC_VJibSG}-*eno0H zILBZ7HUD74(CwQ)cYd+8SV;613bnAA5AZhrKjg3C3cTFN%xl06~qflnNsevUY$^mA<@Ob|Ht$zb$8X)_V(1(b;{m7=8`8u*|~GG zwcVY#_AcHbyH~M`i*q^d+Wnm6=<{Q6!qH6z48|%=UM^Z)_@pxC<#MO?DcN5zi1_wi zC&`@CSw}aN!VNiOf7#=7CNj96eYiKh5}PaYO6AqmvJna;o|3)6W%$U>EVLS{BBGeh zS~sMdOQFMwd}k0J9(>8P6AsXk?{UR?1yXzi-*Sk!rENbE}x| zSeg`d$*NXfF>sY;aQDtjzqY48U)R^4&-KXnw`ChTYr4B_p=5tU-MouJ8!zu%!ken{ zjh*M~R-Sjm=%)^!o9iE_&-V{NsxIR`Bm1L}<09N$w+HikEGJnMEZyMyizI!u8l+~T3vyjCP*sl@5Pf`J&2_Q zjc7KX2v?B(vG(pWw~hF&8_}^&C*}G?Q8H*(V9s` z7o`&6wpzP|Jt<$sYZa@wEZ59EE~bF8bwE682Pbx zM=h3c>5@cUWkr*!Hrh}f_5-*U41bTS#jk;ZwY3fVWbcWZYC0X&)qbtRfsx1eI6pLy z-JSQ7CeoSmen>VL*hKe1hC~v5bhDsMiPmKhbD@F2arRwmbD{6i?N-okBS=1OHw^Ad zn=i1ZiWp7bpr`CWuosln1|xBuf6ZponUuqs=HBHAInd`VCZ$EGwq!yvxl)+hZZx>! zsRnnf7emn|g-=`Iigtvm?AmN~SHTzQRJk!9>!=F%_=}xMtJSNwWDQ1dAe+s{mf2$- zlcmCKX0)AnkH42&4G!zMx%-jKe0LOkEQxYD*j1H2uhYq)5E$R-Rk`fH7>hM0U@?)Q zt~NT!;xdQxtBAww^XhC(cyUc4G$)%5FG(fCkjoy$nUJwMTtRqJ!lb|S&M2Hb_IFB= z<1_){?`7{-QI|>68=@an#`Qs3AFuc{G29=I z6s~~;FK~9PJTCYm9EWy;_r`oaAT`V08&#>897Mo>mnR<~IlvxY_J|y6WFPO{N&W-f zF@ypSY?}?q0@OW;0!cg*5J?Ca|49HOW=qV6Y}jpa35COAw-<2n!qR%vKz)BhuNd?j zEc4T@q}pOIst04HDz&qwQgNj*VyZ8i`kalqxY_FRcb?stFjp6KTJ?xKqf^=(Aq&~l zo}<42S06b6P5*W*O{a0JMAJuVYr;5#A$lKBbXSEF^t?fID;@G^Ea>qX9bT^~M$SMC z`@VUT$$<>SyQ6ZsgNUt`y|Y*8^;k_t4wb(5cSoaM9V*4|kD5&0r)2MQ9+1*%&m*ip zFs3!+Js=~g28>S8Cmb8Le+H2ZULcdn&J}wZ-;opu(g2K}Ebm$@S|p@7(6$JAqLr@D zP_)_jT`q6V?S7A;tE#Gg}Jtx3606=}tSsI<*d_ z<_i9R>{;PUsJwec^gRjKf@;nSRZ5Oi!U|&$DJ9JS0_&DcMjTBqAc5>zkH@^MHn7YZ z4mCE#WPeKJe>ahvO}DL?knYFyhx!(v%QI&P^QeodC8>5=`Z7N-=`CtA$fCpVPfF)g|*$` zr0jdEwtIIwE_`v{ZC8n_ezkV-g;(EAGP;+K3PA<>TDVW_s=$=%K~dur;kP)Q*p;QX z(lvSUp_lz>+$icCdEg?vGX^z{#NZ*EQyr}EOQIgXfR1;)g)Y`&(b2`~Coi@Mme@hf zLKGFVi--PhlE(0MTSWMn98KRz{z@EIPw9MXSQd}P*zJ%k6(LJPFyFL6+ZZ#rJ#ybX zXYIAuc6R00ZaP2Z&<4m@tEv(hbh*f!aWD@;lPIpJPF`#(H)Ob z+(TRpip;Jt;oRwrS0h5QJJ4i~M!~$@4s~@1{9|LgCT49*>>4rVKm%zum&m|Uny^$O zq^6KQ#_hvlBY!Q9_Tdr@l;J#xFhzqLbyO8|7Mt*$wP!UASwb87qXw^E?MO6s=dbP0 zw{$I8R$FZdR5s=}T7nA2Syx^ci8eO%$9o^x)_(ClzvW#!&wloe;hMVU`Za3?zGCZ# z4Ay`u8O1o4;w~7w4y$!YA*hY{03P>N;ZdvQ9N&bSVh15O$z9n4F9u#1@=k}xwAuvJ z%3-)_%BN(9u@^J5GfTJ(P#ZAMxq6BR&>u}+SW4pfs7i~Ko5b(b2(Jv`{@{m#!IK6U z&tS47uS>Gc?75I>U$t~=*OIWWEx2acva<)8w#*yxpBG&**wZ_&yS=^pQ!Dv{KhzpS z)vZk}xz6zNKro$|w{HHK-Mt5@O{qvA=yv&C-oDO``PH=nE9sPP@*fCS%io7r734(G zU}17kk^yiSV_pZL7`5B|PvfrT`0Q(+dKT5x_YAMOC;1yAyA*n_vnwE=t=k=0SsqJU1pR`1=3n?@(Y|;wy(0Pfq;qu8GqoevB^L>+a-R$A9*tiNEo-U;i83(HHnS z;W_Af8}}K}Trq^}H`5)N>5eoSHF1u@MHW}%zVIv0K<%jUAqTthLvp$?qwH;98pzQp zjH9bI7-zY$8TYjx@6bq*JkYH+jp619&^QcSR#S5ey^|izW}OX@{HVd8 z-zRWm8jY6%`_YOD?S6C>>ZEB?I9-%9hIC?>T}rQ)tbr7wNBJ;sp615zyXO@P^XC!D|^4MJzi=s-u{f6$qt3Mo`>V2Ybu zX#STm|D4c3a<09)E?PZUXd33fu&jShQ?OVpI@1YrAOeqS5hP&SF62G? z(F*_SnA(sJQ#zm?Pqbl&Q0v=vc470%0KV*`Pb)in7dRX>O%-RzH~W)%rF@&OXW5+7 z<(qqb&%o3g@v#lJQl-sr+creTw^w#(+`pOMym`SsoE2vky~!H-RJDfnUoN(uv0>1? zwH<$y{&OF%d@k41JG4x1^!Y2dDo;OS!<^*S8hDk5xHDvj_HGc7#@Vo; ziT-d6KDP4W&g^TifiSPV2CtZWX4(f=pWQ|-A+#uaC70bsUr|UhGWo-kTRACYnfAl@ z9hSWzUdQ7~O4rac7NSh{I27?UUX{drnhy?E*ry^JoZp#I4!%d+V$p8txuO*Huye7l zCfG1AP<6?0)RW(&(qR2!FyIeHOzu!HQ|pNgS8l5mx`K03!BjF-vpFYJwzdpM06~)Q zIAwNs&>sj!jqY|KlkrBD^=GO&f-R|Va^fd8lhI}~8twAWdm~PluQ^-r#D7vDbcb4M ze2KU}y)~y2+ZV;Wg^avt(Alf7-^U+`qR+_VO&7e0Mf38Ns;CT)`@?h}4hRPhiwf=#7myz~rJv*q zJSrE$HrOHHGNI=-K=2DTFLMpFT0~NC4Pa|jHj_pR%v={5SC5S0ue(TlRq_e=31nAk zriz5435Ev>?9aq<=`cz56fO_*@|ep2=1Q2|GDoKO8~wG#a3H8}9S>i+d~3FlR(YCg z8?TeiyQO!lH`v;vE3bf$4`}nl*h~i(l8g4IXg;)2$ zJ5Xz!uo17)Ue3JSY;ZXPUQ{~~y(8D;bONPL3Ge^lIAKHE;8eVgJC5^Yh2x+_74SXG z5mzk0A%}Npw;bprP=tp>gUc0&!D_`hQR9X3M_77jtTxWa;RE9cIVmtOHPs_fzyn3^ zcmUa;eaI(4sKZ=kJjKDHe@(F5O!J!&8rZ1|4-!w#3N*bmdVsVu9TSQuAoOA8j@>u7 zYM@uQc6DoAx~@_YtjmmS^XB^fOD<@$d%k%2oVkglMwJW4L)``WkKTId^yI^L_}ncT znA(jO8T5^Vm7n>7)q8qJ{pMT$&u@0$f9p1~cX#tW!VL;6rvwdmh|X{T?z5jh*@HIV z)@YI{j@%XQ8Q5Xwd`($| zaOXL?`y6mD;J$!F@L`BXP&twTB%h2s>rl0{CuQ<~bW!d7N==`^hYdQut zduly3E3<1`J0AMZBHR2#ZO8IOw^Y}P@w)ETRImIezxmlu_uO^q#_c+L)R!-=-Nt+W zaO6dMAQvCF;fniGT`QNIGawFlU|oI$Iog5g)G&A1IHD^X)eTG3KNOc;UQSAkmPOSAmu;<+%k(K zK?{nVq=ym(@}{DcjbKfgkOmS4=`gXF0;Y>!(YyF_w=Wo+b4j}4!ojNk`E^%*?%cJ* zx9mutdD@2V`4&F?7-E?Aw(K1%2bK)4t#TT=>I*HQ#&3mIoN>e5yHDY4{Zlm3KS9e0 zQhrIf9D37$-0qJj^MA-E9iL&Q7v1oW;VEk)j-<8Nn9F3t$!s>#*cgcPcsHuw*bs3!>^Cy*TlmK&zz557YQEtdWP*Qe*Y?d2mfWkhF7Ud_mg{~4JqSQVfN zgsW4P3f*KXOC>L-vXsk@O`Jb8uePAogv^1aI+xcJsg#mi&Ov3JI#6Got}xgAe^8?S zdnKPD+o)pshu2sX%RhJ&KgVh;|Ace((WxNkuAaC@aY#4-Xtx0BWC`xg@rVJP9zKkM zj^Qy;dPM&O5X50jY8j1w>3H*3C9Q6gfc(&W`k0s)GvNsx4P>s#pfuToEgpPg-=z&#G z!~sr4b>H; ze-RcII_B4?x+mriJTmXjhqoa)11llHeS-v>^}dN`iG0U^Iw_} z?ijjb;{H2_?_71;vfHWetW0^E;D-Y#KYC>19@!k>E6j_eT=TcbmBa}&i7`&F;aoLd zFcAmj0E__#lu90Zd5HrAZN?J^s?HOz+!v*4t(jt53rMfSqZXuBDCI=@3gG?<9FZO^ z2&lFTyr>2EUlmdsT8qVO)_(&u)`0ph)HFe9!@E-iM#APe3eQg7=rjUGQClQefcXmi z&!!XYts~FzfAN?H7xbCjjnm2W&J&lkr4~QDIyZk56q}?F^0A=UN0;*d-k+3ng^307 zfN(Lqv|29DHFEEb=ZUkhH;l85codCzp*m2d&O4I$bXk%|)8?LW*t)u0J#jjp&omSZ z#OcPybT;!8pcPQVL|My-BBog>_D!*O()(E5J71V}z} z6Ffumj!Qo<%ab_g4}Hm(!6!2^6@yoWd? zmN+#~=9G^(rDdG*qsRE@L&T}x{yyT*z(7ZPCp{6xuDLyUBIN}-fWBHqus;jetJp@9=m$oQs*ilJ_?RAV?)tO<-cH|v$}DK z$M~BWqCt81iF@Ri37ZjZxiI@3;&zSuNH(ygft_NsEWS04uiah`cs}m)IsCx@i9smj zv^(e}my1_pHWP_Q74X_g2#C=hpPLx%^*RF~vW&2Y4ws!6t#>-Hb(Li^tl|I2I5-zRANd$HYs!>g|;VA(d`-I9-iNfQ4e>9P-CR)eikysc{ z;Cnb-E>s>#?ZNRFtpVmGidF#l1n2;H7p#y-)SgsqX#2ocFUkjl#v?O1QFbrjVX*QH zIs8O;SU(7Rkr2t)7YLgLC_3VR5+CyHX-h7@XmIYL)@1-3@4T(~>YJ__%|yGJmc(mb zng755zhS{cgB|l88sMW_FWE5IXVC}T?u6F8Wbm~$3zzo{d}-di;Z4G7I2jXvyM6e! zC&3i*G|IHM2`TV`07Ih{-&MQ*m=^~K?(L6v3YSN{9*ZBtOLlAKngqiwlTH0Y=jCRD|QimDT z438SEvScly*0LFaJlpKnX-=I~0;^cuv-_UlC2d0szQwzKcIEst#YFYp+b$nCwCv#7 z=VrCZP{?}W@K^YsZ~D?||Ej$A>u0X&+xmDM3OvF}p|0G|?zKJ~&k zaUuewZII&Si312_%7Tvphbh^gCix`zq{U~IePPSt&&b|Cv9u%LoL#^rDxjzS6|TVj zc0ZSeL_<(frg)1U^Ch{gqepz*P&bMNVe0Z z-^C-N93G+WK{+nX>;1k^T47C~@8KX92l*6euRREu8w&*5=Xasj|5t1iOY`Zp%aTY` zxFF7BdcCFMY0#~avoN}m#GXK4iEiYOFl`KqmId|%;umgUeM6*`XOmjNeVpK(bM7%> zDrpubrn0kVirEv#OJ!NVFsVd7m+9q-x1g7c++RdPZ6#XHvgBzN=#z~?@L4qVUg(~j zwq8Ttu8`=3eyw_Gnhssl_kzdd^shB&RfZ~ zY(T$L;iKtx`M|ICJv7)rdIVI5{NchXFd zC-e`o6w_G$_ZSV?mnQ|{?=l~XAI*>vW=WJX)`R+QqVD@aK0v||r%$YuWe0VPNolL|ch5ua9oJ!Y4Of zt%;U+kyz8%82`9t42YA7mX^?m8MCh0jM=n9R<>xMPH11SY6A?@tSA){{ZiFGN!Kaz;8<2e8Kp^szfJGsE z(`4j9L7ocWQz&*)3b|yfs5wR{2fBd zfFG6rS|baeQNR536{&_reREI$%?~CX9X)M*$dwUVlI>lOe(BQtZ~R|Q&+DnqV#~7i z=XA~!0)Z}FI)C;^(QFnB9fz*Hbnf6?8!lMBwql#{{C^$1{PNoB3*2T+TV20 zj6^)1l|-pm1pla9JV~|5+&haLVqqe1xtA&@KlJ1mzBp1{ySUcm-EsZIkAC@y8$|n= ziCDDh>dSv|+m`EnVfTfm_CkNl+4F{;7!3C8|hzg`$gAezhLPQxAyE1 zTW#*F(I_Z`!7CPu{(n~I27(Fru>aU@kpFql|6kHm;A$~{@e}2CZ2lPL&g8wAeLABm zjGb$`6jixb;V@$MY1OJTQ2O2z4r7KS=%y;T#X=JqBDS6mHuTgl9a=ar*xoZZC=LyY zV$VYQiTe5;dWR;=z+l(v8CA=}Bk`cGJRP;1PI*;+`SKCW!ibuPntZTdi^YuC)IY1SwmA>N~=8^)>yR|O`)-^mZ%rF zA2q$cVpq}_4q7q+jRVHGh@r!Yi`cLV3i^#0Rtc8t`SaMYN_7qD`8+nX88tN7Wu#s- zHoK#2#neF^*Tg-K9S}}=EFSXuOirKA9FLpLP6XF9w}UPzv|FfQDllhVo1_wopVwwKaTu$5e|IeA)1edX{ZX?S^{Dqb zuOtez6q!0Jyt9bHWM>6)IHmpxFrVh^P9Ovb8joQfy4YrEq`=5rsRu)PWK%)tr7&BF zH>{V!XimAbM(b2Bg+9OX2dSZ7=2qcz#s8jH+dyp;{>D0Isg1%OY;^a7?9@h~bkw|* zsR=KssSbs+>BwRrJ|Ux1nw#2>zLq-f@flq$Zp=-3FgNMWWRuaD%dHP;Vlj6%>vjhj z;We5d(bz1LhTmYaH9B)%u8&21ZdYZNh@8p9Y%U@)pc;wDQHjVv$zeo}&Prr9MK_(K z@N4KFD;OL%poudyZO&?T67vs%Ug;(OIn|_6BJ6SVRu%g*ned`yb?A!_W!9SlQJ&VD zGEJ5tzoPut{4Qk%PR9VW-=Ft-hva%SS7{^iEFf0~jav&A3;_ihTIgNTtJkB5?LZMb zpJp*hiG^?QPGZt>}G7emhaRO`>#LiPCMeP?~8r$S+hC(U#TIrjva}&k#hOQmrKI z?1!1JM43@iVqgF=9MijLA;u-|>7#L{JYGnRiu|r{yfWNmZ)w!I_4E9-&33i1H|@<< z36?-b)olEmIv9(6Ho$C#fxcU(l2z5|VyeoJ9=(QoyFIn6+G|AxSFbiccw*)bD(f*- zhsGmI-P_iLPG$9)m2l3>XXWQiPwo0JEu~Y7Zf_o{N;O?o5nD50t09@pkWR|{Lv&JU z=#+JI{R34|c`#8j57XPZrX~~hP(GN3zH%_zpwTjw59I^Hj{(JC(KRro^Zy8?L-W%A zlx_%y8p1y*|2Md^hH;ELDtKA;<>$C;_5}$zBxsHF@jsW}M357`h&~wNM5Ofd3c!pA z^6U$xpXagABy7Z1#h>@dZ|eQPt+)?U_ckC@ybgp4H5U|h6+kmoR0)+FR<|jH>`N~g zUVfujt#@K6z3H^~Q*v%mo2~dn zg{*>8V9y0E?>R<@mKR2*u1vbB@)be0C-1KUm>?q1_fcmSs^pcT!J4nEs*qv3C*T%% zrGn$JpFq0f7oY`Nvn?%vgUPnM{O_q3q%R5dIc$srMg#3g_DJ7zufP7>nb%)WFeK_d zzx?H%J(pc}DL63s7qwhi)YHPnO0BvQYt02Mug)GI8XWjBXmH@=14L5+3oJnc)MAJZ zuRr%3uX}Ei2w&(uh6;MFS~Mx-6(~DZ>4E;D#6Cd1Oj~-}mkyNP7w=tuXT0yU_kQuY z$u|ePq<5d9kswI{$g7ldRlE|?Ag?OXWJ(H%YXS^7UGO7(-^9KiVjFR7;tTxaCB{vo zgMzc{6(9*%S;9~9jL}jE3LqnX8zijZ&z<<}wBM@0yscVMA(sJ2rh=Et=r@TEj437I z51Y-54P|~$EG3Trc49dfQN~#pmsixtWP%d=*DH9u57Yl zD185eztLxji_5v!@h)o4FKU%?Y$D>6YLyI#mL$C|zYJ2pd;tH0&JB!(jL^hC(0F2b zZ)In1?|*%>7k5P0^D5p+&Y3YiDTnL|*_TNIoG;UTC~*<5KGRpR_13>_uf$%mqk+=( z%OUZa3b{=#Lz)HTlVyKQXNUb3H$vA9Je+5g@&Bq-e(KiJ-=QleO`+iB0x!?Lj9++x z-6+;U8Y9n5yp12<-itp2tv|s1Ngl*d1ojhi-w++yYAlG+>21LAwCjxq6)(taK|qf@ z0~lE&;LohGeWU(r^FDs#xS}!xTu=Ij65kMH`$Su`TA|A5YxSc38ogZK7OK{@Rkfjj zzfp91s$KRV-_9@OZ^5#THb)!R*68YU{lq1>_VE+r35D{$%N&@I;THh0ZvG$s@XiQ8 zcaHqw4{zWJH{bAv^a?iC(|2$*$y;h-i!SI1T+tCT4kfZXb{tL0YSeW!v>P=}(X*nma5NX~iV7=RH@3>ETbo+@TZNS!8#`px z9Zenm9m4RO^>bvgIfXerbA;ip^st?4{$0AIBz!bj}4>-h6@pTG*ipt7K92n!r^ zNtjm$xvKD{+Ozqy&!bK&eY+o{(+k_>?XG_Jz=EuPK0kj!-Q30XJqxl2pzv@gM-CWX z#51&-zHouzr_zfrmR>Zxv~A>t7e`)rZsf&nFXTo>3@?ssd-(#`A>?jxN)EKNyo?Y0 zJ`^-wqaQx-@=u?e{06i&-svU0HB`s8Z7(z#zH`8U^GiQEvJD?4sAzh^UgN{GVp;(M zhsB;b-U5j%qVojk`IN!ON3H>{VpU_V9x`j=!%!gfa&S6k0sB?FrXUNE<1xEyg`7(d zQA0RnH00_lxplAbT}Pgs_y*r4YhSl+;=P{_=lh+BwHF<}nO>7$HSvvC)*ZQR;?1}I z^#022hjzcRPI?i)^tngwx#z(L@44rZBf53#1Rwo4z0tZ?gr^=}dG=kt$IiRrz9ZlJ z!E?|3Kz`LL>(;G1d==j{@w>mI7rH*p|ABX}`=A|vTk|v7cb-~Z$jCm6>%c3r9giP4 z@c5Gl4ovLgyAEHq4u9?y!FkrVf3oGbM|thUUnk!Er}#?$y*;M?^Vk0;U2P+ z{9qJ#F#9ppXQFOx02m&@KzBO<;Zf0D$yz>*64FJv(gL8C+L{fybD9PQn%6h1%beTT z67n>9Caz9jx!}Gh{=h3fcy-r(OD{{l`TF~Bzw_-ceSVPo2uE;rI$Ygy;R@_4;SR7N zjgKrXa+Hgr@}E}(u$w;1UBTVJFBHRwd@#enN7I?=NYv{y2My7vk2SFPC>`nZ1*<7_ zV=%CUw##lm>zb=}HZ5-zyRN!wXMg{qMcdChYv<18U7Jy(9c^e>P7kfENcUjcK>^ad z4@_TkG@{K=Iwzfuy3io^{wPqM@UT~mM$c+mbKh?u<2$8|bIkPU>Tu75B03vh( zUd7J7fUB5w(kJ>ZD>5QAGzEFYGDQRrifuS-2DLuhLeO#e1t~kn5_F|xXbMPz^o{Ac zI|c;=b~9F!FG?l05~d5wB4L;x8B#a^c)<6l*9lM9Og#faDdn0l_(*j(B%Gw`8@&x1 z;w%afA_kU%iC21&-f8MJdPPAAD{1^ycEsw;X$z`o)aq9lpKhqON9`JCAc(x6%;ybQ zvlVuAg)WB5Wu;TWhZL0-?e=-CnM7l4d&dr2;{1m5ulvIza<$!zy1vz>>1xX4;&YUO z5-+Ii_J|=6@AQNf%}SZlZt==}5rg~io8}dneArg3_p~S$SGG3j(#c4ZCb_9^vs#Nz z>_Xa<)@W+O%Muj{rMcQ2tFRn?IO?yDIm4bg-CpOsmO1l-uAyJd)93Y}WGJ>|$&O9M zT4xJy3|QjEa55ClZNK2_{jp3s&Kr|e)%s8>8gkz7$k46!^8)^GqpB*1^HIhdw4stp zF^&$4g}+kqC3K9ZxSK^CXR(R4c1+tEESgG;^BmZNudpT+80CK%t*ivp?_WeU(!+YB zhvOc1YF#~Mq|j1GMe3wI(aOTb`1^uVIQ#PTZd zJnaVl;vem}x@LX)f{Bane-4xh0e{NFD3j)H2Ow-JO_WKeSTN~i51dng=6#UGtDv;%OTU;<(eR`)(Mr_&J5wYbS&T+QU$grojHW7_P0#8AX68s#@`b>%vtFA$MKpIM46Lvr@g|C?Y zx-#oXLAU^t3-dxUgDKaNeqb;U=#YS9Nz>2f6Ux+9Kjw7T`3=^FIcbYmqxMH^sga<~ zEIVGP);ld)y_ms(w%O`$Y;)UmUX#b9(dUIjKb%#*hDp8{^$Og*`;nGmmb8XwmWCQ9 znx)ZodK}HZS)y41KNy5?9YZ%!3&PcqoYmB%(-=H3jn>r#o}&H;kZ-!Efo_!jpClkQ zH5^O9KNI~vlzbDLUvE66xCvVYwO%pYHn>UhT9aQbLTn;$Rd%b3O<9zbPGOc9AlmY3Ji~+Y99$| z3Ue865DE{dI)lzMLcowNSTP0XoBc0UR-|szX@FVmd`rf#P{h$D14pXRs)RI463kTM zNyJ-t`tln`J9~0VIy#JvJL)dqvTRvu;SF8$Y8!`_$9(NJzdP=!UNL_bap%wY^22-d zYPa1M)_U9OMzWhyb?2Y6V*S|*Z&92c4MaV4IsWLZ@(+ts=8{d=$t+I#sK_r-{F!Nu z`<9$DJW(*8za6lBq;LUF;_>juStfOjue!R< zZm;urFs-BzZFM606zgcxwyy3tYc;7w-kCC3fSM(U(dlaB&-fxmxR_KbXZo0_krS$k z4-?+mY}c1(q45cg*OB*Tr8C(v*3$<)G6xv5Z|z3~m1$y36}%)`W_0&0Zduy3vSW}b zk)=yl5`|Z;#DcMo4h*%PwDIp5VY2a0R4?vYuwb~QWw@iGm&A2=IFdsn+wskSBeOIE zLb;U2kdA2v1l^Be#Z+q`zIO~uDDooh{_&dy8I0~pG|wqF6CS=}7Pg*Zm*M7<@|*P^ z3UA`{40FHR&oxQ>#(*Er5jqj)6&JJ(wV=8EUD1f*J#l$xsHNpY8x)_JYETr_^V<6R z7Z;0*TUsz@s~B6n*auU5f~Lh4votME@z`OQ9CjkTbu5Etv@pVZoN?-SVlcB3r`*!` zVOIZ?S{@HSHVa=*p%;?hK08xc=e4X^u@Z564R`B)PS0#VP)unOGo+1Jk|sjj7Bv82 z!On<$GHEg?$xW}M(h(lXO;?93et%r6jRP(iOxqie^Oe}mDG=5GjX-74mJYs5#~L_> z8!##-U;xt7Q=^n0Vo_wx(|`ufot0`+paZgdXD17+FFMj0U2MWlu)aL^8TjmEeJxyW zR3XG$q97S!FQ?52)3NmM!3B_^I*OKGxnk+J#_2Rje5zN#{#v;8KS?QUH+7qPdIVGB+sSmvk7N5f3Z9_{U5Ue+sS`anwUOv!^sftx9F)C=i zhC<ZX*a3AzFQSeiIz zCp}&P>VbGudB0MUFUR9sET<>yFHul-!)<-VYNu~a?!tRs{hCZ`H~XusI-k?x58gKM zuzC5qkhQU{Me)-TF%PZYvF47(Hos%|XA3I3E0J4^v|ZHp^;^3)@Ww6vt|FQ|1nz2} zCLK~#Fgc5GyZ3XBlBV#Hg*leA>Jn)KCYO;R4EaIG08EYR#01?dmumw7zu#TL6{-Xo zV}K)~aR$sk&^Uw9XrnP`hITVGgnj~Cp=pRh)5%F$_7Xi$rc~t75)p;dX8{wE?<&#l z@a3~<7t$*wdf9}};he&LGCMTP=x5<}?A4usY~$>t>Lr_m{+d~7r2<~8UQK412xa3` zY{GUL1kjX_VKipuahyhmX=a&!zkK?BG|m1h`0}kLr!*01&GOyYgu9p)lI|8MFm%(Z zfl&3js8$nlgn~Ym(UB+)W5y*kb?@T7|7$SR4E)#@TKGR~N$ zfA<7pM6M?53YBJy;MSDS=9CJjSuT>Qk0e>b>C@36W)&~RS<|5*K7x#)2qoN8vIX#U zDrkQgalyfj9?J!B5}QgouqUAYxE`4Gs^eg(PDb(%1*9rV<1~^^lgSz6oJq~;0-B#r zJ${Cij?JLhG*K-}DrjO8u*nbpP8sJ3a~s^fqAnf4Frp`kPnTr~-k!lZq4|KYn*@j} z&0-0HT@BnLvIP+!0-0@cJ0Zl3DwXJS2KGI$nXo z!!g92<|Z+kB;kT%K)QcAE))3%1R(&q5>5q;NvK%%rTJHWWE3V|dDp5t_>m7oUnFBQb)T;H0uP-^lEdyv-8xTlqB4wy&npe)O{>i5&)J#Q|kF5;HxrNQu*Z0 zAg|OI#?En>#>}Lm&W5_di6O2|ih)Ed`a7_Xy5~PQ|I{&$CjRrzWp@%+xTDWZVjZm+ zJt=sZ<+NnUD zeJHwF`R=9j^}q>E7eiD!1z57NlcJ4@AAW$C12vsUa8FspLR#tXJ24;sw4C}uAp)(c^KwM1WDxgzj=oI}MZP05Wpo6ELgvA1C-FpGmqF;o&Jur0~L8*JA6#Y?g>( zxjk4s|No8!nhZ`qjscQAGXKFr??*O3^6w*}J@Um5H9(Th-oYr<$$eYYg~(>3!VjAr z=CMJM0sBb~jfln1buF64j&!xdPR7{@gN?#xV;vdn>gpo-){W@6@4zGWfRqe3)M}93w%!)wV@12uwBsZ6Z_7FtA|C4X0>#jwS5hd5&aX1F2<~ zd|cQ)M*72*rwX^ntPY(h#tRp>rj%=d8)?>8U^wd_hSFWwh)||20ho$Jy(k*%tt>CcAbP6ui>S9bp1<0ccf`e=#qRN-{UvEk=^PAR!_hIgsBiS&*H+fNf>&=f%5 zkivA@k&>Ird&=IQ5Svz4s_km8BgtP|-*$)o@xEq0+L?~EMXOEvu`M^IzrF0K&%X_y zb@IA|N13KzUssr+DO}u^@%7kn$x=K}3pTadSW4(%xzr4@SIJ~nHD+zC8Y5l59M|sw zk{GUEea!VcsH+0O4a?xrZA=<|mV%h&hWLXE9_Z(vJkeb#zH!I!9fwTE-5T+rd@nZP zF~$RidncR^%)tvp^+$ykJRx%6?it{Kfn&h|iAyCcKr;I5KbFpAS*fWq^EBAMlR^ER z4Be0JvwUAR;c>=83Ez*jeTchLRNDze(MBMOl_0OT;xa*myw*iYQojcYh!b)YrfPtJryVGxvb!Dq;d^8w|X-#XEZ|hvzGyneK|7T_4 zeADe;nR~@2yOw@#-KyS>7nZcI{DK!P33I|NXPlX;_1fy2lF2ReJ?)ngSIb_7c9W}%h9RJ? z)5j(f{{bf)l4cW-cV%@aobXA>>*amNNgm}IJ4o_o7c;9$)n#z{ybXm+%omS$77AUR zon53D<}d-HN(^dM3^v_6>8+n2@hetURyG*g3eI?a1BqBcQX7RrXBah{54dL$%lY(;UdPX>BhIIV?V`!aY<>F)M zASMY2n~;Zs4pQl1!Rvs?4jc^&+!r0xjGZ)$hdyC__rcM0deVK-ThUsmXkY&AG7uI$2#YV6R7~ zbIHmwO4|g$l~4u{SeI&{4Y1C&-0Hn1v!Y66He(2bB3;&djJ+PCJYPl18_v=0v;w=J zF^Yn350)fb>PviatN%G`m{Ti?f;CZS^zQjzNo5U_KW#YzoKGZ~XsjFiR zt|3@5vlF7D#!oh0l`5uP;LjH;(7%<|iaj)7B>=o0ZhT&&Ad&8YRQ z@~M`;QLz$uVolsF`#C>wn6&_Cjw2HCHV=xVx^dSS&9p5Dn2_ zQCY>i9X^Z2XmmIX)c%eEEj)}>Rq>hfp`U|1Cre)-m4*MydJ^Xy2c9D379v@D4uVV5 z1f~2h(lJGvN-9C)$Kq`M1aSx&5b%Wrvsf+>SlKr9lCG4$amaj6_nhuwlg*;{8C-2j zx5Lns?MIin(x(llvB~_&y3cO9p{w=2jc4|+U9h5KE5@o{+;~wR$`j;zcMFC0<~4dwp4i+mQ>Kl^4uUrOh9djXstqlVUCT zp&y$&!prl~D>eRcSX557{at+e?lF8i!Pm&;Cuu{Eya%}3Umd$T#RISGRT{Yj*!lA` zf=TfGZ1_P-3!zyCFMRZW?ZxwOIKdTZPz!sS$;}vbI!jpurD)L-bZJ-{_w!r^uNOHE zi>}ZwuF(QbugQ;|RpbM)%148=pPyB68P*U2mKHb}rRWjZ6l5@26&LkI3Cw(!1?Ft> zkNFU^QpZmAlN}O<%g-YEqC9Zqrx$#8^9?b7v#00u=#rJ|@95~S8#wcvolDkTc*c%( zYd2kx{OOvf&icfrHDkB_HhWrj;@z(rz00>ef5lmg`$BVT!}BlMwEp6lvsr5l#G6`+ z8FL|)^xV5RwPMXBH{7zg$7`oqbXIi}elJ`IoxDp_{ZY;<0`QAL&!;FK1$sV@I1u|j ztK3zxgkLL|!yIxdjEv(3gWYVlgHYq>Dzn?Mi}4^rvpf<1rJ4 zWgvdk#v_CWUqD+AVb7Il>XT?nb2*?Vt3poZN2H8oiUsRLTWOaiN)svW*yZr#mW9h+ z8pU52iKOiXEUzM!c0pU=_dk4k^S8I&(vTcVY_5u0T~4Fb-gxzJ+uT^#)_BhRhaS4; z(OmzWMd`*zulfC@KbUy)0i%EAg+KY!#UrPs*M$P%jfvBf*}=My$JEvM#F|an`tFX! zgO85%I<=)*lS=p=&_1@p^c{VbP{NIv%CN$=jb*hw(#W(Z{@@-o2l9M{ngfP=^eHL<>mSg(i} z43UU!QQ+!;ED+#`+0=aV{;1tvMfX8XtTYx&{KS1=1RApwQYMD{Ou83p5R9`-7{mH6 zvJoF;cyj2c%voW}XF9qTMY@JJUcYM9P~Vb;$w0#7F+u6~ z#!#(zP0{GQ*R2&0n_Tg4^4 z6b{?u@&t)$b4gT7OgO1tg4&mw!zLxTq@E_3QC3pNvE!pDD%tXR4-Lw)r=+czDSrQF zA6;ch5u{wjI1uE}{q2IdPbO@z(SsC~(Q30%k1KSTkw+;>4!;{ZjCzWz{3Q2NZHmnQ z0kv&@D>kpea_Fp9bkm2CIOl+ZpgLBWm7|~;8Vw|*?qQ11C22mHa+94s`0zYg&#W4b z(d39Yi<)B*GsYrISEt-&8~$1sbjhi_N}b@%EEKJ2AmWhI>sMW7s?!v75;A@K_Ql$ zwUcT^f!l)3Q=d~@2$~RT)sy3F=@eETJU@nN70T_ej!!oHBChsF*inMiU`v$2re_VC z2@uE+Nul}gsVX~SIP7YQ0R8x{qp4H`X}IL~^$nF?8~PB|^B zLuwDSgV|&La0&DsPQxVG;2AKPVfhM412U+0d5{{ICap*uZTD;_2#5$jUh>dVe#7C- zKmX(x77pj4rbNoa2l!^$?=CL3xAiPLt0ua^Y|n;*)joyyvn%dAH0tvAEx3N=_QeVN z^3~Dnt_mb;dq*~Hzxd2?-STW>b+pcDLd;R7p-uQ%IRch#Qv3uobs}4HQCZSpP^>PW zDy$_R0dX1@9v>XVa6D6NQv#;OP&k<#l}l-)A*x_dp(Im50dRaWdO(l{Ybu2btgBp_ zJ)9&Ci+!o1lI$z&>?An|Bce1TRp4Kn|KI>$edO~pt2OV*g!?lM^^L18?<_v7^Cx5O z@CtigaT(ez4-G%Da)D8)i6$4`wBe#}-S-P#9*Nec{fkVvM?_Sz(-mLEGaDC#|DaZD zc;{3m7%3^LvyZ#o7<4`6ULhmCD!Cm47n(7jPhl_LW_a>8p?k{*2m(RN-Y8YY^aV42 zX7mgI_+kdX%Qpx_71fHHm;Uj{1N`!~<+-otE-bdKT;GsfWw%y0dlCyhiox4YzxmKr zPpI@xTm7XQM>bw_&du^g@xdD3JeLYt@0*XFBY#7&9e1W=Ij5hE4OQ`~lGi{H3F~hT ziUa{Oa|{D14c3Fw+zhakgJYs-wLF9L6V)p>@{$u>u7IIBHeH0^wMimG6-oJ}yxrd_}RVxnt$U-OcyA)ShH*x;g4fD?+zR8}Sak^xTG#Mav(%00P{OMfUZn7q7&)9a(MGxFKwyRBFoeBFRdW!SQys-(tz?q}Tm?+NNpBb;bK(76K z>C{b4#^^Ampuqr$(-+dljb!5xp99Z=T0qK4Q`EGM$Nzdn9Wg>od)-x(m=XAwS8FgIH zN!L^ThWAdL(n&Hwa;e2+-0#=n#FA<{!9>g+ObzKO-6o<)D5P?iDH5Ng$mF>#iQx3Z zJ1Kzd1ed9Cl2hEU?8@Pd3wJE#Zm_aBxFhp9?bWidJK=?j~{<*GedbcDtF1cHCjV?<8_5R>}m)|T$xdVo+L9PJRh zzlEGoj;lxQsu?6oA|SGQ^ls<_)T%jsrBXy0Td6D%bb_b~(13X$P(YA$glZa8t^#_L zzO~S?Pj*OD2Sl;8wWYVOySoJ#AmjQzzOQf2w_q=;arg(h91edy9eosX>kCBd3;>Yu zmKh1{8njKlfus_-Qq&v`8;}F;(Hl}WiS7RYk~J(R>q0=#O{wUn_S{sy55EsBTV5rr zj=5vBN*2b2US;JI211B)Uu3v6Wgvg4_elv8!=Ocq#d;g799$mm3|Sh2{&t9J0G~JdiTaWmr?;ez0c_kV$ z^nK^rHMN%rH*UGqSmnl+&aRBr$17a^q1OY~nr-1aqh6*g99cPY^PsTEIrp+Ab+b2- zxgcOT{1)ksvK-iiUzc-HY}cSoKrk%j5U0LIbbJe^lP`tb6uAc^ zi#cFM(LZ7cdnR8x*mcd;N1xqvk<*&;Hw2>2pus$L|D(6x=XZpInW9l{vHPQLOO?J! z=Jx9y{DTjiwlw1FUGT->k%gyqpKk7I=xyv4cU;vht~}$9qrd&OZ;%1G zaX&VBzB=adQ;XN%M6=PEzsY=)Ll$uR2@Buvw*% zm-6+@L!$H}v)z!1cqxAdF_3+*{VP{|DVIc=uB$&4beTj=!eWSf2h#(YSa)zCak)$loA5hOrxbSy z{lL%*bC-x}UjXS=Hysz2fx)AhMln5}04RgOuqqYvj5)4se)f6-X0t<~BFut4Mk`dQ z3f*Az)^F{KmQ40p%Nt8$kQ=m0D&;K~qP;&eoCB7`j)x`xge zXuj;Cd+%A@TTHjET+}tUx_F`1ZI9IkZNA90=-~8)TYHO7WFj3aI+_g|hc4)~H#cVM zH9>2AyiHlw9k^GU@OyUeHyu4!zC(TqEN_JS%6_f_vH@j*T&h&NbWwYbpFT+*B)sJS z3XZ@!g4Qr`*p0+F@KvQ$q=PSwdAYqmB|zuwDv1$K$56nLbifdw@w?7EP26GcS&(0g$|Pw+5GD$`@J)57*hW2 zJBIE!te+Z$lz7Xo&L;eCW+w`KmCPY*1FtLD)w4Nd`J?D=jdNQuS}g#!IG~7CTCIq1 zszw6=pw%1%uAJ{_+zHcXd)=Ha;8)0@>}aZ(_Rxkonkug5!k8*nA3s%0iVOxp`ky(N z6by|_%J+v%4GTRVWmuSxeuNoesBdAF{Cs#*4O|!ZRZ-ten`N8Rt)_aN*PEuK+g`j7 z4yV&(5qDQs>a-oiLpdt%Iy|D@D_UBcE9qf!k7dq%FM z6g(EtUx=s7b73YiI+-@W39yr(K#$@(2zi86k$AlN{BwFQYUon~ye({VQy{An)fIM_&(d8+t^Dm9zTy?aiwce^R@IP+uou9AGbebJcXtDFg=`b2> zkB8lrS&L<4Rb%kTpo!v_#v6BI*;QH&CBo zFDir4JnN*vOJ+t&iH=()?iABa4xf1Gx=Up*9|Ab!FThW0JaUA!PWXX&~}`kokBbhbEfZtIF-uSKV>L(qwy?j&u(fyi z|FZWc@KIIQANbv7pCmJr$x4<9*$4w)CJtdrB+*8 ztydBgaAeu^9&qX7{r}&&CW7dIl*((6bM8&@+S# zAqyLib7nO|G z^sa4{S62!hzA4$89;v52_rdf)FmiR$casG66CnDTd7>nN<4O@2k<*fE!}|_K^!<}+ z>aMTn_4mr)J+-ytCtg2^V_{^FO`sm7Hv%r%cV*&eO0peTr*~&VXzxjA|l34W%F1YFEf%C zI**?%np)c^aBN%Kiq>U|my!tLZt2nmD=2X6;>E2rrc%6M!MF+IAzyQH$JJ0jAY~>F z(Xr(x&hcNC&+{pOWq$s+IfB|V#^y9UB;LbeQtzREOm5R0G-=6gZB0v?mM&YCn?Jf{ zrejV@n%^*oQW_d2Oc>A6=NON{sXK+xL+5EU{|BwWX^H;P)6n`Eeh-#e(WzA)#QR-q zjOL^7|_Mgus%2f&UQ*XL#IN^enO2!)z+U&D2V!)j@0t&~i-8 zCrPn>WcJW#NkefO+6VLOF!Vs|`PEg_W>SYlHw%`ZVg`QJ>qt^5&@<9h=>ZieKq`(x zEXHyyIOZH#kY5A+hr$zA~|7h3s1Q}Z}R#v z_Hbrm!NG89X?5|M0*BWY`c%MOoHobavw0w2X|Q^WxD|aJ4kb-W?ZOq4RL{|ppc1;G z12qcI^^%}vSr>!_VixZ=3c>R*?Y$a38$TtqCvg->SHpruB&3TLH7%GkgHFXHA)P&Y z3J&6Y_s$tJ7LbspPnqIy)6hP`2O}O|nWXN!l#>DvLK4d$iIuowMCZ<;qDf>eGa!}; zixxG^ZfKZ2XAUCWA|mVVyVFAvbOQ)965NQ8D}AAwv7RzsMgtd>l@z%1&YBtw6CT*L zxTpx@`Pt{eW2N;m1C{V621uI7y`^ZKb#(}tTv>@F8<0|3rp+7bPrwYMmgb?o>PPrvFH zt8QJguzci>?`}Hx#?~{d3qBjUS)yMIO9hUQrRwCyee77s#u$iJVzj*c}5yLZ=#H2Qnuj}hsaEEd@-&+6k_TH2eM z+7~WdilxOyqS4;|rI@a6({v$D-{&`7)PIBoL8{EjAu@EaP|^)#03mZnF=mKt+DwzK zU#jIIEBKGXYJN#3EOM0af?u8u^Bp}lA^f;9vS*M&vS%mq?qAF#8pNRGt^y zma;AN@t_(qWTi(jWR8%VTSm&VPk~9H(4;b2sWHqx(Jkx~Mp$?6O3RJ}v^jzu36Em`s}n6{PLv_VM! zp=mozEQbrFZj>!^7q@gUiQ2Ito7N1ev|Rju!?OJoIs7+F+{B}Z-oI+&t~|P+Nw(ln zwo0`9;&5w+Q$S5?x4MZe)`?)Uk+fz_2Zej>=r9)USSZMf8KXUE2>%aY&?{0 z^VnXpY~6~utxL6hw=dws|jXlK4{n&h6&Z~FOU-BPt$Fy_;vPjEHiyyk77?( z&*Od~?%zdm{|9A${yYggU~{ZJ0oZ&L$8M)R1NVRXzrhY=&P16%v|oraK8Tn3C;L*| zzxRJr<`<^OPCL{Vv*9%BKor{PSd4p2WyS98&)|N}(7glvlr#0cp?-(-<8VJ)-v+%LmDjb#2uCFg&of4O$zfAstxJ-@6r=YO*F zKUw;pEdBew+yC_FKc`3R=RBQ1VY>&b;&Rv|ocJQ%y9bNY-B_HS^<(iiT%f;TJ>9$g z4o7kZmYWV>KT`62Vt{4P)Tg=jNAGqIH=tKS1Eltpe40kav=Ob0korhl6Xs83hHaU3 z8ScW&={0q;>@y=3GwIKkJ!SJFSy!BY=C$>ApE-77^YVi=cu`R~8*UwEj|0D_#7IQ2 zPkj(u4c^9D-@m{o8({WQEUKZ^o5PEEs;Q=W?lD!h^Y}Nbo95Nv4{6zB$m2=17Qmq2IR_6Bo!*lizFXhR3wN-Ox*VN8ys;Qbgr@D5Y{51lj z)z-|LH+WU7*#CKrUuysEe>UPjXCuD+-unL!xd|d+uflZx48}Clf5NOo)L?xM?6grB zann{|kqw_7y&vfce?-;|-#9I;7x}$ON%*bx`S9y^7GV#}pZh5(fc;ol zs)3jKy4KK_q<#jIt8Ib1v* zJ@~C_zJ3Ew;XPN+y5xqxKmDCECNG=Yaq9l)x9@tKFMF7;d-hj<+gn~c_IPk)>Y>+d zOkuMZIFf86E-B`Aigw_pAI$<>H47pDN=z1HVT)~6p+jY5d*UnzX(E?tf(JZAe801R z2yXb3l0e^dO>UpZqiOwajG)h8<(Q`Ib1_&*4&{^QB!=as694iNi9NY_4S6E3Tr$jSEf`~7Y{C3c=5#xmMmR(;Ux=}$jJ{Em7jfJ^F^^#?U_@t;w$;ljx}pG{QRNyYuY-#Myxr0W@1wG;`16WyNWw`@uizD+i=_H zrHe=_zYT3U+jc)I0s#qLXd@6;-V z`*$^u0GM1Oz(}N=oGC>C2!L3G8T$`)ZW^G>0DP=9%mVCY8o~un-qq{}@R1e>0K4x> zPKgAXi+mprV^<8EFr--6R8H$?v84zz?KHtoTZt_F@oNV#KO~E){FQz%(9|-(v{cCU z@WTbIzpIFBJ?Giz+D)~43P%2D%L~UZ+jHIY5$cVnzw^yWKXgZ5|HGN*%s-B&YTza}M+-TNSYao&`GwqmWL#SpYkhsO?yCMhM4!fI;>g zd$Qf-&d9+Zf})fMwdk2r2!lp7O&RXb{69uNXUE=)e(uj%|!3`Bhl2?AKI1pdH_i8X`aStSTyRN!|5*)LauM<4hF~=Dy8aoRP1QZ( zioso%m0q*(((^@KG(ELN^J4Ht`z42_Il^f1#@xec7c}20?w4t3a2DLdw;6J;6!Jc? zl8MrR=D`8Br6Kc4LQm!wS3Yp|Yp>WZ`4%{Ou+)CZ;5A=77mi#8ud%Y>2XC=^qB)Ly z;IiN@6BnXsE}AyJJy(F2%N4-6>nK8O zYho|M=o2xxCPp|;jWDltURDR7n~@Bm5E10e>iQLd8N!B{P^A1E=N6H z2S=kNw$~56iWPe_^U3cB6Ni**_oc?7}kpa`N_fq}y6S#(K3*Ytrc z&yv=Fd+GbaPx`Urhs2K2f<@in7gy6-#k5pMN`6&zz*oh2_UL7~4W8om)8`#8)cxJ| z6Kx4uX}&adqLcID(No&eD!Ngx1p9_V-$uQHY^!-T>S!0jiYB-net*zNHqN*(l58Be z2tRY?;%CAn{1jD3e25Xh)$wC~8IF`qqs`q$Qfhi6=_4rv?qrWAup>FXjCg>=B7Gq9 zMN{iDpM)C&?04G5l!Yhs`wdq{goT$JRvB8&o2IO~JQOHLK&0Y@&Itie!76UI$=jOk zwqR;@X_u?LER^U(&HE388Yc#-y{;BZxQe#0UYF<8XM!;5^qj*0}ES$Mf(Gp`^*M66ZS;6q|Ha5%qJh3l$kow z+oCBm1(Z4CxMgF~r{6XvdoCz*u*dE>pA%4{0OIp3!_N2V^4SA@Z~I15W%4K7&< z5(v#kmr*_GAM!HJOl*z$2i!ck=?L8P4CiL_H@0VamVFINW)tsYZbUCg&5bBTG3dwD zquYw){84D#4mh}Dt515jq9?FbS|ery8#DKXcVpd2IE(;7`m`H#upmvQvwkqgKQDc} z(Ky8zpWc)^>zMBR+|BmYC>I1YlM@Vhm6SJJ1vG0Lp&@AX%gZD@sOXc?2cCQq zU){hyloy~!kdBVgD0Z`va+z;yP+Z{MmM$D(92yCgS~QL#g&JwtF;ZNdnC>0v@nl_| zXt=!yOFr^)ENt6tB;p3)(?l-wc-%~r)ay=-2%$0@g@p><$fbtcMoV_xql=0%?h}`q z(u#JidBWfX3NlJd{mt$yYd~k0{Br6=>1`y~mx9+wNXvh)w7BG|*~`zK9X-8k*|PN;RxDp9)(xhKH*5*Zk3Dwz z!5=nvJ+Qdv{gvfwqpzI(^()W3_`0hHrz`_?)*pJ@ezlE8KD=1PywgYl&l(sHLK6@x zJ9k6^0<)JO&{xZ@%*+6y#I>Mjm5aciEeNafiexUE<8>URbQ4oN*GP50A~?K{#FCT| znVH#%c_kx9CYB`JD@GZ?aCS*?aY{)zT!GLR4!5_&@e5V@=K-{ky6wkdDg(YjkVMk~ zduy;Chc!%if8hPWx`qiK4h&M4eBlq97G4tlTb zWTdjPtkIz7lkvO^&r_>SdZvfG0k|o)^pcDWTM3Tc8f7Gm43^~NctPN)*iA!CO90EK zjB%qT*N-cye`r)?Nu+pG>H9>}S0PzpEo7e|GGtE^8Pp}p{!>C1eh&I_cxtq{#N4bz zy?i}BgE;#sCh5g3|B&dPJeGK1$B4oUrx+<;tNnP#yy@dd-!#97pRJj(|7Z-5-m`CC zms1k%ESv26?fB}Yi)L4Ct}i|nQXIWo-O9$<_JBi^cU=qd1hHsqkyha(7!I7V4O{Y0 zJm!sNU!qyUUw#DcvTYCCWq9Z6*63SbR^D-6TxSl*pGv9t0`U3x~ zAM`%;gDlJ?dO=&!2~xMB6NFao7GR$9CFLFOVd>0ybO9*t#CoX|wodmU?s2727b1n6 zid|j|RluP3yD}qz;JxCJ&)qp_*cTpr7G}U7^Qi*{j(oCwYH`F4!W&2MJ#C|Gfgj)@G_g? zUS<;&nTLawCV;6G1jzrVEk&JQ7;~a#?Irxu!luw>Gf{${T$NBO5_F02h{5RnG z@dy7D*V}>XG5-~~-to_HJ=mijIpnk5iuuv@`&c4cf(rC6{M5-1R!<{|CrxuY-$7q? zno=)&a0KaD9)bO_i4l)?v&X|WQ~2*)$!Qe2X7}BgU+7BXX*Awzia@v-eU48{fH{DR zwibS()$MTD)8MMs*Dax*M`)x2;Vc$X-(zG-Dp!xJn>499CqL5DQ;VH}rI6iQ)g#fF z|0Q^T@`KNh_esFp`QL)~`p=2?p+g7XjXp5=;Gy$Hn%Xk>4y~0uxCKvUTTf1>C!g$# zK5+0>^U1*%bee~e=29!oLpsehNYiGexf*LM`QV%AF|GPP8^5EL>sztmJG6@DqO^mt z5wTCT=QL*cZ;psj3;#iEK#ULWQID{d|0UcWeB|HY_TY->1JN-i-=fXL$>?VEtfrVx z4)y9MKgN>_@FZ1jxt}EDEpY!{GsWN=lwz<0xzt&?oTQ(efG364ljG^h!5#Rj+4|~I zohAiOUa`_7>oj8^MSr)_j3y~Mn2ZsLJM@S|=f5)|f#o4C8pCyecG#fdD8mG1to`8w zC}Q9jKKYu7Zk)8A8i3)z zb{4Ruk+c7_Ph+8a^iec+J_L6HX0#+b%P^X3J8U=D?y&8)y=*&Rb1+-3t=qQMcD?mz zzwHp>tYaM44%sZUg=jLC*=d4_VS)+2m{mmdH%vjYAWb;o{$RfsbAABchL?=FCdNW+ zKMEU~i$#1ujCD2lY^=n*(E0tU=#$?=0}l;GAFwU4-7hfL1`Hi)i^P~73+)s>YU!&c zMCf{FAT2^OnLfWmHBuabDy*lU9eqG$sY&>9s`;h(8NT!xZjoEZSzUc;4U#q^<)K0B z16kr26ECAz-e#pdE1$Fckz80Q+3Z8Ft1Np$JkRqqHuXEjTwu{32-p`9V2nsa6?e?# z-E+6j74zq=oO{FEJLc}6dtk18F3zg>`OcYPl)SM=<7t&1HcMy4>I`uSmKZqHMjf@W z>>jx{gVUM=$~ZN5bR;9dW`+gx2Z5IG8yTY_esqqic({rt8+6SHOGmzmC8E4N$6nGD zxRUlTu%-QS#biF2vYVKe5t%%mvO~0;P<>f_cm39SwWI!q`aA0P*B_|2)f?j~BCLL5 zR#v0Pom4tW9GJvcAQ%rtJDX%qzo1~M3l%;@%g@%PQ=h_GY-GxpQ#p$? z-lX*rYH@`ei&`u(rpX4Qs4~)Eq~$~!CVW|y2vgaIOT;jq^vP#YcKJ?;?eM#e?Cjjg z9VML6|DyuQjWMS9h$+4pQ!ti0tUe@VkjG(M>7|_{Y?a}bTNm)A1!pY~3n=qRfe{h5 z;JEP<8owOokYpTH)~>fr01jowNQ{GLha#y)FfHOsHton&xN=-~DBdcIv_ZgirtwYsLsrv!24s^AwgOQw;4)ZWn8~1R{ zv3Nu_!?x!$wb`O=#}uPX<{F$Cjj$b`hbw&2ePSen;6dF@9cdmWT|+u@y1=>PagC4c zloXY4SL5UeU5)g*szZo3l$xxyegrWjWMqtugkl1QX}UNkhUv@i*aw!@lYG?}Ub%8+ z_e{ZNE}JQ4(l}cX<7_jhq$As>Ch!Saa$Q*P32}s*O>;7&4WGr=)am7S568!xB{UM{ zLL6g~3To%(0%O>wsu9KrnQzqAMe>c3a{QoMXXJO~znuS0zRJfK)(3_wUPGj($;YZC zN3a92dR-xxqh6!$kx8@W&l0nyU>Spvc=XB)vrd+!hhE1hZ|e1U!zJ&i-d(-7T2>PW zMps1WYNX|jim>V`Qx%TDfN;3yh#DTlv{z#~8PYR<>B^-$mfo;bv8BGHWlOu4Ze40) z_}RU5FFjjAcJ?UDARBuG4UW~|dfR+ZV~mk2pVB0irPOqdJu1$_T8d%X8^icCbscgG z@08Q2{wbI-VAJO})EyN$%W7(^Toc#I7;bT`EFh{vE9n~7$^xtmDZAkO18h zXsx_Au9Yz?O|2|4Qf2N8&SuOctvnj_NJDN!KCf$EVwC9-XuiNB;GqQ05)zpw*3QpC z${g)GKzE>-Tg2}{kKkQme(uU#$m(zVb3=+;4U#H$BSQPXuKfoy-(KBHcr?vjOUpahA`1(*ltC7T?Tue9Y7gKFIdiK>ja~8Ue27jmY;%O+q`%S)!lHPNZfoF=mAqB$>LNzLLIJ<J{1`0;*Mm_lCu;2M?qf8 zy{RkYRUD4F=~YZKDkUpyDio}+G?f3Zp=-$xSp@Azi~^O(_crB!i?$4eZ79fDFoi5b zTu8p=h2M)W$%@(ROvbF(8Avrtr-D91ueb2i2p=N} zD+M-mMKC1KTyEt+a=5*~rxk6&KHIb4WQCbt_pLm43zm(=kg;5+f)B;o-X3SB5|8P! z1sj2-zOhtTKW^KnX<_Eot7?%d-SCUCw7d($&h1BL$2k{EP?DHN+5ZVS*ATyow%pIm{vZmi)0Ura!K!5P9AeKiX5_s zIiIqJ8Ut-hfPuD$`*jVkl*izHD(qnar{>Tofjun9rtGq)({+6oXIZ(FZEjX+mN<~b zSK#aqvV>VEA!Z4!UKg#b2W38scPG|%YdZ+f3wAI+H($J*e<)uh!J!Nt74?`MJR0s- z&bWRRrPY!J5>rtWFVjv*}kesc247$N&V|>KSK>dMhcEC8#@f= zY!a00n4plBm~u+??r?lfdpF4#D_LGso?v<5tlTe%qP9?43$>j)T&}lhZPXYR6hhI4 zs0t$&7iEnhX{fewhhw-!Yify+A=yZ5!T1bvJT%Ozp%*}{HaKp-jr3Sy+?6}nCH!%C zHM!7ZR>r%^4wQ+q!VD+^9~*aWtT6%52|JL`KU3??FWLK`a31+kWxT0uMcHL#vaGP& z`qt`tS>JxT)G7QClnUoUB#q;T#_@55w3hla#hTnXtkfwqo}x=#F|KQz2#qTnC&m?$ z{1e7UDs@_{u8M3{hW7gAH}bO@cQoG7xVurYMx(HBxYe>TZNqgfm1(ue&apt}ie&))|?o7!tM|e|+bc84NOxQ;17Q)Q8S9?$7;qS#^ z%DIJJ5YSAC75s9)ZW+vc&yypNZ-tS?=a1bn_J*-{j8$x`Z|wZBE5~+Q51eDkRJhVI zBW&y#PbzY!xMer0VnhT2rRs`&LjP!>CBS zHz`OmZBp=g_Ggq90xjOb78+y0!U!uYPp0pNsA$S8q>*;o;7eW7aA_>&tawyrB5I_i z8`4PoK4N7+y5rIa7q7brQCy2tNEfs;+L3y?mU4`)X(^|%Yx1ZPlb9E&G#~P!$I7?0 zgkwBIry|{=R9RVpKrEFVW7N~NWSe>Q%Da&Y=i2bSY5UUzOUst7Sh+e!E!$>}=TWpD z*0__GLV)|zL3RxUQ%t}}N?pmVROpxCvPfyty@#IA9D$tEXbee>#)G)R zG#;=t>tb9<$RHGWLR`{_D;gKwBh|Q|NBSUe(LLA^#a>j8kBG}O(pw{xd7@g6_ouO! zc{N{QTCyPZIt9nh?_oV&Jt7aisn(9gZBBF>rlSH|+Ud9hQSu?!a}QN9n*yu)v}vv3?OsY{poRY}dy)5`KOTY~Q;-otUAk#fBiHY5l)LkI zlHRAsg@`!|rOnOAw7CinLmZPx9Fv42VFGXEGnhCcpTXo3_8Kt3+G2@wyaIW7BSsvC z40aRlM$B~_`b2AH^MDeFs7)YNYR6C_Jus;=gj3>hobpmk>g0VsoWKd-RE^PhR`_Y^ ztSsDGC<+aaH&S>QGXID^NyBl;v2gjE^qIn*1TOVPQ2O%na^MdSc*!_FFC-m6+ahAlgBPF-N$a(qVHtm62Zcl(Xipn8b8E`JmzpQ+!&Wq2`qI7$zI|A7OiPKe z(zw!wKQ0Cj3blQE^qlS6?GN@vzjNi4SF#v(5evKPc1eyMSQwWCR&+HAy}<}`*bGlF z(ts1Ch2hDHpaM=CA#Wq(ZEgp)S?xCJu)%;cssf`bFscGG#??oX7#?HiDi#MZT?@KW zE$B*1{o=JiPd^;q7keQUuq8Tdn`<+1eKT3GV)}rHiNI7z5O+_GLFcdcSdji zbZy)$k^SjTmm6CGcke2TL~y65l4c@O}iA_tMS@xGKCTZ zy5#|YfW*q##0s_tDb&aM(vzPz0bp#s?%Rc3|gST8-3v z-o8EO#tX0e>ak6~+`irR+bf^gxpUPj5D06TEm@3l`)b2$b11uk`q?_!9vRpPrbp@u5}$1js-J`E=b-vIbp5aiLD!G2R6n{>{pgDNIS#Mi5T8*uu-XSk zYd+H|`C`;3R-3D_p>UXkY&v$cuc$5OH3c&Ygfo~P6w?xTiM`G)3W|zC86$!j z86!qyG%9I_wY#Xayg-eq$*CTl(J*m@^5o>?jt)+pK4x-i zNsiwp5j(&=T1=asBa;K%4VL_B_wK!eyD5|^7*U7AQ0U^r8sRkh#oiLGHwq2zesA%#pPs$sWPP-qe~n*y z&A6q5$B7?RjQybqL_7KGFBg|AtUUjl#|iO0ap8n3`bQlj#My&qHjTdX^6?kr*^HvC z+bb7@i(igDN*eJ=^cmZHNZ@2%Zj5*2^L2I(=4##)d1*g$QDIsJ&U4MkNXsrs^7)cz z1&XiG9|-!v_MpGSo$Ys*mBQP7-$1uLKLt^9mWse$->5l zU}HnWq%n~PNLhQ=|$NhM)hAW52HVE6mnlN-Yl+if5RkOJRcOAyj5LGbMz@a=^pkTjTb5QZQS zr^8wb(tY~|9y1wl-498^VPc|_Yhn1bB*^^am>huBRdG2;rNuaqga8Dg630-+r68@+ zHvg)T50{Osnsx8&NT~eb#~$t4ymYL;Hdt1hFe>AulDcupC3XJt)_Yf%1vVDeZ=PH} zH^)<4IHG7?U)P3N(P#KrKI_;}c{GK;RhGLTdJmsr%v1SohcQV0Mu zpn(P~9-9FT@Z=+CJ-AGp(`YL{fcK4jt^UoULOIS6Ile$binpLBKOqMy?{s-ZQI6y; zQunnwW=hX6wGTv+q8Ij-qxbc_QCQo zOHbajXUFuy*-**;ZhJyRt7Of{y0%N>DtYy|<%7rB?jJn!xbTlGr7J$`qVfeLTIo33 z7JWu;hRzkSLw9OYzilA22dPJ4eh`1t^ZCg9LRsVlk!h`0GU=7CFgH7xo12}Rosc04 zF?N0cr_5k+SO~)mqY|8jnv|AF{n+qph0?3Z+;*)@L|{sfbRX(K5dhxSp(6ksG{$M- z>u3nf9dZlzyyDz!XGR#*Pxs~*j!X!f)VCKx$y{2=hEsp<5cT13SpSFt*v>s%tNgIS zCI|Fxt>GFJr~PNOL~gz+eRpYo)vW&h)n&f=QNc0wVTkdZTz7F{R?#ugg-OG7K@~yZ zQ!ZK=nw6aRRnA8xtUj^O6nT<)cmO2xVP0^zD&na{1t8_CMr{H}ToekX2GNGi3N8t@ z2j#W`9xTWS*hX{71N5Hbc)=hROGs8?b9>+w*!*_lPa2WkuAkWLt{n1P$0oW$aQe(p zIRH!r&;Tg_08;?~mjO%jz}2IOI*QZpY;0^5_4P* zg>|iV{O3*(Ot*g8;MJ9ug2Ffvx2`k|T4Cyir4}*9XtsbUXbg8h8LseCTNmEG<)>UX ze9b0%=)SqUERUKxG;~F1^t2Jfk8aV9(59&y-~FJz^pwhJd-lvIKc%R&CbN3p%q5@F z5q{~43DL*+chgM`N#a*Vf8W@7_UIGFjH1RVrY9ibHaMO;pe3VtPBg*Y+UTRvy1T@8vv!138mz#bA|_w1pS4Vz8dtw~`OJh7*V?0`8@YGZk0H&exZn>&GDK&Czz-_uyS8u^$;hj|wHi)zguNm|L$~#bhfHQY-@S zo*9oNQOC*A_o>v{B)UoR6aCma8+Xc0-8sxD*PbGt{7o;21@NAcLTq<5`#d=|o89XY ziD)J4Rx5$+#H9oAh5?k-F(uGr3}Ztib~=+8Lf~?e@I3rg+P-(&b%XXjd&I|kwvm@5 zb`2f_dwz>p`te^;&-0_tsKt=XB($4jJhCuR6#5ZPh8F6Qax_Us#%n_a$-)}NCCsiMJa&pLU-1!C=RNeHl~ z??Vt3NCNQ3F!|fYOl`ZFN(v--15O_v2b?4vfe=$L=gRGIBze7BD!huM!W;59f*yy< zs(jH?neeOd} z8AkhNhwOl8hYJrL?0XD@G@q3pQYjK3ig3V(k!?tl_~ht={n4NBDThhaxzPcheC}Z~ z#aw86u%d>gVY-3&!1NJhLfa*un$nwcZi<}c;i(DSp6G>4!Kr?)p8y;y342PA$4S3t zTY8TOrKPzu(vj?SBL$;Y_H_F3r1+HEE8WgyFBW1?Xg~l59Q_&A!w01UBaAY;D=57w zu3&0{&z+o#(ZOWtO^{w0N=*o+rY4{pwI191i%EQ zcdLrTd=SH(K99*_B_P|Z+onb@%P5WnqC4IYHBs+t+`Vw**crU|nZZH+qb<6{^At=v zK0V6CLGfVp{F5inI+33@c+B7}uxCl=y}S#1mW+ioDI}KL{IW<*SKqxB2EkS6ltHIcib4!1 z4;tCjO=MbT(X>L!*;fO+411G(Nj4t_7(X&{=qp>HJt=6nC#~>x`L6d#pVxi^hDoub z1z4DadIT7my6c3fHD0^|DoIY4JrI_58`gv#PH;4Ym6etInn8BzM#kvg+)Rxj5uctA z^)Zo6@~p+Vnd@O9t|^bPpz4|$qP%?fs#(#$MBn&5KR0^qA8r~Q${)Au`RL`mV6AR2 zZ;CdHQ9Sy0qbAb$Nz@x%1!^yb)$4~`XY*PkX?2iK3oZ(Z>L5>7Y3O^vi=t-GuBb6F z?`gEst|JQKp2pVDSm=aAKfB#OB0Gd(cZwB=*oM^g@sLMGkqz~|IS7XruN!HkLEKGE z1rJa@T!)6lyQndia^pHYB+vDSl8_1}JV;q3A#NysGYOHT0Odg@%J5S@Nr~DrrPJ4V zdeF!tF~KNoQgcpvde(@H)D-I42;H;c{w%?*CK~-3KiJ?KsHlK1Tnb+<=Ae)}GUTCz z2WSkI%nCX;`{3F^6Y}yA4+PD&-j-|y&r3yg5bDYJD^>rV8!tR1HR;0Mtz$;**?Fqx zl*_-dM>I`Hi@w3#eA4t&yLR&1qpj~CRK%X>jNl~k1h_&0K5l{z~qVsEN+yPJl$KzsOZ#1j%xKfSUiYNpuzSviFu<}ZmfAaqFcL63pq>4*JpqCRno zz5#I17(vA2`fI2@$eGJI!)SZRUkJ}|znM>BmiDkU6Y%t)QBS2Orcy46dYBj7>~oqFpZNZ&kk6C?d@sD>uJ zraS_(S*OqX5t=nNFiNDCH}!X}ZcSNo;_8CDepjGj%=p&Dr}y*QMtYyyTQh#ulJz|G ziQe$S(mW?miN577;eQ~1ihA%-XhaHo+(=)W%$F%XTk(_-4{9W>(u0aZQCsZM)N zLQ)dUxgMm_qmY#Y74hB&b?oBuIuH|3#97CXq3(ecnB#^iD!Qk3#t)u+WzQaN`{_lS zzA~nmfAikuo0bjMpewSoWzw|MHtZsLVESDC8M2th5If@{J3q}%gSZ&Ziw!>jc+>Qa zx%Po@|DN`NhEo9KBH5L?IAuQ&{rlIlb4Cr2G0Dxvpw26zA&% zvA_S89bL;?3-g{hWz>SQaCI~ny^MvC>iX47u+U5BRh)Mq?oKAlV|N)<7l!zT5MLhR znW5Psu_}iz%HdOUcuEf6md#I2=XJ@mlEt}6d~*^%$;&gm+&!WQ4bGdoTLIuN5FhmB zND*}lbnl_Jv_Rp>UyUNFGFzVSEAnR{4lH-Jj?BvO`$~P><#YLR6LV5zZjN$MlvV2A zm(t0-)DdkScy_>w&N}$0mI2tQ_&*-Nq0FJ;B7apL<`fWvwb-0Oz^sDIOAS<31Z>}T zeCO8accQo4dcErN_MP$D=pzdrti9pd7k_sBO~=i6^x$02!DpU1Ctu{e)*!eO$Zh53l{sO;;cAg|1t<;rD5L@imu6 zuh}+b-3be!a%?45$^G8;Eb~Ls@?nc=myG0@BYA4h@j2q$bl#WF7pC*n^y%s1_%wcD zke?dl%Y%GYkY@(@5+6Us%a;f~B0$3Sx~W~vNd^b^Z^!6)KpQbUd0*QZ03RErS`3#L zW@Z(+p^g|QM3Ax8f+nBLO1{Sy`dfoJ1KK57ew7ozt){o>k_?!W!}eBraN?ECe5FPwATm8ZOO+fx_aa3#fW(`$7g zeMyMLmd69e)a9X$kXVq_nk81J@-9)CtWrJ`BVp{uJjFhHxgja7`G_A=`&n$2{DNeRC zL|HoFsNh$}$#%k(p*YT@@tAo%XpAAl=R|iCzaip7uCu|}n)vKD;e2K{qImQqu3pv z`DYu2CPr`xZYdlBVaHk&Cv!13R-||_Yn=$*`Je#-mdt`^kyBww(rINb8^N+zHqIf* zg=NWOBcUM$tPnFE#n>ZN!bY<&R*a2h<5(%8%#~wpS0%&JaaPT0unwz^)wA(f88?wl zVhzk-jfkH%1uN60vFU6E_Oi@kv)LRrmmPyM-kaEbb}Ty%=YcL{i`en-mrr0z*ixMM zwwyJy6WI#3lC`i^td*^1ZEOu&%hs`Wb`o39I@ku*$+}oK+sJy@Cf3XP*k*PzJB6Lf zPGhIDGuRe(COeC5WnW=uvvb(F>^zJ~Z%2E30lSc0#4cu+U}e^2YzMoXUBRwoSFx|M ztGQy=uxr`Zxs6@NzRA9Y)j2o7W4V#t#BOHaVYjgFvhT6)vs>8@*bmu{*zN2Nwv*k- zcCmhT7rUF?!|rAGvHRHr?8jK|^&oqQ?Pd?NJ?s(oQ}!r(j6KeN#-3n5XTM;-WKXhR zv8UKx_B4BjJt6#=?`z$7`5Jqjy}{mO zZ?V6y0roa~2m9LIW$&@SV*U3A>_hf9_7VF#`g z+{gVqz>|3pq486B8aBUV@Jv2}XYp*F!*k&^T$xn89cAS$sC1!{@@z z%;QabK0lTp#~1L0d=WpMFXkukC44Dg#+ReVbs}HESMnCVinsFByp6BnYq74fou98NMck#RVJ^WsNAHSbJz<Uma0`#{iUg4;l7vtAMF8RQgCd1p zFH%LCNEaC*Q;ZN^h)&TZ zy2VD(BQ}X%(I+;Glf^0GRB@U(U7R7dh%?1mVypOyI9r?}&K2j0ZDPAPUtAzA6c>q$ z#U68+*Xakscf+$-)A_lpO_kHt^KgNSLqTRbfG zh)2Xv#iQae@woVzctZSK{6hRvJSl!9o)UY-)8g0S8S$+6jd)HxFMcb2Cw?zp5HE^- z;wAC2*f0JdUJ-v3uZlm3Ka1DI>*5XZrg%&IMGT0y#XI7Fcvrk9{wm%VABYdd-^54a z@8V*aVkK~9vDWP>zhqns?K$f=<=5pm}wHd4v46yiwjHZM5hw^XoBl&mvvHV0Hl!G!V z4=JWNrb(nym=mxohjJ>Hax0JWssxp&l9W&RRX`=Hph{7xDov%U43()yAXZE^_I&56 zkjhgdRlX`vg{la<5=W^LHClz$7&TUnQ>Cg*m8%L>iJ6BgOvu!zT2-g&)p#{QO;nRq zgECa3nyjW^USb-?7H6oLYL=R<=BT;q7&T8dsrl+yb(~tD7OF++c+AF~pq8kmYMEND zn$?MFg<7dv)GF1gR;xC(My*xrRJ%G!tydjtgX&aWs#|STJ*K;(Hev3gPiNIt_I)mP*E$U2lmfEVmqVLXD=U|59Jhe@2SLdq>)P?FIb+NicU8*iqJJjXs3U#Hr zN_|ybt-hwNQP--kt8b|5)Hl_))b;8H^=);dx=G!vzN2nY-&NmJ-&eP)AE?{Z57m#< z?dlG-Q{Aa{seW~rx?A0&?p61x`_%*L$Lc5QLG_T@tsYi;)FbMr>QVKWdR+ZXJ)wTC zexZJ;o>ae5PpQ4?Y4vOMjCxl6Mm?vVSHD%iQ@>X)s29~f^^$s7?N@(Luc$w&SJj`? zpVe#Xb@hgNQ@y4Bq6XC4>K%1Jy{q0+e^u|R57dY1Z|WoUclELQL>*LvDyj})mlL-M zo3tsL&1SbbY)+fYq#gECxN&Z`*Op*Qv?XC6)^7{gl5Ig-iY?WaW=pqa*fMP+Y+1H! zTMptMg=~4Yah-h~9lp-4&J8U+>)Sim_O$i(^>oS&edV&dy<9e}+n}cP^>jH_Z)j=l z>FRWKZEow?)Y{e4X5Y}hdUaQ?y>V4f+vYZVi@rD-yViDfwyk%xm{>cK1uKBP-U({Tbs5+?FdFJa*^D@s&)u}J8 zrq!#=uU%a+$bOueu*bX{XQuBlFAL0voAkxGu(fSYG1pdMfSGz$?kRS34NWbEn*{cSKBGA9W5IO>fF@V-PY6I)no5&+l1^~ zEj>M5CwH{1>2+wRuiLG!J?(4P^_nkNcb(j6LaVxZ*O^dX_v%is^}*`SRh!z}T|K?) zh$k%_-uBL3l-<_a+uqgbY1`P>zPY8Nt+TbwwyvvhQ(FRf-qE$Ty|tyIv#ZxliP!eD zbo6$|!BxG^1=GvR=pO+Z0#FtQDy>)_+Z18QSHT@0v>0W~q8$^s&>d@5p}SH+5` zisf7x%cmmt1cMX!2Yf1G`RFS>iNq3D#?YvU1F_O8V)#_Xf!M1^tcdbhKKg+!D~4($ zo;a3sB!*8UhEF7xv#u6>UKOukJRkkU(bv7IqpNkj13aXw&AjVaV_tiDt^3|h>snT~ z+4Qet^?H4Et%0PstzOl2ira*Gz;Q=!PkYPSzHal{W8JUrH19js*jw9sT07cY?VX!f z!FaUw5@bEww4ohx*wWet0ookDk(>HD?Q7aLK!gLBVRBegFU`V}~HCwcwEKny|3P>qFb+xQ%Z?7(|h}6cQ z+B*A8a2z2}XO`DiMa)Z8xxTBcba!>Pb(;7)8cpNoXfdyzDO8)j4Qo2uPVux3!DSr#ts7A~_)T-r^GJj*h+?dH`pdniZGNkg!6P7IIr z7T{fv#-OdUqos3od#iJ9>~%*Bm=^mA6w$8PVCJUi13!x?xp)P%K9vAzr z#{xVHhS2bA8iLhAs&Fq=c#&D*KC{A$to-||{1=(|_n8%5WL3D&s_^2W96cuwgO?10 zPaT47u)}LNxf{v8YZDGz8Ur1T)AS=pOPjuWnskF^!d*kK3&T0RZ5?gxE%wE*i)bEC zHZO~HQv1pJ;#$1Ay{)HhQ~M^@$uY>j#7uaqz9ekyLq62L!W6G|^|XK!P@hw@gqI=g zRJp5dQ!n`5i??WZ+sNRr^Y*R-<4kyyXHEO&80_7IoH}DKTD#C5wY0Xjb@uvnOEc_& zt+%VQYg0lDD}Co~qy|fa-f3ogrEi?mdd;VUPm8M=hmB6Xhr>!ZxR+ySv3cw`Ies)h*(fJ~6LPoX`%b(`AbJ z?ee&FUA6_fDP7po=dj9`Q`WW1`J39klt--GBlOP{KUAv-`L)#4tJ4T+y6vSlU(tuQ^%`}w}=P z*$RvS+Pa8nUdkX=Skk8o_gcAVB)ry3edE?2Yfy^~TAGT=7*tgrhbrRG(A!A-SyddW zjzcwZ$TYdgxvDPqthy`?#mlIUl~Epv=T{!jr97TXc|4bjcrF$3TqtBB`U z5y!70o^wS!=ZbjFmGPV_<2hHxbFPfjpfX-YWxR~aco~)PGAiR`RL0AQ#LIx9Qu71~ zMdD>d;$`4$o!HxW8IgDyk$4$a(?+?(%czcjQ62xHI{rm<9INX17d3ILYT~%m#Br&K z<5CmPxh9@-O+4qCc+NHPoNMDb*T(Bx8!w|aUPf)ajM{h^wed1)<7L#w%czZ)Q5P?x zE?!1myo|bd8Fle8>f&Y8#mlIRmr*m6ORNmg*WyQcS?q0jS*(omvRE1AWwA2K%VK4e zm&M8`FN>8?UKXoId0D)S@^~3TI9J79I_XItC8p{>KV z8uz_oU7Ot8ve|Z8%cv3zoqagD z1%BctykEagQ6>)kVRxJ8Zi9b{JbE|50-|F0l^eT&DNt90Bl=96U8}qLR&{_vo9*~R zxz+qnZ_)=S^8Cpw9Xh^iTdR;X=_S)_irp{2WhqYLCVi}Glq zTd*d*2|L%dnScxRv0iItSWm$Y3j#?@C|*J91sG&P9$i1{DR^W-V2}xUO*WY~CegaB z(w#BDqZws=33i!~n>b;CLnLs5f%>5nxN8bKP+yWn2XLY*I=ghy1kuO^PHRKAw|#Z* zIt*W&)YabE){_)}WZi>~y}ez!BTNGvNgC?yqQ`Wv^}MR4(y}yFH4#g@2{QGUAX94r zSr#3T)p8PKS_Xnl%RrE683-~h13{)`ASj-5m8s{zz_MWk#d4{%Y#2R@r)mj0vS}TIg{0NFsywYm7=vj>7 zl~%ijXI2XV?Bm~}TW!{@q9RWFD$8b9SJYY02(q{ZC`RWh%gPhZCanlE-x3t#WtAm4 z$R$Q+{U93hpD9fZDo>?`jsIDoZA*jG-?qF5p=_T}=Ke za0afKGYDkzw;IsUGYh{;Y$b}Nv!o7nvnW}OF%h$tDA)3M@XTt<@GQ>NI?HRJx3T~wq-g;ntSUuT#F(vjw=P)#RG=3{9fPZ z`P!@Z9L_zTvwhCzbMM@ldj^!WI*j5~EXGRf37MDX$|$czYf9EEWd+qIuSMzh2zb)G z7{%)j*l3XxcQxX*$jO?eb%LX^FJfI|gjDtZI>`fnoiqZJIKp2ijQ}P3hYFH*61_O% zsCsEvqg#C9>X2#}Yg;dkm8zL|QvQOZ`Ug*{r66f-gC|v0kmQviNL=rMprjS;ua{~r zNM61EdNCXL@{+7sjw483(f;B)9O#o)H0(;N2#=#n5s6pwBxlh~afrDx1d00~9c>wF zISM)PeG-m}J0ekXUgZ7KUwjuuM`iEDos)Q$C`q53Kk@3Gj>?{j*Zw3YM=oCb6Hm^m zytDg@@6Vt`T-zikdmyfI;>k9owT%%i`da*xb0F`;LGn%lVDaorN2R&MO<$gKl9TcmEbS4v z+1xVLa+Ktx90befmSAZw!3eotTU@JPP zg*IC2Gq&&p0<365iycHM`iCeb%3_hOcO-2@OV)`F6txj8MMJb?g=kojBGyTIDF4z} zqA^yoih2<3`v*zmkSRYoVt*@I@9if^<9sHL3y|#LTF^>1*oqEnp^>Q;-9{@qz=}4s z*uhyrw1YE%L|H6Sw30TWCF?{7irR>lq9IzcLNu&M5hGI)O_^$;F;=pQym8@b17wuzbwor8EN1~*8q&q(nPs%dg`H^_i z%Ah+x5>JYZ?)*qR*#`Dck%t{uqGTJ`k0qXL1N*GRlWkykm3XoZ?7bond#XgqHn8JL zJlO`$)e=v(VUYI}f1SKa@y@rU-az}?Cgzot72B3Dj$xcaXp^hc1rh`i7~A7Rh0Oe7 ze1MWyQc`Hj#McMF*Xs!U2=oM51OYCxEPu>n`Dg-13|aQs^qCB9)Y#)gjtbn}%66!z z#OK%`$|0Z&Cdefv1_FNqazal|=;^55NMIt!Bw#OSgn?W!kQW9+iv#@Wi^YK!CVyxn zd!^5IlKsW4vCN#wC6%OwqB4**16ebWH3KKvK08_MeJa`>g)(7z@*=dTPa2}{sD zL|c}Z|Fmdg7httOlRB;z9-s2xC5OS$p>HP*$E^)zO2Vr5yCX-@l~Yr(cO?lr&Q?i!}IBnfKH4a zkO|-@0x-4#bO<9w6vXmDY%vHe18Tt`yFm(f#;%N{AxL3h`AFtOF-9}S!FrHl6w_mv zPG&ll=`_}v4m83_B#^8aVTEXS$QTt}8Oe$f&qEPLvrHT;8ljowNwZNwI*lA}2(;DW z8JTvF34u1E-I?yn=mE(PXd{efP8{Yq1lmY`3}Y%|y7@Mqv!T3&a^6CrGZHjqFBCd! zfnCirfaGB)dx#$iWEqM*6go+MG#^c3I+aI_1rApXhvwmUuB8{A%^{!1u(xBtiNjMm z8jKnXP9C1up`&ShG@beB%-^Nh1r58o26iiwncfXNB6yoKfPsv0j3dqU;3S#r(W*sb z?gn%sR6bH{05+K;fz5=dTf#2pcY%ErsdzS}$=m>JCd5%fwfP`W1N6qxqe^e)cr(XW zX)s?=`U-C5i$D+a3E%>73`!qHUq(HnAED5Wu_L3Fu?J&s#(qFQ*6GJO{aB|T>%6Dz zZ$5`-HoW1(J;9b}!NHsdR5K!npr3)y_XNy7&;$58d;0)m7vd=oZ$=+;6lgu8ALAoM z9XL(U@Bpy`5j&wR$qQ}FtAXvA<80mux)ak~n095_ol#5LkjYG-C+LT;ej2C&Hev2+ zfmq#m(u87Z;#itEmL`s+iDPMkJY+bQCXS_vV`*j$%{;c5M>S*A%gSaR)l8$%0jIaDW5n4e*15oqy51AwyOi*op&Nae)6AiCN0I{T7hKEww+c4lBNKH7(D34M92C(C$&R&x|;j#`afB?=shT}`_R zkaVgM%R(UP6Nvf*qCSDBPas91<|x!0g_@&KBMQh$+vz&?s9AgWYo4U5}>zKnWCKSE@Nu(SChP|I|0Mo-3mz&4oQ(?C?Xpy5b09E*ly z(Qqspjzz<J^Z&=-;&VUcKqxen+@G-4raj~VZX{D2S5M0ZB6Izm6uu8dvzsFvk>GkP-iV_blv zooROxTw(DBkk*$gEE3ZCa^;of$}7ti`iVm;%N0Ho_F$y-H zJ20MJqZqZc0|T+E3*DLDo%!9Ft+Z6z)Jky*>0?w5FuO<35+l|0*5NRfzgl*5r#7-mT8<%!HG9-1SXj4fg_od z!bj5-9l@E*bP2GH@C!2!@o{6v-<$$Xr(!AW8M zSjHU2BFKb7XFV{S=|PMU%oz%qP*|a(v5awuG!#~dL!O7i%0?hr3B|R+Lf}~DPvEh+ zjFXu|v4jdGjL$Ns3UnA}IE*tKrl1UmafZVbl;JS=1`d29j9|`CSP2uN5NQ~EBRUq= z!`N<^kj9*J#tA%XB4Z|Vau{ z3K|+glMhkCL`I4wN+@KsNIuIlmEc5k?L~8)L<>|W(d=h5ydpXgvk=W*MZ+uNOkku+ zi{^Qc!P)A0AqM9uLU$aE!Fh_X4tb8@xsKtvj)DG0aA?M3V1?)0Iu3U0f#HmUklQ%6 z9tZ1mG#YWmAtI8YOvWJ=;-r%X#Ig{W$#gbj4j;{BIuG&23HeM@RmY(k35ys@m|xB~ zg>fq5G{!2(#AA-`0-YFXj^cTa;yH?VM6m&!?T9g+=PMpjfWtEt&)JKI|Mm1FF(d71 z@f=0GFpg<6S(mJAOwfV7_{L+1t|g=0y9o*STP=SktXQXsz%G*wXw){3V=dU#6gy?6XZ5(R&G?3)SVa6MQ8H^@AN*cyN14+{UIgax=PAF!&1m2E=9>NO7 zO6FHVJ{_7Hf#VqIypzuQ(^-Ey`;!h2PlHeKrt^HIvz2uAGo5Xvv#oSk*#H@`lFpeK zkF{(kjK^9A!qypj3LY}!VTEXlcRchHoySCQ`+qjhXoNY8bS}u|b3wK+nQ1yBWOFPzeAdf>KWESZfHI%U z)^pj)=`BxSXb zYq*eoDCC?JvR9KaQ||DUcHPNb6_cU49yHb4WQ>Xg(o9X}{7mNjplbo*D#BPlpc7*q zaacnU=f8;c6tSKnwqC?~inyYRpzQ|a3t**)b)pXf(^REJTt&s4rDD!ZF^?_g7>hZ^ zVvequB}>?D3CowT#S+d;3Hw~a`b#jj5uFyuN(qlGWyw;OEM>`3mMmv}IdjT6(y17m zfxZmSVn?cEe=2$QD|u`s`&P-htz-`?IscXH+ccJ+#xpyOC8u!)rm^HSmYl}^%;9{_ z;e5{H6*P}m&^$ix&r{HOe;&>$8NfP5Ix{X%;tmfG_jZ7|w}YM#xVHnuy&WL#?ErCa z2Z(z+K-}A*yQ}fSp&o(}UD_0bF4^wG-&#EGWtyy&{^57g%!+~LrxBy#M(K2rqQ|Q- zPJtV;{13lPhb|6x6-sn&c!c|{P5AK|CHgYh1J$b5!1k*43Ke=VxPtDc>H+Md3Iq;Q z#e$E%2B2S5y{Hh-+h8W>YSjYJ3st{?{$2GLG@klb@Du+)Jns)|V*{P^j6X2WCPAUZ zll1xQ7x|{f9o$rf(o|;3L{}gTR?u&H(W?@Dg;WX~d<>P;3+AKu!fWWYum=4V zHlc^Y9`sE(gkA~9&>!JT^hEdueGtA!?}HoYcR>BR-H?wy=sclEw~3e0yJ0zcHLOB^ zhIi0|VHf%?96+yyqv)@23OyChp^w64^iH^jehK&f;z1Aeu+X7r#c${Wu>>6--a?m$ z4e0E!6Wtr?(XrtOx-^_bXNI%r#_%mVFkD5~gP@9ZCyoB-pkYAQj2iT& zn1j9)ub>~rV)UU{f&LS#(Q{%W`b=y=kBJY^Ut%|UN*qKViBHix;tTYPIFB9?-=QzW zb@YO`jUEucqW8li^nG{?AH6wC{lq*~qxZ#Z^u2f)6;g{n7cDv4j4l@Mql3l2&)qNR zF>w!d^$>j}no$!Duz*@cy$GnAK%Qq8MHhuu(Hk|XLbiTV{f-)}Q9T6CQZ)hRVWgm1 zgweQzgx*qass}9bh$a4D398#g&?`{S3rMyS?S$~F9XeErRuuiQJ_O;OY8dcWRW$Iv zYB=yWRSfWVtP(+ZfKf`}p;(`m%5F`+)`)+$!d;cCrIQ5zZK+PKc)2!D~+RoQG|ct%S8To%?{*6E_j{ZFQ~f>@7zGTU&)L!%p4LPHCg82@;exYe(ru z==xi6+}3xU>4v-O^j{)+Se2t&)ns(Bs=)u@^q)@qXMHy9>R+$=p#pcoBlunOI;U)EepZflR7pvN-d|_1NcT%f)W!{u7(6^~c+yyH#E>CFMwb!i>j=6BXS_Sv(`&h<$3J$KT@ zc2?lNWpz8_V;XM{=<$B?$``u7HF?g*F~eRf*ts$A++zptGdqoM3M!PewRL&i%&SjJ)bNZS{s1?r&;U*7e7+cTUc_^768{h6K}{9UGdX z!bbQzt|?7^u*mDhj$d5MI#iY4s@&&;<$YiI{g=AUUynbf{;Zut?H4rbpjg6qIQ5CMmCywa%XFt6t zy(DvK;=UtKhWy>7)2hFC{NG;#C}PyC!P4YGCl_&`T*PaoMW+6TMJ6s!$A7sz2k4BJ zb!AA(DJv@1mgH*DJwt1%(B@TCl$MA1`c_s}`b@>zrf)a-;0r~*Wu+!sZTMzXA6+jR zta9!ut-F7|gmpFe$pfpsgX*|OsZoHh7HX7A#mCc4bAR5xNtNZ=uZ!usnR`08ubsa* zY=566vs{cn&;G)5iCu2=236w1n~9t5Zkur0xAU=A@9kPWmcy>Bfx@g4Tep#`9P{YAqHwTY7|6um7b~om)bkpBgY0k#I<>B?Mt7~n|{SWSJ ziofEr>4)0$$MO!FQa6{KeWZ&{yy#n!rM>v_XEiep$JX~fTAg>}dd;9MQ6X!a1_qvr z+n+QzZF>gFo)qHvmgB+iDdjo`Op3cR7J)(+ zNu<^$Oh@zVm@y|>Ip@((B~dAYXVTKkrnOEj4N=+a9EqvHFJlOH zA6rkZxC?mSPt3~b-|5ot9-2`*TK~MGe$wp2J%6c6JiBK1;z%I}pXR$vlyMP95 z5$A`7&T~2){vhkt_k;f8u&z|!Pv?n%aGvThq@=W}jQSK%m234zoL1uL!F@bhTA>|M zQda7t@2YdN2zU7Nk&-eKwWHB@*L9=gD(6lu$LTbtjhKS|HD&n~RpP0M+RkvV6`Yz3 z_;R2hPEOSLCG9`p(f_naHwyW$KBfOTYg7)*QFmHM4Se94(xl+4H=6=yw|BlA9}z9P-Y6 z;Z3#aMRm+xUAWH6}`9b?*+qVi$HjiuGkgK-e_;q!1%AMT;kp z!L2iwKmFj;i|03WDN7Iitp2Y3+dXtU>}H?Xp{;bD{k^zI-_=#WqpMy|)vvUvenVIN z+RS$2zAC+wU$(mE$QN9;$1gH}zOL+lfBtIzhZ@I@t5ht%>G<)&`>%Bh_+_us<3gp= z{qzjOn$?bWcM#7_AiKmKaS6{j?9;!l|~w$*h$-Y=+^_raWX?O*Ao$$I-?l3P>v z6X!eJAGM`;h@sV!nvRdIO`6UJNIV(pxQa^ zw+}BLPr02l{Me|Z-8)r%+nX1kziVIn!rs@8z8BR0>h!DcR$iI9R`FHAz)!voeC3CT z_U{H1xE3@7{Qaz(&DD2@+8j^w3oed#Ym>Q0y?()&b4dfEPPvWQSlZA&WbV=_Yc_qo z7Q4cHTpN^Ib_KP`&TAoGg*#er2y~@gy;1MT8>x*QelT^k-dX2FE85;!oq`5oxI9I_ z3Vl0WTVl3yZZ#?=o4Nx@8-v>UUu+EjYL}r4)PLAzdg{7cc9AYEyU37|Y+NGaR7_XM zBZfrKK7y+QKZDVrHv}01=@QqV3!p#o6lx$Yao7EC2crLnK*a4*^)Irb`*&Bli=HXD z)bY%fq06^#IdknxeVF@^x%(5MZJXvNZ|*lY>v-fP-3gcapQm-%cjTuZ%M@`@xo>`# z8CAUcVdTD>`@TGU?)L#JhV30W;dJGs9y3OJdH>X-_PGSJu*=nN?N7^p?zC@elj&=P zo^N-JQfU^?d;jFj zsN#1-?rqWL(B;nJLEk0*;JRbzg;uH=E1RZt&JF0ItKLj|M^BsTb-4DN>EfCGk?ZbL zez*6p9{c>mYoGZXY2)8_UB!m~#17J~z;R{b$BOUjoX%bt^v1gfuj^vS)owOJbP>9N zYs1zKm}3;LK(fjv`xHrMMZPR7EzI`?*SEB+BzsC$MY%7PDpe|~)CULtvch;fvYB-9 z%gfKk4?Dc*rTq4V>nE=0-RfrTg)^(u8v5kByZ;tCrtj#>P9A-hY#p0CsPRbrs#^{3 zy|C=fFm3;UU;89{eB8JvC+l=T?xoQOB3>99vtiVp-=7>mux^Ik-q$a@e*3he|CHP| z-$vB_?Smz=Qa%|xefFoXIyWS}|J@4_-)grtx}G>}&>vmc`1v0%#eR~y)NtgRE2pNv z_x(%7-|Cu~-f#a$u2OWkEWuR@H-e+xB|xvo z`)SLc|97^@8l~2{04?u8+R!@?dwvJ9epZLk7aVnM{g<0VTo2#(olz9jGyeY93$8uc z_T;GG-_7ILwRPVn-FiW&81`O+A@v!Tk)FZ#Uf8~KLCCOO#)RUe!}``CMa`#9eLmtX z*R7i_T#V^GaM#h#Ygha@{MVujjVr>xv;Fe!#xX(f`(~V)X&St4cv6g})1KIiOIPaB zhE2)dd1n9R-S4$tmAJQjK&OzpopTp_FzryZmN;-zFrxB=VU5ftaOl)^Bug zvhA6W;aPjq>(^OttbG6726gF-^ZpTw-`SIUEZx=pZNIi}CaJm%e0}lWlQ+U_Du%e# zJ~Uq6u_bzXp;y~XrO7z8_(}Ndtzup7DWjfrQ2a3LQsPzHt228EO4Zvn%D%{l$3MH= zSN-3(;%R5+Al@JApu`&!rNU}2{%8BFuCqMAMX+hzRgJ#zQ*h^Oh$6!3{f#n8r=fk& znf85KoeD43wM1`t=-O&%>W^(gcw}?)5x2q5USAtF^md_Q&6dFj_BriHzS?|ly;t>xZVBth z9PCqDx^ewvS98)UHTBi88`pi9JAHG=a=kjGg! zZ+pxgcQEkuP5tkNixa-Dn!ZoBC4Wv#^8%+st_zdK>T7I@v7r^<#wERv{l9VrC0Jht z{^@q>+Uj~L5b@5egG%4p>Sn7A-U7DVjCJH&wJm>lz#Bk$ppCx0O}mR{n=k8aM_>Ow z&!^p2E{fZKx|iEpk9)amd(ZU1Zx@u|_XbS3Z>zXX?#>b8P;DcSQZGKF$AAQeh zW$j{h!}g8FMa7ZtJQ~*N_R=`#q$8bY9r|WP?VK^?hAC5CUO3$CL3a7hm(M5r9-BG7 zHaR}*n@=3q)d+ETPafTp8asWBU<50Gi)P1v{mr<4ay#+QB{NpnsU0K_ z1B%-$*>q}~XH`&_<57R}y*#2S+4tbN&?yt*Pd_<&?t_9%q3O>2?H#|L_I{ezD~H3A zkErst&Ybk(?;Gbo<2d@#+pgh>m)HNecfYUc#FH_X4y;zcIyPYW_A|YL8^?E;zUR6S z?)$X$j6c45?`DzXmgln`y>swyZ;WbQyH)jO>t%;~ZrfCL62G>+BfqbcyTRktpkt42 zwZ1X9!{OI1xUMbG7I?gtwkfqa3U;Cw1x95@?ZvAj$$;tN`*UTR0 zKGkd95~rlip?k+ijtiJL=-JEf_nlcRct*Tp^U;JpekT?!*;D@MnVpl)_Pldz{G^xm VXQc0|TekeI1$m{%qWu+${|A np.ndarray: - """Same as `maps.colorize_topdown_map` in Habitat-Lab, but with different - colors. - """ - _map = TOP_DOWN_MAP_COLORS[top_down_map] - - if fog_of_war_mask is not None: - fog_of_war_desat_values = np.array([[fog_of_war_desat_amount], [1.0]]) - # Only desaturate valid points as only valid points get revealed - desat_mask = top_down_map != MAP_INVALID_POINT - - _map[desat_mask] = (_map * fog_of_war_desat_values[fog_of_war_mask]).astype(np.uint8)[desat_mask] - - return _map - - -def static_to_grid( - realworld_x: float, - realworld_y: float, - grid_resolution: Tuple[int, int], - bounds: Dict[str, Tuple[float, float]], -) -> Tuple[int, int]: - """Return gridworld index of realworld coordinates assuming top-left - corner is the origin. The real world coordinates of lower left corner are - (coordinate_min, coordinate_min) and of top right corner are - (coordinate_max, coordinate_max). Same as the habitat-Lab maps.to_grid - function but with a static `bounds` instead of requiring a simulator or - pathfinder instance. - """ - grid_size = ( - abs(bounds["upper"][2] - bounds["lower"][2]) / grid_resolution[0], - abs(bounds["upper"][0] - bounds["lower"][0]) / grid_resolution[1], - ) - grid_x = int((realworld_x - bounds["lower"][2]) / grid_size[0]) - grid_y = int((realworld_y - bounds["lower"][0]) / grid_size[1]) - return grid_x, grid_y - - -def drawline( - img: np.ndarray, - pt1: Union[Tuple[float], List[float]], - pt2: Union[Tuple[float], List[float]], - color: List[int], - thickness: int = 1, - style: str = "dotted", - gap: int = 15, -) -> None: - """https://stackoverflow.com/questions/26690932/opencv-rectangle-with-dotted-or-dashed-lines - style: "dotted", "dashed", or "filled" - """ - assert style in ["dotted", "dashed", "filled"] - - if style == "filled": - cv2.line(img, pt1, pt2, color, thickness) - return - - dist = ((pt1[0] - pt2[0]) ** 2 + (pt1[1] - pt2[1]) ** 2) ** 0.5 - pts = [] - for i in np.arange(0, dist, gap): - r = i / dist - x = int((pt1[0] * (1 - r) + pt2[0] * r) + 0.5) - y = int((pt1[1] * (1 - r) + pt2[1] * r) + 0.5) - pts.append((x, y)) - - if style == "dotted": - for p in pts: - cv2.circle(img, p, thickness, color, -1) - else: - s = pts[0] - e = pts[0] - for i, p in enumerate(pts): - s = e - e = p - if i % 2 == 1: - cv2.line(img, s, e, color, thickness) - - -def drawpoint( - img: np.ndarray, - position: Union[Tuple[int], List[int]], - color: List[int], - meters_per_px: float, - pad: float = 0.3, -) -> None: - point_padding = int(pad / meters_per_px) - img[ - position[0] - point_padding : position[0] + point_padding + 1, - position[1] - point_padding : position[1] + point_padding + 1, - ] = color - - -def draw_triangle( - img: np.ndarray, - centroid: Union[Tuple[int], List[int]], - color: List[int], - meters_per_px: float, - pad: int = 0.35, -) -> None: - point_padding = int(pad / meters_per_px) - - # (Y, X) - left = (centroid[1] - point_padding, centroid[0] + point_padding) - right = (centroid[1] + point_padding, centroid[0] + point_padding) - top = (centroid[1], centroid[0] - point_padding) - cv2.drawContours(img, [np.array([left, right, top])], 0, color, -1) - - -def draw_reference_path( - img: np.ndarray, - sim: Simulator, - episode: VLNEpisode, - map_resolution: int, - meters_per_px: float, -) -> None: - """Draws lines between each waypoint in the reference path.""" - shortest_path_points = [ - habitat_maps.to_grid( - p[2], - p[0], - img.shape[0:2], - sim, - )[::-1] - for p in episode.reference_path - ] - - pt_from = None - for i, pt_to in enumerate(shortest_path_points): - - if i != 0: - drawline( - img, - (pt_from[0], pt_from[1]), - (pt_to[0], pt_to[1]), - MAP_SHORTEST_PATH_WAYPOINT, - thickness=int(0.4 * map_resolution / MAP_THICKNESS_SCALAR), - style="dashed", - gap=10, - ) - pt_from = pt_to - - for pt in shortest_path_points: - drawpoint(img, (pt[1], pt[0]), MAP_SHORTEST_PATH_WAYPOINT, meters_per_px) - - -def draw_straight_shortest_path_points( - img: np.ndarray, - sim: Simulator, - map_resolution: int, - shortest_path_points: List[List[float]], -) -> None: - """Draws the shortest path from start to goal assuming a standard - discrete action space. - """ - shortest_path_points = [habitat_maps.to_grid(p[2], p[0], img.shape[0:2], sim)[::-1] for p in shortest_path_points] - - habitat_maps.draw_path( - img, - [(p[1], p[0]) for p in shortest_path_points], - MAP_SHORTEST_PATH_WAYPOINT, - int(0.4 * map_resolution / MAP_THICKNESS_SCALAR), - ) - - -def draw_source_and_target(img: np.ndarray, sim: Simulator, episode: VLNEpisode, meters_per_px: float) -> None: - s_x, s_y = habitat_maps.to_grid( - episode.start_position[2], - episode.start_position[0], - img.shape[0:2], - sim, - ) - drawpoint(img, (s_x, s_y), MAP_SOURCE_POINT_INDICATOR, meters_per_px) - - # mark target point - t_x, t_y = habitat_maps.to_grid( - episode.goals[0].position[2], - episode.goals[0].position[0], - img.shape[0:2], - sim, - ) - drawpoint(img, (t_x, t_y), MAP_TARGET_POINT_INDICATOR, meters_per_px) - - -def draw_waypoint_prediction( - img: np.ndarray, - waypoint: Union[Tuple[float], List[float]], - meters_per_px: float, - bounds: Dict[str, Tuple[float]], -) -> None: - w_x, w_y = static_to_grid(waypoint[1], waypoint[0], img.shape[0:2], bounds) - if w_x < img.shape[0] and w_x > 0 and w_y < img.shape[1] and w_y > 0: - draw_triangle(img, (w_x, w_y), MAP_WAYPOINT_PREDICTION, meters_per_px) - - -def draw_oracle_waypoint( - img: np.ndarray, - waypoint: Union[Tuple[float], List[float]], - meters_per_px: float, - bounds: Dict[str, Tuple[float]], -) -> None: - w_x, w_y = static_to_grid(waypoint[1], waypoint[0], img.shape[0:2], bounds) - draw_triangle(img, (w_x, w_y), MAP_ORACLE_WAYPOINT, meters_per_px, pad=0.2) - - -def get_nearest_node(graph: nx.Graph, current_position: List[float]) -> str: - """Determine the closest MP3D node to the agent's start position as given - by a [x,z] position vector. - Returns: - node ID - """ - nearest = None - dist = float("inf") - for node in graph: - node_pos = graph.nodes[node]["position"] - node_pos = np.take(node_pos, (0, 2)) - cur_dist = np.linalg.norm(np.array(node_pos) - np.array(current_position), ord=2) - if cur_dist < dist: - dist = cur_dist - nearest = node - return nearest - - -def update_nearest_node(graph: nx.Graph, nearest_node: str, current_position: np.ndarray) -> str: - """Determine the closest MP3D node to the agent's current position as - given by a [x,z] position vector. The selected node must be reachable - from the previous MP3D node as specified in the nav-graph edges. - Returns: - node ID - """ - nearest = None - dist = float("inf") - - for node in [nearest_node] + [e[1] for e in graph.edges(nearest_node)]: - node_pos = graph.nodes[node]["position"] - node_pos = np.take(node_pos, (0, 2)) - cur_dist = np.linalg.norm(np.array(node_pos) - np.array(current_position), ord=2) - if cur_dist < dist: - dist = cur_dist - nearest = node - return nearest - - -def draw_mp3d_nodes( - img: np.ndarray, - sim: Simulator, - episode: VLNEpisode, - graph: nx.Graph, - meters_per_px: float, -) -> None: - n = get_nearest_node(graph, (episode.start_position[0], episode.start_position[2])) - starting_height = graph.nodes[n]["position"][1] - for node in graph: - pos = graph.nodes[node]["position"] - - # no obvious way to differentiate between floors. Use this for now. - if abs(pos[1] - starting_height) < 1.0: - r_x, r_y = habitat_maps.to_grid(pos[2], pos[0], img.shape[0:2], sim) - - # only paint if over a valid point - if img[r_x, r_y]: - drawpoint(img, (r_x, r_y), MAP_MP3D_WAYPOINT, meters_per_px) - - -from typing import Tuple - -import torch -from torch import Tensor - - -def image_resize( - img: Tensor, - size: Tuple[int, int], - channels_last: bool = False, - interpolation_mode: str = "area", -) -> torch.Tensor: - """Resizes an img. - - Args: - img: the array object that needs to be resized (HWC) or (NHWC) - size: the size that you want - channels: a boolean that channel is the last dimension - Returns: - The resized array as a torch tensor. - """ - img = torch.as_tensor(img) - no_batch_dim = len(img.shape) == 3 - if len(img.shape) < 3 or len(img.shape) > 5: - raise NotImplementedError() - if no_batch_dim: - img = img.unsqueeze(0) # Adds a batch dimension - if channels_last: - if len(img.shape) == 4: - # NHWC -> NCHW - img = img.permute(0, 3, 1, 2) - else: - # NDHWC -> NDCHW - img = img.permute(0, 1, 4, 2, 3) - - img = torch.nn.functional.interpolate(img.float(), size=size, mode=interpolation_mode).to(dtype=img.dtype) - if channels_last: - if len(img.shape) == 4: - # NCHW -> NHWC - img = img.permute(0, 2, 3, 1) - else: - # NDCHW -> NDHWC - img = img.permute(0, 1, 3, 4, 2) - if no_batch_dim: - img = img.squeeze(dim=0) # Removes the batch dimension - return img diff --git a/internnav/env/utils/habitat_extensions/measures.py b/internnav/env/utils/habitat_extensions/measures.py deleted file mode 100644 index 5dddcae..0000000 --- a/internnav/env/utils/habitat_extensions/measures.py +++ /dev/null @@ -1,560 +0,0 @@ -from typing import Any, List, Union - -import numpy as np -from habitat.core.embodied_task import EmbodiedTask, Measure -from habitat.core.registry import registry -from habitat.core.simulator import Simulator -from habitat.core.utils import try_cv2_import -from habitat.tasks.nav.nav import DistanceToGoal -from numpy import ndarray - -cv2 = try_cv2_import() - - -def euclidean_distance(pos_a: Union[List[float], ndarray], pos_b: Union[List[float], ndarray]) -> float: - return np.linalg.norm(np.array(pos_b) - np.array(pos_a), ord=2) - - -@registry.register_measure -class PathLength(Measure): - """Path Length (PL) - PL = sum(geodesic_distance(agent_prev_position, agent_position) - over all agent positions. - """ - - cls_uuid: str = "path_length" - - def __init__(self, sim: Simulator, *args: Any, **kwargs: Any): - self._sim = sim - super().__init__(**kwargs) - - def _get_uuid(self, *args: Any, **kwargs: Any) -> str: - return self.cls_uuid - - def reset_metric(self, *args: Any, **kwargs: Any): - self._previous_position = self._sim.get_agent_state().position - self._metric = 0.0 - - def update_metric(self, *args: Any, **kwargs: Any): - current_position = self._sim.get_agent_state().position - self._metric += euclidean_distance(current_position, self._previous_position) - self._previous_position = current_position - - -@registry.register_measure -class OracleNavigationError(Measure): - """Oracle Navigation Error (ONE) - ONE = min(geosdesic_distance(agent_pos, goal)) over all points in the - agent path. - """ - - cls_uuid: str = "oracle_navigation_error" - - def _get_uuid(self, *args: Any, **kwargs: Any) -> str: - return self.cls_uuid - - def reset_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): - task.measurements.check_measure_dependencies(self.uuid, [DistanceToGoal.cls_uuid]) - self._metric = float("inf") - self.update_metric(task=task) - - def update_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): - distance_to_target = task.measurements.measures[DistanceToGoal.cls_uuid].get_metric() - self._metric = min(self._metric, distance_to_target) - - -@registry.register_measure -class OracleSuccess(Measure): - """Oracle Success Rate (OSR). OSR = I(ONE <= goal_radius)""" - - cls_uuid: str = "oracle_success" - - # def __init__(self, *args: Any, config: Config, **kwargs: Any): - # self._config = config - # super().__init__() - - def __init__(self, *args: Any, config: Any, **kwargs: Any): - print(f"in oracle success init: args = {args}, kwargs = {kwargs}") - self._config = config - super().__init__() - - def _get_uuid(self, *args: Any, **kwargs: Any) -> str: - return self.cls_uuid - - def reset_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): - task.measurements.check_measure_dependencies(self.uuid, [DistanceToGoal.cls_uuid]) - self._metric = 0.0 - self.update_metric(task=task) - - def update_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): - d = task.measurements.measures[DistanceToGoal.cls_uuid].get_metric() - # self._metric = float(self._metric or d < self._config["success_distance"]) - self._metric = float(self._metric or d < 3.0) - - -@registry.register_measure -class OracleSPL(Measure): - """OracleSPL (Oracle Success weighted by Path Length) - OracleSPL = max(SPL) over all points in the agent path. - """ - - cls_uuid: str = "oracle_spl" - - def _get_uuid(self, *args: Any, **kwargs: Any) -> str: - return self.cls_uuid - - def reset_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): - task.measurements.check_measure_dependencies(self.uuid, ["spl"]) - self._metric = 0.0 - - def update_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): - spl = task.measurements.measures["spl"].get_metric() - self._metric = max(self._metric, spl) - - -@registry.register_measure -class StepsTaken(Measure): - """Counts the number of times update_metric() is called. This is equal to - the number of times that the agent takes an action. STOP counts as an - action. - """ - - cls_uuid: str = "steps_taken" - - def _get_uuid(self, *args: Any, **kwargs: Any) -> str: - return self.cls_uuid - - def reset_metric(self, *args: Any, **kwargs: Any): - self._metric = 0.0 - - def update_metric(self, *args: Any, **kwargs: Any): - self._metric += 1.0 - - -# import gzip -# import json -# import pickle -# from dtw import dtw -# from fastdtw import fastdtw -# from habitat.config import Config -# from utils import maps -# from habitat_extensions.task import RxRVLNCEDatasetV1 -# from habitat.tasks.nav.nav import DistanceToGoal, Success -# from habitat.tasks.utils import cartesian_to_polar -# from habitat.utils.geometry_utils import quaternion_rotate_vector -# from habitat.utils.visualizations import fog_of_war -# from habitat.utils.visualizations import maps as habitat_maps -# from habitat.core.dataset import Episode -# from habitat.core.embodied_task import Action, EmbodiedTask, Measure -# from habitat.core.logging import logger - -# @registry.register_measure -# class WaypointRewardMeasure(Measure): -# """A reward measure used for training VLN-CE agents via RL.""" - -# def __init__( -# self, *args: Any, sim: Simulator, config: Config, **kwargs: Any -# ) -> None: -# self._sim = sim -# self._slack_reward = config.slack_reward -# self._use_distance_scaled_slack_reward = ( -# config.use_distance_scaled_slack_reward -# ) -# self._scale_slack_on_prediction = config.scale_slack_on_prediction -# self._success_reward = config.success_reward -# self._distance_scalar = config.distance_scalar -# self._prev_position = None -# super().__init__() - -# def reset_metric( -# self, *args: Any, task: EmbodiedTask, **kwargs: Any -# ) -> None: -# task.measurements.check_measure_dependencies( -# self.uuid, [DistanceToGoal.cls_uuid, Success.cls_uuid] -# ) -# self._previous_distance_to_goal = task.measurements.measures[ -# "distance_to_goal" -# ].get_metric() -# self._metric = 0.0 -# self._prev_position = np.take( -# self._sim.get_agent_state().position, [0, 2] -# ) - -# def _get_scaled_slack_reward(self, action: Action) -> float: -# if isinstance(action["action"], int): -# return self._slack_reward - -# if not self._use_distance_scaled_slack_reward: -# return self._slack_reward - -# agent_pos = np.take(self._sim.get_agent_state().position, [0, 2]) -# slack_distance = ( -# action["action_args"]["r"] -# if self._scale_slack_on_prediction and action["action"] != "STOP" -# else np.linalg.norm(self._prev_position - agent_pos) -# ) -# scaled_slack_reward = self._slack_reward * slack_distance / 0.25 -# self._prev_position = agent_pos -# return min(self._slack_reward, scaled_slack_reward) - -# def _progress_to_goal(self, task: EmbodiedTask) -> float: -# distance_to_goal = task.measurements.measures[ -# "distance_to_goal" -# ].get_metric() -# distance_to_goal_delta = ( -# self._previous_distance_to_goal - distance_to_goal -# ) -# if np.isnan(distance_to_goal_delta) or np.isinf( -# distance_to_goal_delta -# ): -# l = self._sim.get_agent_state().position -# logger.error( -# f"\nNaN or inf encountered in distance measure. agent location: {l}", -# ) -# distance_to_goal_delta = -1.0 -# self._previous_distance_to_goal = distance_to_goal -# return self._distance_scalar * distance_to_goal_delta - -# def update_metric( -# self, *args: Any, action: Action, task: EmbodiedTask, **kwargs: Any -# ) -> None: -# reward = self._get_scaled_slack_reward(action) -# reward += self._progress_to_goal(task) -# reward += ( -# self._success_reward -# * task.measurements.measures["success"].get_metric() -# ) -# self._metric = reward - -# @staticmethod -# def _get_uuid(*args: Any, **kwargs: Any) -> str: -# return "waypoint_reward_measure" - - -# @registry.register_measure -# class NDTW(Measure): -# """NDTW (Normalized Dynamic Time Warping) -# ref: https://arxiv.org/abs/1907.05446 -# """ - -# cls_uuid: str = "ndtw" - -# def __init__( -# self, *args: Any, sim: Simulator, config: Config, **kwargs: Any -# ): -# self._sim = sim -# self._config = config -# self.dtw_func = fastdtw if config.FDTW else dtw - -# if "{role}" in config.GT_PATH: -# self.gt_json = {} -# for role in RxRVLNCEDatasetV1.annotation_roles: -# with gzip.open( -# config.GT_PATH.format(split=config.SPLIT, role=role), "rt" -# ) as f: -# self.gt_json.update(json.load(f)) -# else: -# with gzip.open( -# config.GT_PATH.format(split=config.SPLIT), "rt" -# ) as f: -# self.gt_json = json.load(f) - -# super().__init__() - -# def _get_uuid(self, *args: Any, **kwargs: Any) -> str: -# return self.cls_uuid - -# def reset_metric(self, *args: Any, episode, **kwargs: Any): -# self.locations = [] -# self.gt_locations = self.gt_json[episode.episode_id]["locations"] -# self.update_metric() - -# def update_metric(self, *args: Any, **kwargs: Any): -# current_position = self._sim.get_agent_state().position.tolist() -# if len(self.locations) == 0: -# self.locations.append(current_position) -# else: -# if current_position == self.locations[-1]: -# return -# self.locations.append(current_position) - -# dtw_distance = self.dtw_func( -# self.locations, self.gt_locations, dist=euclidean_distance -# )[0] - -# nDTW = np.exp( -# -dtw_distance -# / (len(self.gt_locations) * self._config.SUCCESS_DISTANCE) -# ) -# self._metric = nDTW - - -# @registry.register_measure -# class SDTW(Measure): -# """SDTW (Success Weighted be nDTW) -# ref: https://arxiv.org/abs/1907.05446 -# """ - -# cls_uuid: str = "sdtw" - -# def _get_uuid(self, *args: Any, **kwargs: Any) -> str: -# return self.cls_uuid - -# def reset_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): -# task.measurements.check_measure_dependencies( -# self.uuid, [NDTW.cls_uuid, Success.cls_uuid] -# ) -# self.update_metric(task=task) - -# def update_metric(self, *args: Any, task: EmbodiedTask, **kwargs: Any): -# ep_success = task.measurements.measures[Success.cls_uuid].get_metric() -# nDTW = task.measurements.measures[NDTW.cls_uuid].get_metric() -# self._metric = ep_success * nDTW - - -# @registry.register_measure -# class TopDownMapVLNCE(Measure): -# """A top down map that optionally shows VLN-related visual information -# such as MP3D node locations and MP3D agent traversals. -# """ - -# cls_uuid: str = "top_down_map_vlnce" - -# def __init__( -# self, *args: Any, sim: Simulator, config: Config, **kwargs: Any -# ) -> None: -# self._sim = sim -# self._config = config -# self._step_count = None -# self._map_resolution = config.MAP_RESOLUTION -# self._previous_xy_location = None -# self._top_down_map = None -# self._meters_per_pixel = None -# self.current_node = "" -# with open(self._config.GRAPHS_FILE, "rb") as f: -# self._conn_graphs = pickle.load(f) -# super().__init__() - -# def _get_uuid(self, *args: Any, **kwargs: Any) -> str: -# return self.cls_uuid - -# def get_original_map(self) -> ndarray: -# top_down_map = habitat_maps.get_topdown_map_from_sim( -# self._sim, -# map_resolution=self._map_resolution, -# draw_border=self._config.DRAW_BORDER, -# meters_per_pixel=self._meters_per_pixel, -# ) - -# self._fog_of_war_mask = None -# if self._config.FOG_OF_WAR.DRAW: -# self._fog_of_war_mask = np.zeros_like(top_down_map) - -# return top_down_map - -# def reset_metric( -# self, *args: Any, episode: Episode, **kwargs: Any -# ) -> None: -# self._scene_id = episode.scene_id.split("/")[-2] -# self._step_count = 0 -# self._metric = None -# self._meters_per_pixel = habitat_maps.calculate_meters_per_pixel( -# self._map_resolution, self._sim -# ) -# self._top_down_map = self.get_original_map() -# agent_position = self._sim.get_agent_state().position -# scene_id = episode.scene_id.split("/")[-1].split(".")[0] -# a_x, a_y = habitat_maps.to_grid( -# agent_position[2], -# agent_position[0], -# self._top_down_map.shape[0:2], -# sim=self._sim, -# ) -# self._previous_xy_location = (a_y, a_x) - -# if self._config.FOG_OF_WAR.DRAW: -# self._fog_of_war_mask = fog_of_war.reveal_fog_of_war( -# self._top_down_map, -# self._fog_of_war_mask, -# np.array([a_x, a_y]), -# self.get_polar_angle(), -# fov=self._config.FOG_OF_WAR.FOV, -# max_line_len=self._config.FOG_OF_WAR.VISIBILITY_DIST -# / habitat_maps.calculate_meters_per_pixel( -# self._map_resolution, sim=self._sim -# ), -# ) - -# if self._config.DRAW_FIXED_WAYPOINTS: -# maps.draw_mp3d_nodes( -# self._top_down_map, -# self._sim, -# episode, -# self._conn_graphs[scene_id], -# self._meters_per_pixel, -# ) - -# if self._config.DRAW_SHORTEST_PATH: -# shortest_path_points = self._sim.get_straight_shortest_path_points( -# agent_position, episode.goals[0].position -# ) -# maps.draw_straight_shortest_path_points( -# self._top_down_map, -# self._sim, -# self._map_resolution, -# shortest_path_points, -# ) - -# if self._config.DRAW_REFERENCE_PATH: -# maps.draw_reference_path( -# self._top_down_map, -# self._sim, -# episode, -# self._map_resolution, -# self._meters_per_pixel, -# ) - -# # draw source and target points last to avoid overlap -# if self._config.DRAW_SOURCE_AND_TARGET: -# maps.draw_source_and_target( -# self._top_down_map, -# self._sim, -# episode, -# self._meters_per_pixel, -# ) - -# # MP3D START NODE -# self._nearest_node = maps.get_nearest_node( -# self._conn_graphs[scene_id], np.take(agent_position, (0, 2)) -# ) -# nn_position = self._conn_graphs[self._scene_id].nodes[ -# self._nearest_node -# ]["position"] -# self.s_x, self.s_y = habitat_maps.to_grid( -# nn_position[2], -# nn_position[0], -# self._top_down_map.shape[0:2], -# self._sim, -# ) -# self.update_metric() - -# def update_metric(self, *args: Any, **kwargs: Any) -> None: -# self._step_count += 1 -# ( -# house_map, -# map_agent_pos, -# ) = self.update_map(self._sim.get_agent_state().position) - -# self._metric = { -# "map": house_map, -# "fog_of_war_mask": self._fog_of_war_mask, -# "agent_map_coord": map_agent_pos, -# "agent_angle": self.get_polar_angle(), -# "bounds": { -# k: v -# for k, v in zip( -# ["lower", "upper"], -# self._sim.pathfinder.get_bounds(), -# ) -# }, -# "meters_per_px": self._meters_per_pixel, -# } - -# def get_polar_angle(self) -> float: -# agent_state = self._sim.get_agent_state() -# # quaternion is in x, y, z, w format -# ref_rotation = agent_state.rotation - -# heading_vector = quaternion_rotate_vector( -# ref_rotation.inverse(), np.array([0, 0, -1]) -# ) - -# phi = cartesian_to_polar(-heading_vector[2], heading_vector[0])[1] -# z_neg_z_flip = np.pi -# return np.array(phi) + z_neg_z_flip - -# def update_map(self, agent_position: List[float]) -> None: -# a_x, a_y = habitat_maps.to_grid( -# agent_position[2], -# agent_position[0], -# self._top_down_map.shape[0:2], -# self._sim, -# ) -# # Don't draw over the source point -# gradient_color = 15 + min( -# self._step_count * 245 // self._config.MAX_EPISODE_STEPS, 245 -# ) -# if self._top_down_map[a_x, a_y] != maps.MAP_SOURCE_POINT_INDICATOR: -# maps.drawline( -# self._top_down_map, -# self._previous_xy_location, -# (a_y, a_x), -# gradient_color, -# thickness=int( -# self._map_resolution * 1.4 / maps.MAP_THICKNESS_SCALAR -# ), -# style="filled", -# ) - -# if self._config.FOG_OF_WAR.DRAW: -# self._fog_of_war_mask = fog_of_war.reveal_fog_of_war( -# self._top_down_map, -# self._fog_of_war_mask, -# np.array([a_x, a_y]), -# self.get_polar_angle(), -# self._config.FOG_OF_WAR.FOV, -# max_line_len=self._config.FOG_OF_WAR.VISIBILITY_DIST -# / habitat_maps.calculate_meters_per_pixel( -# self._map_resolution, sim=self._sim -# ), -# ) - -# point_padding = int(0.2 / self._meters_per_pixel) -# prev_nearest_node = self._nearest_node -# self._nearest_node = maps.update_nearest_node( -# self._conn_graphs[self._scene_id], -# self._nearest_node, -# np.take(agent_position, (0, 2)), -# ) -# if ( -# self._nearest_node != prev_nearest_node -# and self._config.DRAW_MP3D_AGENT_PATH -# ): -# nn_position = self._conn_graphs[self._scene_id].nodes[ -# self._nearest_node -# ]["position"] -# (prev_s_x, prev_s_y) = (self.s_x, self.s_y) -# self.s_x, self.s_y = habitat_maps.to_grid( -# nn_position[2], -# nn_position[0], -# self._top_down_map.shape[0:2], -# self._sim, -# ) -# self._top_down_map[ -# self.s_x -# - int(2.0 / 3.0 * point_padding) : self.s_x -# + int(2.0 / 3.0 * point_padding) -# + 1, -# self.s_y -# - int(2.0 / 3.0 * point_padding) : self.s_y -# + int(2.0 / 3.0 * point_padding) -# + 1, -# ] = gradient_color - -# maps.drawline( -# self._top_down_map, -# (prev_s_y, prev_s_x), -# (self.s_y, self.s_x), -# gradient_color, -# thickness=int( -# 1.0 -# / 2.0 -# * np.round( -# self._map_resolution / maps.MAP_THICKNESS_SCALAR -# ) -# ), -# ) - -# self._previous_xy_location = (a_y, a_x) -# map_agent_pos = (a_x, a_y) -# return self._top_down_map, map_agent_pos diff --git a/internnav/evaluator/utils/data_collector.py b/internnav/evaluator/utils/data_collector.py index 99659b6..0cc9117 100644 --- a/internnav/evaluator/utils/data_collector.py +++ b/internnav/evaluator/utils/data_collector.py @@ -7,12 +7,14 @@ class DataCollector: - def __init__(self, lmdb_path): + def __init__(self, lmdb_path, rank=0, world_size=1): if not os.path.exists(lmdb_path): os.makedirs(lmdb_path) self.lmdb_path = lmdb_path self.episode_total_data = [] self.actions = [] + self.rank = rank + self.world_size = world_size def collect_observation(self, rgb, depth, step, process, camera_pose, robot_pose): from omni.isaac.core.utils.rotations import quat_to_euler_angles @@ -131,7 +133,7 @@ def save_eval_result(self, key, result, info): if result != 'success': finish_flag = 'fail' database_write = lmdb.open( - f'{self.lmdb_path}/sample_data.lmdb', + f'{self.lmdb_path}/sample_data{self.rank}.lmdb', map_size=1 * 1024 * 1024 * 1024 * 1024, max_dbs=0, lock=True, diff --git a/internnav/evaluator/utils/dataset.py b/internnav/evaluator/utils/dataset.py index 7db38f4..00045a7 100644 --- a/internnav/evaluator/utils/dataset.py +++ b/internnav/evaluator/utils/dataset.py @@ -1,3 +1,4 @@ +import collections import json import os @@ -232,3 +233,97 @@ def log_print(content): f.write('\n'.join(log_content)) self.database_read.close() + + def finalize_all_results(self, rank, world_size): + # Only rank 0 aggregates and writes final results + if rank != 0: + return + + # accumulator for all splits across all ranks + split_acc = {} + for split in self.split_map.keys(): + split_acc[split] = { + "total_TL": 0.0, + "total_NE": 0.0, + "total_osr": 0.0, + "total_success": 0.0, + "total_spl": 0.0, + "reason_map": collections.Counter({"reach_goal": 0}), + "count": 0, + } + + # loop over all ranks' lmdbs + for i in range(world_size): + lmdb_dir = f"{self.lmdb_path}/sample_data{i}.lmdb" + if not os.path.exists(lmdb_dir): + # this rank might not have produced a db; skip + continue + + env = lmdb.open( + lmdb_dir, + readonly=True, + lock=False, + max_readers=256, + ) + + for split, path_key_list in self.split_map.items(): + for path_key in path_key_list: + with env.begin() as txn: + value = txn.get(path_key.encode()) + if value is None: + continue + + data = msgpack_numpy.unpackb(value) + data["path_key"] = path_key + + acc = split_acc[split] + + TL = data["info"]["TL"] + NE = data["info"]["NE"] + if NE < 0: + NE = 0 + osr = data["info"]["osr"] + if osr < 0: + osr = 0 + success = data["info"]["success"] + spl = data["info"]["spl"] + + acc["total_TL"] += TL + acc["total_NE"] += NE + acc["total_osr"] += osr + acc["total_success"] += success + acc["total_spl"] += spl + acc["count"] += 1 + + ret_type = data.get("fail_reason", "") or "success" + acc["reason_map"][ret_type] += 1 + if success > 0: + acc["reason_map"]["reach_goal"] += 1 + + env.close() + + # build final json + json_data = {} + for split, acc in split_acc.items(): + count = acc["count"] + if count == 0: + continue + + reason_map = acc["reason_map"] + fall = reason_map.get("fall", 0) + stuck = reason_map.get("stuck", 0) + + json_data[split] = { + "TL": round(acc["total_TL"] / count, 4), + "NE": round(acc["total_NE"] / count, 4), + "FR": round(fall / count, 4), + "StR": round(stuck / count, 4), + "OS": round(acc["total_osr"] / count, 4), + "SR": round(acc["total_success"] / count, 4), + "SPL": round(acc["total_spl"] / count, 4), + "Count": count, + } + + # write log content to file + with open(f"{self.name}_result.json", "w") as f: + json.dump(json_data, f, indent=2, ensure_ascii=False) diff --git a/internnav/evaluator/vln_multi_distributed_evaluator.py b/internnav/evaluator/vln_multi_distributed_evaluator.py index 9cbb0bc..9b6f25d 100644 --- a/internnav/evaluator/vln_multi_distributed_evaluator.py +++ b/internnav/evaluator/vln_multi_distributed_evaluator.py @@ -41,14 +41,6 @@ def __init__(self, config: EvalCfg): if 'distribution_config' in config.env.env_settings else 1 ) - # check env_num and proc_num - # priority: reduce env_num first then reduce proc_num - while self.env_num > 1 and self.proc_num * self.env_num > self.total_path_num: - self.env_num -= 1 - log.info(f'dataset size is too small! Change env_num to {self.env_num}.') - while self.proc_num > 1 and self.proc_num * self.env_num > self.total_path_num: - self.proc_num -= 1 - log.info(f'dataset size is too small! Change proc_num to {self.proc_num}.') # update config config.task.task_settings['env_num'] = self.env_num @@ -67,7 +59,7 @@ def __init__(self, config: EvalCfg): progress_log_multi_util.progress_logger_multi.info( f'start eval dataset: {self.task_name}, total_path: {self.total_path_num}' # noqa: E501 ) - self.data_collector = DataCollector(get_lmdb_path(self.task_name)) + self.data_collector = DataCollector(get_lmdb_path(self.task_name), rank=self.rank, world_size=self.world_size) self.robot_flash = config.task.robot_flash self.save_to_json = config.eval_settings['save_to_json'] self.vis_output = config.eval_settings['vis_output'] @@ -239,9 +231,10 @@ def terminate_ops(self, obs_ls, reset_infos, terminated_ls): result=obs['metrics'][list(obs['metrics'].keys())[0]][0]['fail_reason'], ) # json format result - if self.save_to_json: - self.result_logger.write_now_result_json() - self.result_logger.write_now_result() + # if self.save_to_json: + # self.result_logger.write_now_result_json() + # self.result_logger.write_now_result() + self.result_logger.finalize_all_results(self.rank, self.world_size) self.runner_status[env_id] = runner_status_code.NOT_RESET log.info(f'env{env_id}: states switch to NOT_RESET.') # need this status to reset diff --git a/internnav/internnav_habitat/README.md b/internnav/internnav_habitat/README.md index b7c5d73..c877b1c 100644 --- a/internnav/internnav_habitat/README.md +++ b/internnav/internnav_habitat/README.md @@ -32,8 +32,6 @@ internnav_habitat/ * `measures.py` registers additional Habitat measurements (path length, oracle metrics, step counts) that are required by the evaluators. -The `refactor_notes.md` file captures design notes and TODOs collected during a -previous refactoring pass. ## Habitat environment wrapper diff --git a/internnav/internnav_habitat/habitat_vln_evaluator.py b/internnav/internnav_habitat/habitat_vln_evaluator.py index 0be81f4..137a446 100644 --- a/internnav/internnav_habitat/habitat_vln_evaluator.py +++ b/internnav/internnav_habitat/habitat_vln_evaluator.py @@ -226,7 +226,6 @@ def _run_local_eval(self) -> None: # noqa: C901 self.model.eval() # resume from previous results - # TODO: Current read write op is not distributed safe if os.path.exists(os.path.join(self.output_path, 'progress.json')): with open(os.path.join(self.output_path, 'progress.json'), 'r') as f: for line in f.readlines(): @@ -240,7 +239,7 @@ def _run_local_eval(self) -> None: # noqa: C901 torch.tensor(nes).to(self.device), torch.tensor(len(sucs)).to(self.device), ) - if self.rank == 0: # noqa: F405 TODO this need to keep in evaluator + if self.rank == 0: # noqa: F405 sucs.append(res['success']) spls.append(res['spl']) oss.append(res['os']) diff --git a/internnav/internnav_habitat/refactor_notes.md b/internnav/internnav_habitat/refactor_notes.md deleted file mode 100644 index 7a197b4..0000000 --- a/internnav/internnav_habitat/refactor_notes.md +++ /dev/null @@ -1,66 +0,0 @@ -# Refactoring `habitat_vln_evaluator` - -This note explains how to split the current `VLNEvaluator` implementation into the -framework's `Env` and `Agent` abstractions. - -## 1. Construction and configuration (lines 45-135) -* **Environment**: Habitat config loading, dataset split selection, sensor parameter - extraction, and measurement registration belong to the environment setup. These - responsibilities configure and own the simulator state and therefore should be - moved into a `HabitatVLNEnv` class that extends `Env`.【F:internnav/evaluator/habitat_vln_evaluator.py†L45-L103】 -* **Agent**: Model handles, prompt bootstrapping, conversation history, action - vocabulary, and instruction templates are part of the policy logic and should be - carried by a dedicated `HabitatVLNAgent` subclass. These fields initialize the - reasoning model rather than the simulator.【F:internnav/evaluator/habitat_vln_evaluator.py†L104-L135】 - -## 2. Perception utilities (lines 137-236) -Depth pre-processing, intrinsic matrix computation, coordinate transforms, and GPS -projection are tied to the simulator sensor geometry. They should move into the -`HabitatVLNEnv` so that observation tensors returned to the agent are already in a -consistent world frame.【F:internnav/evaluator/habitat_vln_evaluator.py†L137-L236】 - -## 3. Visualization helper (lines 238-309) -The dot-matrix overlay operates purely on rendered frames and can stay as an -environment utility. The helper should become a method of the environment (or a -separate visualization module) so evaluators can call it regardless of the agent. -【F:internnav/evaluator/habitat_vln_evaluator.py†L238-L309】 - -## 4. Low-level point navigation (lines 311-347) -The `_pointnav` helper controls a waypoint-following controller that consumes -processed observations and outputs low-level actions. Because it interacts with the -robot's state (goal resets, depth resizing, point-goal calculation), it fits inside -the environment. The agent can request point-goal actions through a method such as -`HabitatVLNEnv.pointnav(goal, depth, ...)`.【F:internnav/evaluator/habitat_vln_evaluator.py†L311-L347】 - -## 5. Main evaluation loop (lines 349-520) -* **Environment**: Episode iteration, resetting, stepping, intrinsic assembly, and - metric gathering should be owned by the environment. Wrapping Habitat's episode - lifecycle in `HabitatVLNEnv` keeps the evaluator thin and deterministic. -* **Agent**: Generating waypoint predictions, maintaining conversation turns, and - deciding discrete actions are policy responsibilities. The evaluator should ask - the new agent for an action by passing observations (RGB, depth, state metadata) - returned by the environment wrapper.【F:internnav/evaluator/habitat_vln_evaluator.py†L349-L520】 - -## 6. Language and action parsing (lines 522-680) -Instruction processing (`split_and_clean`, dynamic prompt assembly) and action string -parsing convert model text into executable commands. These should be encapsulated in -`HabitatVLNAgent` so the evaluator only receives structured actions (e.g., STOP, -MOVE, LOOK).【F:internnav/evaluator/habitat_vln_evaluator.py†L522-L680】 - -## 7. Metric aggregation and exports (lines 682-745) -Writing JSON lines, aggregating SPL/OS/NE, and optional video dumping can remain in -the evaluator, but the raw metrics originate from the environment through -`HabitatVLNEnv.get_metrics()` and rendering helpers. The evaluator should simply -post-process the aggregated numbers.【F:internnav/evaluator/habitat_vln_evaluator.py†L682-L745】 - -## Resulting structure -1. **`internnav/env/habitat_vln_env.py`**: wraps Habitat configuration, episode - control, sensor processing, point-nav helper, and visualization utilities. -2. **`internnav/agent/habitat_vln_agent.py`**: encapsulates the vision-language - model, prompt management, observation parsing, and action decoding. -3. **`internnav/evaluator/habitat_vln_evaluator.py`**: becomes a thin coordinator - that instantiates the env/agent via the registry, loops over episodes, and logs - metrics. - -This split brings the Habitat evaluator in line with the existing framework while -keeping domain-specific functionality in focused components. diff --git a/scripts/eval/bash/start_eval.sh b/scripts/eval/bash/start_eval.sh index ce41df1..a7b3639 100755 --- a/scripts/eval/bash/start_eval.sh +++ b/scripts/eval/bash/start_eval.sh @@ -3,7 +3,7 @@ source /root/miniconda3/etc/profile.d/conda.sh conda activate internutopia -CONFIG=scripts/eval/configs/h1_cma_cfg.py +CONFIG=scripts/eval/configs/h1_rdp_cfg.py while [[ $# -gt 0 ]]; do case $1 in diff --git a/scripts/eval/bash/torchrun_eval.sh b/scripts/eval/bash/torchrun_eval.sh index 463570c..f5a7fb7 100644 --- a/scripts/eval/bash/torchrun_eval.sh +++ b/scripts/eval/bash/torchrun_eval.sh @@ -1,6 +1,6 @@ # use to run distributed eval with 4 gpus on single node -CONFIG=scripts/eval/configs/h1_cma_cfg.py +CONFIG=scripts/eval/configs/habitat_cfg.py while [[ $# -gt 0 ]]; do case $1 in @@ -21,7 +21,7 @@ CONFIG_PREFIX=$(echo "$CONFIG_BASENAME" | sed 's/_cfg$//') EVAL_LOG="logs/${CONFIG_PREFIX}_eval.log" torchrun \ - --nproc_per_node=8 \ + --nproc_per_node=2 \ --master_port=2333 \ scripts/eval/eval.py \ --config $CONFIG \ diff --git a/scripts/eval/configs/h1_internvla_n1_cfg.py b/scripts/eval/configs/h1_internvla_n1_cfg.py index e81ff52..fee0a06 100644 --- a/scripts/eval/configs/h1_internvla_n1_cfg.py +++ b/scripts/eval/configs/h1_internvla_n1_cfg.py @@ -42,7 +42,7 @@ }, ), task=TaskCfg( - task_name='test', + task_name='internvla-n1_dist_eval', task_settings={ 'env_num': 1, 'use_distributed': False, # flag for multi isaac sims, must be False because currently internvla-n1 agent unsupported batch observation diff --git a/scripts/eval/configs/h1_rdp_cfg.py b/scripts/eval/configs/h1_rdp_cfg.py index 71b519b..36d4c84 100644 --- a/scripts/eval/configs/h1_rdp_cfg.py +++ b/scripts/eval/configs/h1_rdp_cfg.py @@ -22,11 +22,11 @@ }, ), task=TaskCfg( - task_name='cma_plus_refactor_debug', + task_name='rdp_refactor_test', task_settings={ - 'env_num': 1, - 'use_distributed': False, - 'proc_num': 8, + 'env_num': 2, + 'use_distributed': True, + 'proc_num': 4, }, scene=SceneCfg( scene_type='mp3d', @@ -50,7 +50,7 @@ eval_type='vln_multi_distributed', eval_settings={ 'save_to_json': True, - 'vis_output': True, + 'vis_output': False, 'use_agent_server': True, }, ) diff --git a/scripts/eval/configs/habitat_cfg.py b/scripts/eval/configs/habitat_cfg.py index a079c0c..b4f0e7c 100644 --- a/scripts/eval/configs/habitat_cfg.py +++ b/scripts/eval/configs/habitat_cfg.py @@ -29,7 +29,7 @@ eval_type='habitat_vln', eval_settings={ # all current parse args - "output_path": "./logs/habitat/test", # output directory for logs/results + "output_path": "./logs/habitat/test1", # output directory for logs/results "save_video": False, # whether to save videos "epoch": 0, # epoch number for logging "max_steps_per_episode": 500, # maximum steps per episode From ae33f0954842e971c32159c659c18796ee653374 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Wed, 19 Nov 2025 12:55:05 +0000 Subject: [PATCH 21/35] fix bugs in evaluator and dataset for distributed; n1 and rdp tested --- internnav/agent/internvla_n1_agent.py | 3 +- internnav/env/internutopia_env.py | 1 + .../env/utils/episode_loader/resumable.py | 2 +- internnav/evaluator/utils/dataset.py | 4 - .../vln_multi_distributed_evaluator.py | 11 --- scripts/eval/bash/eval_vlnpe_distributed.sh | 4 +- scripts/eval/bash/start_aliyun_dlc.sh | 1 + scripts/eval/bash/torchrun_eval.sh | 4 +- .../eval/configs/h1_internvla_n1_async_cfg.py | 20 +++-- scripts/eval/configs/h1_internvla_n1_cfg.py | 78 ------------------- scripts/eval/configs/h1_rdp_cfg.py | 4 +- 11 files changed, 22 insertions(+), 110 deletions(-) delete mode 100644 scripts/eval/configs/h1_internvla_n1_cfg.py diff --git a/internnav/agent/internvla_n1_agent.py b/internnav/agent/internvla_n1_agent.py index 600b0c8..8e696af 100644 --- a/internnav/agent/internvla_n1_agent.py +++ b/internnav/agent/internvla_n1_agent.py @@ -32,8 +32,7 @@ def __init__(self, config: AgentCfg): set_random_seed(0) vln_sensor_config = self.config.model_settings self._model_settings = ModelCfg(**vln_sensor_config) - local_rank = getattr(self._model_settings, 'local_rank') - self.device = torch.device(local_rank) + self.device = torch.device(self._model_settings.device) self.mode = getattr(self._model_settings, 'infer_mode', 'sync') self.sys2_max_forward_step = getattr(self._model_settings, 'sys2_max_forward_step', 8) diff --git a/internnav/env/internutopia_env.py b/internnav/env/internutopia_env.py index 453c374..4faee7c 100644 --- a/internnav/env/internutopia_env.py +++ b/internnav/env/internutopia_env.py @@ -38,6 +38,7 @@ def __init__(self, env_config: EnvCfg, task_config: TaskCfg): ) self.episodes = generate_vln_episode(self.episode_loader, task_config) if len(self.episodes) == 0: + print("No episodes found for the given configuration.") sys.exit(0) task_settings.update({'episodes': self.episodes}) diff --git a/internnav/env/utils/episode_loader/resumable.py b/internnav/env/utils/episode_loader/resumable.py index eadb4f6..506a672 100644 --- a/internnav/env/utils/episode_loader/resumable.py +++ b/internnav/env/utils/episode_loader/resumable.py @@ -41,7 +41,7 @@ def __init__( self.retry_list = retry_list if not os.path.exists(self.lmdb_path): - os.makedirs(self.lmdb_path) + os.makedirs(self.lmdb_path, exist_ok=True) database = lmdb.open( f'{self.lmdb_path}/sample_data{rank}.lmdb', diff --git a/internnav/evaluator/utils/dataset.py b/internnav/evaluator/utils/dataset.py index 00045a7..35e7694 100644 --- a/internnav/evaluator/utils/dataset.py +++ b/internnav/evaluator/utils/dataset.py @@ -235,10 +235,6 @@ def log_print(content): self.database_read.close() def finalize_all_results(self, rank, world_size): - # Only rank 0 aggregates and writes final results - if rank != 0: - return - # accumulator for all splits across all ranks split_acc = {} for split in self.split_map.keys(): diff --git a/internnav/evaluator/vln_multi_distributed_evaluator.py b/internnav/evaluator/vln_multi_distributed_evaluator.py index 9b6f25d..37bd6e9 100644 --- a/internnav/evaluator/vln_multi_distributed_evaluator.py +++ b/internnav/evaluator/vln_multi_distributed_evaluator.py @@ -88,7 +88,6 @@ def warm_up(self): action=[{self.robot_name: {'stand_still': []}} for _ in range(self.env_num * self.proc_num)] ) if obs[0][self.robot_name]['finish_action']: - # print('get_obs') break return obs @@ -165,10 +164,7 @@ def env_step(self, action): self.runner_status[ np.logical_and(self.runner_status == runner_status_code.NORMAL, action == {'h1': {'stop': []}}) ] = runner_status_code.STOP - # print(action) - # t0 = time() obs, reward, terminated, truncated, info = self.env.step(action=action.tolist()) - # print(f"inner one step time {time() - t0}") obs = self._obs_remove_robot_name(obs) finish_status = np.logical_or( np.array([ob['finish_action'] for ob in obs]), @@ -181,8 +177,6 @@ def env_step(self, action): ) or np.logical_and.reduce(np.array(finish_status)): self.runner_status[self.runner_status == runner_status_code.STOP] = runner_status_code.NORMAL break - # if __debug__ and np.logical_or.reduce(np.array(finish_status)): - # print(f'finish_status: {finish_status}') end_time = time() duration = round(end_time - start_time, 2) log.info(f'[TIME] Env Step time: {duration}s') @@ -231,9 +225,6 @@ def terminate_ops(self, obs_ls, reset_infos, terminated_ls): result=obs['metrics'][list(obs['metrics'].keys())[0]][0]['fail_reason'], ) # json format result - # if self.save_to_json: - # self.result_logger.write_now_result_json() - # self.result_logger.write_now_result() self.result_logger.finalize_all_results(self.rank, self.world_size) self.runner_status[env_id] = runner_status_code.NOT_RESET log.info(f'env{env_id}: states switch to NOT_RESET.') @@ -256,7 +247,6 @@ def terminate_ops(self, obs_ls, reset_infos, terminated_ls): reset_infos = reset_infos.tolist() if np.logical_and.reduce(self.runner_status == runner_status_code.TERMINATED): - # print('finished') return True, reset_infos for reset_info in new_reset_infos: if reset_info is None: @@ -279,7 +269,6 @@ def terminate_ops(self, obs_ls, reset_infos, terminated_ls): def eval(self): print('--- VlnMultiEvaluator start ---') obs, reset_info = self.env.reset() - # print('obs:', obs) for info in reset_info: if info is None: continue diff --git a/scripts/eval/bash/eval_vlnpe_distributed.sh b/scripts/eval/bash/eval_vlnpe_distributed.sh index 14f15b8..108a6f8 100644 --- a/scripts/eval/bash/eval_vlnpe_distributed.sh +++ b/scripts/eval/bash/eval_vlnpe_distributed.sh @@ -1,12 +1,12 @@ #!/bin/bash -# vlnpe distributed scripts for dlc and slurm +# vlnpe distributed scripts for aliyun dlc # use this to run distributed eval with 1 gpus on single node # set use_agent_server=False in config file to use local agent on single node source /root/miniconda3/etc/profile.d/conda.sh conda activate internutopia -CONFIG=scripts/eval/configs/h1_internvla_n1_cfg.py +CONFIG=scripts/eval/configs/h1_internvla_n1_async_cfg.py while [[ $# -gt 0 ]]; do case $1 in --config) diff --git a/scripts/eval/bash/start_aliyun_dlc.sh b/scripts/eval/bash/start_aliyun_dlc.sh index cb4efc6..6fdc5e0 100755 --- a/scripts/eval/bash/start_aliyun_dlc.sh +++ b/scripts/eval/bash/start_aliyun_dlc.sh @@ -7,6 +7,7 @@ mode="$1" shift # remove first argument so only extra args left (--config ...) case "$mode" in + # start to evaluate habitat in dlc habitat) echo "[run.sh] Starting HABITAT evaluation..." diff --git a/scripts/eval/bash/torchrun_eval.sh b/scripts/eval/bash/torchrun_eval.sh index f5a7fb7..195e6d4 100644 --- a/scripts/eval/bash/torchrun_eval.sh +++ b/scripts/eval/bash/torchrun_eval.sh @@ -1,6 +1,6 @@ # use to run distributed eval with 4 gpus on single node -CONFIG=scripts/eval/configs/habitat_cfg.py +CONFIG=scripts/eval/configs/h1_internvla_n1_cfg.py while [[ $# -gt 0 ]]; do case $1 in @@ -21,7 +21,7 @@ CONFIG_PREFIX=$(echo "$CONFIG_BASENAME" | sed 's/_cfg$//') EVAL_LOG="logs/${CONFIG_PREFIX}_eval.log" torchrun \ - --nproc_per_node=2 \ + --nproc_per_node=1 \ --master_port=2333 \ scripts/eval/eval.py \ --config $CONFIG \ diff --git a/scripts/eval/configs/h1_internvla_n1_async_cfg.py b/scripts/eval/configs/h1_internvla_n1_async_cfg.py index 9ee5b83..4ecbd46 100644 --- a/scripts/eval/configs/h1_internvla_n1_async_cfg.py +++ b/scripts/eval/configs/h1_internvla_n1_async_cfg.py @@ -27,13 +27,13 @@ 'num_frames': 32, 'num_history': 8, 'num_future_steps': 4, - 'device': 'cuda:1', + 'device': 'cuda:0', 'predict_step_nums': 32, 'continuous_traj': True, 'infer_mode': 'partial_async', # You can choose "sync" or "partial_async", but for this model, "partial_async" is better. # debug 'vis_debug': True, # If vis_debug=True, you can get visualization results - 'vis_debug_path': './logs/test/vis_debug', + 'vis_debug_path': './logs/test_partial/vis_debug', }, ), env=EnvCfg( @@ -44,19 +44,19 @@ }, ), task=TaskCfg( - task_name='test', + task_name='test_partial_pe', task_settings={ 'env_num': 1, 'use_distributed': False, # If the others setting in task_settings, please set use_distributed = False. 'proc_num': 1, - # 'max_step': 1000, #If use flash mode,default 1000; descrete mode, set 50000 + 'max_step': 1000, # If use flash mode,default 1000; descrete mode, set 50000 }, scene=SceneCfg( scene_type='mp3d', scene_data_dir='data/scene_data/mp3d_pe', ), robot_name='h1', - robot_flash=True, # If robot_flash is True, the mode is flash (set world_pose directly); else you choose physical mode. + robot_flash=False, # If robot_flash is True, the mode is flash (set world_pose directly); else you choose physical mode. robot_usd_path='data/Embodiments/vln-pe/h1/h1_internvla.usd', camera_resolution=[640, 480], # (W,H) camera_prim_path='torso_link/h1_1_25_down_30', @@ -66,10 +66,16 @@ dataset_type="mp3d", dataset_settings={ 'base_data_dir': 'data/vln_pe/raw_data/r2r', - 'split_data_types': ['val_seen', 'val_unseen'], # 'val_seen' - 'filter_stairs': False, # For iros challenge, this is False; For results in the paper, this is True. + 'split_data_types': ['val_unseen'], # 'val_seen' + 'filter_stairs': True, # For iros challenge, this is False; For results in the paper, this is True. # 'selected_scans': ['zsNo4HB9uLZ'], # 'selected_scans': ['8194nk5LbLH', 'pLe4wQe7qrG'], }, ), + eval_type='vln_multi_distributed', + eval_settings={ + 'save_to_json': True, + 'vis_output': False, + 'use_agent_server': False, # If use_agent_server=True, please start the agent server first. + }, ) diff --git a/scripts/eval/configs/h1_internvla_n1_cfg.py b/scripts/eval/configs/h1_internvla_n1_cfg.py deleted file mode 100644 index fee0a06..0000000 --- a/scripts/eval/configs/h1_internvla_n1_cfg.py +++ /dev/null @@ -1,78 +0,0 @@ -from internnav.configs.agent import AgentCfg -from internnav.configs.evaluator import ( - EnvCfg, - EvalCfg, - EvalDatasetCfg, - SceneCfg, - TaskCfg, -) - -eval_cfg = EvalCfg( - agent=AgentCfg( - server_port=8087, - model_name='internvla_n1', - ckpt_path='', - model_settings={ - 'env_num': 1, - 'sim_num': 1, - 'model_path': "checkpoints/InternVLA-N1", - 'camera_intrinsic': [[585.0, 0.0, 320.0], [0.0, 585.0, 240.0], [0.0, 0.0, 1.0]], - 'width': 640, - 'height': 480, - 'hfov': 79, - 'resize_w': 384, - 'resize_h': 384, - 'max_new_tokens': 1024, - 'num_frames': 32, - 'num_history': 8, - 'num_future_steps': 4, - 'device': 'cuda:0', - 'predict_step_nums': 32, - 'continuous_traj': True, - # debug - 'vis_debug': False, # If vis_debug=True, you can get visualization results - 'vis_debug_path': './logs/test/vis_debug', - }, - ), - env=EnvCfg( - env_type='internutopia', - env_settings={ - 'use_fabric': False, # Please set use_fabric=False due to the render delay; - 'headless': True, - }, - ), - task=TaskCfg( - task_name='internvla-n1_dist_eval', - task_settings={ - 'env_num': 1, - 'use_distributed': False, # flag for multi isaac sims, must be False because currently internvla-n1 agent unsupported batch observation - 'proc_num': 1, - }, - scene=SceneCfg( - scene_type='mp3d', - scene_data_dir='data/scene_data/mp3d_pe', - ), - robot_name='h1', - robot_flash=True, # If robot_flash is True, the mode is flash (set world_pose directly); else you choose physical mode. - robot_usd_path='data/Embodiments/vln-pe/h1/h1_internvla.usd', - camera_resolution=[640, 480], # (W,H) - camera_prim_path='torso_link/h1_1_25_down_30', - one_step_stand_still=True, # For dual-system, please keep this param True. - ), - dataset=EvalDatasetCfg( - dataset_type="mp3d", - dataset_settings={ - 'base_data_dir': 'data/vln_pe/raw_data/r2r', - 'split_data_types': ['val_unseen'], # 'val_seen' - 'filter_stairs': True, - # 'selected_scans': ['zsNo4HB9uLZ'], - # 'selected_scans': ['8194nk5LbLH', 'pLe4wQe7qrG'], - }, - ), - eval_type='vln_multi_distributed', - eval_settings={ - 'save_to_json': True, - 'vis_output': False, - 'use_agent_server': False, # If use_agent_server=True, please start the agent server first. - }, -) diff --git a/scripts/eval/configs/h1_rdp_cfg.py b/scripts/eval/configs/h1_rdp_cfg.py index 36d4c84..c5fe705 100644 --- a/scripts/eval/configs/h1_rdp_cfg.py +++ b/scripts/eval/configs/h1_rdp_cfg.py @@ -36,14 +36,12 @@ robot_usd_path='data/Embodiments/vln-pe/h1/h1_vln_pointcloud.usd', camera_resolution=[256, 256], # (W,H) camera_prim_path='torso_link/h1_pano_camera_0', - vlnce=False, # vlnpe by default - obstacle_detection=False, # whether allow flash across obstacle ), dataset=EvalDatasetCfg( dataset_type="mp3d", dataset_settings={ 'base_data_dir': 'data/vln_pe/raw_data/r2r', - 'split_data_types': ['val_unseen', 'val_seen'], + 'split_data_types': ['val_unseen'], 'filter_stairs': True, }, ), From 53258b1b8fea51905cec1e9d8a135828aefb3a1c Mon Sep 17 00:00:00 2001 From: wangyukai Date: Fri, 21 Nov 2025 05:07:08 +0000 Subject: [PATCH 22/35] fix comm log concurrency issue, create file with exist true --- internnav/utils/common_log_util.py | 2 +- scripts/eval/bash/eval_dual_system.sh | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/internnav/utils/common_log_util.py b/internnav/utils/common_log_util.py index b04830e..d012572 100644 --- a/internnav/utils/common_log_util.py +++ b/internnav/utils/common_log_util.py @@ -20,7 +20,7 @@ def init(task_name='default'): NAME = task_name log_dir = f'{PROJECT_ROOT_PATH}/logs/{task_name}/common' if not os.path.exists(log_dir): - os.makedirs(log_dir) + os.makedirs(log_dir, exist_ok=True) file_name = f"log_{datetime.now().strftime('%Y%m%d%H%M%S')}_{os.getpid()}.log" file_handler = logging.FileHandler(f'{log_dir}/{file_name}') file_handler.setLevel(logging.INFO) diff --git a/scripts/eval/bash/eval_dual_system.sh b/scripts/eval/bash/eval_dual_system.sh index 56e4b40..165fd3d 100755 --- a/scripts/eval/bash/eval_dual_system.sh +++ b/scripts/eval/bash/eval_dual_system.sh @@ -3,6 +3,7 @@ export NCCL_SOCKET_IFNAME=bond0 export NCCL_IB_HCA=mlx5_2,mlx5_3,mlx5_4,mlx5_5 MID_RUN_NAME="InternVLA-N1" +CONFIG="scripts/eval/configs/habitat_cfg.py" srun -p efm_t \ --gres=gpu:8 \ @@ -13,5 +14,5 @@ srun -p efm_t \ --cpus-per-task=16 \ --kill-on-bad-exit=1 \ python scripts/eval/eval.py \ - --config scripts/eval/configs/habitat_cfg.py \ + --config $CONFIG \ > logs/${MID_RUN_NAME}_log.txt 2>&1 From 50b1f24837784f892b3012967c0aa62e856a1898 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Fri, 21 Nov 2025 05:37:34 +0000 Subject: [PATCH 23/35] fix progress log mkdir race condition --- internnav/utils/progress_log_multi_util.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/internnav/utils/progress_log_multi_util.py b/internnav/utils/progress_log_multi_util.py index 7ad3655..d2f8d82 100644 --- a/internnav/utils/progress_log_multi_util.py +++ b/internnav/utils/progress_log_multi_util.py @@ -61,8 +61,7 @@ def init(dataset_name, path_count): global INITED PROGRESS = ProgressInfo(dataset_name, path_count) log_dir = f'{PROJECT_ROOT_PATH}/logs/{get_task_name()}/progress/' - if not os.path.exists(log_dir): - os.makedirs(log_dir) + os.makedirs(log_dir, exist_ok=True) file_handler = logging.FileHandler(f'{log_dir}/{dataset_name}.log') file_handler.setLevel(logging.INFO) formatter = logging.Formatter('[%(asctime)s][%(levelname)s] %(message)s') From 8665b380c4f6f9143851b2fdce25cbe479cc5f84 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Tue, 25 Nov 2025 09:43:06 +0000 Subject: [PATCH 24/35] fix comments --- internnav/configs/agent/__init__.py | 2 +- internnav/evaluator/__init__.py | 6 +++- internnav/evaluator/distributed_base.py | 2 +- .../habitat_vln_evaluator.py | 29 ++++++++----------- scripts/eval/bash/eval_dual_system.sh | 6 +--- ...rt_aliyun_dlc.sh => start_alicloud_dlc.sh} | 1 - scripts/eval/configs/h1_cma_cfg.py | 4 +-- .../eval/configs/h1_internvla_n1_async_cfg.py | 8 ++--- scripts/eval/configs/habitat_cfg.py | 2 -- scripts/eval/eval.py | 6 ---- 10 files changed, 26 insertions(+), 40 deletions(-) rename scripts/eval/bash/{start_aliyun_dlc.sh => start_alicloud_dlc.sh} (99%) diff --git a/internnav/configs/agent/__init__.py b/internnav/configs/agent/__init__.py index fcafb67..17b3e2e 100644 --- a/internnav/configs/agent/__init__.py +++ b/internnav/configs/agent/__init__.py @@ -5,7 +5,7 @@ class AgentCfg(BaseModel): server_host: str = 'localhost' - server_port: int = 5000 + server_port: int = 8087 model_name: str ckpt_path: str model_settings: Dict[str, Any] diff --git a/internnav/evaluator/__init__.py b/internnav/evaluator/__init__.py index b9929c8..fb77eb1 100644 --- a/internnav/evaluator/__init__.py +++ b/internnav/evaluator/__init__.py @@ -7,6 +7,10 @@ ) # register habitat -import internnav.internnav_habitat # noqa: F401 # isort: skip +try: + import internnav.internnav_habitat # noqa: F401 # isort: skip +except Exception as e: + print(f"Warning: ({e}), Habitat Evaluation is not loaded in this runtime. Ignore this if not using Habitat.") + __all__ = ['Evaluator', 'DistributedEvaluator'] diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index 7f730e3..9a9c6b1 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -38,7 +38,7 @@ def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True) self.rank = get_rank() self.world_size = get_world_size() - self.output_path = cfg.eval_settings.get("output_path") # TODO: unsafe for distribution + self.output_path = cfg.eval_settings.get("output_path") # habitat env also need rank to split dataset cfg.env.env_settings['rank'] = get_rank() diff --git a/internnav/internnav_habitat/habitat_vln_evaluator.py b/internnav/internnav_habitat/habitat_vln_evaluator.py index 137a446..f3c31d3 100644 --- a/internnav/internnav_habitat/habitat_vln_evaluator.py +++ b/internnav/internnav_habitat/habitat_vln_evaluator.py @@ -10,11 +10,21 @@ import re from collections import OrderedDict +import habitat import numpy as np import quaternion import torch import tqdm from depth_camera_filtering import filter_depth +from habitat.config.default import get_agent_config +from habitat.config.default_structured_configs import ( + CollisionsMeasurementConfig, + FogOfWarConfig, + TopDownMapMeasurementConfig, +) +from habitat.tasks.nav.shortest_path_follower import ShortestPathFollower +from habitat.utils.visualizations.utils import observations_to_image +from habitat_baselines.config.default import get_config as get_habitat_config from PIL import Image, ImageDraw, ImageFont from transformers import AutoProcessor, Qwen2_5_VLForConditionalGeneration from transformers.image_utils import to_numpy_array @@ -29,23 +39,8 @@ traj_to_actions, ) -try: - import habitat - from habitat.config.default import get_agent_config - from habitat.config.default_structured_configs import ( - CollisionsMeasurementConfig, - FogOfWarConfig, - TopDownMapMeasurementConfig, - ) - from habitat.tasks.nav.shortest_path_follower import ShortestPathFollower - from habitat.utils.visualizations.utils import observations_to_image - from habitat_baselines.config.default import get_config as get_habitat_config - - # Import for Habitat registry side effects — do not remove - import internnav.internnav_habitat.measures # noqa: F401 # isort: skip -except Exception as e: - print(f"Warning: ({e}), Habitat Evaluation is not loaded in this runtime. Ignore this if not using Habitat.") - +# Import for Habitat registry side effects — do not remove +import internnav.internnav_habitat.measures # noqa: F401 # isort: skip DEFAULT_IMAGE_TOKEN = "" diff --git a/scripts/eval/bash/eval_dual_system.sh b/scripts/eval/bash/eval_dual_system.sh index 165fd3d..476d04d 100755 --- a/scripts/eval/bash/eval_dual_system.sh +++ b/scripts/eval/bash/eval_dual_system.sh @@ -1,11 +1,7 @@ -export MAGNUM_LOG=quiet HABITAT_SIM_LOG=quiet -export NCCL_SOCKET_IFNAME=bond0 -export NCCL_IB_HCA=mlx5_2,mlx5_3,mlx5_4,mlx5_5 - MID_RUN_NAME="InternVLA-N1" CONFIG="scripts/eval/configs/habitat_cfg.py" -srun -p efm_t \ +srun -p \ --gres=gpu:8 \ --ntasks=8 \ -x HOST-10-140-66-68,HOST-10-140-66-182,HOST-10-140-66-181 \ diff --git a/scripts/eval/bash/start_aliyun_dlc.sh b/scripts/eval/bash/start_alicloud_dlc.sh similarity index 99% rename from scripts/eval/bash/start_aliyun_dlc.sh rename to scripts/eval/bash/start_alicloud_dlc.sh index 6fdc5e0..3785363 100755 --- a/scripts/eval/bash/start_aliyun_dlc.sh +++ b/scripts/eval/bash/start_alicloud_dlc.sh @@ -18,7 +18,6 @@ case "$mode" in > logs/internvla_n1_log.txt 2>&1 ;; - internutopia) echo "[run.sh] Starting INTERNUTOPIA evaluation..." diff --git a/scripts/eval/configs/h1_cma_cfg.py b/scripts/eval/configs/h1_cma_cfg.py index 331a0cb..ffa5ce9 100644 --- a/scripts/eval/configs/h1_cma_cfg.py +++ b/scripts/eval/configs/h1_cma_cfg.py @@ -22,7 +22,7 @@ }, ), task=TaskCfg( - task_name='cma_plus_refactor_debug_local_dist', + task_name='cma_plus_eval', task_settings={ 'env_num': 1, 'use_distributed': False, @@ -51,6 +51,6 @@ eval_settings={ 'save_to_json': True, 'vis_output': True, - 'use_agent_server': False, + 'use_agent_server': True, }, ) diff --git a/scripts/eval/configs/h1_internvla_n1_async_cfg.py b/scripts/eval/configs/h1_internvla_n1_async_cfg.py index 4ecbd46..7ccc1f3 100644 --- a/scripts/eval/configs/h1_internvla_n1_async_cfg.py +++ b/scripts/eval/configs/h1_internvla_n1_async_cfg.py @@ -33,7 +33,7 @@ 'infer_mode': 'partial_async', # You can choose "sync" or "partial_async", but for this model, "partial_async" is better. # debug 'vis_debug': True, # If vis_debug=True, you can get visualization results - 'vis_debug_path': './logs/test_partial/vis_debug', + 'vis_debug_path': './logs/test/vis_debug', }, ), env=EnvCfg( @@ -44,19 +44,19 @@ }, ), task=TaskCfg( - task_name='test_partial_pe', + task_name='test', task_settings={ 'env_num': 1, 'use_distributed': False, # If the others setting in task_settings, please set use_distributed = False. 'proc_num': 1, - 'max_step': 1000, # If use flash mode,default 1000; descrete mode, set 50000 + 'max_step': 50000, # If use flash mode,default 1000; descrete mode, set 50000 }, scene=SceneCfg( scene_type='mp3d', scene_data_dir='data/scene_data/mp3d_pe', ), robot_name='h1', - robot_flash=False, # If robot_flash is True, the mode is flash (set world_pose directly); else you choose physical mode. + robot_flash=True, # If robot_flash is True, the mode is flash (set world_pose directly); else you choose physical mode. robot_usd_path='data/Embodiments/vln-pe/h1/h1_internvla.usd', camera_resolution=[640, 480], # (W,H) camera_prim_path='torso_link/h1_1_25_down_30', diff --git a/scripts/eval/configs/habitat_cfg.py b/scripts/eval/configs/habitat_cfg.py index b4f0e7c..2fc6111 100644 --- a/scripts/eval/configs/habitat_cfg.py +++ b/scripts/eval/configs/habitat_cfg.py @@ -3,9 +3,7 @@ eval_cfg = EvalCfg( agent=AgentCfg( - server_port=8087, model_name='internvla_n1', - ckpt_path='', model_settings={ "mode": "dual_system", # inference mode: dual_system or system2 "model_path": "checkpoints/InternVLA-N1", # path to model checkpoint diff --git a/scripts/eval/eval.py b/scripts/eval/eval.py index 55b4814..617ed62 100644 --- a/scripts/eval/eval.py +++ b/scripts/eval/eval.py @@ -18,9 +18,6 @@ def parse_args(): default='scripts/eval/configs/h1_rdp_cfg.py', help='eval config file path, e.g. scripts/eval/configs/h1_cma_cfg.py', ) - parser.add_argument('--port', type=int, default=None) - parser.add_argument('--host', type=str, default=None) - parser.add_argument('--dist_eval', action="store_true", default=False) return parser.parse_args() @@ -41,9 +38,6 @@ def main(): from internnav.configs.evaluator.vln_default_config import get_config evaluator_cfg = get_config(evaluator_cfg) - elif evaluator_cfg.eval_type == 'habitat_vln': - # TODO: add default config - pass # create evaluator based on sim backend and run eval evaluator = Evaluator.init(evaluator_cfg) From 7d5daa6cd1db845ccc29c12e22f3dd4bf1187a68 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Tue, 25 Nov 2025 10:21:26 +0000 Subject: [PATCH 25/35] polish existing configs and bash --- scripts/eval/bash/eval_dual_system.sh | 2 +- scripts/eval/bash/eval_system2.sh | 17 ++-- scripts/eval/configs/h1_rdp_cfg.py | 2 +- scripts/eval/configs/h1_seq2seq_cfg.py | 2 +- ...itat_cfg.py => habitat_dual_system_cfg.py} | 2 +- scripts/eval/configs/habitat_r2r_pix.yaml | 83 ------------------- scripts/eval/configs/habitat_s2_cfg.py | 38 +++++++++ 7 files changed, 48 insertions(+), 98 deletions(-) rename scripts/eval/configs/{habitat_cfg.py => habitat_dual_system_cfg.py} (94%) delete mode 100644 scripts/eval/configs/habitat_r2r_pix.yaml create mode 100644 scripts/eval/configs/habitat_s2_cfg.py diff --git a/scripts/eval/bash/eval_dual_system.sh b/scripts/eval/bash/eval_dual_system.sh index 476d04d..cb52d14 100755 --- a/scripts/eval/bash/eval_dual_system.sh +++ b/scripts/eval/bash/eval_dual_system.sh @@ -1,5 +1,5 @@ MID_RUN_NAME="InternVLA-N1" -CONFIG="scripts/eval/configs/habitat_cfg.py" +CONFIG="scripts/eval/configs/habitat_dual_system_cfg.py" srun -p \ --gres=gpu:8 \ diff --git a/scripts/eval/bash/eval_system2.sh b/scripts/eval/bash/eval_system2.sh index bedfbb3..409b099 100755 --- a/scripts/eval/bash/eval_system2.sh +++ b/scripts/eval/bash/eval_system2.sh @@ -1,11 +1,7 @@ -export MAGNUM_LOG=quiet HABITAT_SIM_LOG=quiet -export NCCL_SOCKET_IFNAME=bond0 -export NCCL_IB_HCA=mlx5_2,mlx5_3,mlx5_4,mlx5_5 +MID_RUN_NAME="InternVLA-N1" +CONFIG="scripts/eval/configs/habitat_s2_cfg.py" - -MID_RUN_NAME="vln_one_stage_with_qa_bs256_backup-checkpoint-21000" - -srun -p efm_t \ +srun -p \ --gres=gpu:8 \ --ntasks=8 \ -x HOST-10-140-66-68,HOST-10-140-66-182,HOST-10-140-66-181 \ @@ -13,7 +9,6 @@ srun -p efm_t \ --ntasks-per-node=8 \ --cpus-per-task=16 \ --kill-on-bad-exit=1 \ - python scripts/eval/eval_habitat.py \ - --model_path /path/to/${MID_RUN_NAME} \ - --mode system2 \ - --output_path results/$MID_RUN_NAME/val_unseen \ + python scripts/eval/eval.py \ + --config $CONFIG \ + > logs/${MID_RUN_NAME}_log.txt 2>&1 diff --git a/scripts/eval/configs/h1_rdp_cfg.py b/scripts/eval/configs/h1_rdp_cfg.py index c5fe705..f7f5695 100644 --- a/scripts/eval/configs/h1_rdp_cfg.py +++ b/scripts/eval/configs/h1_rdp_cfg.py @@ -22,7 +22,7 @@ }, ), task=TaskCfg( - task_name='rdp_refactor_test', + task_name='rdp_eval', task_settings={ 'env_num': 2, 'use_distributed': True, diff --git a/scripts/eval/configs/h1_seq2seq_cfg.py b/scripts/eval/configs/h1_seq2seq_cfg.py index 0d2d9de..5145637 100644 --- a/scripts/eval/configs/h1_seq2seq_cfg.py +++ b/scripts/eval/configs/h1_seq2seq_cfg.py @@ -22,7 +22,7 @@ }, ), task=TaskCfg( - task_name='cma_plus_refactor_debug', + task_name='seq_eval', task_settings={ 'env_num': 1, 'use_distributed': False, diff --git a/scripts/eval/configs/habitat_cfg.py b/scripts/eval/configs/habitat_dual_system_cfg.py similarity index 94% rename from scripts/eval/configs/habitat_cfg.py rename to scripts/eval/configs/habitat_dual_system_cfg.py index 2fc6111..7604804 100644 --- a/scripts/eval/configs/habitat_cfg.py +++ b/scripts/eval/configs/habitat_dual_system_cfg.py @@ -27,7 +27,7 @@ eval_type='habitat_vln', eval_settings={ # all current parse args - "output_path": "./logs/habitat/test1", # output directory for logs/results + "output_path": "./logs/habitat/test_dual_system", # output directory for logs/results "save_video": False, # whether to save videos "epoch": 0, # epoch number for logging "max_steps_per_episode": 500, # maximum steps per episode diff --git a/scripts/eval/configs/habitat_r2r_pix.yaml b/scripts/eval/configs/habitat_r2r_pix.yaml deleted file mode 100644 index 454cdef..0000000 --- a/scripts/eval/configs/habitat_r2r_pix.yaml +++ /dev/null @@ -1,83 +0,0 @@ -# @package _global_ - -defaults: - - /habitat: habitat_config_base - - /habitat/task: vln_r2r - - /habitat/simulator/agents@habitat.simulator.agents.main_agent: rgbd_agent - # - /habitat/simulator/sensor_setups@habitat.simulator.agents.main_agent: rgbd_agent - - /habitat/dataset/vln: mp3d_r2r - - /habitat/task/lab_sensors: - - gps_sensor - - compass_sensor - - _self_ - -habitat: - environment: - max_episode_steps: 10000 - iterator_options: - max_scene_repeat_steps: 50000 - shuffle: False - simulator: - agents: - main_agent: - sim_sensors: - rgb_sensor: - width: 640 - height: 480 - hfov: 79 - # hfov: 69 - # position: [0, 0.6, 0] - depth_sensor: - width: 640 - height: 480 - hfov: 79 - # hfov: 69 - min_depth: 0.0 - max_depth: 10.0 - # position: [0, 0.6, 0] - forward_step_size: 0.25 - turn_angle: 15 - tilt_angle: 15 - action_space_config: "v1" - habitat_sim_v0: - gpu_device_id: 0 - task: - measurements: - distance_to_goal: - type: DistanceToGoal - distance_to: POINT - success: - type: Success - success_distance: 3.0 - spl: - type: SPL - oracle_success: - type: OracleSuccess - # success_distance: 3.0 - oracle_navigation_error: - type: OracleNavigationError - actions: - stop: - type: StopAction - agent_index: 0 - move_forward: - type: MoveForwardAction - agent_index: 0 - turn_left: - type: TurnLeftAction - agent_index: 0 - turn_right: - type: TurnRightAction - agent_index: 0 - look_up: - type: LookUpAction - agent_index: 0 - look_down: - type: LookDownAction - agent_index: 0 - - dataset: - type: R2RVLN-v1 - split: val_seen - scenes_dir: data/scene_data/mp3d_ce - data_path: data/datasets/vln/mp3d/r2r/v1/{split}/{split}.json.gz diff --git a/scripts/eval/configs/habitat_s2_cfg.py b/scripts/eval/configs/habitat_s2_cfg.py new file mode 100644 index 0000000..3debe85 --- /dev/null +++ b/scripts/eval/configs/habitat_s2_cfg.py @@ -0,0 +1,38 @@ +from internnav.configs.agent import AgentCfg +from internnav.configs.evaluator import EnvCfg, EvalCfg + +eval_cfg = EvalCfg( + agent=AgentCfg( + model_name='internvla_n1', + model_settings={ + "mode": "system2", # inference mode: dual_system or system2 + "model_path": "checkpoints/", # path to model checkpoint + "num_future_steps": 4, # number of future steps for prediction + "num_frames": 32, # number of frames used in evaluation + "num_history": 8, + "resize_w": 384, # image resize width + "resize_h": 384, # image resize height + "predict_step_nums": 32, # number of steps to predict + "continuous_traj": True, # whether to use continuous trajectory + "max_new_tokens": 1024, # maximum number of tokens for generation + }, + ), + env=EnvCfg( + env_type='habitat', + env_settings={ + # habitat sim specifications - agent, sensors, tasks, measures etc. are defined in the habitat config file + 'config_path': 'scripts/eval/configs/vln_r2r.yaml', + }, + ), + eval_type='habitat_vln', + eval_settings={ + # all current parse args + "output_path": "./logs/habitat/test_s2", # output directory for logs/results + "save_video": False, # whether to save videos + "epoch": 0, # epoch number for logging + "max_steps_per_episode": 500, # maximum steps per episode + # distributed settings + "port": "2333", # communication port + "dist_url": "env://", # url for distributed setup + }, +) From 4f67d9b655e29deac4bc154b6fe7e12f94513575 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Tue, 25 Nov 2025 10:44:13 +0000 Subject: [PATCH 26/35] update bash align with doc --- internnav/configs/agent/__init__.py | 2 +- ...licloud_dlc.sh => eval_vln_distributed.sh} | 33 ++++++++++++++++--- scripts/eval/bash/eval_vlnpe_distributed.sh | 25 -------------- scripts/eval/bash/torchrun_eval.sh | 4 +-- 4 files changed, 32 insertions(+), 32 deletions(-) rename scripts/eval/bash/{start_alicloud_dlc.sh => eval_vln_distributed.sh} (63%) mode change 100755 => 100644 delete mode 100644 scripts/eval/bash/eval_vlnpe_distributed.sh diff --git a/internnav/configs/agent/__init__.py b/internnav/configs/agent/__init__.py index 17b3e2e..ee00ef0 100644 --- a/internnav/configs/agent/__init__.py +++ b/internnav/configs/agent/__init__.py @@ -7,7 +7,7 @@ class AgentCfg(BaseModel): server_host: str = 'localhost' server_port: int = 8087 model_name: str - ckpt_path: str + ckpt_path: str = None model_settings: Dict[str, Any] diff --git a/scripts/eval/bash/start_alicloud_dlc.sh b/scripts/eval/bash/eval_vln_distributed.sh old mode 100755 new mode 100644 similarity index 63% rename from scripts/eval/bash/start_alicloud_dlc.sh rename to scripts/eval/bash/eval_vln_distributed.sh index 3785363..cd7e176 --- a/scripts/eval/bash/start_alicloud_dlc.sh +++ b/scripts/eval/bash/eval_vln_distributed.sh @@ -1,4 +1,8 @@ #!/bin/bash +# vlnpe distributed scripts for aliyun dlc +# use habitat or internutopia mode to run distributed eval with 1 gpus on single node +# set use_agent_server=False in config file to use local agent on single node +# internutopia_vec_env mode: collect all GPUs by ray, observations are collected in batch # Activate conda automatically source /root/miniconda3/etc/profile.d/conda.sh @@ -6,6 +10,20 @@ source /root/miniconda3/etc/profile.d/conda.sh mode="$1" shift # remove first argument so only extra args left (--config ...) +CONFIG=scripts/eval/configs/h1_internvla_n1_async_cfg.py +while [[ $# -gt 0 ]]; do + case $1 in + --config) + CONFIG="$2" + shift 2 + ;; + *) + echo "Unknown argument: $1" + exit 1 + ;; + esac +done + case "$mode" in # start to evaluate habitat in dlc habitat) @@ -14,8 +32,7 @@ case "$mode" in conda activate habitat python scripts/eval/eval.py \ - --config scripts/eval/configs/habitat_cfg.py \ - > logs/internvla_n1_log.txt 2>&1 + --config $CONFIG ;; internutopia) @@ -23,6 +40,15 @@ case "$mode" in conda activate internutopia + python scripts/eval/eval.py \ + --config $CONFIG + + ;; + internutopia_vec_env) + echo "[run.sh] Starting INTERNUTOPIA evaluation..." + + conda activate internutopia + # -------- parse remaining arguments (e.g., --config xxx) -------- while [[ $# -gt 0 ]]; do case $1 in @@ -57,9 +83,8 @@ case "$mode" in sleep inf fi ;; - *) - echo "Usage: $0 {habitat|internutopia} [--config xxx]" + echo "Usage: $0 {habitat|internutopia|internutopia_vec_env} [--config xxx]" exit 1 ;; esac diff --git a/scripts/eval/bash/eval_vlnpe_distributed.sh b/scripts/eval/bash/eval_vlnpe_distributed.sh deleted file mode 100644 index 108a6f8..0000000 --- a/scripts/eval/bash/eval_vlnpe_distributed.sh +++ /dev/null @@ -1,25 +0,0 @@ -#!/bin/bash -# vlnpe distributed scripts for aliyun dlc -# use this to run distributed eval with 1 gpus on single node -# set use_agent_server=False in config file to use local agent on single node - -source /root/miniconda3/etc/profile.d/conda.sh -conda activate internutopia - -CONFIG=scripts/eval/configs/h1_internvla_n1_async_cfg.py -while [[ $# -gt 0 ]]; do - case $1 in - --config) - CONFIG="$2" - shift 2 - ;; - *) - echo "Unknown argument: $1" - exit 1 - ;; - esac -done - -# use srun for slurm eval -python scripts/eval/eval.py \ - --config $CONFIG \ diff --git a/scripts/eval/bash/torchrun_eval.sh b/scripts/eval/bash/torchrun_eval.sh index 195e6d4..5747eea 100644 --- a/scripts/eval/bash/torchrun_eval.sh +++ b/scripts/eval/bash/torchrun_eval.sh @@ -1,6 +1,6 @@ -# use to run distributed eval with 4 gpus on single node +# use to run distributed eval with multi gpus -CONFIG=scripts/eval/configs/h1_internvla_n1_cfg.py +CONFIG=scripts/eval/configs/h1_internvla_n1_async_cfg.py while [[ $# -gt 0 ]]; do case $1 in From d7e12e9b97712534f09924363aa459636ffe6c7b Mon Sep 17 00:00:00 2001 From: wangyukai Date: Tue, 25 Nov 2025 11:36:21 +0000 Subject: [PATCH 27/35] fix CI test --- tests/function_test/e2e_test.py | 2 +- tests/function_test/test_evaluator.py | 11 ++++++++--- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/tests/function_test/e2e_test.py b/tests/function_test/e2e_test.py index 023508c..d50e9a6 100644 --- a/tests/function_test/e2e_test.py +++ b/tests/function_test/e2e_test.py @@ -37,7 +37,7 @@ def teardown_function(function): if os.path.exists('./test_result.json'): case_info = {} test_name = function.__name__ - case_info['case_info'] = test_name + '_' + os.environ.get('JOB_ID') + case_info['case_info'] = f"{test_name}_{os.environ.get('JOB_ID', 'local')}" update_jsonl_from_json('./test_result.json', '../total_result.jsonl', case_info) else: print('Warning! There is no test_result.json') diff --git a/tests/function_test/test_evaluator.py b/tests/function_test/test_evaluator.py index 155a3b2..4c884a2 100644 --- a/tests/function_test/test_evaluator.py +++ b/tests/function_test/test_evaluator.py @@ -49,8 +49,8 @@ task=TaskCfg( task_name='test_evaluation', task_settings={ - 'env_num': 2, - 'use_distributed': True, # Ray distributed framework + 'env_num': 1, + 'use_distributed': False, # Ray distributed framework 'proc_num': 4, }, scene=SceneCfg( @@ -70,7 +70,12 @@ 'filter_stairs': False, }, ), - eval_settings={'save_to_json': False, 'vis_output': False}, # save result to video under logs/ + eval_type='vln_multi_distributed', + eval_settings={ + 'save_to_json': False, + 'vis_output': False, + 'use_agent_server': True, + }, # save result to video under logs/ ) From 4eff8f9b3042d18aafb16adebae52f0797f606b5 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Wed, 26 Nov 2025 07:39:38 +0000 Subject: [PATCH 28/35] rename habitat_extensions --- internnav/evaluator/__init__.py | 2 +- .../{internnav_habitat => habitat_extensions}/README.md | 7 +++---- internnav/habitat_extensions/__init__.py | 2 ++ .../habitat_default_evaluator.py | 0 .../habitat_env.py | 0 .../habitat_vln_evaluator.py | 2 +- .../{internnav_habitat => habitat_extensions}/measures.py | 0 internnav/internnav_habitat/__init__.py | 2 -- scripts/eval/configs/h1_internvla_n1_async_cfg.py | 2 +- 9 files changed, 8 insertions(+), 9 deletions(-) rename internnav/{internnav_habitat => habitat_extensions}/README.md (98%) create mode 100644 internnav/habitat_extensions/__init__.py rename internnav/{internnav_habitat => habitat_extensions}/habitat_default_evaluator.py (100%) rename internnav/{internnav_habitat => habitat_extensions}/habitat_env.py (100%) rename internnav/{internnav_habitat => habitat_extensions}/habitat_vln_evaluator.py (99%) rename internnav/{internnav_habitat => habitat_extensions}/measures.py (100%) delete mode 100644 internnav/internnav_habitat/__init__.py diff --git a/internnav/evaluator/__init__.py b/internnav/evaluator/__init__.py index fb77eb1..16e0a4b 100644 --- a/internnav/evaluator/__init__.py +++ b/internnav/evaluator/__init__.py @@ -8,7 +8,7 @@ # register habitat try: - import internnav.internnav_habitat # noqa: F401 # isort: skip + import internnav.habitat_extensions # noqa: F401 # isort: skip except Exception as e: print(f"Warning: ({e}), Habitat Evaluation is not loaded in this runtime. Ignore this if not using Habitat.") diff --git a/internnav/internnav_habitat/README.md b/internnav/habitat_extensions/README.md similarity index 98% rename from internnav/internnav_habitat/README.md rename to internnav/habitat_extensions/README.md index c877b1c..41dc200 100644 --- a/internnav/internnav_habitat/README.md +++ b/internnav/habitat_extensions/README.md @@ -9,18 +9,17 @@ utilities. ## Package structure ``` -internnav_habitat/ +habitat_extensions/ ├── __init__.py ├── habitat_env.py ├── habitat_default_evaluator.py ├── habitat_vln_evaluator.py -├── measures.py -└── refactor_notes.md +└── measures.py ``` * `__init__.py` re-exports the public entry points for the environment and the VLN evaluator so they can be imported as - `from internnav.internnav_habitat import HabitatEnv`. + `from internnav.habitat_extensions import HabitatEnv`. * `habitat_env.py` implements the `Env` subclass that wraps Habitat's `Env` object. It bootstraps episodes, handles sharding across distributed ranks, and adapts Habitat's observations to InternNav's expectations. diff --git a/internnav/habitat_extensions/__init__.py b/internnav/habitat_extensions/__init__.py new file mode 100644 index 0000000..ee41522 --- /dev/null +++ b/internnav/habitat_extensions/__init__.py @@ -0,0 +1,2 @@ +from internnav.habitat_extensions.habitat_env import HabitatEnv +from internnav.habitat_extensions.habitat_vln_evaluator import HabitatVlnEvaluator diff --git a/internnav/internnav_habitat/habitat_default_evaluator.py b/internnav/habitat_extensions/habitat_default_evaluator.py similarity index 100% rename from internnav/internnav_habitat/habitat_default_evaluator.py rename to internnav/habitat_extensions/habitat_default_evaluator.py diff --git a/internnav/internnav_habitat/habitat_env.py b/internnav/habitat_extensions/habitat_env.py similarity index 100% rename from internnav/internnav_habitat/habitat_env.py rename to internnav/habitat_extensions/habitat_env.py diff --git a/internnav/internnav_habitat/habitat_vln_evaluator.py b/internnav/habitat_extensions/habitat_vln_evaluator.py similarity index 99% rename from internnav/internnav_habitat/habitat_vln_evaluator.py rename to internnav/habitat_extensions/habitat_vln_evaluator.py index f3c31d3..3a2063c 100644 --- a/internnav/internnav_habitat/habitat_vln_evaluator.py +++ b/internnav/habitat_extensions/habitat_vln_evaluator.py @@ -40,7 +40,7 @@ ) # Import for Habitat registry side effects — do not remove -import internnav.internnav_habitat.measures # noqa: F401 # isort: skip +import internnav.habitat_extensions.measures # noqa: F401 # isort: skip DEFAULT_IMAGE_TOKEN = "" diff --git a/internnav/internnav_habitat/measures.py b/internnav/habitat_extensions/measures.py similarity index 100% rename from internnav/internnav_habitat/measures.py rename to internnav/habitat_extensions/measures.py diff --git a/internnav/internnav_habitat/__init__.py b/internnav/internnav_habitat/__init__.py deleted file mode 100644 index af9bee9..0000000 --- a/internnav/internnav_habitat/__init__.py +++ /dev/null @@ -1,2 +0,0 @@ -from internnav.internnav_habitat.habitat_env import HabitatEnv -from internnav.internnav_habitat.habitat_vln_evaluator import HabitatVlnEvaluator diff --git a/scripts/eval/configs/h1_internvla_n1_async_cfg.py b/scripts/eval/configs/h1_internvla_n1_async_cfg.py index 7ccc1f3..27b8837 100644 --- a/scripts/eval/configs/h1_internvla_n1_async_cfg.py +++ b/scripts/eval/configs/h1_internvla_n1_async_cfg.py @@ -49,7 +49,7 @@ 'env_num': 1, 'use_distributed': False, # If the others setting in task_settings, please set use_distributed = False. 'proc_num': 1, - 'max_step': 50000, # If use flash mode,default 1000; descrete mode, set 50000 + 'max_step': 1000, # If use flash mode,default 1000; descrete mode, set 50000 }, scene=SceneCfg( scene_type='mp3d', From b4a199802cb9b0b0dfd465643cbcbf4d1a58fcc4 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Thu, 27 Nov 2025 05:42:29 +0000 Subject: [PATCH 29/35] fix comments --- .../env/utils/episode_loader/dataset_utils.py | 68 +++++++++++++++ internnav/evaluator/__init__.py | 4 +- internnav/evaluator/distributed_base.py | 82 +++++++++---------- .../vln_multi_distributed_evaluator.py | 2 +- .../habitat_vln_evaluator.py | 11 ++- 5 files changed, 121 insertions(+), 46 deletions(-) diff --git a/internnav/env/utils/episode_loader/dataset_utils.py b/internnav/env/utils/episode_loader/dataset_utils.py index c85c2bb..f740922 100644 --- a/internnav/env/utils/episode_loader/dataset_utils.py +++ b/internnav/env/utils/episode_loader/dataset_utils.py @@ -442,6 +442,23 @@ def revise_one_data(origin): + """ + Apply an offset amendment to the start position and first waypoint of the reference path + for a given trajectory, if it belongs to a known fall-amend trajectory group. + + The offset is selected based on: + - `fall_path_z_0_3` → fixed offset [0, 0, 0.3] + - `fall_path_custom` → custom offset mapped by trajectory_id + - otherwise → return original unchanged + + Args: + origin (dict): One navigation episode item containing keys such as + `trajectory_id`, `start_position`, and `reference_path`. + + Returns: + dict: The amended item with updated start position and first reference path waypoint, + or the original if no amendment rule matched. + """ trajectory_id = origin['trajectory_id'] if trajectory_id in fall_path_z_0_3: amend_offset = [0, 0, 0.3] @@ -459,6 +476,9 @@ def revise_one_data(origin): def transform_rotation_z_90degrees(rotation): + """ + Rotate a quaternion by 90 degrees (π/2 radians) around the Z axis. + """ z_rot_90 = [np.cos(np.pi / 4), 0, 0, np.sin(np.pi / 4)] # 90 degrees = pi/2 radians w1, x1, y1, z1 = rotation w2, x2, y2, z2 = z_rot_90 @@ -472,6 +492,20 @@ def transform_rotation_z_90degrees(rotation): def has_stairs(item, height_threshold=0.3): + """ + Determine if a navigation reference path contains stair-like height jumps when the + instruction text includes the word 'stair'. + + The function checks the Z-height (3rd axis) differences between consecutive reference + waypoints and flags True if any jump exceeds the threshold. + + Args: + item (dict): Episode item containing `instruction.instruction_text` and `reference_path`. + height_threshold (float, optional): Minimum absolute height delta to consider as stairs. Defaults to 0.3. + + Returns: + bool: True if stairs are detected, False otherwise. + """ has_stairs = False if 'stair' in item['instruction']['instruction_text']: latest_height = item['reference_path'][0][-1] @@ -486,6 +520,16 @@ def has_stairs(item, height_threshold=0.3): def different_height(item): + """ + Check if multiple reference paths (or waypoints across paths) have significantly different + heights (Z-axis), indicating non-flat terrain. + + Args: + item (dict): Episode item containing a list of reference paths in `reference_path`. + + Returns: + bool: True if any adjacent path segment has a height difference > 0.3, else False. + """ different_height = False paths = item['reference_path'] for path_idx in range(len(paths) - 1): @@ -498,6 +542,30 @@ def different_height(item): def load_data( dataset_root_dir, split, filter_same_trajectory=True, filter_stairs=True, dataset_type='mp3d', rank=0, world_size=1 ): + """ + Load a compressed navigation dataset split and organize episodes by scan/scene, + with optional filtering rules for duplicate trajectories and stair terrain. + + Supported behaviors include: + - Distributed slicing via `rank::world_size` + - Scene grouping by `scan` (kujiale/grscene) or `scene_id` (mp3d) + - Coordinate system remapping for mp3d (`x, z, y` → `[x, -y, z]`) + - Start rotation quaternion remapping + 90° Z rotation + - Filtering repeated `trajectory_id` + - Filtering episodes containing stairs or uneven heights + + Args: + dataset_root_dir (str): Root data directory containing the split folders. + split (str): Dataset split name (folder & file prefix), e.g. "val_unseen". + filter_same_trajectory (bool, optional): Remove episodes with duplicate trajectory_id. Defaults to True. + filter_stairs (bool, optional): Remove episodes where stairs or large height variation are detected. Defaults to True. + dataset_type (str, optional): Dataset source identifier, such as "mp3d", "kujiale", or "grscene". Defaults to "mp3d". + rank (int, optional): Distributed process rank used for slicing episodes. Defaults to 0. + world_size (int, optional): Number of distributed ranks used for striding. Defaults to 1. + + Returns: + dict: Mapping from `scan` → List of filtered episode items for that scene. + """ with gzip.open(os.path.join(dataset_root_dir, split, f"{split}.json.gz"), 'rt', encoding='utf-8') as f: data = json.load(f)['episodes'][rank::world_size] diff --git a/internnav/evaluator/__init__.py b/internnav/evaluator/__init__.py index 16e0a4b..047a95f 100644 --- a/internnav/evaluator/__init__.py +++ b/internnav/evaluator/__init__.py @@ -3,7 +3,7 @@ # from internnav.evaluator.vln_multi_evaluator import VlnMultiEvaluator from internnav.evaluator.vln_multi_distributed_evaluator import ( - VlnMultiDistributedEvaluator, + VLNMultiDistributedEvaluator, ) # register habitat @@ -13,4 +13,4 @@ print(f"Warning: ({e}), Habitat Evaluation is not loaded in this runtime. Ignore this if not using Habitat.") -__all__ = ['Evaluator', 'DistributedEvaluator'] +__all__ = ['Evaluator', 'DistributedEvaluator', 'VLNMultiDistributedEvaluator', 'HabitatVlnEvaluator'] diff --git a/internnav/evaluator/distributed_base.py b/internnav/evaluator/distributed_base.py index 9a9c6b1..9df4e74 100644 --- a/internnav/evaluator/distributed_base.py +++ b/internnav/evaluator/distributed_base.py @@ -21,16 +21,17 @@ class DistributedEvaluator(Evaluator): Base class of distributed evaluators. Args: - cfg (EvalCfg): evaluation configuration - init_env (bool): whether to initialize the environment - init_agent (bool): whether to initialize the agent + eval_cfg (EvalCfg): Evaluation configuration + init_env (bool): Whether to initialize the environment + init_agent (bool): Whether to initialize the agent """ - def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True): + def __init__(self, eval_cfg: EvalCfg, init_env: bool = True, init_agent: bool = True): # distributed setting - if not cfg.eval_settings.get('use_agent_server', False): + if not eval_cfg.eval_settings.get('use_agent_server', False): self.local_rank = init_distributed_mode( - dist_url=cfg.eval_settings.get('dist_url', "env://"), port=cfg.eval_settings.get('port', 29529) + dist_url=eval_cfg.eval_settings.get('dist_url', "env://"), + port=eval_cfg.eval_settings.get('port', 29529), ) else: self.local_rank = 0 @@ -38,32 +39,32 @@ def __init__(self, cfg: EvalCfg, init_env: bool = True, init_agent: bool = True) self.rank = get_rank() self.world_size = get_world_size() - self.output_path = cfg.eval_settings.get("output_path") + self.output_path = eval_cfg.eval_settings.get("output_path") # habitat env also need rank to split dataset - cfg.env.env_settings['rank'] = get_rank() - cfg.env.env_settings['local_rank'] = self.local_rank - cfg.env.env_settings['world_size'] = get_world_size() + eval_cfg.env.env_settings['rank'] = get_rank() + eval_cfg.env.env_settings['local_rank'] = self.local_rank + eval_cfg.env.env_settings['world_size'] = get_world_size() - self.eval_config = cfg + self.eval_config = eval_cfg if init_env: - self.env = Env.init(cfg.env, cfg.task) + self.env = Env.init(eval_cfg.env, eval_cfg.task) # -------- initialize agent config (either remote server or local agent) -------- if init_agent: - if cfg.eval_settings.get('use_agent_server', False): + if eval_cfg.eval_settings.get('use_agent_server', False): assert not is_dist_avail_and_initialized(), "agent server requires single evaluator process." # set agent port based on rank from internnav.utils import AgentClient - print(f"[R{self.rank}] Connecting to agent server at port {cfg.agent.server_port}") - self.agent = AgentClient(cfg.agent) + print(f"[R{self.rank}] Connecting to agent server at port {eval_cfg.agent.server_port}") + self.agent = AgentClient(eval_cfg.agent) else: from internnav.agent import Agent - cfg.agent.model_settings['local_rank'] = self.local_rank - self.agent = Agent.init(cfg.agent) + eval_cfg.agent.model_settings['local_rank'] = self.local_rank + self.agent = Agent.init(eval_cfg.agent) def eval(self): """ @@ -152,16 +153,15 @@ def eval_action(self) -> dict: """ Run evaluation on this rank and return per-episode metrics. - Returns - ------- - dict[str, torch.Tensor] - Example: - { - "sucs": tensor([0., 1., ...], device=...), - "spls": tensor([...]), - "oss": tensor([...]), - "nes": tensor([...]), - } + Returns: + dict[str, torch.Tensor] + Example: + { + "sucs": tensor([0., 1., ...], device=...), + "spls": tensor([...]), + "oss": tensor([...]), + "nes": tensor([...]), + } """ raise NotImplementedError @@ -169,20 +169,18 @@ def calc_metrics(self, global_metrics: dict) -> dict: """ Compute final scalar metrics from global per-episode tensors. - Parameters - ---------- - global_metrics : dict[str, torch.Tensor] - For each metric name, a 1-D CPU tensor with all episodes across all ranks. - Example: - { - "sucs": tensor([...], dtype=torch.float32), - "spls": tensor([...]), - ... - } - - Returns - ------- - dict[str, float] - Final scalar metrics to log. + Args: + global_metrics : dict[str, torch.Tensor] + For each metric name, a 1-D CPU tensor with all episodes across all ranks. + Example: + { + "sucs": tensor([...], dtype=torch.float32), + "spls": tensor([...]), + ... + } + + Returns: + dict[str, float] + Final scalar metrics to log. """ raise NotImplementedError diff --git a/internnav/evaluator/vln_multi_distributed_evaluator.py b/internnav/evaluator/vln_multi_distributed_evaluator.py index 37bd6e9..f56732b 100644 --- a/internnav/evaluator/vln_multi_distributed_evaluator.py +++ b/internnav/evaluator/vln_multi_distributed_evaluator.py @@ -25,7 +25,7 @@ class runner_status_code(Enum): @Evaluator.register('vln_multi_distributed') -class VlnMultiDistributedEvaluator(DistributedEvaluator): +class VLNMultiDistributedEvaluator(DistributedEvaluator): def __init__(self, config: EvalCfg): start_time = time() diff --git a/internnav/habitat_extensions/habitat_vln_evaluator.py b/internnav/habitat_extensions/habitat_vln_evaluator.py index 3a2063c..75d71f8 100644 --- a/internnav/habitat_extensions/habitat_vln_evaluator.py +++ b/internnav/habitat_extensions/habitat_vln_evaluator.py @@ -23,7 +23,7 @@ TopDownMapMeasurementConfig, ) from habitat.tasks.nav.shortest_path_follower import ShortestPathFollower -from habitat.utils.visualizations.utils import observations_to_image +from habitat.utils.visualizations.utils import images_to_video, observations_to_image from habitat_baselines.config.default import get_config as get_habitat_config from PIL import Image, ImageDraw, ImageFont from transformers import AutoProcessor, Qwen2_5_VLForConditionalGeneration @@ -618,6 +618,15 @@ def _run_local_eval(self) -> None: # noqa: C901 os.makedirs(self.output_path, exist_ok=True) with open(os.path.join(self.output_path, 'progress.json'), 'a') as f: f.write(json.dumps(result) + "\n") + if self.save_video: + images_to_video( + vis_frames, + os.path.join(self.output_path, f'vis_{self.epoch}', f'{scene_id}'), + f'{episode_id:04d}', + fps=6, + quality=9, + ) + vis_frames.clear() self.env.close() From c6cf34dbbb4340c729c4807b106ade68f3bd25fa Mon Sep 17 00:00:00 2001 From: wangyukai Date: Thu, 27 Nov 2025 05:46:00 +0000 Subject: [PATCH 30/35] remove useless line --- internnav/evaluator/__init__.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/internnav/evaluator/__init__.py b/internnav/evaluator/__init__.py index 047a95f..cdceadc 100644 --- a/internnav/evaluator/__init__.py +++ b/internnav/evaluator/__init__.py @@ -1,7 +1,5 @@ from internnav.evaluator.base import Evaluator from internnav.evaluator.distributed_base import DistributedEvaluator - -# from internnav.evaluator.vln_multi_evaluator import VlnMultiEvaluator from internnav.evaluator.vln_multi_distributed_evaluator import ( VLNMultiDistributedEvaluator, ) From f74a79be4df018b6167e8e47b9e73409cc11becc Mon Sep 17 00:00:00 2001 From: Yuqiang Yang <49871992+yuqiang-yang@users.noreply.github.com> Date: Thu, 27 Nov 2025 17:02:34 +0800 Subject: [PATCH 31/35] [file] Update 3D Printing Files for Camera of Unitree Go2 (#176) * [file] Update 3d printing files for camera of Unitree Go2. * [Doc] Update readme for 3d printing models. --- .pre-commit-config.yaml | 3 +- README.md | 2 +- assets/3d_printing_files/downwards_slope.3mf | Bin 0 -> 201196 bytes assets/3d_printing_files/go2_stand.STEP | 46768 +++++++++++++++++ 4 files changed, 46770 insertions(+), 3 deletions(-) create mode 100644 assets/3d_printing_files/downwards_slope.3mf create mode 100644 assets/3d_printing_files/go2_stand.STEP diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 47e3a48..a66bfcb 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -1,5 +1,4 @@ -exclude: | - ^internnav/model/basemodel/LongCLIP/ +exclude: '^internnav/model/basemodel/LongCLIP/|^assets/' repos: - repo: https://github.com/PyCQA/autoflake diff --git a/README.md b/README.md index 9e17af1..1518bb2 100644 --- a/README.md +++ b/README.md @@ -36,7 +36,7 @@ The toolbox supports the most advanced high-quality navigation dataset, InternDa ## 🔥 News - [2025/10] Add a simple [inference-only demo](scripts/notebooks/inference_only_demo.ipynb) of InternVLA-N1. - [2025/10] InternVLA-N1 [technical report](https://internrobotics.github.io/internvla-n1.github.io/static/pdfs/InternVLA_N1.pdf) is released. Please check our [homepage](https://internrobotics.github.io/internvla-n1.github.io/). -- [2025/09] Real-world deployment code of InternVLA-N1 is released. +- [2025/09] Real-world deployment code of InternVLA-N1 is released. Upload 3D printing [files](assets/3d_printing_files/go2_stand.STEP) for Unitree Go2. - [2025/07] We are hosting 🏆IROS 2025 Grand Challenge, stay tuned at [official website](https://internrobotics.shlab.org.cn/challenge/2025/). - [2025/07] InternNav v0.1.1 released. diff --git a/assets/3d_printing_files/downwards_slope.3mf b/assets/3d_printing_files/downwards_slope.3mf new file mode 100644 index 0000000000000000000000000000000000000000..05cf34d0d82e0558b7d466bfb714e8beb2895524 GIT binary patch literal 201196 zcmeFZ2T)Yowl2K7$&!(rB}mRFNX{Tg5J3mje1)07mW7j#huS5 zqS_jzPtsCjCfeU)YkwSiq0e(iSqbx<-E5!41Ml*_UN{Q7H)T8Y zlzX%BLs`Q48sYX;Cy@$+6~@djAUeSRf(|Xnq3`Hz=V0e;C+6;A=j~`CA?ogWH`>TRoBSN}IdGW#s*Z*+ z06@Ve6d)!9Z#(`&hX6qN_Ns=ei9h7mM0p8|DFXpYflN(JnlnD$XuXJs{NXuvMCiFO z@B1o^hRohc*Bn@X&c3|jwUF_#(a>TyuFGwsGE=d&$P85X@A+|0-A4uo?@o`zooE6o zp-9*v#u0ORba=zS@Cg8rt$JdRWG5*Ka0);?UKw8BxNF#Y>P-*W0$!G<%env}RzD2h zjW&YN{#RpVob={6ZinL4j>?80_mNS%_O#=X# z{!AwiI5uv8;!@fVaU87q9cLrY-acA-gAX({TZ|tj0l?^&joOmUnD0B>_r zvaukY-*y0`LxI5@>M9s70I+*E?#9XDMrsDP&lCx<9<#&25kcn7K|>M%A+M#h1KLBW zt!`}M+!nV)(f}%{;hjgIT8!|oO(k9c;Sbva$B1We5}Yx`Hn^+0GC06_X1xW|jUz>! zxfEW$3p$3s=??~^!WanygRrxXK%VJS8^t-_B8#*5uiDN;@jY-cQgxi6rCQ&4X6MXW z*ZAzC2+*-6Th_y98jvLjt4VUEA`w7{QygpHI*KQG_yB1B=|3@SDqY71S|X9fHXvij zm7VjvX94_^)Sw~QX_|IhWdMi5_c3SEx!L>>KviLqPxmYaoL(>>9L?nz*P(=4BEcS> z*U}lsS;y|TYi(z;)2&m(V!A+66Bq^PT+8U8W+I4C=aB|@1F@s#1&CQs*f-8!ha#vz z|No?dApa>41Ny@cQK5?4k6uez{0K%K%@cu8NVm>D;@XWo{Rp;W9ab5xIHBvv z0gBl{!~AE{V2zo|?wo(8j8zl>Se0->zg)n2Diex?aUGMvH39yX+-x0q7zpvrZFYFV zNhGL77_^;#f-c=elDoeEU5)*5I2HT~A0R5*eab42wb@#)3p~9BfbLSTV;2c*pU?nn zV0r4ux1N3g_#sWAE}$8*6H5XWYT$|I65rQJG|~)61Z>ZPR)0~PeuCx@1DX+FGV(K< zk@+|gbr7HYxar>=t14K65+S?@lt=XY*Bj;|r>DkjApDR)CQtzw>$@hj+cL2cHG(1% zEGUh`u|vy1G9wZM1rbi?)HJ+gce<2VaO z5S0hyCzBCKE+EN24jBbj7_N{t4%tt9C!p$GT1;rCCT;17$kr9IYs{Pfl zR+~0(f^#C&l@ktIPfgr01DlIE#7*CEC4{SeDjc#?t?*c7B2AzXgtQG;3Al1@Lo@Iq z#K9mBTam*k87v*7rUy)773?~ccxF>6p)vB56;AO4_)KxyD<;C>NsX&3GO(bcra=wA zec*?Ndo1zY0n1bcJ-jh!=x{m>7nH>=V!Vv-Q7h=`-KSuwk(?Fsjv^R`F7STrknJ!U zq*8MRuPQTP!GQQ74lc*AEruU(%m_0U2ZT%{5-dubz0pH*SONtuNz{n;$w&K}dSL8l zF0!25Fd#&p`4T{2D+u8-_Wdp1v;xh+k2kHW=q zHi6Gv;HChhi{i=wBfYaKgV7{W0b>GFdmU;7*7_Bf-lUc4)AInrV}Ng>D?_CtUCLlbTSPYD7+FiM+7H#}Sztu}LrX?Q7+c*3s4fjzB1 zNu)#yLe7EMWKw`t7|4c=qeak6wGa43AfdnAVYp(8QMLevVGP;ui(*8lM>b0H8`((! z&TIq@Mw*Dz=g_j9Bh2J5TnS4DMv8+=r@a|z2C3P5aa!Db+DVzcb+oUGpus^RX8aH% zCIawQpKMQ`{;WQS-~y@5V#bc>lzNE2wK#Tw=u{dz1$zaep^IQV;rbqN%1wa!GO(Oh z3}-%Z!(mAh|7qH0>!}+!A($Rv1|D@PZ(Xt4dT}~GeCpf0NUfCTP9mD)JKOE66C00cR#T<;kaMr1vUrY2j@`%V0I-m`*Gyj%jfm z@pa(bO39iQBWZ>A-py&7edI=Z?3IVl52=D#A{nt^F2^8(Irxkx;EZQJBwO=Yx{DTq z>LQv!Yxjd!k*v5KSPI-Sf2(HZIMJ(uDIdHd2E+aeX7Px1NMT0`^T&8Q+HWZmRF_Y7 znjD*<5y)|3sf@=vHS31{rb&&Sx5q6Br*Mqhqd4Sr9E~j|2wc@Rr)^dTDbqxtjq%{r z>b8V;?_*d__#qL%0qr=V}1|CsfA5o1d@mBR3tluH*WvRjyf(=T{+4JKM$`% z69I5V40Anx!?&@iO>G1P6;T}5cXEJei(@rA*#F@)KZFpe(;5a}_d+RxCO}ZdXs|Dk z#W+THaD{G0PaQI${W+c>Xlz#*NG1;7OmF;VEVgk#Pj3uTQt(4@laB1JxBlw4S!_+LOEfHw7 zaTuINI;{FF5s}k{WJSP*;x0$a?tq)nSrp~C_*8MeNn(cKfu2i5t@IFZz7@ll4Z-~q z56lV!lQ%|wCoG=J7X36v8MCNF#7l8Z2D(EAr;db0DCZ{w8=DMFM}q^ikHn3r!Od&# z;qf<|Ge*!faE&Kpl)(PHvV$il1T7$fzY|jp1EYHwHWh?bCE>pbO{O@lw26v9GM+d_ zfQzCL{^bd9E2YiOCb-cPYP_F?=y@?AF;?Bpz^i2x)hIDz@(4yKglq>>%1wF?!* z3T7C!OPF>P+yx8`uP_<$>f}WWxa>y4!0A3SxX~Sig=nhqIIm_$AonqNx`-}R>r^hs zpaZoye;W!6jk5xuA9@EToCts@2!Zpw^N95j@&pm3u576c&f1-d-Rvx|L>SA68O86c z+U(=XV5#v;%xwzXBOnv>kT7i;!qagaR-7Nekr_VtnJkzee~ujDsF;S`GYh;bYB+3E zz{+dOoobDQ5h_#NfYL%dmhR%515Ji;7~yLij{dGE+=K%iMh@q4sF+ZTFXdNv9=!&q zH&G%uWmylwT+l*zRRR@oRe-?LLx7q6c?d}aB(UkQ`hi>y1Q#bB+hIUGr7hms(tL&* zhzGbHfNt}HLENY+Zx{ByG zNZ{&5jrPwj=D^uz#d*jX%7wz^9mvH^QP>s{@oRk9osYYC;ad;DM}}4o&O{p2-~bAw z6U**MVIgV)kV$a4z{9@*Jq(Nk7t@EwfXl)NC=B51iGpL4DiswrcrM2P`j##@FNgrM z7z=z0Wn4ypNS0!J|2Snpcrb_r%?=05-;LPdfmv_TYDfYn0TCiJP!I~L00^F0L)Y&w z4^jdY5@R+b@&U#ZKs=|I z004Q@z+bv#wpYQQ&4ga1;BQmBx|;xi0B(SUf5Q)=3QHs$Hb7^Xk}ZvM|Ei{eMv0nj zDDH?L=WU_-G$jDwzJGm0zzj2=sGi(1_aPk3+j;Aw_3OLOJ%un3;h zLCjNll6(rkttM(GW|!(G^WyVf|1~GSyH0gMQ*R34h}|G!E;4~vN8lH>gyzk z$?lGHBrVE@{0 z`(sgEwc*wUzl`t3QeM~Q+)Q5NbQQ@i^-Tg{0L@iF$mVcwtAnKFU&F^|j zVJbH`cU)O5V!Vf?h^6gvctxBH=ImeYl0hGb4Au=@;fNlzr@E(g^dT<0s1+qeyb_Zg zH^3>LA+7{d9NW;QZ@(BM&n2<77aLQPoddG+w`d*Z-khD4A|}hZ$&sy^BVf?naYHkl zJ&aS;w-W`@r6EeN(NJ>25Y?tm3cqKXL?bDE>eZ)Cd~)k*_2KHs~zQ+S_aJsoA+ zt5#|a+NlmtCV$8pjKNfsQw73)Wkd9^?t?Ux21%zs!)_dOh{`^i5*QVCMFk(p;k zUvI$!gACpWy?f_A95*8m;y!qTQ*CKN+I*>xEV=(MZmQ>LL%R04yFp|YiBpfis}%Xs zn|N*-clv%rdJktmu%b%0xi6HlEMe~PNUS3KYY`+E8F`paM_ zw5fs<5x2p+Q-*IZaC2HlkeezKP^p`|d;if+t6R$BNqPB2(vR$Sw`Ct&R~D}y;QIkf ztoR?|;%;SE3>Foj@?8(`uK?a;P%#b;HA=nrPd-`;ge=hkwfK(kL7E=jKWm_yH4~?3Bok_t=Nfa|X6OnNu&ClHGl^Z>EEe ziIFz!6)&3yV`azG@ArB_0rE#e!Ts$1CYJh?c~rdFp9Ra{y-}Il143;09|paGgRR1| zQe?h-5)o-!wy^j?7>`hox7B3)B>)qZ82+iZbfCE1LlBY@w?V8pzH0UewRrndM5E=f z(dMT~WxFHBcQZYx;L9GyeJ`871F9%94u(ja3xS82q^kD=$&XP!Rl=VG6$a`$pN=h% zzAN>~byV*;DSz6iir~5`w#)ox@J4%QX?uEnwQ%B(X=(IN>fXt7Jx3OPgq9a+D51(A zMuw5I6RkHcR0#*6IDV=sIhIl>{}5V9VJmoK`eazYm20ArHi*jq07Dfhc!aU57WR8~ zA=b~|2|k*AT=J&ARF{T_>J>5c*3$Cath}0AA9Jf?ZshEwzq0i;Q;Uo|f(iZmh9Ty9 zRQPl*OX8~^FF2E3*kS*nwjpM@aiDP=*6u%&h)7kaje$RC%wsKk!Yd7GgF}m?|t3b(Qf( z8-iJ#xZ%`*UU`**794_v@GqXnhBiIY*pk#VVF-j>iV(6K{xBF87k4e2dncoj`I(uL zopaNXUF_~+<^JZpNblz6hVT*QemCGuT*ll5_1KE?J5eDL@)O~hBC+o5Je_xc7e|Tr z_JXRCYClKYeYQ^C9jr5%Bgd&5CC3zFuGv$S#BCBC|J0dTWv>H_S#2*l=Z6?!s?Ng~ zy%)8XXX_qMj)T?uOZ7fjdhv$tq#7ACHwA5_3&Ch7f7#C~!CHwMEb#L(44WS22d1R; z5ezXVA7I!CSjI4zLe9nWXu->C1%a)5t}^RVHG$W@N1Qd_({^aDE5 z%ih}kd_31(FS8igo6pQ<3oxsAHfyzVY~*S6^Qmx7vgo|FZSCzG_!JymJt+0H(~N+) z&ChRM_hwl3jV~l^pTsxLxzo9HDJea+R_i*ze@|F>u1)+>1TT*8Xj4#DRVg>^mNNT{ z6@)4fy$Me`cbR#()9kUu76~rFY#d1RO|;S>M%P$hsd>W+vd*mj#uiVhag%_hcGlEA zG&nRxC9$17JS#hnGS@FbsZq(~xnYwaYH_yJy;hgQX6n02Ki~UX?lkV3&(#cX%#pr_ z!N=Nv%?f#KKGz6KQSn|p&&qL{T*x4HRT^}USmU1}OHS+M zytt_{&TRK`ZbJ@a!jBd&#lPGbFKC!q1L(X_Q5pe7Nmq&!OOLA>Li2wli{p&{r zHc;w6JtDZe*|^-ld(ZoC|8v5*fm$W7bztK420B$ zu$wjT_ld`W&itEx#uxTWl~17nbTZ=99%y>q$PCv80GFk@X+QAH-YJXetcyz8#C7vv zlGs=PFdw`=yFm;f2v`+yUB>m#XQSd~WJqrCA@x%rmJI^9f2`}6q6Pq&njj3WTYmLS z=7l~h3^b5&?+_yo1yHs{F*q5DvN1HS8+nr*XHVgNi3(VaqsfBaloi5qn0?!;#gO zaAcr|8lbYr%n^fwzMl9%8{?HLP*7nyD+G`r)Q<(#s$bLwRH8PYtAp&e-5~p&e2_g# z!r+XZ_l!N^j9mw0r+UQ=vd5Gsa05+fJun1b%ZyoN>atF94_lA<%HE7}#Wl zUya4t@FWH`{gdW7DxhSMSKxnP!^g3y1L7w*2c}a%wiqOjHqH#lI(w!OhSP}o4~=BV z`~sryI7ra!l|mP!QD)%BNFZ7XWKA z<9pYzO0fVaeg|(x#uFdG5Jt;Pfs9iJ>KS=v#k7HrDZGon6sZ32B=J7*`$O51-7Z`W<1r!jkCMJc9np316 z{bOqb7)LiXD0oMV2bnMjxZ{I3Bur_0;>$uo*t#Jos(3Oa4-tY}MG~wyAQrgazz{p7 zlXSNUf?&vtLBbcGDB)26tdOnmVpkAsfdBO#J;NxBHchjBJoU>v9gfYsoz`;y{0$v11 zBqDfICkrwg$F0)n&ok?W@gQEBF5vsk6R>#|H>9pIg4DrkZILm;K!@77|4M;%@bkM( zm|3d$lq_lAYviC2v2*{0Ijje9m!6>~zyfLpk-&))8)3n4zEe^_+Ch(Oj#0!$OaF-w zj|)l`-+S(9n;XvnVwy-BaTYkXnHq(If)VCUjKRg%!NCgo?Nyk1lb#{7{Obsi(qRL# zz}@lBSU>_4v@?L%{H+DU0t)*t;{vAy15g6-#5P}WZ++S(-Ua{Vhzarg4H!6RqX0UL z1~oIp%`u6epoq;;1$P)7u+NmKWbw(6WT&4O>A}o{v4B}WSRrDCJ`di-iv_NBaJUoe zM8MG>iNFCScoQ|}a+ky$@8k0w%O*3XKP5%?!Co1ZH(p<^&vLRsg*R^)((o zQ$`Vk)1L*_bb<3=1suec(V5b)&LK3OEEJT-fQCT%X`Izk*euQkFuRaQgahVGJO-y4 z`gPvk83VzU8EE(H2KJz5J!|_MTqt0rV!Js&7r_9|jDzE#La^#$PM6^7fGqx85eKfP z3{XHCa4y=~M+{;NPh}vWTaDleA#s`kQKNa~#3J`I++w3>3H?@dFnVvD6T#IZAT0g99Nx`^)eI z&|vbkIR>xZ;5D4d|EwJd9`dDr*#}ML#hl6^$pO|L^uUQefHLWr0$sY^0fJ2B1j2!9 zV(_RI;NUqcB0Piy5QdE2t&}Q>9-uE8OaWjs^~+fk zjPP7Kcn$f5g{C-8k}H z`;|PAHTJz+#&Yjez^de9@sXdiO&l9LQB%yv^rw~86oHBm@wxqj=N-@{ARYoBAe?yM zF|!KzY84@Z3_N@Wn82reKoS7N0S5qlW2g%Ny1c@{CjJ#QkQ&N*0c22(jVA+NtI^gW z1XSX=dGG+vF6!qHfNGAo8vuws|A+l=Aaeq<_-g)7P@`Q+kiz$ce`mmDe&NnldkDIP z2=F%pl!j1N5R6fn9|21JncqCFJ!=(!qx+jp(jh1>P12pU0R?3a=XxQ4!}*U}cPRqm z+xXD6mKO;n z9HsuJs#-eS2B)xXS81FcGb!SNvNEo8BC!5Qa5?y&&wn!lzN-*#EoJS++dL?o=6~LL zonWox^58y)`~LOTi+d0F&oip~_7DE{-b;AnAA4_ebh|i}Ml;3eflV@rmA0Pz*IDyajI2kbK(5Am8 zg2TkXzg*TfsU`om_?aP4J16k>F8}{r`_t2F7~+=zKm|BK0Tmz>EIo+rMex}G@z+Ff zmyzYWsCCc86k zaO|@o1n<8_;cun;tRntqp8v~4iBEGo{B1CQ!w%rE|67;;u0*Ax|FSlX*ntyc5Oc~) ze_qymtRVhxJMOQpnNXGVoQ4`5aizmdG(rKXf}JmV2Ic^eWZR%l_?21-MjD>cFuU%c6?n zE?ZK;Xo28YnZ(L#Xr#gSy~Kn{R8>|VAR3GFN7joW)MBN?R7R{@$v?pTZ*4E8OuGf0;98msr1f#%hk ztE=%-FQiC9n!eU5NL_3|_eXvp7#H^q;*JZ__1gG+(7EP~&+^U|Kj-NR;De zFVZs&FU$G*J+Hy2M8k5UkI`PcnlpM;&!E^haQ4VVPr>&2 z+p-HoL@cMxCYDW_$&?;9S*2pKqi;t(ri@vA>ax0^AMca?nd(q;CBkNo@584Xi1IXo zl~)AXOqBfPXto*x!XU~*55Aj@M&I==mV38E@kMjd=@xhA)ajy)Bk6-A1jh0*-F7)%uXwkT!t_)}5>`V5NX&<9W~ zp9PU9W31)lpOuAyNL;!eCfN;A1f3;3V^7F=cMD{lH(?B2UDC z-&ouDq~{P0pCCs7#PQGB`X(BL-uUuSf0@8Id&|_aG>s^qgfwS2_+Qrh@K!W0AoNsc z3nQ(!2XhLVoaC12x}{L`ltxu+(vR6F)4I)vru{xsX2C714j+p-U@t+PDzUl~9_%`} zuuVHXBb-L3nY^&5q8wLf`uwwH&C%s8=Oiob@4})3d4ka?*AuiqR%AF{ecZQgIy-E3 zKe=Q65{=ALgBJnPmS#TXG0E);-DN|j=6q(mwb$Oy%sD3)FAn~ajQ*L~;M@@pJ34=) zE-umNkIDV6_rAa&xd>m2)`BXNZr(G~&N1lCU~a{GXI8ZT%el&7X+SSexY3~JURBig zHjiAkDv>1{Fg~+W?Qm1OD3q{|C5FBEluqZm{r+9en~7fpyU$CMXGrIUKSVhvIQ(!z z1Sa%1&RsQqxpvWRnAhEcrg)~-KsT+@F@eD+;f)l5R1tqnN~-nBk_+g=-kW|z7I*jLh39GjxQA=o@(>&@6QKaS{Rc!(FI1)9Bd zA*7hNRaHWNJ$Y_%muu@f@r7ZYHr~yd@5qK@-oT@Ebe}wy>2AuVPy4WGi+h@iz2rlv z-F=TcA4D`75==OcEVrNNZG4;D{8E>ay;l<)_L|5(P6j4Fck11ZL(4eARo`Y$^2jp~WMeg#)pbYTBxK`*Id zd}EAcu11-AauWhH2+;U0kRzJa~DRi`sfdX#U0b@<*f$E4?)6`R(YdCG?xjnV&7?7rrEM6ibp3p>$oF zBVUoD6C`FWZNv0PC&o2B=?_>G3*@{9BM67nckYCX#B?Ggcj}Bjc)uJLZ#DB(w5x## z^s$*<2}FwaM%}@0`GSqr7F<}vESdSngpHwJJn*S_2`MnFqlg|M_9G*D|5NHC^#fCS z^hW;UJ=*$-2fo;qctrvMDf`pIon;{^qk-D4^R7zZT3_zG1#7Oo_=6Y*6$dUYD+Vhb$IO1jPXWO@ghKc( z>?w{OB)w4X3&bP|AFg1-oocC7TvPb-^LlIWprK*`Hwwue&)xVgKHUKjFYSM1X3o0E zG;+gO0Unjz6*GLByP6rEP+8*Cx~LSNS~WwX9!==o219RQq&IeN(ArdSZjc#_?MGS)aGWsV4css zSe@oK2M?>*{apRfCl95we1uEL#`rTC9qVr!vjl7*)a8O$JY+t%%&y;xKM_bseeC5< z6wO`U{GruWup5D4$7B>-Pn2<9SvMIkKe{ZYUv**DgwOJF2qv(Bb~`|s*)IvJFoGVp zSe*1@F-mN|v-DH{UjOE11G#x3>2g`v7MEe|^%rYo?|%h&R#uYXou`z!V4B#!@#&3O zK7Cmha&%8;0BAO@NP!Ow4z~Qr2@NQOLOkB^9yKPx4ycbsYMDcQrAY=1XDQ$p`KqY&_7JRRJ`WE*SQ7t-M}Ym4YE$`H{B9c`lV6#Dvh&G zRCAjR?V6`qUMr+Pu3AY)?^2th;Bn=($li!_B){fRVnzolF|IM~o#EtNOxq&4&+aco zsns*#!*@?E6-;VY=-sw&Ete6xhE7VxJb_%bzdX2N2 z`+IMj&OA&Cx%vonELlxlY&A zU6J6*!59@BR1C&4X=Bj|YD3?IvT z=ia=I&C(Tz`Sc6)SgsG|7z13Y)#l}!)KwYz_XTFKA26% z1mm?NJ1dGj&FIM2i;CV_h)VTMyPjO|>2o(DexvEwh$qB2geS#APVx4;o&cM{@83mV z2#SfNV)9i4uP{2yr;#ly?f5mFcV|qMQU1<}kjm7DJJ}qF@gF~hAAQp%osn9wD>n1G zHa!#G#IMk)!@X9ur@q(22~54dp#X1={l0JM3%IuJtXWW@L|iWY6ln`gb+)W7Zs%}q zbEqP5V;Z0zWu171^h4vHinC^A-$D_nyU|`7JwL*c5ag@U?V3p8SF0o+wh8cw6D&9c zvLMEJ9Gh1(xuhiY61E6?ja=m<> zFCF?Bqzj%5&{PQut|n%a4k(=?t|Q4f!6UQ|%}`Z{4_Q=k`P{cr7B@(FZbj4a1O94s zY^=DQ*D}hE^fqgTv})y!%n!}+i`??1wk)j%vp*Q-fzVivMp&;QRrEF0W0%a~TMCx@ zB@jkS?k~5*3~6SsMtRqMS;CWHDE|R4kS)~=Lp(?pCRNpY^`hdH?r=Firh0Kj2$SOv zIeOSP(9p3+R^4ZN!IY%z;64B1PSSZN__p$VSHGNCXh-;RXM58^*&-F-c|kcM!ZxbV zf?l)1sO{G62cN$V2D5w!i)j5=Q}{zLvzz=xyIRcw9V25( zLF%D7p(Pgw?|!jlt^}Bveo%2v^5pcVe(rVb#juho>Y`z6{#0U)@O>g{@OMKx$WUz(F?H?>{ z@01-C<7bBI#pAk!@5C0*X>E6nm>RtD**{8pS1NGhRJmOV_@>Lv>^biKY zYL2&PWllfO2jz$h2Hpjnr7@mIX z9{*DzZ1D@=6e@dXlv_@KKk)HX03X$+G~^!n&7ye^ahmV$Zs$*ZI0uMcH9x8AI*+B4 zX4k$&q5bm?-3e)*^)5@$rI9{UgW4bMPo6E3mPZzFO$moCJk7IOH`mT9+!wbKw~6qv zqPv^eNP4u9q*R9DB51@&eZp0W&na_NUL-fLruxQtSkAEMqUpR`;jcpOXk zHE6$FW`wWMxZdZNl#Px#cPQ8T4n<85(HIqKojxjIF(J9dLr6Xf-ZQ6ATm!yjA1==% z;jr=g=x9k+o<05UG-b^7_|Jq->%ZP5|27PpCCQFW_$Y=+u)1N^^Uj0|{M#U$wWUPA zh_`quUlbn_yQKJ4CWOAVo`>m&-@O{s-&{T%@Z9+hK99A$sUEKfNvBA0lM^KS^&HGG zZtxxXx;c!CiE`jhU|2_q_!4STzb4my{C&8mAIWM>+r0f#_Yq$0j+|iMDF1*(h_LO{ zi~XMo;Q=J;hx=_;xYs@D6chN0_4i9wx8!#ik;z%JlT23}mST!TzXetqS>g8sBT^MI z?T%tj4{G(bSvYcQ&WlpP0uL(Z8|bsU!=9bOMt+)WI!RaP#Am0c35v~Z$?RGog?~M8 zdlDp;nH>sgGjHMOb9N((Hva%BPu9n}# zM)bmYwd!%B5Y1Y;=*GoBS+nm2T;UZX8eL3pj(`|IA^B}?_O9SLa-h^m%-*#gqh4@BsL5KH&4j8h5|>I*^+5(Dury$fcH+I@{?B5K*@)y~VFNBRd&uBy4UZWm)iDB7{MynXQnrec7lmV07j4F3@2$K~iLKsae{G?#wr;u6Xrmsp67M3n33#frsC}=k(K)bm@)P%%@f*v^!eZe6+sZkln;M zV{tK;ROc6g!XYn>jLP>+%qzkV)iYVc51wgV=6nOlA+lVsvt7Nil&`l~IS0mF<{hPn z;cr42=>5eVBiD}2j`H!=#?e@O`DOm?+%+@pTS=3H&7^zPC2FVJ#jcy*kXrdCg6>Tp zZ)FrL&BbaG>MgNX$#0P?n$4KB=hv}%yQQmA&c8K$-+zUrCOZ3l!^Jus!+?Bp!^?KA zY!hX>sA|l{Ts3N;zxq~Jb&ClNM@`{X^tG$TN?$z_b=Y!08e5X~;%5^2>oqZ5G)>@H zwK*5j#bd=~A~tYgCeX2VgIsM7`N+3sAS-k*n6U1`9;r@0a{KFrhqdz?x?e)PhPG09biJFfofvr_C6mJ=hQjv+Q1xuk23 zyb)13Y7R=igZ`2dpVBv&uPa?{B#b;VUa`3L(>9f{x9WZ>>SNSQ?@IXREWOP`Vz>@wK4(620&a$a&=fc<3J`L^G5 zO*wRW2d~`&?qEOWaHrLdg|M7({Mbbs#dmoK9n$c+#Z&QlpM0}EHJ_l}x<&M)Zi!&} zfx2JyqpK{VHwAUMUo-Bjt&H%V2oFp37=>8^Ig4H$E4ac=M8t6Qv;Je#j0GRhPH8(Pc>|Lspl7;sxn*x{aE1^b3b|(% z#QuOhPv=Q&Tis9%gCoVK&ensj{?bR?COZck{QAiD{4dfskMEXzUKGG7dxT|pH87auR%>zUY@pn9Wysy*ku4k+L)fn&{?RDbOH;5%ox%e?pqT@dhiFaE%F}_7N#MG0S0NIOHy(Z^%8FO9+E*=TC z-jS|hAU~#Omg`)+u@$z-^i$rca}v^!%UsOdiPNU> z^PP%}7l5W{oN6tLVD^beWzt)MO!A#N=F!2mhglMxq^Xm0a?5EGZn54n*AUu7v%GDb z?Yb@U>g5l=Vw^g;9q(~Jr~lRw11B>zB+hL=X-Hq0oSloW!O1M(} zBQ@p2#aW#MrM#8uDQU#;L%>Bat>^{C=j0fRVv3=Sy|S7WG7Fy;M!VPDw(3c_lXYKi zHq_nKZ!L~Euq5<$_|7D)G3J6=z4YWY$-!3BL(1{J?9UHvVc~+GtY@O(KDSNIv=ZD#Br|g;lxVefzQMdmY&s9APq)9JJKa%~aE!;= zv2?xTfd6*(6x&fU8%dEd^Ar-Tb<)GKBlARviR5D1WQr9T+3H5vRNCiVU4!#7w+{*m z?l}_!_0yNi$*fRrZyGH5{H+_xuMRDx?~{P_lho!i%JifY@71OSc!DDzYr_2H*i$yC zhQum8#$6odj#R9fVjp*-T(6!QIPQp^hCIRFxE9Z%XuR+}@UmXv3N`(lW*_@>tbuis z-bkS|wCso1^h8BM`67)8{@Zm~@rNX$8JZX_+tQ7~7OK^%cf3QTF8*i{B@F!~?|thBOJnsG2@|JMhKc0`_xYjP;{n0_7)FDhOan3JTGuAE8lQHotWZ*U5 zE0!fT5im@{6;GZPH?hFmn*z&voD!REGD!e;cS^skEBj-p!C)@COa@x3Cf_HWt zma|~U)udp|>wvDlx66gc88=sRKSn<)UrVY_^357*ua(ZOypjKnbqbnRw6A}0%7-yPG|adB3i4XlB)5@Q;=j!LDq6Dq zVx{>P@yug&FStif_H@NX7-YD{37_C^rJzN!6a;t=sV#TDW3ZJJe)4&J z&@a=U+#sBis^Ft{d$v360BPk$Jjbq4%SZ*{OZDoSvxil#>YK#xUt#X!YAxE5s|-gppr3R=?^Ak!5OcVp}%JBn}nU&fQ34_CI9v zDccjYu2~Gd>RFEvkW=^C|A6Z4_EK*l?zsLkOD?IFB3e%TUHasqYmRUU_W`{npFpnB z!2Hj|u{uvV^N6_Hh19`oe(F~nf27wwa9N+(2x(Sb+F(U;AU=9cdB3_q)<;#{-ZI?{Kt+vf$$Py9(Qn~8VmpAar-rP`nVx*Q(s&6%!W zY1Z;fd*hg#n8D*^N5D_DAcKMP9~K?YrH6@L5^xjtRMv4`u5Y-p*^x!i@=M6>IQ099 zNQ!>JnoYLSBLaK$=eE4ci|^I#d2K2u0~nvN*`Q7rj!1Xfzbh7M7ZU}4`NCiQe!tJY z^i}Zc(yV0I1Ya=+QHsSwf_Udn==NYRcmDIZ-WRee%Wb5fF-QNZKh3q&E$G*KbDYUsqm@MYfSo*03 zTf)+x!qf}A zR_ZadpWo=eeiEWe$zaY>c%OknDTRSlMyLLvCZVz4h}`DEY<|@L$JbW?#T9g20zrZ& zXdqY!1PE@y-JRe*xVsHHgA*WuBxukCcXt~kKyYVpcXyb98J6$ge|M|4wzle4-P`?M z)qPd{y1Kg0>2t%5Hx{Mf)WywsjCVkB&qIyIfz`*UlAWKm&MlpX`5E0Xbv*!Q(~?}$ zef%SfAAJl**JAHLvp8dsHDnNDX2kZ=uG*H zn`LZr*g2%6;CjdG%D&o&H9eVHrRj zxk4HbKCk6+p)^E~jCW(LqV8B{1P9W*qrn)%jc)&pQE%0O7X5OxcwP-__aBQn!7P1L zqwt%gRsc!)ReJOKg<`afPuBQs5#;@R&iWCS8z`TyCYhNSuTSv#+J?%XR*zVS2_wa*nChN+^wkPW81QPXgBZ$@!0q zxnQP8wc#j2Hp$mG+r5!aR5~4P#&tXei4^oBnsWQ+hpS`6QkWz%_ zjk2GI_v@yya39`lQ55w(wl>_d8+>EPc034O=JFB#&Hmzp89DT$=IY6g*h=(FmKK7CEFUF74b^ zX>zjo2=J~Ol4%PS9Lj*EE{{NMeg-9cy$DBZF^grc_zwGRST&V`ksr4lNAg?Bw5`67 zee_jgzh7geJH>)4ibujhyYWaol@5ER8Ozb{YDFo-z2brbmM=KlWtpe%3yq^(!rY`X}^G@u|c9g3R! zPa_OJD4Q}gdYX$lYT$~a8!ccaU)XX=md7sg$lY27@1EjO;p+A^Z@Y$eH(gydlg68l z+v%V}pdOt#9S`gF@U)+2FBVhESr?T5aW$amw3>Q=hiOS_)FD(KUs5WjeEYT&-FAnKhGYo z@4{(WU-o%Od%e0YOxLK-TqkC(we;Z@g6NxBeR<|qKx^NRbUSjhmV@gfM)4~w^xyr% zGYMx*+xMqG##ZA?!29=shxMrEFC#NoNU7XUn=A%DmWt}kfkHkHC6uT?s~ejiB#}63 zIe%ybEvtk}se@)!0+YTI6qd}|pu*quNb$=0pt(_$k;c#?0>7*CDKzdYv3Mq;i0D`K- zhb_;i$5p@d?-8f1-P}{cHs64dF}d5<8pKploO?*AzV3AWO8oE)5gb*M{82KE@hivP zGQY;EIAC=6swdqKh>kHwhq(WAi?D+(BYkI@&OcL(%HLlw4aj_)31W!L5se)ZG(t;# zf0h#FtvEad>wBoGNxMcFK5T9%V=={9apFtjdb0s#eg~Ug4p4B(NHcEB_E77VmwoEb zt-cgEp5aG(FSq2YMYWlXUPbr!-Dl)|^pXT};|cXYEIssmHn;)PvmEol|Bt2j|I!KL zu(Nt*SaP^n^P@h4P)}Sk^74GLpZK_BWn_7!q-2Ho`31T8cm<{8_~p5|g?RpxEXG~u z=vj68nN|P4lRdNa|8G@yvS$Y8|Dgo_Hv#s)lKsDUoW}?UAme}s2M&0kYF@<-#<3I~ z;Yl;2Z`VPx;QV>6D>c7LZm8A3Tp%4E7ylY{BGdbR%}v(YR#&|S*FKDh#f`(5!B=lK zF`1Nt!b@}!0lyG=*1p`|)`uW^+n#(cFPP4Pt_LUcR;ttiAS8Ti2|7MjB5k2L8gAp+I~I9nr{3*C zAGgSh)-p}cH~^5x$749TNL5Pc-X3`o=QxKOklZd6u-rM1IM^AMI9tbYyRJz$x!sxV zJ4&@{lMoArJvp{(Vit|mWSGEa7hvR^u0SvxjZ+&w@7G-THCt4qtz8I$z@%|6H{o?B zcT zeT#E`Au-0GApsFwLU=Ou*X$K(xK&kJjKqR-Czq}`Eh074$E!3@5V!E_+sDJ&<%i=1 zA*6qR$L00mAzCN#GT7hq>JU$SkQ10)>3?&$nUR=LR0JK@a2-Tu;`8eAD`eQGehzGQAh_{)kEI_Yk;XC2!hxp&CTq@ zlI_(>U()$lLCc*`VOkucJ>J$EU$+ zkf*VUC*=)a+M$(!VK6KF43aIeW@;*GT=d1Q<^fR6JA3*Bhxm@-0iW*F4Iik*Pzqs1 z8=VrpS7RJGSrShiV)xG*)iM65f7%Q`GZL%JGP^nagCC0Yp>}|5Ku4$H8VxOOnJ1e? zyyso_cI?Vl(^IQBp26_w$-&Na9YSNJ;|Xe;e$KtV)T=MtE0k@zoH^T-8xUIW+WhZx zQbT@0Lv?-OBTT{Iapl1mK`eg!;E8yPe4J^dJ#fj=+aohj`S86+zbbS9d6_DL(Usr} z$Xq#H7lZr_-z3?`YjpZh5UHJ_bcVby@@90_71UDS9)yBdgBPD}M{}<5d}(n`)%jbr zXMxJ6>S8V0P+)0*;q-f&v(+c!D+^@%!**4w{u(IIWA41($*6?f-F>8FFVR(mUo+JX z&_SW|FmmR;w$YSv7DpSlOPjWh%8Bwu(^98xAclVJWjG=LcfjK#(bTG`USX)p-Q(uX zXj~#gYo?;Lw4eS&Gvn&h2?YFjV`PO!g0O zi_o%HgY}mKBp%K$m^45s&2Lprgnkr)ij1FffTbb@#b)Us__P`Q(ZX&u0i7G{Y^tc| zY56J?nBY5J>FaKU7TNRq?(n7$KXcq&Yl`>tx~v%*;7$Br{pWe|@Z^OB`y_=NJ_T&B zksOLxy91lG4iNQs>zX5#$mqzAvT}ruIdwi0HkTjYV&@-Tr!_gy?jZo#joGSQy*B@_ zpj)FV4aH5j5ox-sGtFlx3Qc_D?!tl)_Lb zZ1TX*z9F#barp^9?0z(E8ZuEBd;=%TzpUZ_0y53O1WqCXRO{sjlh40eR`~3}^`&8e ztiN5;@bbEL5OYmLlW%dx2Jl7Pavuzz**$r~(p6k}Sh3WR1_lAQJnUVm+>aG47y+es z51b1k--e1uKBk_<1|Mpi^jSNIsrYtD=%;J6-YzU$O+(3>wshq-3~d%AkOxPJ(|b+! z%4J`6rX_-TVK;RW!6Gnz?$NnLI=iS(^`k#($W%G~-~YaRxV*mPZ->ra?FrcR*$TE* zzIla;U)9{)D)b)r;v}xl*%cAc5SYvT`m7U0#?Ne_t_qOZDWB);rYrAtHCTpQubTLd zpuEuc5ta`_Ig&G%m5w`|UGUOmyF5OkC8ZFEe2EB&3T?9Z`_FNE^Kl2p&Nc`=;HVg= zxf%|#O7A*4IwIzgV=6mf8cabr-)(FW`qFM5Z{$*ltr${gaKI>)y=rCTp1K2^qgRI)1p;CX($fOc5-ly+& z&#Ol1(NwDOg`_DlCxAnr!`)lOMw4YtpJ~Flo;SP%PO@+~m}&=Y+SAxj`6(w#tkSuE zc@2jjvfj_xV+^Qt5ntdT(H~Eh&2ga3FVs7QPolf}L5840Z0l%Mcvv4MK~c|@aau2I z0YjbCS#n?LPg9YVd7SfxN{<_tyN}P(agw!~!lvRFg}aq#WCBpdPC4D4Ce67{bSFs4 z&cJv?yBQx^mQuj19@=*^1<*A6P5HtWNA-+PL!Ix1fPj6yQ1C4y8?ph(>V)kC|HvxiERR|rMR_3vkaKIH%sD4hXUz79 z@|FVQ9R#k)sr23&cGic#o|g7lpVuot=?VPwdpfy+P1{Unl#S)Q8x`|^%JPjFcWb5Y z{93IZ(tePF3;5Yv^Ar=*d;TD@?z`MUxCwg@9KFr0va8cONer=QN6$V#yy4eGt5yBZ zN-oZrL5T6e>e6Tq@=k z1UVKmLSbwa`(m)eb0lCK*I*u!@3J;VMCSA@%m6H(_~gy{!4BmcLxcIpC?Pclb!9+i~v!=LzBuVN>gftTHU)bHVjFK&M0S9Ei9{4kt znspTZ`V|q1Cr2rv*09$&0Q_(wz$5^EH(FZ#eW&Tz zgi|#>zIDQE5`C8H{cvA_ic@tqF~iL?Pq-*5uOLKJMCroXpT^-B)_0J~cb8fOeHQKp z1;b%OFD{12iv)f>AfUSNS4Esxl%Z^h%g*Htq5bpga4F-tRi8n;XfFTIQ9>G1ZYWlb&dc+kPB?V+{y5i&9z}? zeech3M0E2HHmq+?($>E#QNkB2EBaRQ&R_nxb?$X3aSTVE26pV!-d<`$b`n!?Q&BK;{N~F(S>HXh9i{|&1To3rEe4K`auOd^6D@cYL2e##A_)MlEzBR}g#vZIr z#ytK^b;oA^43rXB909=^G6Il=!{?3wMU5BnN*iAJ*sE-G=e!^{hJo>Ef-Iz2E?OOZ zaUrxk5xZA#`5w=TCe$NSVp!GDPx)P|#rh$f>K}wHK?^2hgR6+WHk^@X1jR^RC2_jt5?zNka~6{!JR8Gqt4 zxv=vlX$Rfl{Q?BMdNbZBse<#8)$9zkB#HuxdmSF`OIryE&qE_gyxLpa#>&U$xH|DY zIu<#b{);XGy5%E;hz7&aa*U2@5vWqXv%-i;`$D6CY zbNb)VA2xY{>gzw<#w)9Q%_Yr7@D_fdC1p{4a97LTpJ^pj#V>#OQQ1aEeYUj1Qa*Tc zB6lko5{>#^wl2BdkJ$X9K+*WPZ&jsh)coW^uvG}lOaA*6niEOk&gIZvT*fltV22!c-KYoy3u+NQw8RPrEl5@;%#1q81A?|R zW88~(zX=^Z?#r*yvHV4tkFo>NUlu3_ivmu#sOpnyLi2+ z;2N2nPZ!ce)ngO0LH?jCORO~%hRAenWk6;ZkJzH_(@p$50%!HC=^k|E2ni%ahQtBQ z+n-mPCqy9Ap^8n*OxjA|`M?>Knd3z2FyL^i0F~3{V5-^-2dK~c#R2nr{#=vy)lstL zS>#JVWyBNcyB*Scm!jW)cclg~ajQjKrV)FVkVEq1=WGoxTnX2`F>es}TT71Az7{hgg$b|nnVC1M@3q-JyZ+na8!0SqtQHGk_xrN zJ)$A|h4tT480(f-O6uu4F)`UGDG|FZ-n`y+V#DUySUz*@5wVy<(!5DM@bo=N)PiM81Zuql?b7SEU zly^=7sdWl}M2DJ}ylmn_$D@g;<=bNJJN=ml1M)cA$Ik35YAr1;-FlKYB+F<@rwckQ zhk>?#*s*4>R3LlWJAMZ}DbaEGz>95n$#@CKy(@8{lN~R?h`>WOF1LTvJt9Xq55u?C#3~gzDAgE_4B>^}p6s?qs`yCGy5Id$ zzle6{M?`!?SM>%4goB|8C|LwaYb(Yicd2VQU=7Yt0T3vv@%POl&W?)>ujpmzd$D>VfoHRQ&QKb+hAw=C0DWXa`kk5F=r9M`=gyp|YJ0 z=@op7;g_bUFGFlm+p$5tbCP>!Uw%K)@Z%&QU6=VUX2xS7(s6$QS+%{GQ@)&5s&D2p zx@)$Q0(smSU-yt0KIC&a>o5kcodB=SUB%z^R+;U7Z-BLbN)RtM%knbauU0p?#R+#ccY}_#&N$Q6LTf4>G>Hhb;1@Sq!z{CY0Ad!@h!v7dc7{9 z&-OD?)Z&~GjM`X5!l;pTKTOQ^9riw<`HT#wi&jEHPn&s<_y|?c|r`X4pt`A*!rOx zlEwXSiLqIIIQ5yj0^G^to&=AL&vF|y+(3lQvyCaH9$hCc;h^-Hx746zLicNOYeUL&Bub; za?kH-xO(&Eyoasd~zgTL}1gP-|ycXaSn?3x*d-9 ze(m>p1*IY*G{f8;Z`!HpxEh)!pu+}ElH*KE`(J$isr32B&;WuyE;sp*RL)S3#BdOo zne~wuG)4ZqdSo>Cu2qHHjW)jVcAs#=afWXmmRiA--<|^1kwkOA7d2XN)MRBV@1?2p7wPm z6Rgr**|z2$emTB2OC*6vE!aB4WIJptDk9&r-xMF^ei6{=e3zdnTP0h<`a^s>H?EDX zm7|O%Dm6phJuVy5)az~swkLE>5b+UDCf9i(e0FodszI@5>@G0@G90Fbd`Hb^_og$* z7okT=Djofr@?%-n`6Zqj=DvSGycFBtfm^qTD2pkjpMJgw6`67byeiu^kIo!(p3E}=D>I|+}BTB@ed0!S>Y(U$}%(n6;MaZvl;(Hq6lS`8X z2ri}D^O>LF}IA5Xzg^;vhT0rOvC1(r9)a8$FNe| zsV5H8@`{b6zfEc^Rn9+M`}g$JA&dD`#{E14j5gP>)3RV0m6OwUl@IypdLeq z#RitCwM67Q9zW?PQa{_6H>YY+5>Iw?gLc-8f5h`>i>E{5GovygJ9L>mKifu_IrS{M@Ra+6ilJ;)CQ*XhQThk~*vQeZ%F$AN zW6#IQjeQwQ-|t(%z$zcLX_&-79O8Vr0)|0%$4!PRI<`|K-tI*eNnYq_;vj)SnC|V~ z^404Fuvotp7~^hisQ)%!40e_JIHwy0p=qG6owRWG(kVMzq^H^kcu=g}54a#0KtcqR z&Al%9mT6LG0{nHE(!zFJI_%ArIBX66#s8xP58E?1{bp9>adI6Q%qI0Bh&`?;L*qs~?Jd$otPv;V*wr>RvK(l8NsDAIW1bSm*=({GRF0-LOsX}^I{q|pFtAl! zj!#@}Lc<{w0N;AaV97ZO9Bqb%a{nfZRzN=g^*bw3FOSYhsUTF>sry>9B+A>8YDp52vuUG1}baIf=x zc6aV|0fLPjwDDEL0@lY{dCgntl6={dQ@2Gd%7jh<(dDubwsLD0#=tL~hEu(Bq8a%c z2aCeZch&#~lm>QG>q`Gus08#~Qs{zTP_SOF)1gtxhJfi_OD;>HYyPix_)GWye(Am@ z4rL_N4C+1DxpQSg-NVvh9Orfne2ZkmP+wcoHo$%}xB_$zeEnjT<}XG#%~yf*OD#c7 zQv8P;nQekOYSgMXn3HDU3!x5G>^p~*9HC|^+ZRtg>!k^vArXcDQ1Q+j2#kg!Rv9T2lX_i+Lr<;RPiK$^&G)swr!9FI=dyFY%irW4gNHnFVo`uy+& zz%#T04)pm2@7tUTLXMsu6%}y~zn3F*%l*Fbfp9x0x1jUdx$>H?PhHcK*d)6J7%(aT zLe055&fq;g0=Y@tNu#In_`!)pzx&f#bckmfzwQ9iF6xf-XM9Zf)DO?g6Q+9a6YRJT z$kFw@zYO!djJUqm6f-S6GXa#%L6!zZSrpZHK6m6Et$F@JIWfktPA@W+FlykfSt*}| z10ig@sTLZ6Rf)rPuuX7x!V)AIxmnhF#qVZ(J>{4@@~`~pOJ z+4mCZ#R|@Ul#7uOE7T?168?OlRyh#UyBxi8c5_OtJ1l*6#8w}!$)J$*<{S^i6gL4` z-QrV^*~@Hpg=B!VjN5pzeM&d1e1s?4N{{?t5RZPU^32SX)bkc0nqHz1uOok1m<1`O`3VEHcBO#Lp>zV;cmIq4vQF~$_*rBMY9>Du9S1QhPUe8WW+s=kJ zi(s|PHDIjtar~R`L5ny%jkL}7Zq~3yhR3+1E3D%0&s+>6a+@tZLmkNSl}73Q1+=Nm z%(Ud&NEE*LNqtu00m)pVLE=F?%v%^ONTxlSdG^vYBQ1Kt{Z6gF%C`zLovg<+8qR@cQA*Pc>RRSxt(bLm zx&}~gVC<#NJ8dsajla`Wp?HMB4B@ZRxHYH+hq_SY@FR+GSDn}d`~rf#^wI&_g$Xk< zTRX#0CILIZ`a`yuNO%2bx)cWpQMc*0vpVnWkT{+dovhc|ZJCb`JPI=3Smi(F?J`*k z^Ig+ha+<_>Z|K^d>9$BHm2)bu$W#aPEikr!)GafNPK^R<-6Nq&Z&%8OLi-5iWl^}H>Wk{omT*t+)6kxX^SGrN~ zPBp;jfQMCMgl7h?*s<%=`&P=y(Jv+P*1TH4?PSY0t-+|7h`w1lw1=VqKMLXQxwm`I zJNSZZ-GUm-@^BZoE^*Ft_KcYJfQwQ5n;g?LnL}qKt9iepXRKj*rUVPz!r_zc;K@p^ z>{BqNKIe0S*;&yDg!}Ig;||e&V-xfL!CxU3=Pi(Cd?P-5clE-X4?s zc>FmKmG|<`V;bbZL#$raPPDsq?QANbaYpFCCC*JH3}?=m~z00ONtz%M-EATrU>{90Kp<}C3>~)PVC$x)e0@dE z?lOQ`V52X*tovTB+SJI(o7dj@i<5I)%!u6vM&lFOdM_U`5(>Fq^(kUV*23QRAY`Q9{-AwZWQ+R@#`&yROC zhML7Kmf17B!`4j&_v9M4#~vH9XGOW2i}NY$jKLygcGX5Sxb|_>cU2k-|R8B=zsy-(X!zhtglc zH?Pw%*A;sgRp-rBZ-U5yE zdFs{U7Mpf|X9_B!_Whf+{@IOl0(uWQ9cj#To7_y4_jhab1e{6He+fGSp(f(NQdu7O z66tTJ3sc?tu{Q1H@6=tD-;a_yJ^ka9WTK5qb=#b7AFGmbt^y9jaj_Es;l&!b?cVpW zqSMl4Mvk@kDKx6MhFI*{9(GVvlS?a#;qgwLZrIG`bFoz8xuA-vqxL9~jr>QIrPNgF zw|twPJNch|f7wvTj!husO*~Ei9`9Om2pWob7IsPu%guZ~%|9G4YBUa@_ch?4WOg@A>TdN5xV7Db#ln$Mn~3sJx1k zw54yng3Z>s;UEafD+s%brw$mG9ijU9!LN3SrLgVc{k$TQ6vMUV>^}>5YZ1R;JoAR5 z0?-@Tjr`|hWTDa>*}cTG7;0X~-<9aEb;Wxt>Fj&$6=&@&h^S%^!^teArf*cG+h4f_ znPS7(&JJ;r2fIg}r!cFv_7TjX5pW2L)xr8T2Y>4QB^AeuRgjUuL?5m_YIbL*6n**M zW0TaQh5W!fYx~un45OEJOFKM8=`{#X+Ya&#{_V(qZ2o2c=bWJ0@8>s5 zLw-YfkAe8Lu7zOrkcVYrxQHpa zkyh3tWkd>)%^5g?oZjx~^ZV|T=4|}~CK1?B%Z(qg6YmU_Be$Dkpp4V<>Emz4OkV(Q z72_+}Ezy>s7NH#s{4RNEO`qgG`Tk21PJkABWA8pLpS5a~CR>Yor0HaEHQZXgR@mJblWoI|%*#8FJ(941B)*-#oae5%^0`;N!r+8S;VYZ|C%x zcPXufM4|6QV7wtryh6p$JboS&+k4~|P#kubAldAf%21dm(l{a7>V!3# z7sxje@e7u>EPhq&Jucenbv2SFayRxI96blV&w;|$NSjz)>p6i7@7dFc2;b;)*Z4?Y zVExGRO9RgV-$?rtk#o~<`xEck1RF2lfmY$pKH2{|+-FF%RX=a!eWAwgWa1YQpEi}< z$+cXi-N}4~=Z*%s4}bJE*>(N=Azkvy!Uul`9YYH?y> z+zF>ML|6O!H2B;Jw>Q0_$|qbEF2<%b1?s8yR}+1g#lN>C9@=zibVomCES={FINZ8> zM}!(G2rUOYWJyX?vlCzLs0~EqP)e z0GScJPsq-%{HE~jXK+%$r$TTrTjLT>3gb7vzPyjXymhJy4~Xt~-{nz}n-hFoV=geY zFm{-qt0V8Hi+hsr$5>$eTw#pf!4`@$l34D!>~jU~LB?v0$HwI1#wjxe@y|CbN?(I& zZ)rr86WM92I^GNpYE+rQNmAZsvzg)yv&9^rPTEvQ>fv5b6`$-g7bF+Bh94wMsh=~y z^(lp<)re(bCTPVP3o~y}_7yQQ zYN2M|tuAOXUv+9}Sci)xka>|nDbDxzzdfMQ1V1%~D5&ap<+ZY`f8OA%H)TECp+uwM zmv2^*=!#@xU1Uy`ST`_6Dp;@WIUZ0%Q!|lqeAP7-#*=osic!K1$?wEA` zJqKEzLGlVLR)XCy1@1D|$~(tLHy>1uL6D3y9v6m@yvomJyZgc(*RIY-XL$n7mrx1C z_CZ30pg;+&S7aVhZ$NO2r(~_B>G(01i1^)ai1^ca=$U<6#oFXs-y36sUx9bmPG(#J zhsN{wlZz8)%(JYe4>0Nu2N8%(E%WKfwio0`nrmt;T^J zV7%Zmt&CHskt^)-&gG9@jTQ8Cz2V*Rq?XREJs`RzudsW0QY`zE8wYUaI>q?qAFGmI ziB#WQc2@nA%(>U91D7WkMLAd+*i}@kz&T?cWfR~vkjIhdA5)h7_sUfwMs-W4b01Ib zbrZd!7A6;AC&dnryAhZwNfL*PEukZn@eRU8t@YG9A6yh%5*qV5<&6DlYDV%P{!0yc zl}C$T0(6{BX4Jm96gGl-9~w197Ax6+d+$Hyvl5Xq?6%JeyR3udpo4O zLf(IL&iv-=HePZ0>k|;~*o>b%=<;8@ z6Qg=pfsYceXBvXEI{j4eXUO08$q}irLXv{>Shv%x@(z5>s^VRe2pxz!X^+PxEt7^@vn2yS63pL@NS~;ajDY?2bwY22S?1Hp19+X^8nHv6QBk)d}BO^0B zIKC5{wHq8dEGLqo>mVMGMn9?mES@xpls{(a4yrFg<0T#d);A$9Cv9Onh9fiO_nzdG zmmRpAsa*$DT3UVS%MCwy#4Lil_-?J)U6;`_lhXSlU1?81cVlf3!%>COC5&F1&&`B${+7t)zB4|x`-H10Q8#AN46dh z`-ig&jLI^A_O8nap@}`5IE#*lBOvH$`(n^-4R(E@aK2~91OYvECj!8iaVD?`kQ*p( z)@<(Zv${fS5aM!AN6@FF=mvgyOD+QQs$%A+t#iF9sH&{$l+>al-gnz*uuM{lT@(vT zJbLu6Wct)^Wed=)e8TxjlA&no#Lg)y z6Pk3vJfcPpU_F;DH{tNMAJiqN#A}AOvqCrQ)E+d_ddfeXonC+_5-@_o$IX>}nEhaU zT>4wo1Z&}FX|o>z>=IsZIjPDE*T>&{sXTgXP*oiwY>IJ^Q?ueffrpucyd5l6aXa^O z>VYbUxgYRs9$J4YmsX_*!H1Drlih6uq(+P&Z8hS^cJn?a*vvDSs-Q~Z;?TQxZOe-j zWvZJSH=2mKfT&ogLh_~mS*jF9U3K@TaDT_qZ}$f678HNqHfV1h1;RP1Cr4CGt|nx#PIa0Ui^NM zW`L^TfX|9xM4_;4eBwY;jMs=dg`0E>Gkf?^zSQ1EU^n60mz7|1gPPKS56?_|o+zwy zkmzq;l{>k!EiTMQ3qJ`PqQD=o*GvzCCQkn&6wmynL13RbYkl&_8j0${M;`ZEgMfjqKlfXP&FlNRks2%`hCz<~Axtf( zoXl_|U$Nt%H}l?zY6k`?$)oq(g70vt^v*x?FK^Fo&`GI-%Sm4KaP3AvFi_DJ1{BtI zms>rr-n>OA>+>(B@iL={B%6*n$pP#4{iTLLg>4`A$CbYQmUVp6WxS>*YOw&D-Jc^ zWINou%hDjZF#~h1$3eBoMA27~h#h$2=(h|SNVA(oo)C#@AC03|M|{* zv?F5!Ou6~R;;HUk4Pd&twFFMI@xDPgs*TF)N!-pkWOJz)#TqcN{0F=r;Lof zG4b~@mp5PIkm70pqxO3R4+F4KO~NPnRnb(zpV`BWT)CwqmA~eSxV&6SGnnLl79oJUPjvkq! zQu9A4v@9igSkGW?D|hrv*fj|zF?)M@Zv=v`ld-hE9$omLfG)PY5L+e`GQ3VQwQf5g zB37J^pmWEc1QYw+m>&*&{4O`c!`!g;7hT;(35sTzZ^zq3?eaC;Gdd-Pa+5=j(izZ8kut}h`Hu4ak>6> zMx#NGr0$Kq_1G^p#aGE+d_rSs9};3Vf9Z$kGFi){5RAOuvC4hff{h)G^$WhjT$6`) z7|?-RsgJKK{9R~HYUAVsgL*n2=PU7E!Tn4sZ?Qbe(rY^Je{!5x7Kv|vyK{d3DE5-t zm+I>r!6A)%1-!nw8|@`^?;`yQP>YqwUnT`Lf}ja+sCf{7z2qEJ z9Ks?nL3rxIYaeuPd^7WsXP`7QvRO%z42BJ=e)H{Si>_0v>Z&ANUb0%Zo4kWeR|>Auo%)kJIpBR{vO>Hp?k$PdHjP5U!J zxzHxj}KF8o;8ylwy z!+`60)w};ZX0UjRLCkOGifPIPd?%+g%a^732ZvuYQ93_bX;AKtikq*B?^iLixZo20B{(M4d4 zUc87Iqm8FkRJgUp)ZXg_#$qD@y}{~!Y>WLAsw%cVn8eLa+k#3&ChsVWh7l3zQU2NnX!jj(do`{>MIO9^h%u zljbh?F`hQW$P#UUaJ^}%Pbb0ed+@XzPHkz-snnAX;VO4{ov;U)2gxD@-eYyx52?1HOw z41MxkU*2f;U0`ZDQn9jj{eDG-MG}T4`9@Xh&wISW;m?EGs)DEggQl;JYUBCdE>0nM zfB?ZAf&_Od?h>FtLkq#(rBGTRB|vZwTA(c2R8;TN9_DEA(4J{v6HI<^-DJf5%BRk3QyFYMAzhR^m=*J^F zV!ik9>%=YkNP=1E-^=7Ok~f_3Xsp?C9&DWQ;XXKc0LMN<++WuApmmx+hIUUSfhDUUEbS!wZ5S#^ zjU{YxpzI3lKj2Y6?rQ}Ykpj>V&tOIJ0F;I2t2$1(%p2qDRK#M$pzd2 zKbi|FEXP1Y^LAp&5ZW`Xq#*0qy_m1I-6^63FS(DjAjCB4RD!NDHvzI?|>PvF6AA>9tSexjpjC3C@~<;RZUPx^mFT*HjR#d!an7t%N9C+xPo`tf(;beO6z`wbIdI zoiuL8(tDy1M-)N+?Y$tc6o{5aNem;CB-;=)g=SHR53dnyjMx0&T3rJ0R7XXi*c=PV z1=-7vMQz>gJ*YpbBr^8+2ACVx2F)aDc`+uKlQKbWi7b{CPO&z-l1^xy+AVet} z<_Qnf?!P29cAx;94d)0BHxmPxav^6#cCrzuYbQS&7hA%^kU)CE>TJK*xAvM2YFC`G6zY#CYH7Jz z&ODhxxdfJ!TXdHdSFB}_2cr+OJ3>*1*>6J8O!TUAI2EkT>^!{n%`DERwb67QP9cFQ z?*Vd4>ak!ybyHMuJhN03$)~Q{Z%^V;l>{^xHj{OfIBOS|<0r zmVJG4YUz6fg)oL&6dhX1JLO_t!kz45R?=T%+(IlZQ?N@=?ZLwW6ZEL%GQ^hMNAqA} zEa0ySkp&rz*3!)x#@5o3DWrg~G$u>h0pN_F@)BT%pLYp3Q-h0TDKxuG5H2)gs%I%Q zIjqAUX%b1x6oLQ2WU^CW(lXf)7)+*Uh{Vl9pyyAGhf+b6n+Mv*a=T;4q zd2I?hOqo*%M>yv7so>!T{LUq+u-r-iRbiVXddm4mQ6zdgkXnS(uB6&SEuLf=2M@Y1 zn?HxPF}9oBR11Shzs7zG$(ZfnNujHW3vTAoGR19Y7AnqIlovVI z@jOklt=G?xZp=tAkcPa17{J;!Sk__fJespOcq{J=4lc!GGLPO@)D)%P2h0diE&yiu ze#`@BEaUzH-{4P_35Fb9C5o_xKW~6Um^Pz{6^AV+JYb|wK#^cJP_rUE$o4E%VPIH+q|5) zUs%2%7c5gUtsyN_;-i7@)d$}zPC*McK`f({J@KEk&eYH$v9U#Lg(Ajy`4tOBzxtK1 zZKkB4hmK`&S*%tJot=|53CeSV$1%+jL@o$wB5Ar;bEM1$CdgE7)uH=eL-XQt{O3|| z6N&geW|k&?bc~|r4=ZM$w8H_o+}7GQ>vl6bLUC{su?v_SxGZUdfU>~MbUN>gW6F!i zn;`*wAmy!9$1gNlYpWIG`3&tmg0r{*t}*bMV@P|Jll}i}GC2$^)g(6mZ6C6+p>hy% zokHIah~JQ-d0B0LUi_IRy?bsIoX40PqNsu8;WNz`0LlMFI4*}r_SZPmL-a5_oTiQg z6!Pk|PTFURuhBZS;7qiSf+isYyx7kbBIbA4n>@5pZ7jmn6A(u{SHOvLl)81BEl1D^ z=v6`(Ok=h&^ou4bB)S*RXkaQEIr3N@TGI@d)@!p2$+$_xHR|

PL)P?kg?Db859Q3dKR+I9VH>Mh;MJp>wRx5LS4(lG;gjzc=LQAeNwE zdbVX?d3PG@-Kg9RpmHV4KOzXv38G+Z@qY{oNfrl86R}LXW@zUZBsWHS(AH%oTND`P zLq&c_A8YXSeoW*!w*Hj}*O>Zl1=&dzSM;}1-@Y?Mebu0UTzG73F}YX9F@jwdGh5oH z9AVS^HGctGmA`vXYWr%fz0~{6wJwtj#=RaL(UT=Jx^@T8abh8In|~-uID-whfY=;c zk`fL#C_H?6{SkDmyH|0k#;qR_Eo^3$=yUc)?q0VS58w2;4sr6kImL0Qhby(Ch$pi5 zax27N>L@d>fH~B`7+c(}Z>qX)o0@pRDUc+;PW3tj2j~SX+ zv`$7Rp@U;#-$V_QEsJy}`PR>o+D{FY*4d<#7*T^j=S~okCZbCvJ%8v=MJnyjAU%NrLyeW z%gTyMOv%&8NzJPA4-;8NtpN`-t^``^2VlgR)@v#|{?(@yaIg)jE9=}gH_3q={=qLDxBy&S9Gu>^Q$yO3f>Z!frKFEqzomNOfP+43$gN!Z3jW(HHc_pKClkp zKr_nCPN&=-Uf0X@#BGrH7`D+IpY&YGlBq(n&!b|#axwR7tixe1@UFSPdcyN8ihKT2 zJ17L##B3V!J*qRKaQ#Ro<3ZgL<%z@QkoIePk?l61)LSwnIF+Pzs^yle%8fv0qPVl4 znZX3rv+8rs4=jPN^bvAe6-k^IhdQz37Cm8rg~PtSJ&y;b+E}RzeeIlT)>Gx((B9@V zO*+MQw_0==@{ZXmq|7CciNUtsukGc9{mB!=eht1qWw|vfJxai5SyPsxPm?_TX^(-pfXY2 zM~3!6_;b6ffAyN#UFGEl?TU@AN)>Cn#5R28ByQq9xBO!3>Us%olO&HhSW`r+nB&XY zy9XmS!+ouOMA=7v-i;vSp6Jotf*fkf0AFDEmr6tSD_@N0*v-vE-^&gD^ z48+qP<=6UoKYhc#hM4&ADcRk?#*lscqa@RiqY7;&|7g`79LV>d@3vwV8RtXx%Vj7e zXmv|B6&#QlmU1(H@ny`r`fo&3m5gwb^i|hj_s;v$x!=A&H<}2`4H8%qM>xhb)EB+d z5xw)Iw!WPNHr{NGJ#VQb<&5lD36Mh+W>ud@-!=zcVwYwvsM#)`KMng!6*`0MpIkLv zv5eAcIhp!<`uorKn?K)^OWr-peg>Q+V_J4AmGl)mS-PJzv@R zBBsyz&!xP~otDJz-4##R1Y7J9WfEC*n9ui$tp?`6tZ!TRzq8THN1uKOo7iUkofnVx zl(l9O*0Qy>aeKHUg*mj|$~Vla_W}@YI>Yr&+Fz?IrJ~x0m20o4>pks6*2!L%AYaNg zj(iB1w8|2rDIe1yTT40k^|8xB(eY90PINaRm7b@t+E%Vq0PG}1tY}3l$`GjQ+&Wm= zUjD@p-g=~&J-Cxl9sk`xdgv-R!SX}zuXULgDXT4;xxznn0Z;61zxUzz-f(14f4`kh zFNr?g4hmkpF@mW*;HdvnFK`MI1iH%^Xoz=3Jk=v?9#ecw``S8T4v&oEtg>#%e*U2( zzPZs^fkFto`BzG@NoI{m(^Fi^L67Y1JS?=9tOSnk9p;LrwRQZLQOu>vbaXl~bUGkc zF$vFZbU=yxd&p{-?dexRcIq`A!&TpOn;w5;dEzTKo% z?c*rXl}HAQcV6xN3|s2Ax1t$mCCycc3_ztmJLCu>a%*4YJmeF+hP+>GYmcGEVCea& zk_$vurn#{Tjs7o3zWa|#WjI~ym~h2zS0W^R;f5d+$zjXz*Q3VkIgi@wa;|{3&k{P= z6`mEpJNz0g#bLU|BDMyp6w6eT)_)apq{wHQr`e8OQH>{7g>;w|X)1l+mCnc`tU1J# z{dzisKu|V}I}L?|Zc7GsZbro!imav@Vt4owk`@oR0$bB!b9yFkz?O$z%`pAqH@lJ+ z$J^xkE@ZP{n9J}UkfCPEGDF2pfoQpi0Ycz3s5nNSp?`R!SfQVnBkU%`?FO4Rj}s8U z2vh@_g$44c12&_6hrpqjZSzAlf#o9`FxiO6M&?coNRq{lI&tY3JVwwmS+b{4HrNj= z9c;(1K!X?ebp>I@#o}YvwJo&4sEW4u7bYcBW@g+MmIa=Ko|c{{;Yw2$M}R=$Y@RZ% z`A5F1uzt;XpRhnZ>p2Vhz6)gjH0P^S!pKAr@TDKib5G4BYX}KHHgPa#bvZ7vuI&42_;=RHCQPI;ZYk684H!$v`K(V0UkQX=If{4iAy2ywh(RG55oLCV? zQ72^|2c3OKeC4D-uy)E_;SWX0yOBzQn0`#rW)eSR0LzHmL8Mg~ zV)$SiQ@=Y3a(k=}`w4W%vp{|-tLlH;_Zw(EyayO}a9b*^Sl4L(I6&&3qqzNoUE1nz z?Mg|U?_2||5woE&In0en(i&i3r~7~kIYGT~Vk%b7Y8{#*V!iWpASVXAD?RPW}mwk^kFDmvO*DbJxRA5{?ujw@PKGqFa2k~>( zvsw*N8)j2ct;I0*@8cYsKjhxgL3f4 zy&8)4)=xDv5w)!G6Bty0#;JI!Yzw5joh{K;d8(3J{2rU!2*>*Efj()-!?E zXcAkEzGK~Ge+x>5M9XLSvQ2_!DGe9f52S>f0wO)>C?Yc%+2B;UHk13rV}@heErdon zNJ}7_(Q6tvgXcl3L19Fu`(IVRRDStt{>VDgJQ3mSN<0aP)+BK|_>wSuB|8~#+q&Ps z>^!=z$wHADPxpQ?kg9bNfsCyvMN^vsaqrnjL%t$;_Sw!VkirwL#wV#-w4qj6HUsTt ze-Wx5kN4-%$L*ts}u3(YX5H3;_t|5o2_vnG3GIzoleT*~?R+By)7 zAD+HbXSOM2+7Gr2KSoA%^{R3nv}$~$2m)mYOF{A(JiW^4UqoPXhHp zD-9~uP##uX>2Af>kv9*A!Fu~nT+Z>OkU_cwt+$uQqtD3c^F$*J%<}?|equ{t>YL`P zEDExrQ;inPxyXe@3~dL!;%DIE&G~|#DIC?>^a^36GG%w=>E~6fP_qq7L zdK_M5z~tISoLGAGgCEFxUbbN-pQYjtse#d6>Q!Zz2J!@!z3*zDqSH)eCP7O-H0pzr zQO+07l?HjF>hj_pCgpOtar+_1*TNP#%9*XW;*<+o0b-~v2G1qeo5zjY`2(g)*h*E z#FYAqD<_=IG2REKMnpDs^y-6?ea?8SM_vx&xMLQUc2H-z0Hk!`-8r%qcl|ck46iSi z8jjPNA6H~DPw5JVnDwAxkXJ(o?zUV-Xay|K+K}W3ou%6%08*Kj!XTOD^4=Zi(sU)O zIgHW+JauevnJdfnLgN9*74Bv)#0aD$<_-nn&@(q%_jkAcfV7o7VI*Oow8cm1ABUHy#U=G>&Jj4y+^;$A9k`8q1nh2VnNcaTKhPyTwWKGT7qeDne}l zo7PkoVii=_TI}+5-|~I%NVd_z9vw|X4D=BVRVdoY1tjVS(nSey__L@qZVX6D$>`|L zZ4auDXq8G?k7M?nNQ+#)!t=u2B1pYoOGZeVP0S}x&G^{Ax89igR_tN748E{ULAo}_ zhCfXUd*N= zg{G-1H35pQE);@wK4V~N%tJ?N%@Fd)Ls~1LMCkx@z1{4N%#ugZaIBDD_tJ=x9NJlg0wyEXd*x=C8!zP;Yh-X%60-oxG1ootOE#zMg#Tnzd!c4 zDX@(8C?5hx2I!`W<3M%v7#J<@nd0}#Lg=(`VmTD8NCIUYld9nopiw|QzFO~d8d;p+ zP{2x0q$prvMpMOf{ukdBtdZ3T}#@z+OBH(X_Dsbwzb;J~4 zb!P$6NKaN%vSDIb>e;I1c44rj(pYhnf(hyL5z~;g%&VcxY7a;L`RSH~i>K_t=T2$m zu4$^qfi4P^rm%p@-QX8xEO6s*>9B4LpMkw{dAF7CrLOEg3Cl0$L1an>08ejW> zD)|o<3wkQum84jZf)Di>P%YcAz z%G|{tA4EcKdRESOwZgNXJe#*?JH!%^l+6t`mwG$mG`NDm9C^j&fX9`zcfuSuW+!`q z26x>HmiLw=K5=AoE_w89KL8E8`2i%{5G0e3lWUrQunr=vMyLys#vI5X8Ifrj#BrA%^p z<%BDO9!*v)6N~aG(5`4puq&uWxu3TMX*@SvYJS|OB0N3*TMdhq1)f=O=Hyd&crcdpT@3mjS z|2^ldt^(^)+}wT+N7^d6SKNi47*pgVEIrqxg4{YQ881}^yr_E@9Y^w4P?t_=SycZ- zOSnHp;9iG;X3wf3>7ODT%(o1_JV?H6PZ9Ter77$lo4hc&j7p=GV9TePOL_Mb{Y6&7 z5F-tqRm%WM6M|V^Ob7eJ(sI9olOcdde4DCx9?D0)aZr+Jzn z$ijsavR;iMLr`ik72FG}Q- z-zl-NU84~Z(UQhct>d}t-rG;@V9Mm7)~9kPSDz8d+Tg|F*$7-7%e|yGR}hV}*iV&Q zb+8{KM5xKqF6UPq>g$TykBnm{k-1Po`4ckbKjtBwvHmNIjl}XM%pfy4;tdFgoSXSn z*~Ve}YGBcWZ-L&_z?YuFy@P3Gg&m7rI&YAl{eo0|_DkrgTu!pgsSxH~pp^S>#tAlC za|(5xOsESN-YJrg8 zb#Bw*WD*62DXfvRt=?yKCkn_U%_jEybvbWRm-t!^zc`=oTC(n1tng*6O&)`#W$A|= zY0|UkLYF)4AR>ZQ4{OCI>!Fzsy%=Pxy^3981OHxP8HsA&FD&&>dn_%vE)}?wZ zJjYwor>t5WonH6L_yuW9phrrc!Ra#+;d6wzrJckUO&yF(u>Qe3TMACe<#+K@FBFi? zim1Ii?_^>o@1~;qv9wEdke8I#H7GMHr5_`(?3O`s6jCm6$aRtdRYyDa)%cUay#s%8!Bi0Dum2-wC;%){`!+qjxH@_4cgcC-4P#eBKlFqS8vuajKpI z>+j!uN_qcLQ;O*4g;Cj0M2Fr~@ccapQ|*`Mv?!|l529O?>tV-jevQz`8ry(xIY#(S zyNZw!WexgtwEToyet&3A_l)rakDOikAlIW;jW%wQ+$_eA&cxVz{A{Sa_7Pf>{9SV9 z(2vW9XhtOC{V2(T&&y7EtTQJqP}Z)rr)_=jvD{33;6{B?UiYXU@Ft{Tenpq@qmP?y=a&VS9g*b)LTSgP_|`x$tp9&b6+mt6?*4KlkF}lW43F8135?E{1PpWs;?_SeaJLqIKoH6c|L&fi{QcZ`I_-6nzJ`VqIK&GO zXyEnVciV)n!$EjM5D|m)ewY=GXEYEZALKc0^I5KeOtcr28Dua^rJucsBnXt`v4bh) zcA!L;8cXB9^eoFShy9@KkgHKgrilt5oti`UmFgG;RLbz@#4k}9=P&lY3BU)d*A$!U z18Xw14G#4Yr|NwWLxqqHDCjmZQ4?%s6C_Q}x>h9UmqygN@oSbnf*AIMU6Q(uC;fJ0 zW`!8a9TNXrM)M=u{)GY~**BTg#YoRAYut~>lCy?Wx=RarWGUZrr-~m^venI9kXAGF zAZ5sd|4u3uu*Tl#LOwNXl=1hWM)sd0qqw23sF}@TyI0yGYtoiLy^9cb{lH{Z;g$B! z_pEv}NPWHxmhFd#H_op&w|nQA-fsit1YKNG8JAGT=zo>IefGHku23nBIB~m(G2dHn z=k=2!b+>%VK)VGuYo0x<7rIXEDUOUM$M2oPP`3DMtXocyOn*}?8nc15%F7+Jep_-b z5sqeHXDZ%$Zt}!y33M{n@}DF!K|CnfGsAOu9k`k!%|^CD${78FoX5Mw%o1=cZgMD8 znjEIh;tQY>A9J=skm#^&}F zdy=6PzOItNsXdB9wT7mFwV>!)!i2)9MQCl$>?V-W;of|6?J6pRXom3=goAtgQM1-2 ztCF48$ulBF45d$m>xIP3-D^1t?k7_SkXEr+u^6!pu+&fI9v#-MrU|yzYTPXc)%JL? zBMT{UGZwLd!V?wM0*?XpbDty+YsJGmFcpN?kHYpGJ-SlB^;3WGM!8$Ov3@foG7Via zso<4Wm&Hz0=)Ewb*%C-&W~}iymcJT4m!>(BdvaK-@fRg1kYUJYWZYBFjx@YJsm6e$ zX>Bcso>30BkQaDwKruarpTLaTIuk)!DdS(k@;N<2cwds2@V?woO;JI^QB{>zM}BF- z2){rmcI0(|D+k~F;cCKw9@kIV-ziS zA=^m?`+3YTD}cIt0XM2%_of%U32{cTI$u78l3;&E-PmHSoUq^q+oJh^_LuR^d}H^a z0EN~Bk!luYRL*t_davKMaz0>_;Ky4=Gd+!;ndQ6?F#$z2kb}ra$uZ*AE)_=4`g!HC zkUF^$@FGWBCnLb&h^}Q#X_$DYd?>g^c-c>8(+QnR2%I8>9;r)0Xeqbu-*}&Hen+5_ zRE6zG6Y#{L3l!j3j&hO?LYsF>!V*N1onHv$NrK}@6%(9`BUfC31_7(GjB!r1q}+&%}f zNoh6TpnXop;)*<$K3@n_81)EwY>@FsfWTQ#n%|{(K3o>zYF2b*ca=8uGtfi- z(n7Jf@qsp{HC#7!{!ya90fWU@Qa=H){q%2Qfn4chujySyE5#pv>J_Feuzi=A%gIo4 zs$X^@HRLuitU$Sr6w9EU=lZ!)L$&?&ry`E8f3=yJWh+v)j>>Rlh`lx(6EiN5+LdJH z|JlT)vL11FJ7Q>4!OzL)>-iQfTlYucm!oUVN3x-Y{%UDb7ZGKlGt(|&;wHnEo3m_0 zat!VnhwJyt4IB+(NmRY|bh(50Wi)=u@|#2Nff<37YKZW#tX4r3DYfEo7wJH@}R%>?p&{DLgkweF{g0HQ8&q zT|H=;>`8W`G`DcDxH{^sMM0NpBApnqD7A_OelI|>QN79TpoZEzI%-|%l!+F)c#rs^ z?dT-ck@}n>LFRX*6WyGRXw952Yf zR^xco%TEfab;Z?+*(9t<0O;!jJtUNlEZ-7j>>iqF)uyP8M6J z2RE)hOJq_uHqH^hZny6UVC=+zb&(kjB$c%D--5JCcA}^@yHJMiDNi2#5LQ&=&n{9F z_d8_OfN_v`Tu0CG0lH6A3vENXTqWdC^a3bs;*7w3mik5$6OrGg1{j)^Uf-7Af!=S3 zp<)nc9v@3uT_y8Xf@jHTRnAvdUkXQeXRGbBFz!jz!}be7*)M_BV_#}vI$P5Bokx_& zRPy3)W?Ewt^Gf`nE3xb83C~pcU#<2#)9Vgln*^dn9$F6$au?mP?~6Q)+L63U+hq$$ zjPB(F+@3uUL5Pobs4={3YnC~pL?q8R#c*Q-2AqpoM?;w9=!08YC}<#rJujctTXb?# zJ2wPiw@1!4_?`CM+WX$Uv5(>#cj+08ZW`$1oOOE3{+`O`gC7Xya8AQC=uedypp%9j z^viKx8J1G`85OAy~G3>aGjrmpQTX_1KArnguXwPEV(b>$mH7P>WY4E z+v1YR*L*?=Gi!+~)1UMbLX1ec-2I#tO52F^^ULHyP;{;)xCB9jBZhl#EF?eby*>Oc z`g0&dp?Rn>MXxvf#oyU4uT<22T`0d&`;Yv;Kj-@^>FN>R&&-~;5ZQtMtKMqZ0{*$- z=f;OcT+-%gU9Id{}uovFJN6=Cr?i zRn&I&>EJA1{X^e7)joyt4`!u!?xpvCv8Mkv_q3mUhzyI2%9Dr=jlRZSugy?Rq}X>*pmZh_ZafZittzL37^QaDsfu_*r10uL$9A4zWA&K zXeTCDke^DA`S06@=&w5o|6{^*eX}6(>e=s|y(i~>b5BYgiu>OwD*rAS_WAH>Ea=wb z_76qP)0>0KU%##&)~vYuUzC=psz*l$_Vz|cM?bys2@idGrJQ6S^6&ch8ne6LoP_BI zTh7p+=$ot4-z*5hgG3cx&hd#||>|N6^pE?F98dr}F7rfA{y1x6fO$5hl$c zRZ>U;`UUr~_BG8N`~LmA^sQg}Tk3H-zqY^A=lyF~Os3>}PxJiW&wX{Zh%ebsc-Qbc z2l`a-(c`SM()7B3kRc(b{Ay(-JCX0Sq}LP28-p@$f2&d4O4YLtE1*Fu^H~ZhOK=L| z#xGwJR=Uprw+v6=|Er|JwdwVA)~Qg?q`Ez?ae;4E^$%K7=A7azsk|fD7AhT*^i>9R zyF($vrZA(0j^vTDei;BtP4AuURaFiwQ0;jzKScg+)V);+y8HzQ zyUOjl7`|0_XpK7EI5nuruAkjEctZJC@RXpA>&48U)wP6bibs3l)m{}(Yx^4tYr{|E z+6?Xm^0o(`}D8ufv4J^u_v^+c%-S6_r?oa9ed6q+RhBkc4L_9O|WuQj^bLFC?K*7Ph2_Fc_d z3pJ_eLwoOY_T<%$NjT5FS7!pw4_u7y-F*mAbZ8QveRVM_@#>Y?LrBe_tVIu3M%VST zmF~~<1}bmv@{#cd0H{Ia>29Kh>6tf2?)ZVB)gz+(;O48x3JGiShpEISNEX?vhN?-~FySO|V}AJ5HP2v-H^VRc7GI;`)BfV=;g7#$;WWY_9f8q7k_&}r zQ?T#37^%_f3pj2X78D(Wn;*Sq7x`spoa^RW@Fwls68sf!O4DH^Bo{1GP2NEP_jFoh ze(5_U6RcWkSjrA_c_f_nIONIKPBE>S>v55~m&SB~o{Etc(VAPGAcYm8#!4e8oduok zW1X98^ajr^JiRT8ei9hV3=h`?lrzEky#gUUthb6Mxpj4%J)e_6sxuua!>gW6S`G&1 zCA(F|h^Bp&6ufk=iYYy8|q$U4u^j$&h?3^&O|Y6hRZ~&-gPb!uMoB603Fv~;wK%b zuKk5)C0)-fxm2!+)$_q`PLL~H=&QD8#JKFuuPuw?||1wADAiO#P{kA!Mw!OI~ zKF104NLWe+oBfQ401%Z2XXg2I{k6_7``L#$%Xgj>HNS1NW?DnU(Dir3TWQ?+HHAYH z{pps{Gfn>%BA?VH$i`DX3#Pn!ba}FM*mD^d`=!c)B6VgP=j+++hbs3kwf=OJejCE< za+g&moqF~!{!*{MfO~_q%H@yg&aiRKJne@*34OI6MVq_%S-A9+jlA>vxF%}@|02rLC;dKaP8rJ(O*HOS>aaIXA@NnU)llFIfQG1maivw^ zCKcLnr?N%Vxc}Ak+k>rvwt|}dNTu9ApM*;fqUv{4_DVYk^PJoigTpD@f2IY3dK>Ye z{o;Nh4_m*cgTZRa&{}_w4?Z5kzM-!U@4i%7eG)D_Q9hDuJ6F22xfSm3ax_>d**$SK zWg9lYXP39_KN8G4-xMxB-QbX4JYVO3czeGS>S8cmf)8v%u(ZjT&-<)wWqerkO;RlL zq9Uh)`v69Amq3Yw-PvtP{WZyF0B8JK$Cx3{C2;neiDmqkM``#A+2=mIwd)u5HW(<` z?dk7}ls22W4iQ=Ff~gG4_h5gzG$jC0g2Ac{hMzBhWZapOHzfMzMt(@vVF2Gu3pP9vAau})Xe#s22X z`PpX33XWZHyxlMb6soL#Wcc4XV6wUI6nYxb|2FV>;PcVk_B9qO)4~$XSdy2X0ZDXY zXzt`331#HuTC22B3eI($@JwYUGpO(!U?{FhNCeb9k_w5%mVn-kpR`Cf7K4?CEtAjI zYxEy+y2$U>mRLnUoJe-yAb-@q?|sm?8f}}VWMDz2BDleA=3B|yDEr4O)c2^KoAc;f z*Xm!>4#to9vx!g(`{ErPakj2)#;B&`okT6hY2s%+?94K1FFvX0vY~vs zn5<bvQb-hfgg@8FVW#iRZIc?HyA4?;W0e*&({a;~Rz6UNd zl3D}O^@>Ad@_1AZW7Jms3W$EgZ(T``g+`sz{;vQ9r4}k8#;<+d64k7Yig+SLaB?KZ zYgAyz$z%)>%8J2{0%Xbljs-Eh`!WT(%VB{l2Z+GQAz-p4s;@Sp#H3=9C7b-C@KkXc zSxDRDCCwC)c;cyFxbQK#UM*|59yO<6Q^7;j>nTwtX+*R$H9k`-i{a)mV*I{p#kqF{ zW!^nD0-ILq)AsP{$ozroTJy|`76BZ%AskV!Jn3d z1x!~0F{@9KVu|gRn<2DB@Kv{Pk5XzBJ|`-OnD{1OqO=?|G>rF|;k~Ocx%-p_t$tT* z4cAwx=8H?*v$+SmE{YU{x5@arz2;TF@MDAf5E2~`h!l2YTmoxJJ6dR$7sr#US>Rj| zC4x`gdc9#wF%+PLZBY%85yt0pkbUVPkZjZf$5M~qp}{%mKD3P6N-yKMb0;f?mj zYFCIn3fPjtVP%sS2XFAZQOZpPlf=G~_zrxT#0(+X@v)=$Zk6Gkb|1ww2BST`2S${w zI{^@770xhiz@KHv%CLU$SfDBZ==8zW7}X$LIjx#~m?1^dWx@>w>ITDUoc&dT{Sa6E z?mZlNzRchitqa3|BLNh1;M@C5+U&O))Nh204lt3Bt}9ryKXE0`T$niV@3Sanr;Hr` zSw!QVg^u!ll)%~Nm*UsiQkqmVtO2j692$de_R&dI>O&Rw_f5UuMoF%JRGjiqmb-`L z@D2R9%4&)}P_O6k8THX5JTt=Ur`#LI{bT5#!C|Ha!ZmcbXPJ5#Ne>PB;_H$|Eu%Zj zorp@QA5&2j$zNP%8x8vcvH(GpuquE8p4?Q%XCN`lVC`YhVI#(tas+Y;RE)iGp4_uC zHZ3UclIFOMOgZLrw~i;j*%f(d^;=9k6D?wSCM$b2ky@vKK(b`3`(Z~4xf;^k6f}FD z*Bet&?#NsXdnlBS984bap-NzroQU_WpDH+kQm}`*xG5{MHlfm+J}#&>p3k+7&m2+P zwqC)JQwh5@khIVD^S!POe2vn5zDF^iX!(zp2sg}hT{c<<3zU01q)_YrZ7=nL!G*si z?P)LeySW%o_ygiDe=u3ccjWVG)(v;!$B6uvvQ7|($cueQ(xitXb$vff^bqoqCe=~; zNoX5w*DAYL_x^o~=O=9rG?V>!nlBfbPBWj!OnEKGADJqqmw-gIb8g_A=tYNVB~PDM znmN;trUTbD!8{KwuLgl0QRT$ZF;?EID-P5dpWSeI+jJe`vlV{q~K)q3at zmT;SrAPbg_KZza&l?XZOSDT@@L;J)xQcSGg?o0g4(kFkI610Ma87)RQdWOp;u(Zk! zjnJ^T@a9A}jA(7wPd3*0`vDgjy=f7}{-S#gqMxFDNjkW-Qdgg2TWm~z1{%*{ym)wc&z6jbIFZu{s zdf+1~iEecuSSjtskc-NXlkz^SP2`aq$sM*8iC;Z^;?e~#wF@6+obc*lmZ+phTMKS_ z2{Eesgi3r`l|GZ}&U%OalJKL)gXd;I7Jo|g>Z!xK7FWbtimT8hRX-{aVg+sSdj2T2 zYAE5&>=MN7(@!~3YsSsOwkN4oj0~;*q3GvUGwtSM8H|G=zGN>Vue{`a*VC|7GK)nV z?ASC52T={Hmg|7 z`__vl|3Rg5-t(10-ziY;5t$g;*CRib3UulCPR|NyN@_YrQJE~&nW+En_{tYHLe!>c zIe^@gvV z#*`ep@cXC2v8t6$h{{Bvsd7Y)n6G80?&yrDT>h1BoZSwm1HLlHxy3nLXKmKV`o z_fHHstLon%35}{8KMAF`V`nwF=o$j{*KU%}oT0>FdZC_VVkPKLX}bPvdCFwGwopJ> zM%UlGOe;%~KIK)O+S0eI*vZcA9&vjHbPF7ocU^83zAC6_L*;M@wR*?w63k>~ooBnj z0h(`_cEM zZoSCCM$i+B7jBQlmecV$pNi69$5n+Vq6Ad|EIp_xbK(C`e-*oOJSyz}6rHD|`?3i+ z$4W;$cIQ>0PO|@@3N;ACQK2GZA140QR;Y?sktOd)g7lr(0Z?CpkS}@9=LC)}eH?eK zt-h$GP*vA`e&H`Y?Wu0fOt91NIbj|T_S&bicW?&mWt{brV~T&mxa}S4^9zax+hP-S zy}aPtV}3i@Vtv2l1^-!HaE&aKZSF%#sf>N3Vw0JdDutCUGaUR`mrTak&*3er--3AN zNGk;{a;IDN7Q8H9bW0s726}Ak^Ag zH>n7o5t+QUUv_DtOMfPJgCemke>dtJFkawlRcoTAZ}Ktgp^85H=)BsamsZ%-FwVB2 z?gz%Tu6{w}UQBxLaUz_56xNSYEB_x^UjY<*B z&aN2wI(-K4SME_T#WInRqFjaWkgHx&3e+$Watii2Ff0swS#;UvMy$T|rGSl=16YoS z97wGqRKQgs#=;aC!Pd{E=xMW-v)h-VlDCJ3N-FybowLTD!>1;OXq{DH^qOX>?Ll2} zGo24Hd;Ipe=d1#Dg2zTH7A2u*LpW=6;5e#;!kZj{#+1gNOqCI6^x~0|z^E7WUWOHn zwU%>EB&5__Kt(N{;gOQ?-6+U7_*Q59Cot0r17ssBVCz(6vIx2u4x23=5QDFfDvmrZ z!?GK=7p65Ia5XOay3v=Ye1AP9#B>m38jQv@fM2P0RQ8*zYy$a31$ap~tIQ}C>o8i8 z%q3tDL+xzWkA|LvGVL}{0`kaBX^@E*nw}ZsqE>r4370Bn-d6!8;+HxD6Lo8xfl-3{ z;olNfxr~_C1*Y=MX7BOP3l%-A23&Mva5FBU%@rFVePSZ8`|!RGCplcsnb-?JX8ih6 zl7|(8qUk2-NRG$D%2nns#Ku)>9T7pbMawgEiV_pRbP@7XC3|rVWY|j`sAVu4a)zm# z=Q^{Csc;(DK|?oISqnrDl%XOD6F+PFoYn2_E{6niA(!hYXoMm~@=CCYmEL ztoTok;xeArKh@n3!U+Y~u@% zJIM%u5Dw+1&W0Ae2n8mL^^Bc%6 z-#CnV;wl+mzh;r0V@8k=M++WMR*KO9Sy|^U&`=M#XO)mcGO<#^oPy{B(?x!irh&G= zrx^zTPc(5R9LL}(a3r~Kn9E5=@Kj1yFr26GZ23lkT#7#;KztzO{=y2J&}B}FT#)I% z=FQ_=cliv*k&gPKcG)CV)2KO@N;M$hvrKV5EQS6!BZg^4+eS(AnbEGQBW=@|jk*S- zrT9ZS3QIvFvhedkVk!%8l*kyv%chE7YM8PGhDue-Cdvi-qW8!cCvCkfF5MW#gd(rO zGq!-m6rRSMwr)v#PtaY~!J-*E~ z(otp78rS`J*v!I3fD2cc-WF_L4hJo6 z_1d%BJ=B2dhD5T_<-&MXyR2QXRfK^>O31tRB)1B!Wn>v!Kk1s8XxG$WqXU3rsje+q&l2@ zW$iExB?>l))qVtH@mN#sEL*4Wes5a!V53O0FCp#w9bDv1*ds24UExRgs)>^DBEznJ zPh_@h!tiO!0UX?zBTUPq_5~#?6a_pEL$y%aO-`T+-@^i^1=o_e)I{m(NuFFQUc?OB zXO4dpq!cZL7Oq2#Dl4?j_xGcO5ObA_Zg%5jeV=M-imZq%MC(Pz3EB9HGde-19xw~PWBV)p*dz@&lV~lL{PI=M z4I9DtS6NVL1)3&tz?CRHXM_$GTyq))ZZ`ERuu#b!36WPdBMpMN=wb)CE1==m4~vm! zTXB9`t8d=}6ZOInCj3hyh*TKGGD5${?~J12#hH^$o7ASGf;dbJIHBIQ7w`szJbid&6YLzw8pkJ#d5 z!9n`f!W6zz;@%|DOUg(TB|aLeBzM&5-IbM85-F)P9UE@YsfX-psT}t8rH?b7P}`WMJgcgk@uJNjVt76YCYG$`Pt0qu;Ix*_!e&3l^+aWYRj4>RR-LMg11h^`&a`4#vGR{92&8+(m{*ES zc;-fakgwuUQ*Bme^|*EgruBSpZ@1a?70lMg<0At;37$WtK1W84~rBo8^lm(JpJZS z>8eH8u!EQlT;piVQ}Wf#5Y&273$510EB(*RmCT&Odp^Q6uErCsEWJ!u43fX|ou&Xc zYMnm5$|CBBmy7QDN>*8-tJvbMS2jXd8m=pK+7tkkI$2da3(8us@OagV8g%xaE_%r@ zKJE*>&a@;5y!#Uv$(@6HKH@ZS3_#hseI z{E8)ne&;kumw8u>Gx(z8vZ0f2&rmc%;zoa#)}vzOsQ4t-t~l;O2h~qcMT6T=ZNfm7 zaxNp*-iKixBETPf*{P_r|IZR5#nW08T^M@?*br0q3V1P! z&pUCyU0Q{cze3rfjichDSUa%hO5Hdhzr3ua9rPDvi-Zz^a@$m`%9}#7mk<Ru(I z5TiB>2X>Bl4z`Lx?|HTdPPVN)u zK7W2Z2>Rsr^!g74?}Kx!L#;j^PdDFWYEMVc+riuAamdtrFPlVf;#apk$)oS(6|p*+@GfY&V4}={#NBds`DGUPvEl^!2jnqTmPe_%i--PQ9;1_ zPvrI$C}36OqB@7UM6dH{^sW!Bd#u}RtwV~r{&h~S{!dpgpXZh9_4S9vRm|4T&DGUZ z^I13bREgfiHSeQdJ%RUw%R^AWZp@29`I^}ry?=rbpVfEnj*)ttJM~{zK5SyD*V^yz z*3P)Ks_SR#4w86$N$qqmUi%Q5`!#)SEMxy>;r{$|wf=N;HVg_qaiRS>OX^)`r-vwj z_~$lM|Ks?sGdIioc89@@D6_;KRt;9&3pULJ_3vfch+v%#|Nm`$R{PibT$JyN=u=QrhWL6YfLndfdxPdc ziMG;@~&tN^O>@FHH7J^i%y`ex+R^+dmb0PwMq-2RaAs@RKEVQYpi$`}Dwwxrk$ z;u1nUneDOtAB$5Hiay$Wwr40l$;k}*@R6|PFhxOs#2$>z32`$8!|$|JatC>VyQ*@m zs-$2$JyKu(H9#kTjgS=Y7zitT?K@!rqk%onB@6(=fak3!`%+CJ_JixM&bQ{7K>3;! z+*I7TgTsvX({k>mK>3NfWB+6R86rGhB92=bC)ACkc_ic2!Hyt{5@JX7E*OBsJK|ch$BDfk*|K72m`UfWS>+A9vTbAxWd%|yI zzX7FpYB^))POvG+FMBmNv`9ROrDm& zy1)}X9Fd`b?Z5tJiMk^c&cg~4iEe6|Lgv`E`R@g*GuzdiNku`B z)l^BuOi*7HO-R$qmj4GgR*yC5gJaXw?c&SuA?yh|KVq|r!?+fask@24p=9aY@l$fV zubhZWADIkiR3SIc)M`K2D<^3&8g6Oo8s`Mfs@dPv3^{LX+>>aMuBQjf!or>-dxNFO z>9_&$TUIpbHA8Tb9&!0MWj!x!htctI?JM)_4WVH?av3+`-i=IPd3=_zMK^u0woOEY z{66mZxm7@zbwZD>SAEf#FDG+HBLGkYq`(TK?Wh;*_S~@juDDToQsF||T*r7K%jjIp z?jDj!W4bzBs)d2r;uzuJJ_Dqu$oRhOfz4rf7WHd^AWAH}UxJD&ms0C5DTiED48!zD zLIHe=&7g34hZi@3)w%j=Bx-$oiX+x>B2ERW| zd?t*MlEVhW_S{k$*I5j;;t4lhlRLoNEc{8fO;Z^GcH1T@qs#T2k9}~evb$@Dd(rfJ zub1;5|tH&0n53;hNR@3Ctq$;jQ==gWKRVt8#s@Ck~gwwux5U^m_`}!iN#k z!f_-Jdwz@FWuZFVB-H$<-cW#Z1d)QGwsIpr`BtM9>u&%0M4zS<9(+oz_l|0ku(d%Xw6qaO zItN29&ua~do%O(tBzk8xk?QEpr#KUDhFN?exn?-hKkTBYg(i#cY3t!y;r5G~O9es86!13ry3?EUd z8RD0Vy-TfkfttFB(QO?NQYHAED_G{+*O30nfJ-!n$UYX{sLD|v_CZMbgJTP^yWD*A z=ARK5%A%X_a^*lq^APo*UTi&NVsj4-xANb@Pd@QhDhhWINPL4dB#-b4C-7O=1aIZZ z=C=*1puKZfLM*&!>cJJE9_mhAEf_X-1N;b6k^V z8HWdNWvx#U8Nmo?d?)JP~ZR|g#YvdaDH(1^O-ownA z@jas6*<>Kh9*g|^8)*D+bF*es6cPjd?0wGRsOMHNd5VpTR;edkag--tRS{e&gi|S6 zqZd(0KB)IrNj@QDRdtP9G%a0lS-hlme^tDxWkgVPaNZ-7QA2jD2U~k%ZTg~ydrI~x zj(f@)Ed74U7WLMn$5MU=9bM94KNm!ORk5091v+(E+1kymRlGyX)ec;+4QX9mvQ4UK zU$HKTgHG$x+O|)-Z#8<>HEef6n>DO=LNc|ifAu{oO0<9a|eBkM)m+iT{M0o6$-;}g_ulE9~|9Ax6wA_0l z^6zfsvvNk#gx>C%U&E_chjv64pYm=`|6X|?dl{m9?0FtP8K-~SfZKh4fhNi`sRruIQUUXg;NWTJDL`#=qu@AJg zQvV{Muy7}&DrT^0mBjX0;xYRi%A?A#iheBVn}=aq{mKhbEDZ1TWnL$4D|bF$h!)cin^+gI!?0c-JCeOFs`?l+ zN1>JflE=O?+W*2Gsb(=qt-KViS!f5{Ymb?@{2ED<>u_UHW4_H(roC!+vzap-AS+A@ zt?q^UW!-D9@@wRdtGGNMhc6SIQt;Px zD;Fh3NU`)K&}CoDmQj*0l{H)kON2Irs4S!HeXX2&z$mQ4iUhO6p_(0|2<|as1`8%R9z-Hj^RY+$L z{(Wqip0O_4!{&e~bZlJw@zj`pbMA~-$GL!BmV)O?m|LhVuI9#+TbOh;9kLInH7egW z)bP%5qO|Ygk9XxzOIEkQ3Z_f^;bH{)ip|H8j^#|N)~@p7Jvkpqdn;IZ?pKw+`G3mo z26NA^AFcod%U-9H2THEE1k0hNet`;45^1#OEeT?+XM1sU9XuwH8{`V#=qR%Pc#q-n znZz8=iyWU4J3q#8y|qr@$rXm$%+FZ4k74kcL=rTJ0oDsZ86qtfERV+H7_L7W#junA zj1%iV#?gC8V)7M5Ui&tj6^sX%(7-Kpt4PF7$MSnF*>~`KoL{?WU(35Yxbv5FE;f~( z_iwkqpLOyKhIF!Qooo_rWk1a+3~ghxgW4+va2WTKScYI$R;r>O{LjSUk8z@2k|ca& z@dOEyl&yckq>2n_!jrgibMY1=0hUFftP3JIXT;HuapG^WiQ+iy3z9d!I0PtCf3L%f zrq_r)ALDr6UgLPZBnh@Z?*2_b;wfW0as}@#)*eejmNU;m;@by_Ptm@@ntUmc!}Uew zrR4gCx#Id^8<4XElHb16_O8+6e(z_0MDdynhz<2k<5x)R)9aq8k0irIwihBl*Q>@)X@0fFePgzN zdK!TBKRr!d1_I#XpPuID(`YK^26BHIcZU>I=n_bXu8(otUXu79H>uojhyOxp8-GCz za8?lNGB46``Y*mVn1ex=*Kzc3hw^6y)dV|~Q8UT6lpqlkiVRppFu+=S&;R?a|NYLk z2@=b9xLh26OU4V8?K;_y&NsfK?u6Jc;(2ER&Ng}ZJvjc}b!FNOcAovCB%jm&D9Nr1 z?&tJBN)q}ox?<2&9MDbp9>?Z2hQntPP0%0?&@4>c{OMPv)SApTku|G;s96|VH7~Mq zN^Jc&XYd$D1%e;dIXko1Kk#D~1Ed#(%Fc_FoD!=v5nunCg35H9$+HOr>nJr}DXJ!m zsM>J>xBK(o@(@)QL6fA=^Xt+ZMFd>LWrtk*pAKa!A_B;vR%;Gr{Jc(u>R53UoVOMAL9hQO1~^5JKZnfB}f6ri()}XsL6r|^BHmaW1KAY zzqiUGjgFEOd}N8&CF4bg_RLg;IRacoi3D%41j>>Cs-n)nZd66rqq)Krt$aBh_Z}5= zvF4l}yo5`?&Nc=g_wKenmiThKYI{|7PdW*^{!!V1&GMHwZoVBONjyHX7y=XtKsZQdguITx8wFfb`D04Zi;FCrDiB#F9S}!p{31sDRuuYWK?LHA z*x!Z5A9y22*!^DaAxXeT7E6#I0T?d~J)93|`%fxze_BGy_6IFNV!DN98CV1C-c7Cm z#4N$M7KNyZ@^LD=3wTPL*KgcN%dy#Bzg+=lK&o51FMCCm=U(~=hUVZ<_Iau-@q-yl zS>i?*<{#wc@BRa>Is3;rk`A7tF!rpQI1+9aQaoi*098RK+Pp}_DX|#n;oECz3Q5L+ z;UNmZSrXId)@5Fv=4L@m^Z#l5J~N9W&k27vlx;sdY)lMVvh!v+2;zBX0Zx7`T?u*J zI$Zm{5y&_0@Bcdh`}^+z%svC*@4o{u_Xmko`i;5190i|$n^J=R)qwG<7gokHyiIbDZM36W@c%O3wH7@^Yb3O;jqGH%1*-am3%=d{+ALE$4B(eF5q6n15 zaS!?9Wpb@$D9oWmQDg&Lc%O5b#8}fhti8{l#y9BV|`ydR6y-09XM6 zpiybXjGih7vHwKn`A;lZgRKg;dF|^%wWllFX!Ye<`DK$XwPBBKZjC{}rJ?I&)6Ib) z!j*1xBwJT}EZY`o@KQ0FvaNVVT2Y*x$}n-Ti@PK-Us2ru0h|b|<>2qnAEj~6C4r!8 zYfkR}eH4neAOd@)@I5$5@)gu5-C7pf*>8L=3=#P4zbLL6z7{1lw&IAqSy&w+*x?}i zrTBJdOc>|=UR(tJ2{fXY+`M;+V4ud-z1|$deG2J^>|br;+M%^?+G>sG;D!;=?bSTO zu}NUpy55w=Rke$ea57H&HN7C7`rfi2zKjPrI(Exf@6y~jb=no*C^HX(iWYR9$TEpe z$!uv5rxT$ntEUQ4Hq$ILLm=ABWUDy90~8TbVHu^HMyI@kNsS5QS@||%> z@#4z&o0!Jl0*HV|q0cFk})YVA>P zI#BWbmhu~_jC2*gHr{;P4KJ&AzSQ(|Z25Tq@bb~F-Fe4UFKs!MKIU+rU{kx+^DfUzw z`>sK5KdX=w?JZ%gVMhVkhNc#dq0BZ90GDoPR*i`KDskyW+~Sk__?h&+q8CCa_o2H_ z@1L5w_}$^G0tG~Dy-@gCk&xBvxP8~LTW%8%eC94tru+Eq`4t!-D^JzsTcSljBsh-R zh-UWO3x*>>*#L%vzs~D8(k2vXS_B*uT5tV0ttMBE8ugmq6Aofa?NG{eaPB=z<@?kD z8sY5-iuQ#ME_qA9iZgEVmgD?EGJ`sSThB_o=zJfn~`kP>8p97$_hH=Ei>;(D5XMDf8uhtOlSh;VmH?>kMffuURT83Zu5qSXU(CH z8~@%tmnQ1{IGv*goHaj>X6t1JF*L&JhXOZ6Dz1o^pX024NH%|T7H?$mg||dmeIAC& zHmWXxIIM6}%79*p!%#MD@hX7DI6sc~VEPVLZJPFH3fm0ZhVv?gq{sw%p|bPc9Zp*7h98ctCM37LF@Stt{srS z!*;8{q#736XduGXW0o?7X3MhAdxK5?5(Tyv_`1v_mrgFIOcSV#M2Ipx>^gjLlx7PE z1ez@av-?$7>?Tkg6rftKpxmcZK(`zVE(>yltEqBCSIO(%lsg(Vt23>W~1oyv&ZtpKmg>#2X5Z3 zD-JHV_6vKmh2j>Puf9Kv&jx_(lUxKA=*%5lJ6L=m(K2|gL@-J~29Gl{a6r$hwO#>o z5VV*aAY`x2Vn7)nxgq2hOa^QE6csqAmk$J7tmcQ8Uh?;S|udRc$qQ0>Y z{KUc_6_Ajh#N^h}VXuElo23!q$-_7__PZ5V#5}e0IdlexhZ2p`FgnxtDZdfU*duRl zyCM?dIC8GdQ>e_DQgWP{38^i8H}JVD9)_W;I-gJB=m zeuS4=l+0^=a_SfREr-7WA)XFk0$Gr4m7$Jf``aInKHa#QUFFad+dY5!7qtN&7JS`G z$J7fmvR@5cpP+AkeuYTm@ha9QYw6_laGQ?lM|0x@o{;)8_fwL8ue(e$ z@P>0f5o%!{dEtj2vG<>V?}BgvE*94nAwXF;G$nYTr~kr6zQ`+N1LnuEZJxwJDe%nT zTS)Lh-pIwAPNA{90Pet?YEtHQ4oQZl$VcB1JuAsfK84WfvhI7pTz{X<6dpqJ{beh` z?FiB1d5@3KsWg*;@3#!B{t%+ar=D)1)6+NyXWlupXjtbirmx)~Xd!X05%4|u=1s`- zd;cfvCz4lw0XU$U@%ZTtR7(k{7PtHYWcaGI6c8T2`gGgdBX#hb@n?&vLyAxv!@qg$ zio9W#-+6iyL1PkEX4jlEwpd0MrlcHKUBl7>Wh@jEgLWHRP*A$lcD z^&`^$V*WmU%8MK1Q>4o6zCV}%wc97vVKd_$uzONAwJMZ3t@JcHL7&BnAD)wDy85;9L`5t*#U}NkJfNzAk44qr5Y&F-?;CUd zDv6tnfLqeIvraPzx*FMA@A)C3;YfO39-xSklDHhWN0*)s0fRw1+&_vUJgsiNPTBYMF)qCX^StF9IWzjJZFCz zL?RFO=U}J7E4Jp9!&)$qGWy;s8?~cwZ&xK8Q(O?)^~{KLdvL7F!_NzIrIbHsxS;A2 z>tY-C-FRg$y!#Ui|NKmn_3SO#ldAe0w7jsGOomhX7TDgN1>BNF_78<9q@f4k)^DjwEbr zKz6`1ZySbW;*Y3%VF9_+L87w<>^A)>fh{EYe#|qNcLrNqwTsQG0%UIaoYCquox^yU zeal|OHNNb9puWUC+bCA?XM4dd-W-PY(teln zyry)Ja9UR&i>h9o1(xE~W`J?7e=_w$#0^5^GoV&mqi_&UE$u0ick6eIbP#arH$U84 zwZ|p^{n1*s@kZ{^jn1HOAnQRPu)LDx7tFVkmX&F9oPGAiJD>P=j;P=@uM;6mIuWg= z(9S43d>RqW-lXDso;0H=z%YH&7P}K>p)F}yjU8jd(}D(U1fJ|r5<2R%x2)mX&w4`l z*&zom8g~{*=IHY0^hj`TY%-SCD&?zG#rf;{$Z4PKSsMq>c-MvtV@jI384Jx0FQg$9 z^b8?FzQJJ3ZFu?-hxt%Lqze@`6p>LP3PXEo1|i4yft|fevtf!yk?Yi(l~-P*hYkbb zs8HK0Y0jjcm;#OU-VaYLGbBY9@^mrlsmF95$u9O|7fgL}r{^5rxO*%6odL~Yy=$@9 zOxQ6&AVE^GTGWUJ%H!l8=%7c@MC7$`8#yln#;cI4L4)slI)1n=(EgG4w zy-H==cbFyy^K~J+f6_^mvBKP~a zsxQotus`(=5>X+&iJk?P&TOVG*Goe11rx}1pF@PPRJgB3hgpI6R7}5xMZ+rNyOSlz zZHzk!LhWi$mRvP&n zpO%-6dg*`3sb-%Um5hG~smGyl>70!o`QF5{qGTwOwZeb#cS>a*9U-0Zx_&T^#A?2$Pa0-CQ0X35(`!vqZ}0+~sInu3GBKkfjpf znIG;?LJRTquqiSV>(*5ZAI2a{2fIDLS??&{AN0J-_Bc`&CeLPpCq~)9?)m(e!Stx0 z>0$zFYjH)?dcW9d^yIC^Ek`(w)kA7i&-oUsfg?7hwC5u8 zH9sE(?OKt?t_ZU55c9Wwz9`zI7PJinfvpJIC4u`QL8Jvc1vXF9Sys7!I~rMMds)uk z@^rwNh(=5zWKG(vp@_Xww9ArnR!5)69=*n%kaOP-N16-Iz3y)tia~q!z0=pt9qebX zK|2*|jAB|0MG;X59cm}G>tQc#xPjF*WzU(3OVuowE}O>i0s_aW!k@H^<;Q_>%w>MV~hijrmoP zDy~(eV6=0-O9a{euKOo@ieDwnfP za3jmfC_n$j0z&M!^^$wRaK1)%@6`Fk${dYB+d`Kkb+Zv zK%>)zI-}bY)S=+tZU-zW|5}57d$SED>a~<9)Qf10(`DdnQ(h|OkFVn2>}Vo>I z#c_=VzEjzhLcy1F&ff#gfrgfACkCiUl5w)q1{sQOc#jp@%2gC77o}d^X!iB=$>(da zVPf}=yKh97oEXNvMSU(82*^n^BYJRZnRUNIu;4=&z~9FJe(b*+a0DAMPV!5|9pIA{ zRU$st!M<1~nix31e_IC_y|`_HTjdQ!Sk1B2ExpuH55wPtKJIl%yJq&$UX9EXy{kfD z_lO4-GaP({mojfbV*2g>houhr>NX|b=u=A+93{@4vHwF6f`wFZ`FKE_NP-%xD5{F| zt0kIkSBB zelr{6>FE6TPVHz&$Fko!Bb6NnYby)Va;o}FJ95yK?@G6sLB5vt!kN{?`^Fvj85ZgA z+G%-zXgU_b!$W-0a_rxW*^189(q=jiw!kUVRo&oNo=nAHV&;Tn3-w-PDwX?B&=)h? zz8o0Yk~9Z@+ufSqc(YKQU7B~G<*pytOJKFeh5wTV<4hO+kp^!4Wj?!q^Yc(xCG5ro z<#N{$7>(UrL(QrT_Ue09jFl8^ii8!lqooBUONKoV zq&{d_Feg7xSN*&c*E%2?>?ubc&u(XEbhl(O!pH}rysuiLtD4E!jVRlbr4B56Yo`;H z8|U;Wb#?QQ;jHnJ1b$`&FGF|(JQ=Njz7x;GCDY1N1Ub&7%OeW8ThqzqD@}@a!zVzu z5u#iukss;9av+MYOOfE@h|dm{`LqELH}@#~!8zGv0Yd$MYlge)p^>2ojJ@5$3g^FG zKtvqiIJng=p9*b}g$RpFybLE!*Qp~(nL64~^2yLAR|6%X;wG&XX${vAu}o}Sc)spX zQW&f(=8F+ScpUS~hJmR@SPz0dyKO_glxe$ugkE=CSRh`QI0zN%zo-_SXL^Ef7_ir+ zx1q>i9t?_ygBSLQRD;Q4j`c%R92pI0cBE7YC(bbQ{aJ95db#IPs=|2;fm1DikU5u( zpPpk#i`n#rOQKCl`<=AIpj&pYUZB?x^4CP4)wAvOYBo$6*nAeIFhUe#PY(F&fIk3< z{7hDWWs_q^xASKYd06mVxMWo^{4^Ohl2o%qQBgnR%V5kHacvGf>@s4|lN-6e;pLw8 zRo@4`H&cy(aR!;!famTBRP&v<0s&*lSV`0AnVs08V0df8y%0xbywI-yRC$_b{-Nlx zDg-sJ85MUnv_E83U;)rh=egZ@po5kmhn$4EqIm z>Dm-qn~ezRec;G%TrfPR8YmHuD|cEtOa?XI`zZPG{LM1$l*-j*UZuI)t};%_Qj!3f zfmIb+6d)S+1U|&m#C>7|$b1xRfJ}#SDyo-ohX{_nNQW`>EvD7+VV*Qh&?SP&Er>`4Hwm4fG0mJAy_A0L>TEeW3_v8rD$GobqoHqBF(gQalD2%dt zqhm<7WWTFZGJVqyTff4nI%8S%aw=6Ruvs3X(T;PZi;jB0py;v3AylNw60#x_s8M4| zJr|Xre%rL^1#Pw*gCtDxYNWIKxuG>yOtJDv9f$6XtuoSNEY$JTlVFt1=T|oYc}9^< zLCcNcHJ%s}K69R)asNSr)rX2}f><>xuB;EiIft4l38&KMnxHmZQB%Z?TA`@6tW*Zf z%j?^iXbbeIQAswG&^7hb5Yb)cHEjlmlg!!rmcdB@`z6{|H_ucOcX9BD1wL?}YFk;R z8I4tiYI`At0Gt#rL;8Ckfyr`(t_U`2PqUXHk$cKB9)8crkH)4uL{rN1sa5ed!7HUX z1}fRpk-35OY6^C~$%JI0o4R3~anq>@@4DY6cN({SEg0VMbB?Nlm)}LWUHP;_aGI8I z!Ce~!Ta(>I-YcX@2byKVxlbD?Pbuc0Qc6zvK{V-EPh8ytD%ArT=c;)-88ZxW+k7~* zw{(*Fe2Q-->HI8|FGm+xhKE|cOE?J-Qhub)d1M`D05B=ah zG)e?ZB&gHTs(MP<;cnm{Z6*<($(qZ~ z_C=nFO|-u0TT<qsC0>N70%~()jqdro@TttG)M3+|w#4+YVvlPxPd&im~0+)_>&Wt*=z{{UYtjm5_ zIs`@gur_A)y;n5UAwf!gvHJapMTp64`;I8TpjT$ONr!-fCI)bFAU5NbdxyI8;7Y>m zZje5P6m>EGLcLwU%Qn{vc8;N{mp-nXB%dB&#K!u%piN{(*Q-bjrj?DZqLBH`LXO@z z|CPqYJxFmLB~u+ZGSn8?nh2Z0x~u-0piXSdwU2q=HY@~zL9ZDU=MpqT{-$h{r9ZZ` zJqvYAAS?p%F>%e!}?52)uxm;i3%fKbNn`HFN9c15{+iY%s;~{@2fu|^{7bT#P!G2L45KE%%fD*?)EZVL! zBbsPnaC!uhl(FTTWQM1CAAavi6$Ha-B7u`C5s;pX*2hXKF#|qj*9{trj5O5Lf+n1; zX!oN-Nk#**$pExdbSUH);>5H0m(Xt|x8*5gsq!6WbQ-&~!Zm zSZ%Z37eer&XVQ z4e~`1zzhLl50NUc!GV1M7Pi9w#$r{G!MgGGO0~7np&7Rw(c4L;D4?45FR77(<{LX} zSs(*SgcP`Hc;CASq*$49IF%x%#oTd3Iks`>gpBwuX7)p5%P(bnFmjnS4neJW%QbhP zmGT$$0{hK+M))J@8L=xJiCqou`mc;s1DHEq)Yw~Dw|xV@HoBDB)H}!`V8=6^2lpEEvQ7zHV`~J*0)tG9Bd#csF zuD53|1f&%Qk;VyZOE@B%PF>JuZ+>$61B!9l0Z|-=bYM6Tg#fJFjuVon#0Rt~EyJsT zN>Pm2?z0x$swms%q<9&!nEsZ>t%wk`VA&-FZCH;keVUF?qrG_apZd1d*6k|lz$?l8 zghnK*N>)K-VIopX3tAjouMbBj&3BXJ@TvIn0B1bm6K&E{gMu3 z8443KqQq0G)WGqg(>E;zSL>@EyBV)Rnw%=UGv*0Jw%;6ry8~EcCuk=^KV_NeT|>** z18S@uppPpxdE*;SO&05o#p0c-B=K!5DIZ4>kQb(*atNkve)Zri zmf$bCJ*8r2LVYAP;lsW76W_2@hkQ;2n2(6xeqpK5Z`527&i??#AjN~^0MqgR-Kg-f+W^bgaE-4iFhusbI}1vCShzZuK`RM+JFBZj+OD_#l3#bIf1vIX zbsAi5Q6Tv??!L&%G650Ia}D6}us|P_#_dBBBTOBs^H?uBDDz}r_$k#W<;A1C(|Lh0rmkj zouH~Z-9;~lXR*X?A6j493mOx^=X9fcRWqA?vdHj^xUo8cux zbj7d@oki1-RYDYqp;RkBA}9*QPQ--`^wHZ!Igfdx)J&utFFM>}BPC{t837VlB`8E} zcwQ#LT#UjZbID3Yhha?#8p^|$FhFIQr3p4~IHt8llZ0vli>b`!txC9{%R;Q7QH}S} zJ6puK(uFWw4Pd`PquQD7i`o2@lb*ZGkOViWh;$+;cYNcG7d~?G)i7XJg;VOM-M*ir zL#dpHM&%dFUQEB%(aw;ZEG`>M!rC>=Fa=_b8j#di5Hw6k8$58Qwve+(?oIQnmSzeW zt$}DGl@zl?lnZfZf z$*=ptGLnjzLYKq@`O-$plB((^#$fjmVJIhLtcbueol+?>u^Fom`rm+WaOfexWH)R+f zq>t2APuseH_8o7H)l|#JOi`6gGwC|ZHc8Z5S4z^GG5#BZovDSiE-fR%oGHx#Ma<2X zX(~orJ9#sEiisRu(3G*D}}0L z#EdjzFsO0N*;>XY9t%3wOkuQ!E=qd1nl9u8*3H%ymOkAGqBpEc65>rKf*`|4>;4OK z8b$k;(zF;L4dUYQ?FxvHXwD2;g)(*nZSl~ciHkz~)>-&l%G1{@MH1k>vOJT&zK5@E zKWt&UvzQ_UI%GI8XB05NE^CaTdMc-psz?&?7Tc`ICXgl8ir7^HET{eGzsj$iZ-2pbB?22s~nm(&n~%KZcR&-_fZ8ZUL$L7GL2HG1+z?qG&{fPSZ0m# zc{@eB@?3>nvr1kahn&v%yIi_ZR?7}+7?Hx5YEBHd4bjNbr-ad7UED|7jrDLpOLH7T z!6@}}BIRfsF!tHn$pW>5SKY!obGY2jOPx%ReYn)RB}n3_V3HXG`yW zF5}3;@jdI4%RR^oao|DZVGXaCFTzGqFxzFx=frH5%iS8bIM@i4aBT-ID8me0m?&)3 zK(qmP()>-Dg4Y&x-dp&f3W08QZI6^Gyru7b?*u4p8hl|(O0AQyNvhG*Gf}DnD=I1I zuX1viBZ^9dBJ0`KsjB`zhUf|d8jY%B5lk8eoDAh@Sm0yso9w=@%7Q&Q$r(%f26cy7 zKsY94U5ddE8eB&2-vZaeOi`SX1GT?c{c6R)D9luu<}?87z)du1xg0+GAELf8ERJZ| z7ALs7yF+lv;O?%$-JN96;0*5W1a}=IxCeKF1Q~)uf)o5r&bjx#AH9F9y-K=v&o|w> ztE=XeY&C26&n2SkY)0%oPdW%fPkBM~q;n8zm5;04vM}nWDZ;qIWGjyvs4GJa_KFgk$$j3_l)a>0875jq_p+m?a8v02s;hYDxNk*=Rbx4 zM!8O&xaHH6L?pYG@9NlGZKpO;a?wsJZ+=_-LMorc8*<;Tmt#E;YgzB}&sug%%%RYv9xW{>dxUuMqd(;E z1AF|l&ZeJk+*$(5uKZtDP<8r^{iI|zExw+EKSc{eo+Vs`r`9HOnf6>$BYFYHxhx~F zUZ)^y=Qz(?XlRjP)gv^M)Mff|PK1>Nkh;ik2P7_|CIL7bf3IV*og_t?)!OeBrX;j^ zdi&wuZe!v`t9(;Xk%cw)Ty_mx!o}?9Vns??vWw(Oj@b?Kxx+ci(6wtT$cfoU@8CJ} zeE$c|he{BtxkC`?bf^9MpK!S;La;=zxbw@V~KEO}Tz`~PSfa%u)$ zMy#TvVS>uEzty`IST+30V(6(imFY2b_@dM?m%k}IB)WN94~F=7Ioj0Su2Vag`9B*h z{&eaA*PZb(IpwyeUp%Y7!&_0=yf1c<7O~(O=oj=@0NW_1A%9;zyT31ae6z4wT$}S5 zpr@Oyw+S%U63!r`*o|=3@4eha;hCp`M4%J+mj9|Ca0Eo0q>fubyLn==WOAH}9wfQ* z09Hh9=h(D-3xlSr{J1YjwI0+?w$NEi8wJzD{xne}N<`F*kUOIfttK(VMtFgt)x8?i zsXksVSOB!%%V}5A7!sn5v^{sd^QU;aIKmzfrV+q%8qXdYMDxiWlR~Yu%dAXubZ%+T zX#Jeq^x5hQCSQAN8&%dFtNv@&pBb|(mI{oplLsA93OJhNYL=$zV55XzR>=#s$nkTG z_9pq|2u0-|23D*!2H}a;v_87#p!7qt5XXc49{B%$sVZ9Pya}|XhQD-Moo(1R>!Jctl!K>DXkRs#YEyIjh-!y##CV5=;r%_+{Q3THHX(zj1F)v-YYs zD&R&tHc!z?HMY_uaCdCY|41{yYuaKBr!m!K^7>Pu21dQ2l>W=Ys6NYZ4}HAiil6uU z6BO*1?OShZOL)ukqSC|utlV=JR-Gw)`RX+RFg}YDnR7dm#WN{FV&`m z>)gog6d~DgCVf-Oxe-)0sP=k&Q{gz(0rh5bUpESJA8o!SFLTAdhSk4o56Xu2iGMck zL;t!~V01HSwDEa~t46)&&=cDU5?jytmz$uV`?7a0;CAG&Fd7GWQ3!eRX`8RQdNj~C z{kC52L+;t~3NCn3K55MUGy?vnbbPlZm8Y-Wg2-dct4AFe_8aI5W}(}ynpmBH?DlRb z0E-{%0R?}2HUv$NQ~A7wx^+$Nmvy`QYY(JZ4#s55Mba-u4_%Xj{OTK&K+uVBP4!-679K%*{o+y+?1_ zS^9ERjRS}`TwK|B*8zxVUaWKRN0(g(b;)d!WSiwG~U$I~vPmOt%YYILygwk@#{axGoIOVsDg`5J!6a+o-RmiA=~ zq6w2RCS9sN*pl|}9pXznWPWL!{^8dph&pM^iNG2f334s~Wr+%|spva2VAl%uB`~9Y z(hwj`@55eDUt0&D)Z(BAs3OX;Q|gjl0b{OOg#qt}lupqma7%9y(I*!kA<%TsF=d%g z{kz4HCPrq|jN51D~;yX;ekM8xpH9cwJOL zco9%nzjq0D+1w0N4UZe~8s?dRbmqhk?D<0StuKqr=ywfSW9%-^-i09B=BXK(k*hJ| zLQC3@ta>5+N`Nb1&_X6`s8wEggu8w35a_}2EqjDl#%>nkK-*(^sWYv(e~Dk#-U3vh zOS#b5M>fB7cGWaQYA`0WbqHh$baV*(S3Id#B3i}Bte>8)j;lpF|%?rWd#1XG@J<9X>{aT#(RgN;WP;N6Qeib>jCZ*5J4DkU zVN83tU>L%}ifD7mckJH?>_Uxf23AIo!xhl1Ia4-pe{Tj>GfrLuE8#OQa4%E5fXtlg zaHe&=nHRJS49&o%t)vTJH0yf<0QROL(4soqY!;DL%J!1>7}5+(ip{(TNX+fA|;zWV`9vDIuh|1@(Ds0O)+_t*kVh!JxFU^dS6oOfa&k zkwc*5NK0#Pu$i8bnT8xRuB3*2oNyL=qlSs) zfq^oMbIcTL7j2t1!aMwK5Mr3}&HA$6i)mN)))^LyKnM3fA+7Sw1Qf`Lqy?{*au@iJ&F3eqJ*|i{A3AB$^7md?&Y1keI@MSyeD0xb-#vg0b;E}t17u3 zJ**)n+Acb5O|6_8J%_wfAA8lDujEmCo~+1x*}{xi2kXr*Wb@ z4}sks5yhZ@eov^j8O{NAGUW<6%Eqw=F;@1ump!9S>Wn>uh8vEu#!UP(JH_)Bel^12 zdU)xtPiu8fazDBQOmk>;Vd{sDC~)<+0v!299*^tQZ!tCHDS_jJ+wWp}7KeRVb z&2{nHILQTSm+O|~Xy&bQtC`xOGp^VLd>% z=&ucJ5n6Sq6)!920J*)ZVQd)fQbF?VRQsK{wF~+mJ$FTHa$OiuMlt8PluZw7fZpG( zkpT58W-f+N8&5yiAoJ*x}QH|f{usL~rN zr4&qhp`_iHfHUgKXeP>z1VRAzdQQP(jDcAY5{Otnkh7M5plA9U-rV2~nK|i%HZ}jd zSr~0yESS@gTTyDFgJCaSG4BDkF&5EdpYFiOC~Don8N0)JaFSa8`{Q^ra~_ZCPDCGg zt^AUoLP(%-1RP;n0u)vgm-)h-WKaN82lv`^(kGC55Qn`f*;{nwqz8jMLbGJ{)8<*aWlVI#&S9L2zU&V8i2zAANQn2??f{fBNB^NC1;rco-8l32udt z)a(r=YqL|vbp3eT`Rlp~P6Fq*v1fngre3hoXzYoyLh~lURTi1g8;t*iKOwdRdvm^q zRF{&XW4?Q(DMvH*zEVme7%n6Z@0hfBjs;76MqW&UI~1wPmUW0uIp{4i`K{2k5PIb^ z+-%Own@JSTi6^1Ra}i+$O6+P?2q-&*72J160x_W`1~lF;(fPqa~% zq8n#4seb1IFe}JTBd;N1nab+XN`R6IbSBJs{s%t7`T2PIL}F%wSb6k1iCD=S)u%{V z`Wa?eZmnjLL}C`@cxiNR;VC+#F5Lqhyt2hhQ1sP>(6GYlHo($3^aHzPdAKAcw{|&A zRMt^wp}a~ONk1*EsERTOtf=n}%GM$V4sXg#8OW$A76M9&oi&k?(@q)2Nj)xU%ZrEg zC>OQl*kh}RMqkMmH89Z<9awxb$Gp>SCoOXrYsRdMCKh+ODHxcqvkG`}4ONs$WZ}xc z8q-rQYU2tdk}&({j+{BF0m|JR57=#sWV|SOwIW4gk6CzC`q9zeo+7fDvkS&l(jsOp zBmJ^zEJpo!Y0Pa|iFdepbx9kus!SafvZ}T;F0vG`iB^jyCb%pP7||!K4jA30EFD>& zces^1hI}dUcFCD6X)73`v&=Ixs8w~j_GxaV#Dkl(?l1 zF(K@w{F4?7edofk*Sg=I8sl!fIgpEC`lc(*!0li%K(8 zhC3&P`r85*R(91*NQBHwZYuRffI?jQ08y0Y?;-D! z5?Jei;}>&KU5es)Q8%$WBN)e3S#eQuSacj>l`$EFR6=uC5O^vj;{Xjl4h}IfoNE{~ zlB!1a;5b#L%!nzh%a$oRr#(3poi1i-Mpi#-oMI0qsAOv_peZBSpx#${lQP&sybD+pP*zGui3c~FQP|f=DJ)l z^!0^ziZw=)+eF2L-QOW@-o#Z$D1%C{4QWR{yCSP=0%qC0UG2b8W#*^rQq!wY`t!wS zl^|4y{u5&}r7IEB_=jI;Ri5o*r|g-2L0y`=EVi9(?%{?K=gV2Mztqw+3(%78YzdV` zp70lO6#Y2r)$Qo)QPigtmJrd(Syrtqx-@68MZbRw#oQwM%qLZ`@l!1A_Cv{he(O7% z)=LuW&h85WtwV3MHBa*o+5S6{RTNFe?&v)}5j9CnAe)UMHt?0K%@@85dpq|`__94% zLt~^5Mth5b*+;K3R%dqx=$^kH@xQ(O`ZV7B>(?6TBJViv=kisZ#jjEJ+(SJsV|y zQ7n`NpS1qrf5@pe94*)PABm9Xh6N#j?
We=6mPMDn;$|hB-T{86Ox!?L!DW zvg5~qiE9V&LxnQdLOJV3Gnd(YCnmMqiLq}#TWbSg%bTX~L_##bVLY!|IdSquz|Wzz zblK}s{fWzCpSe`t3fOfcF`@7O*}2@YT#0%|?6>Y#5f@=J!_c@s!U5mbq!)u03lK2H6cvCeB+Jk(Uzr}?Fm zjat=$`q}DTJJbHXZY6m>1fnEr5>Zs3Z8WT+fSvq)5```%Yvi*BEhErYR>i&`CX1w5 z1J~BDr42-q-B66vxKtF`@SO^6o~2Z=ru7}Wb#G$EB=o=J_tA1&Gpmi|y);{D`39ME z4mt;avZuDi<cD)My8jjrUy>ai>aO!Eu2^T_LgZ zh#zJ;eX}*3a59r~N|&AEZ=DBDMwqL!tfFFuGCyZfIR!5I$aFfc^bK(Q@zbhzVUUr} z(e!HFcm91NvJN?@1aNsAu||@yniE~bcZMTS{eP!$+HoFvDC1EW%;W*(6GKc&wuFYH4VZm zytv#bBZ|;fb1VchZ{_1iZjs&yx{=R#T(EWSTCX&ouB`e%ur5jaCn|0}e5gP9E`bcL zS@6f16KV5_<0i=YsLer4;9G45=aaL@8wD!oGAXN?=EVupjKI&4EX~pyutg>DQ`(&F zW+D|b0Iug&xNxZRwV!O3<_FC#%?izKx?navK%PK`osyOUml6(oM592T*;zpbfN){@ ze@C}Ox;(pS5h^VqmLw($7B?me7dRqxC{{;e7(z2hvl~%;Fu2E1{lW4QmjJs7*i>F{ z4QxWaxddjPBnSZ@TS+k5c=7u%IJ4L=^9~#U2#$}L35kphAN?@8rU#0qb{kHjeNHG> zn1LH|EsUXhxaKgQj{C5cQ8hV)8)p&wKL-Z^#bp+~K8txmdg2hdGI7*#%$cc3wJ9T_M>kObwBKzkxTgT@f7QbEFcl9*oXcI37t=wB##H6z6nh4rMM zhy%Ip?-|snY?iUYG4dLkDB%o#Bs^;~2&vB6h|E+It!I{%!`^%T{fFzUoU3O;6;VQ2 zB<;kJ_#wWu<5{bm1GDBVE5l#!$F4>#j3#amxjFV9ud}Qy{)>oA+#Pa@+C2S##BbvM zkXsrr-i~{0aNHtcKYj>3?a!>0+&}n#k+^?Ixls;-c|t@o^t{NTvU5I>A!j?CXTu1u z$YOfdx{}j#o+FM=aIs1y*d&LM$CAOLC~31vo}6U9OS00nrk*y~5K^GqO@H~J1ni(K z8gPg1Po&Pdf8>G6>z$~0t# zLm6ozk*m_ZKq0u#zB26Lw6qz#DBNNRolO8DmcByyVIHUucPh5F>YqdCz3Kfms7cQa z6=X0$KWyCcWH>y*#7UdLkR*MEMiK_X<#!mViaVx-7{Ce-_a=CN9&t($D?A64L7&)z z(M!&uYiCcn0H>k&N4CG|*&}%2gN(OAxL4ZB>`?r2V%TX7anzBco_OLBOHH9X`6N}; z4}EUTdGTR9zhxV2oUyAhnmgS%Y4k+)Ize4uDVhIeaEqq3Zt1vS;CQfqA-6Oe5gLA; zTkz9fmX;ZYS^)(TSYaotus~&~WdBb_Q#=kTgGh`rAHSa{=^aS0hdmA5epFrV!1+Hz ztysri-k)&sH-oKi_h2??M|V4OCTHROCiV|u$40SIj38t05Dl_|{e}G`GD?#XXk_G3ZIqRYJq9;U^G^$c zSz;@UjwBzBXKgUKwb?lFIO_nT)CsFTs{}N-Avb{xd(=JzdIZpWW9xmI7Xx_V@!m9# zB=cNs8W)0m0_ri^ammnNmFMjGlRea|del?Yta7^$_pBXiJnq0cPn`Gv8J=wDVo^wW zaCnzkiD3UT;Kde$P*|bJ%0J}afHzqTA~C|mh|PA)jt&0L5RIrgjDV62%69sP{2QVf zpa@oWxS^~8!&LPnt7U>L^a^$&i>h)ejtzEjEJjNt8Lb{Sk8JAj$ST+CdY1*xfDZrp z1)YpqaDKNhE^nh9dr+y5y0`xwJ`3i&bM=`K6%~owKi5?`vrD@?Zg{q*|GEF+!_1#k z4Z|G2AaCNyjhd|ey47zFSKIXn4!|UR%TohlKdqPZ$IEE|PGQj6HU*)S~fLkQ=VKUe$~urfX?fWWDK zeia$5Lnz;CLZUEV#OMgvemtZj_Cq$wmuGV!O^uJx`r*@D}P;(?3W=QK!U}q3SxPe z1uC(D#YLQ2*cgssfX(?qn@Vo_K-$LlMak+NZVBZR8GQ6yclrU=6;B=C7x$6$(uc4~ zZiZ zQ)GBE}&-Ra1Kz;ofuiIgfiW(6^O*qDiVlU*J=Zc z!H|w?WH0-OZsg4HNN(hj8X6qwsD#1+ehfh3XoCb`)}68INl4R_g=ZMqh=pZ*G!%=< zm~4uXuOYG03!SWEev7QB^;hbziPwaaK`DbVSbMAuHy|8irp+iSPsP@hVxi5DW1t~y zABzU<$JH>%=xD@%Y?MK`v?(XD!&h#KQZle*prZ+QdKr1d2X^ylM?Vzo{Z!f_x7)wu zMHP+#gpCON@d(6zB_EK9jX1=Ri7Bl}I$@MI3~1Z!7x>1#?8EVi`sTs%iK67e^VPu>!nY3Pcfg)|dvZx^wDb#0Y@GZN zmbk~x6li5YnN!z4Me?qDEP%h!37Ca@ED)c8i7Y^#fgQX|g&7)BM#I1zh(jRurxijb z{&*~kOiU%2SJq^g#2Z{?7wQ#UMX==+9DVZJuzyK=oTPt~cR;v*bK(6}^b^Y5eW?f1-2Idr=3G0RKPEQ9 z4X*hS$sW3S7ELHwBN4e#!8*Y4#sNs;Q$7wF$so-iW;`OfNch*yx?LQmT+4N zYKxm8h_I6>hBvs=&fhDzOw-8T(J&hZ)Xn8kJU|fMF-JYGWMt1?8o(g&Q+t?1V)43L zxL>nt6b33i$SW!e?Ybd4mOCWPu09w>*n(j1?9V(!LWl?xRyu4yXcl@(Lc#)mChK3-(hg0G<6V$ z{s}MT`oqw#Q>G2DTp%lIw>&8*91Tb9a=jS?07l2T8J@j zQ8^C~Q{z6*6|=FH*bt6yZaD>JS{mwXS?&;96Nq}(aNJ4}c;|ueW#zCL7xuhcs{@9@ zx}IL*p15!k<;YL!pY!PmN5%RKu#ZtUB(y&#qk|dnaTuT;Fyp)jJdTVZ68nn?A`>6J z>>wIQ;XstaoVmE5L7kq4&5(nxD@_43ZfnX0_DQDL-MK&y1LB~{)CY0n0B`F+1Rh4={SR^K_eP@?{K zx!uxp@|AHb1@|7hc?I{Pz@*wb}K5G_?fiJWZ!pyBa=)C&YvG9i3(p=H{48npYO!q z&VTCv5qp88KK6+}OzLk3J^Z%g8h!mZ4C;M(Y*F9taryFeD`@s|p48c4bA@fyL`qk3Gv8r^?(PT2d@_%t@p3~ zPknDNaV%(v%-)aU8L-d0Ujm+=w%;JzUlz}$-mb>PUtXtYO}7GH3*Gwu-kg5ve);Yu zje?X>e3V((_k7D1cXR&c`*3=={d~RXw)NVcIlJ|GyXe*jyoYu%ck2y!TAS22d;QhE zpR?Tk{KrlFX=6kE^>L))ORh=a)$~SR!0oi%t(j9hSKo>_OHYD0@Zs?A&+F@Q`=5y~ zK`(dvKlR@No>ZHp5juh%%JjJUwA=jeuaM2Y9M761s6U){THr@uYoc{{gLMG5M> z?tXrIJr(SG-eaPA8=Ez4Rq{$cLN!WQID3s_xtXud?J8>yFf{EK7Y}?(>%lbF#b^!7 zoWg>mQI0^XL#ZAR8S6<#0*mQ;iR2ruqh}dkJD;P%gWxugh5DZE^8b>dzaWLl2RT*e zAKER5fU8AZ-IDGPqFhv3J@cX41&nQ zlf#ka4gZ|ZasXtq@TI!=!xkRC!DPd8%iE52ao>DofA4v?)7Mj*)sWlr+a{kSk-1+d zwtpJXZqyIp)xz#XKDKY>s%eycGvh;A%w4I-2pN?~?5yCGNR%%Ln!PtW(^oZqwo9*H zrP@Gqzumc~>wbkTmZlvw3Tq7d%BNh#f!D%)q!=#88$1dY)%S06a6#XXadGXwjld@w zAH(Xz)#xK;A9uzGNaX|VoX~RTXyZ`d8oCuL>O2w#?c}(toGv)&ks`E>bUq zuxj>0i_fTU-9IsKv#uL~uVstKi++hrS6_z7@S+p^UeW7~>MjIK7{GhrdY z&=oM*X$l(ms}uif{LJVtIJ#KLNn!TU@L;LiqJ>*jdPx`O9)li*Z;@ENMkG&vWn1%i zT&{nZz_%EOYmm;8F6E7Mpqq|GxfdnNsi6Kj6Dch>3~ z8LsE98@M#4&0Y`@YQmNnCA{U{&RN(<{Kn5yxX3?ToVt$_3{VEfD!{U%Y-`}Z7sqjn zbal6_F2{O*z#JYEW#NK=HWyV;9k}ga#jGZ~ZcLFReIVDN?z-h>RlL2nrru9iPqo0| zHq++i6_%DkV$9XBgff7lnO$4e7wjzh>WYzRvAgXS>BG=?C`SkAX38qgpxFJ6d&TqF zsT>?&|AzF+pc&xx!v|6ydG9cDBAFodId{e31##jQ4nZQ(W=iNl+H_u@r*Q zZxNWyZAXjENZk^Hj=@f(;l?O8HPv}*G+p)uPUt|0PFj4Uw z7j3slf29)4{u0hhrL~J?hqh2B2OL{e3UT$DRO~v(fBZpB5pFq|TAsP$l?6uKLCw;D zW|EdOCdQ5}sbXf0@b&!88$x(8$#}2Z(EIB>L8m&P{I{+FIU`u)J6P<#1Re=*ld9Q8 z^PX{C@0Q*XlXqS+X-q{lBza)iUUtK>RX{N-d6SEhckUnTt*y})Y0!5CCqKpni z4$-!PUlf$n;BLin;=_vx3yuJtn0A}ET{5O5;(1rnGA(;i-kz6}2n;aEvMqEX9_aRH zKbhyxi0ka{a6=WE*M@F;&cBKVO$Zo$Mz_b($OGrA`&~@{r`!Xpp6qQlq?lwwz4PCK z!`NYs)>?bhCA~m*k7}97xwV|J29c~}D<)JwD2tOYl;t&G7w@h_wX5DvpC?#Tx{@OQ(Cpnjvw@P71&kw^Cw8fLX7%N^+0kTF-@c6eoMaa)||V&SjEeA>9A z?u6;)R_dmSy<1%s>@v`VH)|9xAuf4wsn#!pD|ZC+q0^7D&YUjPq#v{~V5P_-q+VZ2 z-!;X6nyL%Yl6Ie=H6@IW=P(PL*6NFSL*0`=ND7}u%w@ktRtTo_SV|~>N6?bZRHUo>_3@&g@r4x_dtMMG^IKaTc_?+((?g}VQQP4H9pzz zlVAvNe%B4XX|?|-EolggS0-5EvV0rOkyRDhh@gThcAaIurIS(ye#N49=qU@9G!9in@`q-d9mET@)HCb!6; z*_R4bN6!fC~u1~9!WrK6%q=8F#onwKV3E0@_g@eb78us<(q#5yF z1H|cpIrcB#WtB7XzRS9M6ggJBZdQH`A?Q9sbYBZ{p>jcu3gSY{AM(enn6I>v-g7#J zHuWu(abmoz^^)EW`+cC3SVI?LVULNlPVsY4{9v|yr-vk7iBI8y;YzvxXUh$)#8<{% zgi4DEE=keS7Jc2;G;-o}$`Uh7N0Ip>-5~9ppGxZi1U96oz}@81ZG8echFr@cy{pXr zJEo1a6hXwPzt~^QJ9=C8g=JjmB|Zn*K55i>J0la6ARIYb76yanViAsr@-ey&Vh9Bd zGyGJgQQEq*u8twfgTgalzQN?q3TLKK2Wd1wiazL812?Njn_&7BSH+RmU$(z(yHW# zmr`tQdl!~<-TRk*A(}6sqZ)3GKoXs?3Q=ig0{E6@``PBd^j;!n;C7BDj+b8W#x4{2 zkWRVq$2A{J(}Rj{MoRryBW7m10rk%aY(N>`q#15td4|#j&?c{>>Zb}q$HmkwNou9;TX7MTf-d)VB5)- zPjik2+_Lx6Y#8&DJ3POV8w>NrjC#AA?_4y7*utty7sf@gMQz}#32jf-^Bayl)$^N^ zE#KMi?Mz6f7Q}uh2ae3%92mh#nSSG|et@g|y(T|cL?Fl`*o1KSN8mH*BLB}wltatB z*mE&_Oe~_5_pK~qk$vlD4yyLsKQJ1M!I=5)u9tE~*vc9vGg|UH*K22158B?4PK^*? z{O6!DGx}1Kf*P2ppL2z`O;KQeix(3Y5$RTp9^bM;vwqc>g)}G3TpszD9DjnhcbxAp zS#w{sy)v#XUod8n?dk;rb9nKVPr_qO*sD_3#Q7^6w)G!MAwSD8z0^3L=BosI_0#lu zp6r6Vs$6g>jPszC63SNh2K5`)^%K|COyDgkLX>Q z7GKK`s}z+B!LKp6j0(s0%IN{Go*Z{nIH7-*y{kR?x>2)89~7C#>V`^L?0NuY!2B`sOr4VSPDPZ6ITuhYw5LsV=}!;7sx201%8KnT5m#9 z*L$L4Anlrb--p*Mgt_@vm6OXEr30J2?XAAGI^K7F{oa0+yI)mq#r@$XtP6enYieUP zwAMAL5oVr?zY(Kq^coKp?eTJ1-!09TEce(mL&}MH-}oV^fPrfR5Z*gR?`1AX5x`fF z96uB-CrT==|5~F!&4FC6G6(}Xq9fE?G8`E=QAip|$WDCh4$ZzT8UNLYO^VG545^um)(ZueUEVy&L)!$LDsIX*9&-`44`da&iX8TXHv0-Aj1EIUY}(?A)B_^ z6{Ql#98!|h>^XzrZpo*K! zyYZhEyJrt&&a))nbNF$o`wcxm83@U%p`qEa{2m=#124J*6MnZq)9l62Vh<_xn#(`* zrT#P{sv{YO2(rvbN&Bce;H~E61t{nsq4I@|RPz@|R z$IdZ$%^etdC1?Qf3S!z2O0}Ljxp#t{)rv%owPR_C7~wq^8rxm_N1|sK8Wf&@o{jUy zS0SO#LClk0uh0D%hlA20VCv{iM%bD5J#u6s=8>3)*u$u1(F$3oNbssVu<0PJ$vxV0 z-k{@$nisjTvp)uMCbL7r$Rz(-LWHtQEM#ZlA)kGA|N1Fsb{RK|d1oIi?*Z(jI3Vse z@}lc^P;xxjd7s9d=P__XW7v{GfU;7Xt^$`Q)>rS6C5$S+X(Y_>0#JUaXD@J&7si|| z*#3T%=dZwYVpPre0@wgEW6rdFB}YDF;msboPFt9QbpBJ{>mopITBPGl$d$MKU0{Ye zhqrY)aws;205^}$M*g+K1{GS8qLtiBhtp&B(ZIr=mBm&`Kfc{;7NxlhOz zw_B^*tqY9oW?z3aEND3t1OpB$`9LErE`^W_=MQrpz=Y~71AzMXDfWV|fiYoTE`7T@ z00PG*_uXe5@L{dJT1v6SF5GfSlY4T^4}*@m1ZY%+`qK70fk76NUeTzx2Hgrz(2AHF z9tmN}@qhEeCUs)Q2g|_f9>52hd^ooFDD&wFa#};)!tK?&JiX9Gm@6y>A&hhu*+#~3 zaRjH5N#+-TbovoHc{=36y~{D{)`X?^Gi<~a*N%Cs+UF#UeLkRaCiTJZVdPLyocw0u!Wqa z5cEb;_Qkc-qV=zIjW`38yZ*u**3I_H5?L%g;9h*Cp+L6h*Z@-==7*CwXkBL| zA23E4zF^LSm#vbWV{2&Ez^c({BXM;I`D1bMw;>}pd{w?G>RzcM=wn13R*|ER{ZLPr z0OcFvr9=K|P*2-qJfWUKb#qMr^K=23a*@JpA=1Gfsyy<5G1lQDzeu73*(rQ%)xEm= zf1Q`UJpz)Fp($6in3nH;15t*tqpjNwG84If)+FLn)bd<&mBZO})rNnEKEO_HW6sg# zFF~TzpfH<5&9did0ad9fVm5B^$51Nul;PLLcx!yGWR{E`B~Pg@dq%KqC{%XdGM03YEg?0RR+51sC$S}D^e;UaGK2iUeGx^sq8q_yMYXmZ<0={%YXuTdfojNfcoVT>$w_oN zd(XrGdJk&sQ4pCg`FgFFYE2xILk7j?WfW!Ip*HStqgK0{B17Hb$upfmem4o7MQL>n z$optgI!#~0{6o0X8VNZEzVcV>uT$){V2hV@5E@Af=V?egtfPqe3NC{L@b~mk=I-Af zmQRws4xY=t>J#>SCmAs>%>`rFtf^kqf8AXwE%Jr~coUfReq~MB(=k3Ne*MT*Kl!%bjRvnu-xpUo?0kB>bK-jdF={nU+U{<|JE(Q#P6JzOJ2AP4Zi(}tx;T{7<+jZNtH$K~e zv1-1+F>qp6=f!)OnECLfFNy@#Os+&dfv z-lu$&`J?!g>27dvNiX}m%F;ycp@6FbVhQoJ!5@wEFi_`XH1)A(aA;blw;%HfQiXd}g%|R&FUVM#Mz(NlAn|*2y(m@pu@f2CPVItg zGR+jPtMfu^RX%*i1AghoE!}$TJ>)N_weZov7!hDdZ5!LF``E;JP_w>`65g#1=tul+R)TP* zG@E`lR^hExADg-brzRY5?mN4@ok<&V%~_u=%-zM0(EYu46MH*zb92*|AgI|f`*K+! z_;&ig?|++K{eOC$b(e71R!14VV_wkvlizMfHz9XqK-KkVPm(p^VlTJanNoq^-`P%U zyD?u0NqT=z|JQ`zWc?Tae0~I(IlKe78n9R{WNN`D@V#Km zKrAzD)>U%E*dz_R`x}{+e?!+3$;i8qxZoj6t4cL(d`_}&7|aj#Gx$h*LW0z*#{`qA z6zRU1S!d7rs#8S)bvY~Q6&1|JN=^-k%p8hn-W`WDxe&ukilZMNKDnR^RIMD1a~V;8 z2poLQp1`!xGRY=In6iZTB!#1pD)z{zxb?pOGx0{1Rn0@zkTvs{VV5rE&$@S2r-1|a zWa<`%?BIY3X$|QAvG!KMaWp}fsAS6mi$=`M%xEz)Gg>fWW|l3qn3dWoS32>o*?9@76VfC)&%uU z-hE7}+i4r6HgyUPJlI)I&GMIZ4WxMtf&}heqVSjU!XhH>--An24~p8|jG8m+*s@4a z+%4_cMJNR3rrPuB<3W9e0wJoEmQ6T2qxo2pWS)9!tGzs7cVs?EeqSj>F7B44zT^gW z*w1Fr728J-yuIiN=5MoO6vFL%1zqGX>Ip&-)TKpIPswMiyq6Rtg2m$+xGfR0Kkv>7wnsB0jObG5l?kmKd z_qQRN7pMByzuFz=3-GEVyLpD#PDP$ClxE}>M<&EVinkMTiTpc|)zh%ySijElF1l9A z7Qnr}Qh&05j^ck{9-<@(-H6$hpsET!pz_VL85S@k?&oh3&dr$Z~iU<3SmlJ#uF+W^p1nb|JJ0ST)?emria4Z#NWd zJ^77RWHM?Z%o3hEHCNWGJ@ymuI-@udDG3M?W3^}Y{G*q2V2kckmd$7g z=fRG#-^#KkYegVg3Xd6{KIlwDBV`?b+5WJ!vk`LMXdMMKROz%{)|ZwtPkcdVQlAbW z5+r{dD7moSFGYDbZd;JL;{gIy#ynOePQnUW#F%z0*!W@PH)HCIP+-nv)63{o!zSs2 zajob{`?+|y+|=?T;bg~qC|md4*|Eqq=ax~S-EQ5dJ)9WmH#ZB@1Vmo5WtECVk?cG# z5=j6 zTHhGoZnJA_5mT~&O=oaEkHA#@T}ozJWJ-l1zo&m&n}~?gU@#GETXH~#Ol7Zri{}wrZD>SEfMb|kqmWR49K15Bp53uWtx)PR(x-*>K=QjLE@wfhnvFEewnJR7yKDphU z)_=1kEbh!nJER@4DEHkqP;Hrtc^%w#2uUAmAS=fmUUMsQgl#O3>#U0{9;`f-TX3aR z^ct~BUyG@6F_`x=h&mvAvl_~)W0|y;`+I3?nB}ah#bj=|JP>8Q@E*A_x$R|8F(^PN zuA2wyL^1ZOWeTWekanYeFT2=8(Bzm9i>H(hT)TfUT^KuM^?kgbP-dGun`!Q3=6DZW zb7$9EI6XIEd}Q`IIoq$LA9#?xk@I#eCNOk-=!x^xyWO#!Wnphlon%F(HTmosNOqj) z4@EBo;sBxYTr+5&f5Oq-|1Bs(zjN7Lu%nwB-?W(B?=p~|jq~J$o|~F$0EApb{yyJ) ze($e*g)HoUNQf)`gHz$gV|(QFbHPZ3fA7NO@RqKpaq*)1v^3PBplY%k;`p?+z|W@` z+C@gLsXeo}Rt+D#2+f8Y6C`t;yy`@RUp<2AeD1bx$On{85Ctz9~MtEvllpX1y~`K+JaZtZ(z z)Z5cEo@#=A*jJUucA%Qvyf6Qx+~?UKhN$eqNd4WvQViw*XDY~=apl<; z)nH8T!p86RY2pz~DmeP<`QwhLUxz>!iCCePQ*I6>K+B8;BeMi8MIu+Y%gDhd#3cLQ zoC&A_8Bsc?U9r>pp#<)Z6apBJ`(dak=@5BY=5K1>U>V>5I-4O}l^8akGi~pT9OpJF zM7)*=n35fa$HHihIO!H`W350JYn?&pu4YVrJa1Ge*r868R;tnQ>nFb+Jd2AAN98}) zscyXLU|F&Kpj!EG)WH!pu5M{`XZunc?K@MuLlV4DIs;r^izt3=8{=e->GO;SrDsri z3CDG8F~JKB_g;t)<_fi0#Mr8v6JCPuq6dU;@x@ZT@~`QdNRb@bb77ElM~ZWUbbX`{ z)pZ6+*=clWDyYA!rYP#ZKPq2HGi~9Q^l87IfXp}&Da7< zIcnegcR$65UoxT5cMR_u1acWdn{KP}F`wgkxz*!r-R(6;J5k2oNbml0{QilVod38T`SlMAMDDM@8ji z$it~C)lw)q`>Ie3m6u#ncSeb+`q*EctaNc4_D)bKDLj(;Y1n2Pd}M))!kcj>I)3Kv zb#wPXVo2A`V$n0ZgYo5E<}nhghFvm(ESF^uGhlGz`}gA)b~VJu%AAmsas_I-SjY?; z$5LJVuAMXqyp>RkdB2SSVu>{_3#?vxnk&-G>KnF(5sH!SkdU(EnCERB`wHcY|cO{)~DN9lG5y-iNX?oR&n?}M>r|$ z8o2p*#Db15_M{oai?-=i8798ZabFUvxmFYLaICpJJ?DpcfrC!1DAl`>>H7&mVkNm@ ztJp0@5NvO|oqC}j#&QN@^rNo7!-aA}i+F`XrP@(XUnHo^JC=)2E1<2T=o`oX9~1u9@t?ot7jAI{32k02~5S);!$ zgGp_D)GDJPKApT<=fII*bUaHla;NM~GG|Hf02(Vf{{Sdf*I+@x7n@$-B}-_oo7zy{ zu#f%Q!zh8piLLF|W{`bNmlgh0Yu9aakxUUy%a*F*zd4t7lQZn1>neszH2NY!&A$xs zMz)tuO|3fTk7m*ly&2Y_2W_lc9OTa~viC#CGgR0#rzBANY_RedL+L9EcZ%0Mn>3b0 z{?8ZZT!wxx17m_+FFUtW{l-b<7_R1}pyk@>-~W=!M;4pTJm%iSN?o3+_vOT4D9CfY zbx%l-@*3~w`loH{+Td-HwVGO2#+8|%EF(lWIL1BG$SD?#zcN=A7>Q%E?o4+92V0>8pVCTS$faH zcggb-C1SiBGIhU!m_80A?FGuv3f`s!V@8xQ#oT%`_jSh3da%TQgJ_>`8|+RGnGAhi z4DGu;pKn$_-|DT4n~xO)44 zR=5f@=VJPNU7h-Pcu45>yFT7D)6DU?eE{cmtNp&Xaz0jbuP9Tqi)`@m{M_E{e}CS7 zlVjNJ>-h*0-1Jke1VC0B`jvskF4fLAI^TL04PS0knm?OsQ2jq2^q*@4g@@c;9X$m1 ziToZfyZvs*1pRKV{ol^SE7AmT+6>AIj+Sy*_ythE9}0Zjj2VCU`@L+aJAZ{>9d2De zE)*z9|L1B=`}yMz@MKZ=yJ{*=@p61t1C908h9l~NIH~@uv-;y=)qTg_qN2EmteXQg zNr#BGu2;K={RUQEDW?GHzEdRIkH$LtK zze*ZrAr~p`&>jGb1c!oDgUk4!(?D!f6KC6b>q>>ZwFysZk+udc>s)PY=zR0x&9my|7Z|>6NvshHMHtA*t5QP5yRO9Q*^V-?mY^{xF zbu)=B<&B4fvEJUbL(4^*Cze5JSsb4M9E>~M13c3`e?X7y{Y~o7Eq`zSRuVimuRwXB z8BlKA%)Xw=z!MqNOw*pwsHy8n9$njD)eElZ1Vrhy-elk@TVF^npEi@(h={A#me4cW zCQdX9gpNHn%5I9sD#!jlqd=LonNOsM~JCuD|82YpKTCC2=ONc$AMdcu%lXb0b|_#2oth3YbbTEQ$` zI;nJ}C~;fmAyhFEPMK7=S+;ZBs|zY9RO5JR;TA?4^G?u48+Y;F9#Xv8*p09M4UtaZ zX^O`45nhl%aRd6kTQtQHI$JcEaa>vKFOe#!u5yp_@XfVM@$e~G%ic<;5)wz4L-*W8 zl@RSnmLd!6?bEob(loeitFO2lRjVa? z5>6uWl;SZU#x>zFWZ#H`7eV5*a(TZh~bYqLdt#8Wlvnv{P__7P&g)pa77@#9GJ6s?UgHXR{ zY4g;vt19IYPoRr7y3%Lnso-NyP22KBETVpB^QoUAdGPJ6O0#`i{`i8wr|!wVrVO+! zr=~?VpF!83b9Ru@hU--;E34{N>rqd~D*kS_S!7~&TyN%3=W$KKkS;|!{6(kI{gh9q z^6nd-PHuw)X7nhWM@OBLREb_;Eg1BkrAzeIrv8ILS*9t$M2FE}s|1(PDw@__y&l&n zmr?QjPB6%HfPvvR_yh;!tRBn#rbh=VTC4$~IGQ$lzi46WEGm^&L!G&7i5@dGI2dy< z7z(q&hfu0Ts*JO<|H05VZc|VA61~`QOQUM+mJjeFl9lFC_f5G242odjC>wP0>`-%F z@Zg(A`R+V0PfAIMw9)ws`p_ViZYwlJp-G80QK3mH4cr>G1;bVd7^JXLkW8cuz^x*A z*+Kdg_}-C)h6ZI!#7dS~J;%nS-=TEZ(8s3mIP%x~Bn0Z|bjh>fV6wS0B>HSWv5{2Z z2nskxd9p$ifFcRpas~&IK5 zBD7b~viwepB6N`~37;_DsIV-bNan?}&2V(hf?s7MF9|jfJdhRbE_ERA;r6{0MPMkD zIXH6}_hZuvufq5qRR)!j9+EsQAyK=+pK>5@7@Zh3CkHjH@!jBb_WoV4%l{MHpfpXG zkB|`#ss*!bZyM|=DmqiiuIV62+;e|K9=ceNfKT`bwXikd#}~`$yZ?If6Yw*Askcqx zcijH_Eth!F(-~rw2c|NJk%OOywRa5X6R{T0Mq&g4Qr&u6jhjMKBim!%oq(es|K7eL$zP z&j_fVvUgurMDtx~>(^nNN|miqoEIu>V4*kf8Df$ZkTxQT4w5MXh${#a2t28tFy2ol z@i759C|)aZKVM5VWlM0Ar*i%vEEDsPJIK@HfBCCbo!y{SiK_5Dd5E=2C%ot8UTerW z*x+}!kS*^IiZdYYqXuX5-zhkZ6HkoRCV>mj7A@3?frSou&*MzcQ!f)@7aH9{y$8@- zFSXfP)oMQQRixgECO~xR5hR_18c2l>#7*){$Y0fUa8Zuxu;sRT7hQBZ<&S&lq1fBU~J#8#?`qTj_IW z6b89RmGBKEO$U%-e0Y>)Oa9eo5Q!M!@7De_&5Y76LAD$wAa}7Ywyt!wKnwbs!B-Bm zU+u=K?o499i6yB?krIB#a#&z||H!3_&sc<;Opv6Ka;%IE>vXW|jyApKQPTdT;jg(# zDVBzP^gqnuKFlyOU}sKTLps(ct#K)rsmFAQOP7#d8sV=kpAB}UFO3|NW*YL$ceq2xqg8U-rQ>Ud5>w=>!L=My<3jtf6I&?>Si+8 zYmCDDXn-dWJi(`Q=4Ae%ZZEXceR(A|KcjSbKXrF0s?Ffr4^OR==!P)Z7sshbF<+D1jBN%h2PK)8XrL z1Un6qiE9ss0cIr!AZBxH8)_GC{_5pet*1Ec6G;oNG&k)zmcUHM>m0Eb z4pkxxvERa>b>`f6X#s?DPnw0&aKtY&rrqLdRL)FuUFAj3$;lw^GYKwKJL1{455p9X zWUF+GfV{%RtmKl|YcrE;QVe#9T*Vf;Ht8g_eKY=TJ+*|pfi-9|;kr=CJ2XL)kEngO zjax<#o!a|J3PqVZr7U}$e)whhFI@*7TZu~~9)a&PH3bYA{iWIb!IlSso7$;n)<*pn zDn%8#l9mOF2@rI&euho|?QIc)E8MPFt7VHX4xL9*$N>Z$GI1S$7hDuH^T;gP%y)i7HC z#Ppobl*EIFJ&N8DAB)p?2hMft00K46we+nM$2g*6irVI=JB`D3EGCJoGsfu(NNx`gUO zXoGT&4?A}AMDisCtc7+4>+B3Kan5!yA(dlFG6oxK)C)U(DLPj_JM6o)qrOLYsnrQ# z*P1eaOG6o(jP~g%=PC}H3%OOWz85r{*|yhch=NEP9tbC_O582uTrR9MeWvtQRq9G? z@tySaRy}=*hxIV9aonzcoqQ#a_lM)ll8pRoi2|vPm}p^AGp1(He};0H2J8zu#q$b>$ANKGC)tM4wbIKJ;r zO?kwmO;S+YFxCU4EE^kmn-l1wrZFO_Qy#O&qKcKe!>qhaK1nQFl*Ct@hbv8pR)TK{ z{j8LP10{DmOh8@Zs$PQA!NiDCpasu-~$ib)n+55vLrEE(P5k|_# zAiP5BPc5_}V>>9iz{+O{4dUf^ann9e#I<8xwrl zuy(U0(&aqd4Kn4zPgu0aby}$uC>LAzdE}rh3rEx<9t%f;PWX?7^zZZfM}n+*Em=V? z{FbcCd2WM7J0i-NaxGzrl&V!b36!b~y9vo;l43MpC|QbNQ@2SjRvY6L(}g+Rha!JB zv<@NhNNp}B^2jX$4Y=iYWKoz^HCMNo*F|w0p_fAwCg+nal%b?{#8HS5LDo01A>Wxi zLe04q^iR!P?lyLB-xm zbwBV}=tCv;HMr~#n^4kj?SX5QWJ9ewtge+1!$_``^sV0uanvH-`*8|?pizgGwHZ@| z;*`cG42g~8a0jX_qMI_0$x83!;cEJj78bP0VWQUP@TuX=0?>#Fl3Z?5ldaf1$LGHl zaF1&k518oCp6;Ch3Xx(jn4sVZkt z#vHdX28WiY5n}nI#$#OL*MP|jqxzuH3#~Y~{z)Tn08IGT zyF-G7@{Bhtf4_oPhhcmjTZI}iq-XkQCpQl#!zR^iOix&^ZgQPkOc&*lT8fcq7K?;T zRdwE$WO^Oz6^GtMeBV*nN}{Wd8N=gJ%_GO*n#wq?!%jV!tC2QfqGE{&uRR7`grjx} zJ%BSmTJJHekuzXYTunA?G$>wj(rZJZ1Kx`z6OV6}*^A3XNeerGBj&2ZXG%A}L*f`r zH<7C&_Ft%~0poIw8t~Q2urU5?E7Nu|D%WTP#|gF3Mn?;08`db}gsfARxsHue4IdH{ z&*Ki1!*bta#;Zb)S@tOM7$+$oG0Lx2N*4|vF7lAt6qn$ZQl~hEl2UgS{3f*+w#YL+ z$UI1B~`^RMTKGy1>apPbpE*M3l5&aRn~66l?Kqf;4gX z){B&I_(1AEu=zffdX0G68Lj*Nm8G@2^yb|t^3ohia1QKn)X^Xz?}yE@c*+0~I(DjB zD&$*>TR1k91SY3uij?OLgRp*hyEM98$g5ZI&)BG*FH`oncqrb%SEKggs!!|ut8Zky zLR1ygDzK-$@qi^77~Ul*+^YN)ievMQPoHBGJU^`e@aRyhsPp6-|H-sPv-8{h+L&Sd z;M%wf49vk~F)$f4bX&nXnG@hiO;7)huoi_WB$IllJmJ*h7hA$9(05xxWX*|QpWlhD z+|<=5gbunFZA>{Hi*K&z>gG-(%3m|nJ;Yn@Y@Q9+wi63eymnFGRK3Owa*!8t&Y#X) zZIBJV^b2J{VIS26z|dE;D)13Qr<3b9ROHniAkVm>rEl^05sdm zFPssfj=XTlyK<;MDM<(jYw@`kw((zEP)g*jzO>+zVoDQ1iB(qjR?>W(KsB(t*`qh$ z>BXViPWsw)XfDrh<88SzKe|cZDG@YNe@BSY$|d}7UfwEuh`s=0LZ^dqraby)Nm~p7 z6!r(Zg5BML%DAvK5Ukq{B^L<_PsO%PWaft}z6HPE=F2q%m#k1w1Mg8y!_c7|zX(Gr zrVDk+Bub}ZS0*u&S#sZ`QY51m!l7H8M+L!+m@^n9pNoqG#aFZcW>#Y&HLlbaq2I0| zmd|xUJ4<5!t%63p$I^bm6dJZ_PA5;i<{=5m$`z%Hi7HG&0k#>b2HQB)+6Ti0#TH;t z0rHcS(}k*!nXgl0Ezl?dy|yx$La?K}mS0HBMc&dVxKV;}f*_pG%>kroGU>wAPY5!Z z!leqRW`HmI3Yo%xY9$?^ll~~9n=8RtT0_pFX(m7{%anOYS*S%6Gmtb=PY_3{XA5Ij zatDsu{>C&{3c)P;71lG#2CIF)gD{HB)G2RxVbs7L$gJTBZS;2*L8LexjYSrpTbhkp zm4+fFOqYydf*9F|%o3UeZu&O1CGKtqK?Kn;-VAVql)xV7)5?!NIeE{k5WxnU(qxb> zJY0jWI3;zAt}xa3#vR56>z*Z%E?lI0y#?doWqNF86 zGf6TBNYG6Z8`q*T(@|g`!?|+&cQHE%q`Y*H@ug)Ra{rUVp9PtJae3*&=#D=TN{h|Me*IH`7ZjD$yFCBwncVbm59MXo^kUSCgP(>Xdt9=) z_*P}fMy?B&$>95w`QZqkDMkog(LloU(Sn;SP&}(zh4KZzK1l=!zk+G45eXaRS53TLEReKMfeU zcWe+}mZ3ztTdoEQB(jQ}DKtzcXL%A?ZK!UYu>Vj-4#wW8%1O2D^c*GftjcxD2okW@ zXN`~XRzXKVjK~WFvfsZDs`tzo3eGJg{+<(NTOH|ug3kmMupB?3&n>VAb5U?sgYE^^ zcPsN<$#+`s(tXbMFQe5&bA;Q{BbBoo7&C3V4*WAe(pHfUhToguiGKMD{1%zu@%%cd zJi-3rT;|%4#JHY3tW~mi-9RGH7a8LvjyX0E(7oDgsjc|q_n?COBKlM1wkMlQFRT~B5z<5yG@s@F^rIZP26sPN?dEdx8MiMr!t&`zvBk#UB+;8d2& zi80ziFcUXC4Y%P#?w3n-RefOF)uW%;iTl2r-W8@5U{=Gq%IF@Ua&YCt`kbEi-C!y%#btiqJk;&3XP&#HwemBP;({z42f^LP$c+y(cIgW3AaCuyId@iKlL{zly0-C=a zQB$u|ZXm1^SXG&@7vSfpCn!VtIC6;)ZWfDLBvG9xV^mC@xUm}Nh2&>& ziA7jCM5A7ucQn;s^68pDRdd>Qnm=>PXLQSsZ7N#r_^$0W5e4FDi;xmp%zQ(02GoCJ zI?~bfEv%%FQ$2;yq5?z-z`&uUr5W^!DVQfSpNs0k%`SX_heTyv)Cdqeuu3G>Pntks z)(0J*4gXwAZU&v)xalh|%*#&S+mgw<|0S3lojenztHyD0>J!~h}u zpNNP)KOVcE9yjj{j3Hh&)O*W~!$PAPVKzHS-_c)u}`ls^Bjv&Ja&-2VTt#-yuO5dA`X=Ju}+B~3oKaNkV+ zF#LF?k-ZjG9sGCE&EfjX`GFnK|KTJr^*!(UKJgdAKB$S(fqP{TZgthdX4T}V?$x3Z zaq8G-T4a{HK?g>q2K$ui&)4%;2eF+zFoQ$QO99TcqtPFC zopM-2=#K#cB0uF98#?|jb%kzsJ%&mP{RN;R2*ca=4LeqCo>@3eDvo?B7`kdIv5IlC zb)Gbi=%myutdLSFOdn>Bc)zZwG5okb=kkBQW3sOy`nh12&a0fi)Tq1*4_EjhWQ#?c zMGN@HDya+6xNuY;qcZ*>tHl(Cz5sh0fLp&>8!?>kyAmE$qN{7<)r)?#57 zccLL-4sPFuB1wPw`=!6QCEOeW3`4*X?ldToQ4Xh$4BiA={-G(91+tG7v&NtJN=+KO z*a`O_^aGS}^>_E_Z>kTC0y?BO9nnZa{JG@=M=y-Nqk3fH6~0<*cUhs6G>tx}8}BY*qTS6}Y^dyir8obf&0XV(8Xn zo{#UGVv9NT`a^1&+IYm?e6bB{y!MFiqAT`K3Q}ZiZiDAvw`YPg$i$e1Vk{4pd3J+7 zoNwR5WAbA5;Yr+fshTtOt5n|ta2%xL9jy|(bcQJRcb5OO(+YaAILE?1CVn0{mTQ4o zl5=&%deR&evT+kHDQ`+cwB`5o2qC*AmV3!kb>xVM zM+m42gR{?F-2b@Fvf>< z^zy})v1<^20yW77@O?Y*oViq5$>1{L;*T?zE#~s$8miNHVs&bl*P`ANXdeZPkkI^z z^3!c)8kFHoUaiQ+J5H%`k=&ddpC=?*@w3(~RO{mC%NF*X8ojEqDc1Nl5IjJ)ZAZYI zS5iGjgnF9-!hx{?ly+Q{0lcghki@=-y|sL4xIArPPdej&y00BsbAz?lp=;8EDITMrC{l0P(7%KA|ci;4z87bVj2F zyBdmr-GaTYj4w-9ebqoPeO91Fd&A(S+Q2Lv9OenP;2$MdQt#bmc}M!;33oP$TJ}kQ1odvG z0p{Djhb+#}KB2_q%EASjX$xE>B~%G6FC1DC5))^dyr^mIDXO5d`_j&ocgVR`aZM;m z5i9yH(ce?@TuM-Z02eBH1C%pU^KO7#=N}$`&NFi8mNHkOB9#86mj_fOZ%Gp0Xb=>g zCpxyi25smNF!M)%63^tVEX(e)ymOZg&(9-jf29%S-hfb} ztJ(#Ol6OOd_tCo4RB&Ew_&Tn~WB3VK);GJlP$`=L!qL1Qa&Rw^=6uT|AtfKn>sdF} z`@VLb?HV73n*nx2b0DtNgD;eW0aF*ERMqBf$ZC=;k2%C&D2dTw?#_t#SagnvcJ3CR z9A_ADN?URsGV_r7apQldlfOp;bS{2`Zs|_Gg+Q=k8{InQ&bHX>r4OQoZt=2gg)<)+ zVneMj7ivK1)&o4Cbmy>;pz_DIQ2sFP3NdFTCJGC&zrUcW9m;g0oGF=Vp^Vauf6qY9 zoEnqiY=-}dM53&H8vTn7ZbW83*J_GkB>+nFuZrWo4_~tdcbUx7#+H|XMqO>vk`rtm z#=RYE8HTz8Y+1M&5$yh72AvUiodOJ_zb34(Mzig5P>VbuY^X&VkOq{Vi>$^?mV>+a z-z4S`$-nwAKgF-I3{!-uHzsT;=3J$*q2>m}HK3UFWi-C%@3-Fci~y>jf|r~Re>>Ca z!0jcbB#qu-R;d*~f~|`d!TEi+)PUml0zU-O+3-a8sxwmMA9IkgR^5C;XAK5)0VjMl zTwmhbCL8gPn*Z|rE6_ZAP)!(wLKEgW;#4l}kmL)ncfzC-;t7Rc#jCqIyZ`E=xoGra zFMjbu=oduGFD0Z!EC}_P`u76#kGj~)09(1w52N|kdtzt|iXel{ZjwaN7N{*9;YH|a z8YpgvSWG?2I$$;YYkh52hllud)=adpQWl-FICIv1sxY(qf|aC@m?|r(NO5zVi@Ab1 zV2eBZ2Xb$n%u)`@W7OefpqT!M3~rK6NfJOexiaYJ9!OzIq-*3au~NtDP6#zz@K=xw z>T)s*CcGd%DK^4a7ml&mlw#9^j5EmKa){(krUwynnWOh3vI5|G!6)U9RTXqIG$zyJ z%*G1aG}l!P+ZEn^4O>myKmc1DzkChb7QajYTU`Oe47=|^F!he(Zjhg(mZG4GBDdHA z1cXm{=t`qhL5KeG?pc-DCuY=<)U|5rde^Wb+O zy=cAwYbSj=2sOf>k8NH9%DP0j!3RNd2u+BX4roZocqFP{o~9!rAu2r&AKS*?GhzaK z`hX~&_Y7P_tOIQ2e(2JOy)8q;R60OE@9v+iFn1cjyE&$_J{_0|g<9@&v+(@4AbiM3DI6++qqroDOO+fBNK8Iw)% z6vYH|FCAz+=W-if>LN?zB&*#QK~5dVG~;~nj}zKlx}?4} zS$)riH|&MV!)7``89FeRrbRAtMzg>_c(i4nZN57K3Hj=_L6zqTi5Ev@(eZX;6a3^46CL8`84s88o=w zMbd&vc!;70?`@AQg#kF9Cx_-j;Lg_R|I2XKX+#|_2xQp`(NFHZA=e$1+e!HiDJa)~ zfzRT-m$G$2HEgffc=Z^ftS1KtIZ|9wqz0c*58DFLzLMmUXi~ezcZXX0i2O2*NAjN) zpcEoi@=DF6!>ACG`jEvK{+B)W2T4`E!$9vdoiRM_4Q$@Ge_T+KqZxc5zWAG*cE1g3 z6YL?c5PM>?nPPrIH<#$xg+X%x0&B0n%OkwUcJXnWq-5#AC*8s}1%n;GSs}oQqSPOU z7$wK=;Po{SKZQg3%Qc|m*Nv&P1&?_mwB#LTLusl?JAY@?=6)bA(fOA-q{IN|G7?ic z*kUm*!rWwbATu54T?lYzVO)6G>HdBaYe>SotF>yKf|FV6 zc3gF4Ji3~!Z1}B7m}+9u+c-^E{GEZg%ZT`!I(rhymvzKG!OWJ&?XDpM!9FEQSmc>h zI8NBb{6lblh4A@tL{|VYi3ZUnOrb-Pt@P|wm3N}-#a&5uWo=_aEL(n2#)O2SXR}7$9nr$noCe-)|4LW7$NE{sIq-I%GY*uCDz%)ka z;eu_q+ojyCWLhJlP$KurGpWf0#E{pVv7gZ@d0G&XJS2D`7TYd_Bn?|T;Xkc4VBvq# zbX$JCVo0C-`h-bg2#Ej`$%3u%E{Ntf&a2zntXFFB3Cv^JYfntG(v;83(vW(3&s1I$ zEK)*dwO8WUHK)j*YHLOms#j;M_OGEvYEWlP*9q-=tO@gXIW>%X!&?;e09Lmth$EEP zd{X-=cz@<%uU8nPe4vR3EPTXya}Rk$4P`$-;>4H|0UEO(uEmi19+4%|`vkVIP|wkn zEPU>Wta)%Z{VPF&-k;gM5;mXNJHoo3dC7Cv?=bn!>o4x;+{Uk=y?Hz@kB#`TmqdC} zCBF2*(Mul;VNtg4?KV$}NBzn|)S9RnMdm-q@DGc3cC@~B}F#+34L4s zvm?9CX#O}{IF|G$RU>uUMx;eenByD% zmoOfP&@sjblti8QO51J%BVn9};`VcIbKfKsa=#YMfJx1P@ikFjyFqc;mg)7^hhm-L za@^XrUz~SJFadU}`}UGiE`DJ!!62@R_0o%bzsBT)q1)=1z!pQ?S%LJq%W3!7sPNM7 zI7*9XfzQM~034#z&*cREzl!TB^_c+|K%YSIHuL^Je|QRf9??Q6z7@%kIBxW@~=C| z?&T3dt&E@j$kk)9BXy;bxz^W5_WV3_5IdvNRwnux)He_Rvwu@1XMy;Yox4(PCVEq_LKg&7qq|$Y(TSP0Zip$dn;N-WeyO5MQ;xSzEBUC6 z_3OPot6aKkty+FH;^8?f&8Wk5-hNaguv{1VKSl+2+T7I2THFv}l>Ua0@H95s%WC85 zZ6>QQEp(wo?{UQ<vne95rX)HHtcNxGpTtkRw>$eekj@;XL^92!EdXyCF`z0XJ{SF|h@ zO&q>A&(;MeotcY1<(FX1>)~su5k(@!9L;E1rnDu$(UrXiN*7k&Mu(+g9=0vl3hr%) zQ3GjCC*B-}h{L_}>{aCeCCfH5nK~tH?DBFv*l4-Wely+adhQVd%sNJQTSzt4WqM+v z(qE=M0iEe0>5QqW-UgDbUIy_y@fIY1@V}u#j`3vL*80*l9-T19U*}bj98Z_aa|bC= zMA7Omh|sRB#%DK5i+Wa)B?ivPg+=7Y83S{x*CrgD&>ou_dq?m!W&%Bihj^M2 z>Ic%U)-xcJ@yIL~zAVGx z<4>cKxCIfKx>|KdYj#Cj>vxrP7UWgsKMAl^8k;m%f3~X^V^qjNVBD(6V{`^7(ZC!2 zyE!p#TX~r(2Wqy*`C!k_$uz2|mx!k;w{O4QdzkUBuL;GNCUT*U$0Oo)&u%Bi4;tI0u3Dtmicsn$sOFFoc^?dn z{g;qc^J+rlNWIPb!P_GU?=lFw+%!K^DqO^A&nUzXa!ko^7ioESLk?GMC^ z{dIxwxNtR;t%UEy1)xHwsXpYbl0WA`ELF}XFu|!aiY(1GUK&+6)Es38w%!ImEiBf^ z&iDACj09fpPE)43-%bxBiRG5R;4QvVUIFnW5d@BvC~ih^n4H78hAcMdU|Nbz&0fkK zM+N;&-qBa)VNW%&=l2yB`o+k)uUVQ;ZO^}Xnsk$S#`D6W{g$SV;2E5DU#7gC$>zri5 zn7v*p*N(tE>izNfB#^A?Wc*CYR?v%0w2Cyy1GU2q-IH22!%4Eh(sX#tBJhG7!dIwR zPjI!B5xAo%5%zo}H4Z>YknIs_Jer^L`>rp7t@9R?!`Dr6KS) zSs_koNI)j(ABPk)x_Kun`Q~2esXDg)&oE21cd5R zOgW4C?S5Q%D~y|mMWS#33iAS`_`$=uGGFgU&%f{~J5;V5gVUnVvKwti4!`<`YKxZ< zeOdF5ikDK%8(SP-Ck5=;UAxDm$MFtg7-uz{B0Hu54^iInbV{Nj>vDT;mUPhWFNldmB?1XAWS|BMoR ze|#0zvc8l|Z@-pT^Q|SnAF!!1%r9k%TmwhQjcTKvwb>HH3p(m4lPKCTkBE?_H>^ky z{=$G{^k17FZa#8YI$!TMjtoC84nEu84>ykdN?&vATC$XRItnxdU7QWgInT&+lsGWA z5V%C5=oFRO8bEfxIb-h1h^JqzW6plRq01_G+R=K!sAlo`Uho~?Xf_h3%Hb`>%8g6< zuBCTdnEe(e@R=wZEC}b%$!Z*Y81XUUv@GAVu0Ui^lG^wf)kxnu^>+?qUdp|*X4t0M z&5o5clv6#cAUY)K_#e6%r}Z2~BWOqX=MT$^yTPH|@CG$?Z9);}lPk0envtVRD6zm; zX*XS61?jV}#lpXOIEi$rDhrJdJwD_2L8Fp)t%D9gPG1s`>C4hWKvKSSrssB*Q&{X` zt%>^`bbWlE6VrapFS56vI>VQSI>TE^$R3ux8t-_w!o-sI-#fc>Y_LM0A(wJ5Q!`p^mKVL|z19aeM@*lJ zwQ1~mr|<-1rN@t4G8(F-d7xQ?9&OyVTqG}_}@V%#`S5P`5u>_MG3oG4x-l| zQ8eX-VtbBzT%J|RtlsyKf5K@FUT)rDPsq7Wu^2n9(pnP_g_!S!KxSXO6z~QxQ9PLi z{;h7}_MMZ`(G}7=AQR=}FXT2JBMIVW8}wT9ahW!KD^yD)j^H;{E2j4CLr*dYZ2c$k zR{XF+5Q6H5Lg098DkWF&REPSS&Pk<5Sd~*Nh-|@R-L4M_5bfkQwe)W$}0RoKkT9mg!%%6iTjE4Yo!#HC{qY?u;YwU(Xu6 zSlBAxn7Z)ui-cW8B=%x1LW^2Yzeh>=X>g^3R$sNSyI-%$nXkn5*ai8++W$cc0Ui?r^fpW7c=_%Q&tlH~k?94wm+}?Q6 z9ke{UsFX0}IQI?*F{lv1VBd9NC@S&9yze9qgtEWClcDEH=i2u{1O+FMVii7KVw~m` zkU--0!TR3+5f=y$->t{iLTRI4K}{gOd_@hI_4Ww<9?>ZvevXNVMxOX>CpKVJ1F=`F z^9l`9Iy*iLfl{eijCb_)fQ{(j{SrTWAJGFv={8sZPBuzhOAHn5=)YZ{Twa@r{3iOjkIW+q=wZ(uG>Cs{D8L&ub>Rj9l!6^v5Ac%Bhs z8VC^)jZkSjHs#9Z0lxh~WNV`$JNNwv@23HM*ZuOXrp@&E z^hUW=$F(3DG&OK|i{~WPxSXKEKR_MKELKb214VAVKmcwuzTg6}AG@g%ujOvZpgw|-LFwBS) z=OO>!^sA#y@;Rs!7(sM#n62L~B6q?!V~6bf?V3!Vna#(H-N~sp*cesTZ}3YJ!67gl zqmf2O{e0Jf|50L0ZNwV4Wio{sN2EIsO^dq>nRY)3YGRp&_a_ap>KD5XD2uxdnbPjI zt+6?$)E}@qYyLD~rH=@y-wzxFn-#n4ubFNsvvQjW<)4l{wr#)cM*41pdcf#kX5F1{ zo6=sq2u!yv0(q2j^}rM6awoU4Ox!<}f;U?i_U33h@{` z|Iv=}Yq~1y4ky?42R4a4GtZ5SG*`{Fn=FT+7>AQvhuNbuT?CYj)q*P}gfN4HrsM2a zMjlb9(0Vx?4gn(A@WgSs;WXA^tonP&LDTxJU=7fzRuDPynzH7_?jKcBTvlY5w4r#! z%go#fMFS>eR|gjm7OOFse#VD|>jTUOr1eYE`e@-V$CS6*5M~!)dZWfvxmc7|2UT*+ z!AIF-;(=3v4tp2)d1qWs_y^-YYe?V9>bU}*cN;-hCQU@4R|Jg=p;WPg#C=#Yo3T5s z_8ei5Q+Kt1lGK7qL>T<0N^89K16KJZTLU&uhl3mZ$l+U8l(~TnK9rdC0Bq<2`QAks z`sg+FR;x`%jIuEvB?ML@>0~HaN!};>!dB0_7=M#Wck3Mxyx20RJJ>-7aY098`M2Zg z>V({90`1-M2eite&3kdx`uIIbTja&8AL%C8*;GpM(Ea>dzQO(;R<+iCe-*(Vcd>49rw z-j;e1SQzmwZeUhCr|BJcPTVf-QX$3GpjER!d&m_%xhUUl!zCl_(nYN{t7A_`gB?eU zv3I58G_pzlsVs_{<$Z|~w)0KJN;R4vBhJ0C$#b2_3Q#>MMTcAkvAO*r7{&mu7XGp{ zOM9sE@V3835;0*FXd3gwSZ|pu56!~v&>6_T&c88dI`mo{4lHW#&omaC_R3~p`tIJp$3UOhE zLG`&x4uO1A`!DZY;&em*#up6lZl;3W)FeA8ZOaFe`e?Z<1dxK-+2c|~4EV;@Q@U~d z_2_2rnC5kc4}$cIw1{`tpJ=P)FU^xQ(Vi{ku6Mm2Cju_MrO}XxekP|}J;*v57A{DL(gVTOWp9@$FC&om za(5&b%C)?1(a9~%%U9o?&1Dxc5biy2>fb_nKS5;|o@4#1%hU(PR;<++j;$~;N1^v8 zC&lPh-$)QxdWYgqDtT zx`&;Ud!(}|m}`6_dE??(@;m3lW)LOM6GbECPU{7b3ie-Sq@Hd1@X1Yz7@!wq*V_J6 zuxc|r#P}zc^Bz{DJp6E#@oi_d>+A$e?^9veMd~`nCsE8kM#E8}=KV*S7^{$>iG)2m z#p*D(PcNY7-Wd@M5_1`x9-L8fL@2tEtwLzsqIW_lE0(K3C@RHrL}<0ZszNBEkz+-O zkI>ncVzG?9BfwITV@8+`tu+vp76O`x*td*eu_F{tWNA2-(#YB)g!jH;lX0QRqLFdg zjsVCW*UZq!?l~g>WZcw1v^?+66p*M=;x>kN7nuR3=w9wVhUi|h9;TjB!ZrpNXkmKi zs~%wFLfY$$Ji;KN^*pZa0D8D^Wzl-L97n*9e2;(z2H}7nZhjzI&*UnFKuD-*yesi9 z$rYy~kt!n`SK?yAwA093PfM6EFzAoWCCs4@Q^pOLljVNu2T$jERZiEv<7sFay$`PD zEGRQPHDKW5JvI8F{7bUTC@DX`wguUoRtbLpwbX0%S?Zwd_&zjP*a{V#jot(KoQ?jM zT--$M07BF>Sr1Zr3UsygK)BQJIgL-t=YRX2gX<`S9SB{+G+6g|MVLUp)OCj00Sl4v z^#(817q6XsS@Qb`*|KDQD|u=dE~K+kkQStTzRCfFd_G7Ia(hJPjRU4&x8*MPj~b!? zy6OirMQJun59xQ&Q|`pma~qVv(+X>BNCH)r)f_T%7j49}0F`Br_)9k(M0(XfAW{k! z?U91X?LpFl$?-J(m1QGh z|6ZFaW-s(+EO8wZ_up`lagnGIdI}H&17nHqzC@69e!3o}d>88>hWwPb7N+$PnHh$B zTah-V^OV;%M*O7HdK zBU-SV_IyhE(rM@r+JlbD=G$~iYej+65rr9s>K;%Z(?sb%hQm&_)5DO?y>OKd=nfFU zzUJd#%RkpZ1rJt^LV`gn`E&M5H(B%Kc>_5PkD8Wt!aQEw1w6glY%M&fbWOa(xwo4i$9Ep?h72+t_8lX_WjD{*w0Qs)!cN~-jBo`qHNay>=8SbgQ+|?*v*9bUN^L2`z>#5XOfrBgcyf33E%^4mDB#=#Sf9!EVE>;7M5cXgkrb4 z<=xBc70)cUp`_>OI7#$l(&j*iq_#G)dDiAYOTsBY@Y(n)bYkSmc>@=cnMi?K^wu|+ ze;R|?2T#6~39v8p6WXn;7L*QXXx*#*POu4`NSmrCujln#NY)~z^XA^hoM@BTno>f| zUe^Jg0nVT=E7?KNHH|XfA~DRvOyiu;uYkr}wqF+)`x!E9>}qG=$hS0jdxP8$Yg1O$ zZ_!sppj$L33J#gV6iF#;#p->(d`&41+ixumjU@T4uH(|s^dc%HsJ_b;i)kt?g$=$} z(WC2E^d|Z)@eaVooO+@kbF(^|jp^<0QW}MpBoA>Q&C<7Tqo@E#QQuta9|zvo@P``g z&aJe!!f=*a@otS>Gs&?-j19s3YfA9lZ{S1OYP%O5lF)rkMQ&T=#w zlhxNq5+)IEsHO8|RbhhsHsZ-7m6CS#$$8dbO`F}%B^OWC`E!wh*z>AlX*vHT_x0sY zQQgX(Of^I8py$=e-Ln6RYT{2Tg#_zbX?nsBIy@;p*`s9=<_WB~%(HyDrJb+n3lE+o zmIOzHlIiAOPU9#i0#iC-;TyBOLCNf-Ej`&%eLgkS^mVDe3G=V|B$ZT?0q`BM-JO}( z*najOq`izrtEvY078984k~K=aA=>gce<-fvy)lfF9k*RY2+CZ9HvC`2yXB=vM&_R* zS>;a8_~s^Dbo372<0!{>y{<#vCPHhUR+jn@>KN6o#gOZseHS=FBStWEfa3TKGe9E_ zFJnnIa;7u0e=6cSlC5eaQ~!1?Yb)b=jlLu#KP^htHn+%P!JH_1V+ElRLcS z|Ef>vI%FmZwz2WXz#U?ygOjrnMc{Vr;bVqrdtZ$! zz_2b!@wG;1-iP1- z093(?PT=8yR*|a9 z*b&<(_6a+PalOrx2!q#72L(kYQ*a82lLUCrvkFh;y1VFIWEN zPig#|EnQ>MUnMYXY*dXv6MDtRK@@t%$H4%HGbyes(y&_#b)I6?VpE2?IjgWa>>IUKnB9eSon{=YhO(cozL$|UFtSh{vRhl+Xv}yunLz zp)l|?l2V8RwFD)8GGUk;2v4Om8YsKHKIpK;sDp&m^8((Bheso-2&!w`g1%W=WHntj zzfA#%R#;n_8|kr%v>9YwUP~S9LA=u;q z(++L{dotJDQKuss+4af125R)h!~1B*dTq)bnL#$N1ldk@^xYzjfZ^@QhZ^y+ z<9@@Pwr|r&D(%1()oT$JxfkZx0psSOcLwX9b-SdI=w(wEBi*_n?%UZc^rJ@@dbj^W zTM5JR3pqK}VhFZvf?yQqv&_yh^dN<|pkRqnAo>;JUq`Pki-&jLm~?upMHC7K$Z+B7 zh1E)Z&_Zs-x8G}LC99m4;B?3$tLb%+&d-YrN1;{f)h#$v3OV(FU@kqT)l(Ctq0fae z?VQ{exd3S6ABa#NN9Lu|17Iz#m75B4Y3VK$jDB`80yTn3ZT1RPR-CM6?bRjZ08e*~ zNoT8Iu@|da4524WGemIfQ)BAp3N^FbRSHXkI&97huehwE#vEB|&D{EgQGL_DaV<@{ z)c}SbH^O$hCnLwsrX^J|4MzTB`t<;2iH(QJg?;B%R`u*mMeO|MGM&|o?it?|*@KZ& zXVZd_Q%<(+a@j`J0qBJz?y6Zz*H*S&O4oG!1HJTu37H;PAsb-pmvu!R$<%c)Id6Gw z<){Tm)?4%K?~Rke>)#s|CSU`*(wMISmqK@l{}irMx~C%?sMG5rF(0?Yq|hW<)4etO zLWAvMCt7x9L&Kq+Z3_bi)NtOw8O7`GQ~E@O=2(H*;!0m3Wzb}n)7Zi4%35LxZ6KUF zoXdSNC^MpruPZkFoblM>E~qvlc%bExMk60sT<$0Qk|p_ha8Ktw`X&4DFLGYJe0^-jzGA-D z+SQ-bk1>ba`q(piE%_%`c7d47ohT#$uI1&qzc2oMn)R`1?TY!Ij{8X!&|A0liZ9y| zXU8(9oUJUy3MXa7>n+sanP?%pdC0|=0n^iE2m1}iG{Pu&LMmwt=3rUD&Cxul(h9mGP8@- z2OYxjyW|uPq;hZFiPf)Qi)ZB$6_&e+(>#=;N>eNSmu1vjn zJUSWF=FFX~OnvTtzW20DDK{e9I8r+}GPg`!>Ax?`9?^H-IUhGuW_C*PJC{gN2;!?E zRTqkdor-xEJO46)e|B2&d5Y6)oI+O&ryl-^IMcaqXD8;vM7FvRB<&+V^i&ARjNZY6 zc+H!UI;O={N;+c@&+wD^W4rWAmu6PpSpo%AZ;=y~<)l1cR=!s5vj`SMyIH`3du%lTuw?u7@gtRAxV^ z>tcom1ou&LC5S_M97ooiYN~1MQlP0v2%V@^#hP_}e{%>oTQ3L~1;g879%qiDHVh6@ zL9@ZSjO7a}is)aO(fbJ2C@EpHzR!kyVN9`V`=|IOTUB`_h#DQzjg578cI7BP#&_pi zApdWf!?fAWB21Ffl(@*=-Q&Iw4=o6R^IR;;N@F3asTZ#oBw2Mf6{k#4DiCsnudsp~ zYF9$H-grg!^mq5%tP+=~Ow0VP=FsP!{Zvitv;CZ&pF_anxXG;w4zy`S^G>$%r*F?S z#@MgY#y*SxPjKzvv;5IU&vT={0zS`PgM;7nL%+ZaVhFv|3?~B97_yCveSFz7 z@ecWZEy@Wx1>fp##y?_pZo{WUC<8>)X~48(WEC9+-tEPDhp4?P4|l&fNOk_B+_#O? z5R*J)_n(RR?TdN*5AWY&++Jj65WeO!n zK0aoJFPa+0cDMn?_?2o0iLGjwFWOh4Q#6{v5zRy|p&FxXi<%w7X#Yx330v%8O&m?^ zL7*45@8SP$vtZcjC2;%)sxe9psU7kE8e&%AmwGu8NuFv3gDpq_mi6@|lI;@A7ObR6 zv??Q7-xGsqZ>rqM{YEeQxm7TIj&3p`-XRfjU|Gt>U<@DFzT=uGYb>~YC~MWonkY;E ze~SaT*$!nrH76&MkmryH&UTzd_r&+_uyHiu9iZ>NTmnt(3Aqnox}NHU-^|u!&1E~z zhqAyGkBegFNNrJEyEo`Pp#1Kb(9;dBg~fk5Ac8`BKT5V8^5F~ff4iMi9o}=El{6pn zd5HvPOwvt;Y+fQ+ZO8avw(QU}gB^4yjgtVo;@9ty31awe2MmE%DbYl|%?yTYgZg}7 z#&58@ku#U0d@y<`dUk7%8Iowm>!50c#w{*K{EI4Y2`~v!ph4sr9GK(?L%vH|kL_M8 zLd{hVRE^PU$mfW$SL+?Xy4RT5^Ii3j%XG+w4?geJXBR2qb$|jMY!N(^V>lR#IQG3s z?}2cI`;?&YcU6ZF{H8-9@$;of2Jz#kIPm!3H6%0X^4}*NTzEl(+yd6)Fi%ZwtVgdo zq4l{{rUIa!j%KUO22o!lciPHO!q_gSHBodUC}C07|KzkKItV%T8827i)tN+RIHQ^B z6;|UnGK|^d@3H#~blbH4VrVWnstSG+SkY*W8mz$Ilg;Xx-c$4$z)v{^k9(jY>-S@p zY}bU;w8<9auaGku;4`pO0r^Bq61oAipS2+3rZe!UFp*)9O%Rd}MFjeZ47l@pne+uJMJalD+#1TMkp0h|QXaxqV!y@;7|HZ~gh=qXsOzFa>n1b;!<#_yXuwx>snWRmI@e`NnfWTr0 z39~g43x209au!LXR2T{-$?QKL>06(1Gc$diNfJltFSB}6sORvJo{*)<@qXG%pl*ArR!-ouAkcu)wEm>I|IMoL- z*#6*rx5BX~S*`IPD6=u~p&=*}i5a+7M*YE<9Zo;zycbczKEV?ZUiO|UEB+vRc>Siz za3@@W25EurAP)^cUfG}*b4t=(ZoM!!Zc?5+zWa}|?%DVQr2DVWDGIw%y+8DAha(Ex zXSez%Zd>l{w;GzX0Xlro>60bwD7EP=roYQebuwvswhD~NF?T_8k%-sYIu3m8%{IB! zg@89twa}p&rFKJ&zttz$S0K%3UWu_w`m-LlnuVv~uc6~AsQ#R+=O#if&y$o4OAlU1 zM`4G{!SX-@N$8`I{ZdZb`mI5N4uRQBsYCl0JAL*GDdTMyh5pR1^qtYKv^?sPtY+Y^ zEOO}nylwlSk*pj6mes>#C?O3+L{0Raiww+M)x`^*cCW<4%#y*rJh-yZtopsXzgKIp zf>Z05V~w^$Hq_4B10)Q!<^Idt%#<_A!_uYlK7e(Ve-7juY( z<#vcH_9^DY8tvCPESK<|Rtn#xsY&hIjNT-c%Y>pmpKiv!Bekh{3dfhUcix3Fj-G>c z-|Az>L4pc%{mI4tw#=5pOGL$=RygaEY?hN3-t4D4P_AK7P68QS11(wRXI8kT>ywML z%~__)nQI>MRag72Xqu@G0%0`cEm;wig6>TmElFb!Q50Q)I%uVD{}}=`Uy(Bu4rfe04E@y_tpL#EY zDDKQDfmc56!MER=qhTbCN2Gx=2g~^hVaz%sRh~Z3d2e?_qI`nc8uVEuq!+yQ(Y6dA zwW42zj^~R*u|bT^E3$cb4^;>UNpw1;nZ)4!yV{cVQhecY(;WfPv1lXCM3^=vcPZ6^ zMv;uBe6Y2T|A6fA!1<>|WH`tkjg2d4NdBH)nixuFzjMK1k(5f9&`@xy39S_@!Lz+W zJsG^ijyY;`MKF#t%lYK+_oboDAQWe+i^)QjEC!zAASw#7&wrd)vr`fjz>R@9X=&l5 z-bWPKZRhiEunRJ6go#rZ57?xJ6f3mz?3Z72DnDxjk z=O$SAt|CMnYOLla{HmI)gpW83jOqULS}pnK0q&p^gGUH|)tH()(vg2Pn5yHTdZ83a z?5P;3C1epu2zsue$7ngh70H9ME*o(o89}H_u*RKM>rM#QxGWSa%n&1_-}4TavlH~0 zbxXZJnn2rHNZ_2t7z@LStHdz5RzIN<%m$w?J`6aO^r)wtWli-Qee@W;?#Oa3D9zMW z0mI~EaYTn+FebYV2VNi9@91YeHOv5B<=F4&Vml?xnDUKx`u)F=kV^#BoM89wGMV14Uz-@?2<`Ubr&2z|mqwO!38ra(Gr+GH}oRdLXqkDR$3-0ve=? z2nm^w4MALFMo}_DYVonHxB{e`O!*9dF$Jw@1@_5aw;V(~bje$uH zH0K>$VwcP6@f^%r)P>3Db@x^DON?s*?1M^U;}zHbj)gqiG^v?A6vl!|=_ZAb3QNz= zmakR{u0B^VT4_PeXizeC8bkf)AKRow`$Tf5^S>A=7KKR_G=!CYFK{Rqw{7RdkIco~LSj*D12D@LF;kPm*YF$2Z%X z@}2lbLaK=yKjml+jP@ivJ!`3zt}Bgu`Ca%7GF!>K@cMnd>KY7D+-qDV1cC=@f=dEI z{~6KAEU#`M(8;XGIG)D~B}E$PWW>iOF(^$Fej|%Oxn?AzTNwSvqbI6rWrCgfz3n#@ z-{U4NC1s3?6QYcgq)=jzC;enrJSV%ub8x{t;~+KVf+QK41xkjT^lIq)SL{T|M4aF8 zoQ?&}!3FX-tKOojm;Y9+MQ5McGD*EQl7+2BRim6kJ;Qs$gLDris#|6+36Oy)M%Quc%M4^|)Q-HoCi=R{| z8|A#3C<_!h;J{zP6hQ1rRuN51=$0MgRVuu8jnRlS|D+KZVJ}l8>N#&t|Eo5tD3JOs zP`LH)pVD|z7ab%zg%0(*&~TyG7EymiDp`z!cza#?`)8Uk%paA<{onso!9a3@+(n;> zAr46O(EY10AaTaABqN;klO2ViMn!P&cvrEZPBy_lcUjGLoNa|Q-JEGIgJgt@Ig_!! z!T~$zL`4}*OnA42C=gP;5eJR*HF#PGWmKeu7*3z9yNEo!j1j4+bY4sV5-LrBJ{yB- zpGsG@L8lM^6?p!qkaXBr2MHw?JlUXi(MDQP7?X~pF+s>pPWE6#{x&X z(Zi}R%;Nw|A>QCfcPG3!AIg@P6a!o=mO*cK%jbGV`~hXg=tJspBqTpzMm<-pMc&*? zE2*zWD7xMx_f=+fD1pbNk|N$L#m3yz*?9mWC-PT07IB+RVYwK+(J`^A4!BFmnOe4Q zIgbuu;Kdt3r+Kr0eDP5;-2jz?dcb6v%IXl==;h=FB5`QKql209fs>o)?C)O;Ng;-f zy(_x)0QOfF-JLE03$NO|FeS}sEqz1Cd`1*J@nbS|wB9HDQzS@B@RJS1bSePJS7leT z=_Llt%W7G}F*-liAa^`DK|wV_nXRJDRZu;~NiI8qw8gWu7mD#_T}-fv01G!!dhpa| zZm*0;lFw?;i9%`-^otIoGV_fWXC-9at`Ca5(}9U{z#;zxv_c8B6XH`Xw*OKMm59OF;9N(ZIydk}_`$q?%Y_8kgw&UNSH(z!5^Z4J?rVYC6lS_TUpuUU zlO>9)a|uj^Q&~tdI^ei5Ip$;*64C{@HFDPo5Y(K}xRzqk1xx|uGWc;;_ga8tDh$#Y z{L4bsIgmp@PC(TGvs#Z6K%wx>W-k(Q3b;B?HhnqSfh3r_TkS9GX$zE2$6|u*3|~_< zkHKJqb)CA?^w;c_$>5(Yx(74UWdQR{tm$n5ie!TgzrVsF7XYvR4*(V_7s6~ZD3WA) z^zuSx_@B&Sp$jltrha3R)i^OB9FgXXs<}!t6A-Orb_w1Ftf+b}WW#JxtX_rprMh%Z zB9pl!=2dV_M`TJ67`TP_uhHA659hWrnR|X^2{ZQmdKH;R@+Sk%<#A25RrA&n0}QG# zEH!Sk@iBgNp%i*jv4Bf%g6EW#f2EuUbJF`{`oy5sVrq3$Mn+7`>D7hNT ziSbD;ItZoee*$_LcfY<58T60clX#+D&35HbwQGLn@(Er*vjCSPb?j7}u{M<8&edZaLgx(VPoNleV7c zKX)eNyR80DP-O2{IB8eX)J-qY4zq}MNI%-GD4;XHbU$=_@Ir(%#9>CpM1Cwu@x;r4 zHV;4GeLyx{UzJt&j-1rv?>^w=G&QL{hRDFxzk0Wg)9`%g&o|)jrs}ORlesoC*wTg9 z;(}!HO>J4IbR0Bx_D_-WBl>D&W^BDjhnX|a@a9C(W3shh3Ekc~qUqv4w$kNWP!VBo zgmn18!#7-EGVI~^n?wtqSI9b9(sDO{PFVlYSlvH`#t#Qzv>tJh(_OE~bhgy{)Kdyk zEquoX*q&w_`$9XU;ruk3k*Q~3y7?|m-<>z1`3PKe)H5#0M7q8`j?0CzKE+?mn*>Bv zr37CEsX-cO<}9iEb5y#WN2%k~dtC@AW>V8c!cCBq7vk;0x`DL%fRNu) z!~CW)%fwC6$fFR4mzYAfr;;v{)r=e4!V@pwmesCV53E3p)mZ}htN@-=tVI;_}3HpqT2P;x*9?CiP_dX3XC9HIwx(`jTBXD<6A#J$qFMjlBO#2XV`GaD+j$QtCMR zowSG7{Y`Tq?CvVY3!+574w~M{?-ttw{6Y7yZ(Q&GjCrtv| zXU)k;DBV&+l70bA1`3sKM^(dlwx{P`dPHHa^u^jJ&a%Z?-T!NWFLk-Vmr}N&l z$Mk^oleb+{=4@4hKn8iOk|0c@F^V&Osudp<^HNT8<7;v6wVLVDscXVu6-}W=jM&+l z1VI~avo0665FNn6T4&dGVYy*Yzu>Qr#ce0uOvA7~<;+9wJpEsbv^MEKR#|Pp{1cH< z>3kn5JK!gMj0|U`OOvcRlPjJKju1_QEGLs2p2fV%l`V+YQ=UF?Sm(wTRHAdsoJgy4 zXS>i{AI=ZD&zvt)>BMr8l?;*iv@Nteb)^YVBif|<0&p!O%MWxx8nG@_lU8jz-g3*F zFLgDTBh7b+HdRgNuL}FrK>UKO^8<^WnzuN9CRv~%##FUD7zJ^jwnYo~y$$357J2OX zXt%IDI4e~`CKl*c*1;_#7Ex4O0H(xhR%556BpgauYOGlfrXZT6`-16;o4#*ys|XOH z0)Q2uYOoxR@6JjjGj1{_y36?;LQPrupkb^MA41)-cdtPuL<6v(1gmK|oZ8)y$dtW9{Bxq`AA}R5K4ff95_{y+8%r z0cA6Ty*4Fe&|-Bnh$FTwnzxN79f<(}UR2OQPi4p89-%lBDFup2h7Lk`46IgyhCNkT z6XR19>_8|e>t%wcP(qyh4fS;@c%{}+F-ia!xZm*(#!WkjM?xiP!{%q1SQ|0?Aq0kt zbY>k)jPZLoLl%9%j~}yO9a~b@$DnRE9gDgDr+7_wCVgrge{n1E??}qm6wU8G2Drlq zp>qNY_o+sdGxw?UWdS4fF0yd2SL$Df3dkeMhW@iXHoFTFhcaQ7{d$l9urtv~HWcPE z2?cSpwBkRU0;x|8RC%B_Y06>ak09*CZT8|Cq;qgT1PFw@6uTh73o7Df#BVP0fgmO@ z5iKeOisRu^_(RkPi&6K!U;_`6^sFc83VJudJph+gCws~3gppna$Pt%+yxX8mxE9M)h*9z<+nK4 zvgnhN2c%-55>08}ww2WEIUp(XV!XhlwJHDXJ}z#leR!V-s3voOl9i-EgG`ATJXf-d zia9yK&zQ@DTP&&QFZ$0Q3R6&3SgGJiBd8|gD)SWlD$V}#l($^yHo^Vf?L9x}Y&LeF z2o(Bgk{zyz*Dh(@R%B3lNK&U%xlfv>4@hJ9@8tqZWIuE)uFd|?<*G>q3;gP$X#U?g zFL02x1je%k5QYHg2}|uagZM&%n>T6YbxTz&raPiwRF4v;{DX*!BUEV?|4IuAPnA1A z)V+ws!NXnT&qrE(;MY6Px1+!;l6K?KMC?mPx25^Rkmo0`XjdIr_hMol*KV3#T5O0! z0uRxCWG`kFh5ZS9%*c+=Sxw3DqbAe+_z;xG>2*N2RQh^6v-*v?c%1mD&6!F`;kzSMdemCVR{I^ziAqWCdx2D5@*^7s6&b<6 zWF4Y_bkW$q7Vhy%;pKhG529340zZ3kv$Ohl2XB}RklT;V%$&TIqSY<2=C!GU!wye} z!ov+O8;7S)3X-m;w~Ddy&HDA0;w1^~l+_Q2g~}Y2jn>@O1MD)df9MPEYU)q@k(?h2 zYQ-PUwwrR>6di3x9=)f8_f`L*XJLzN+4np1-44+G;x;6HyuN?FU48Vcv~c*zUv|O> z$G7QzTg}h88s2!PZzgwhxt7?XaC<7BpKi)*MJF>}s(B9ueg>`&q<)C18JOT3+F>z# zx36Qw^8Vf9Gk|IHM|$aaW=Q66 z_i|l1dZoAZ)$pfhzAqf*)HdW#vFW}wPCXgY0Z*4#5kZpHl_;Kl)&7-V@#u5~TEEsc z#7UjGEw7Hec{aN4cCzVub&AT2FUHQI1Xq3~IW)1_SgW#wueN@B*Kbr2aW()Qysitk zAL&n37Imzckw3rVb&zy>Cfq)Hp6*i(8m_&{+e~wnqQ1JL`ZjeSc)WDF^QhgX-u?+a zHT6M@dsn%PYHG82*zpKsd}aLFoH3%4*=^-KL0xM(On5X4bPDS?nOI@xGOICcJ@w?0 zEvY7`eKc*?xr`qmxdP7ZQzS?(RFId$Wp4*r3`4~q+NKdmqq(!k`~l5tqGn#_8Wf(v zcK_P14)OwVwGEe%39l8FPYLWRn9UI}t5N713C&3BDEiDa*YdGex3*^rRL5s#dxq@a zPcm3gGwE}=4X?!=I;Iiu>Zqm--W(8b#4b@<0+!va0GoFuz+uI!%0x)plhPLG7dq~8 zGH7To#~b=gHwH+~Z2pD)zpjel&rg=6VX>2}K~r*UI^p%9W~KPtK%2B^Xh^TRn6ABf^}@zAi;k&cx&W%=e$apQkA(a{DGj;bQt%hMG0(4zcBgBT69^ z-6N-w<@HOe;7l7Z9x~vqKIY4kn8+bANP=2B+5t%#W;k1$vgqj>m&a|X5<5jXcPIs$ z&{Jtl%ZymQK~$o6{xI~#H>m~svjjM-e|*KGTv0Rx{<}6PQYN04AQXg+!E1(6geW=3 zzaG`K$vSbI@jFwVK#>8CYURpbb!i%2np(z)GSS2oF#3u-pSujWrhmasQx$H;Y&7@$B5t+ zy9S0_`-RS?c{0q@S6~O~oB{kOc7SeoOF-@OG8talNel47%4w^)J<+kadqAMLEZH!Q z(oFAK(YPUwA5>4hSr))CE>CU+`3Qv45_FQqrFZ+UBi8BU&!fdfpeS(rkW1VNGvd>- z`9sFbF+K)Jfgzb3Q2lIb1KR$2?fIP#`UQmhZbZzeG(u`SV0fUQPUb zUx;)u6C?*Ug6oj#)PDf5<^;;wQ{8a~@7UPCR}n0Y^1i*3eR($qZ?$Y;dkE}Ax2Psa zEo85bkKXihA=!!Lv}axO3^BWhN8Xc`+_JGA)z`G7he;K^G49BL{q@Jc3&R zB;%&XLcO$C0oh*Q6B0J?bis$!YoS{l${>!)CufGb^=5Q(qERyWvC|MyJG^qS<#><>@#tbOqW3qKZ zm`u;qThZ;Mu-bl5Yf+(9?i0%p4fmRGv1%47ZXDHWqE;BNAI!l-vPL(NAv9+BPl_Ax%@n9Y z$sMv_=QE}^F$s15*DS~77f8daQEO6+}Qwk`0hFPocm*7wx+7O`sv=Csjljp92AiJ7^f`# zz2(MDYcR3RE9UHe+O2#kWpP<*KijcD8!@{l$;ggI?hi;!wiM|_v)Ap+bT1Y$Nk1I* zR3%}?XnMelscdXlm=|h%rdbLN_-IF|9Q)%9foe+WQoKW6kIN;EVb>?H zIaNejbRr!wWG^~W!gdmlDudWx%n5AfCe%8>w@K~K-IUBeT9P_ucxDVwyp0jREWr{T z$j8F`bWQ4XJ@4xKojiC^R)K0ZcLC!OH8|%c5XbXpR}1NKCjHKz+$Y4-e}XKV1y1Gp z`A;fKDBCf~@g61rmAR?w9K3#+rnQZ*IF8~6gCH|a@=xs-+%NvjMNYxD z{?jqOWqJxFspccSRWiJ7X$HGZxpWlN@*K0R)#KK@6vaE5S-hras;0YQ|B+cEb!)fR zRh~W3FB4A}UibKU^b`Gm5DvdX1pR-`-E@n`o3j<<^R4B>mJ`=%D&is=^js3$4~DN_ zX2q|H9qxF)?C4(^k$D}nJ-f#JX=0=)?*+zW!Ie@lyKnKFLgD>EwwEC5r@Ejd*J$(g zBR;-po(A@-2O$yVjjG=lGQqGH{emA0HeD|$cU$PgKJotdt17tUrJ|OoIs!<=IVd@) zY>**~x$^Af2&4Ngcn$y6{&>i_pLyc(sqZG~CUw|+aKkVk6||xxb2XTg_p%>&_+Sm2 zsFAFEpZ#Ih@g^OY9uW6V3(&zpP5OMq__$uxS*I2F8?v-j_GrR-_OrH=8TA_@b?Seh zfWpIue%dqdgpj_wMWH+5u)a7=1U_Tm3b*BLhfO#58*`-j}kceEXNdNG~rY^r<`$N64CYu{=c z;)t{FQ8ss@Rz9Ypb-r2sJ$8*n{s-^pW#!wt47gPQg*HU1 zL>fh(!`%QqmQfl-umag89>ibyOB7a5q6cLJ)JLNc>}!|A)64}%wX?bb_jqI*j!<4* zu_Po+I|1p}Q@M)mIH)z`2!s4w*;N?H1LAX-D7tXV0ykx(mk>$Tvmo~ACr-hpcJWj8 ziL3Q@fa};dTJCP}B9{MNypB(x8;3Wt9P^`oq+r~&Z=@jpU$w{rC4YKo0YHO_0yL;7 zK!b|oJ$xoN!v9-IZcTl32K<>%Cs&TUmM2$!ra_)*_SEyO0=1tMJ9<$vZVuj%Q`${? zKC^wHK8obWlc;TY{tWQVm)6zoFJf7OXWl={nq#CJbcb~qWInSs?#;@5$W`)(_di>L zn`Hz83rN&8IING5UzLv$is``i7ji(bgUD<>*jR%E7`DRlu^273QmY~=XWod(%?fI) zw;P#VrgiD0S(tD&2*g;90k(n>i7qzx8AeM2WzD~p1bG-`I(L$Fd`yYdM_7#URNoif zsVLoT+~LI#%iUSllAQk;T-RWS#Au^|jQ>%CF3!bzQ?!25IP?Sc-!tq1@mfA&L5W2| zHYY!G+nM>@3F?}PQ2Bv=&#-RBw(Z{dAN<&O$rNLbmCIIByxI;DQdwjqO zTBIri^RIl-Dr9_`yEDarHfZ&;HfNwu)ofmipQaj*ie!dT9_p4=@9P|U*&ahrs#m%u^z(=P+e)TMqpl5sr zZ-%J3Ll;V#u zu-J9&rDqjAh~l5LT>lbJ@cf>8wWl#2G_~fupofc{|>dUIatvN@oByp|Lc*#9gP*@OFWlvw1MQ# z6S)0ODrUYj=TP)k<6;_#Q>HscL%%tA_NFg@6J{H`mK3&lETPSjoln^uR!{Kb{TzlE<8>ywBhaOCvC){_@=Xfet zG8l5z1qRe#lO;YMLH2D!K}M^_Qhc;^^)#N=dn3EB3MG5aU%Q*LYXc^@ugEs4AeF*v z4{Y@fC2=_;wKWm-r40f|DYmwUChuC~j9u~-N?UcmDrogiB1UO64WkY`9EB$SitJ|A zFh!1M(w_a@z*QC(Q$}D(!^=ZHOTN#1Ou6i~CF-O>bR}!uvhOS9A~?=K%-K*6xiOO` zSr@zaBskQ5koSQ{t_oDp`T%bH<0Z~DdrBARQNo#@?X|qq5&WvAw#jyB$TN8RHAi8| zYsQY4z!SRtImqZBwHn`d^0*Ux4dSBUCwk*(c4*fN6aV+oe-{1J*Mok#9kqbg7d^OW zpQ8RO4(vXB>1nz%uD&JiY1-6&IX7EDNn44x4mj}LO+GaYE!T22uH)Y3MLAV^<@}0{ zaeoZH&Vos?jQxE?WgUORu1xHXpa=}RBXxwLoijx5!`Fqyf+BL+mg`3znug2RkDza> zh=ZH@OBb^?mdsy|6equ>Lav4xPE{tCZUpJ=(-STq#dw%idsnr-A!f|}HCjjci}6P} zn~|Q_C`xM>DD({&Q~$R%*IInIv7#nHL+}e%J=(d3z&J@bd2h4uMy|l#=okcZs5{bw zLFnB}B9?3io4uBUIp`gOP?b=GDki{st#Vk5=8IMG6XnYZXqG9S zv!wL<4I6<({cSw{YI?5GvVY~nR4Rp9j{Ye~o9&m= zAWCE46a-`UDGa^rS}=|f!EM5huW7)J=WfF0J|1P4?$ouMvRta@lN|Q=LeO6Qqmm%= zxm)*hJB-cG`sWqvj=spx0o{^+=2N7321K&lS&Dzrpg=>9tGNSsYsa_e9sp<-j1)wc6M(EDMN^9$RFvIGivQTMFF|qkSs$w+B>=KHf-a$n$cHhZvHO}mL5c17 z9qP>2D)~v3cZD&c=z}+n4D_^SJ4Cc=HZULw?|_KbY?r7W zU8f}E&bUPSE{D@A*ho+o#+i6qw}p_u(K|EcOyUlvl-Fi6AX>aUE^^#@wAU&(+h+clNnQ z)J)9=k-*h21Q4QyAP{3!Kb3NxVI5SRHjv_>cgnC8EFgVfuZcW9Czhh94m6clo*k;U-I;y5mt0Re)oY!?>h~7=C@s7-aj?wW96On zJd4=K5eoipF;I7OtsxI2+Q$>HdUpyI;F_YcA6(i2E=sQfnzfN^DKe4nJ!+z6*TDh@ ztg}=Ox>Y%C4n$mYRQ6U?KRSS!Q7bkb@BXK@2P=>JhTZ<{A@HRvSOLD2Gc5+V@tr9O zEb*PI75t>49T+=#vmAMy)4(x<;lYSg3`V~41`Y`$Uz7u2o*ew5e!qoutv}?*_8r^v z9mQbiy>>;&{i2!3yESM8OJ3(H+lc=Ec(Z$*QbcF^`_JT1ISkcM{x7e-U@hv^mBvu5 zTkS2{?3_r%b8rMKu<{GV!`L10^@W{iF|&RV@t}H3T0BH4uoNO)D-H$o!D`Ly(XFJ{ z-&m**%e#kkQbejD1y(78h_aMTQT80UdYjqosirgtJA3YUgX90rb5i@Q@ak{P6BHFo`$!+LeFX6-R;VH!QW##1rqCcBSj>%n_;Pts>P=)qwK zjpkM7G{xPJ4`H#)t+wly-XtWQ&45|`fUThrsNB=15N!^dwa80!7?fP ztt;cDfy<;j1}X1D{16D;5<`TVyT z>fJ15iPY~qFiNiQnw((%VS}x!h#8SmN1NaE>S|~w8PnWT*BVOT*x`)E-+Ai3UJ9Sb zw5ven&M$#+4aN6+`(pDqa6u=x)RCkvWkk;0=(f+r?(AD4OLB`5KTFkJ_cNL$C5qq| zqlslR8Y-oSP5+HL%o+8Yz0DGMLm*rMuCVI*FAE(>tGP-Ey^(bOPyL(IfxjWnCkk3P=Xm%)z*CwXP&-z9pXr zp1Evaed2-*ovE~n*-H9e`?Yef+B9BWNS?$u{W+vM%BSN#yR#zaWe^sunCP$gSgN&6 zbze&!2zUBIe*Ue~Yu%;z4X`qtd`A5+9=`^xQO{KrJ67w!VhoPo$?1RTFz_3sosQ2< zyHP=D?$@YE=to@2$uVQ88oaM5zhQ?OoPbb$CnrM@vDyCK2?2_zt=Qj_><7 zRldR{BZTXnw>38K;E9$kj)!aSEOS7F#GLGUmjrKANHRJMcv;x*y!T?qr%)t_qRSm%5(2mR#Vf=~&V|h)!9d5`Rk(#o3=b zGoUE#=GUr`W*4cc4!a!Tm>xd|4~ZR&T8e^-92kg)Ge}9MLO~)GR{(P74Hl`|MUt`8T!orN_(1(jG+yx3o;qZPQ1}L(WTHSekWHPILekT&rC9v5aaee z0s9M%SoD6W1K6psyoQOsfX;DvwJadl`HTQU&6rMb9@N&5hNm%v2W52t8>(T_crSv` z3nE1$yuwG>ra$Cs8RTAaZ*Zp$@2=t3+6^Jhp4QU^8!qOFPfl+Tll*~pU$}xcc0a9v_s|M z)le03FUe2k9|qEUJ!! zpeP*+iZ^z^v^|V4g!!1L7&gmBBw(wNU)t(}oql0NiCJu=^m<*3C3>^ezH?zOd^uv7 z&1%#~;|dr7$3{qul>=ZG5?6+W#jD;$;K%FG@b zZ^;~LSWlf_D$?*GCfWOim5vRb#i;$p>t;hCg0=*wvNSui`pEk*@w?ev=bSh0N3Itm zgDXKa0#yaqORV-y&1<_81ap$b88%y}EAkILYE$=9JFNtBL786^j<0`}S`#IeR~uXc#JRn9Za zX>GyReasIr#Ku-lgqv1_={h5Gg}OBb(gPx)^S1i+ z167jw>0<>%x;ozbQ?r!zcY67|$7)hb^f$xxWLMKnDD^bw>GFFCiuN>Et#ZNDZSv64 z#Tcb}0aqL(1pRQ)d$hYem`v#8_ULzXm0zX*NbFHmkNPN6 zIV+}Z2nrwE%8a&k<$P+z=dkNoSSjGk_ddfI-wllS2a-B<9hVHv!pO(R;_iwuF7va(a%NIff33@wOH>n^#kmXCs8 z9Ou%v42lIy;ARkB5q?69iLG8c95J|ZL~|e-C|n^+9@c9Efzk|Xr_I~!o#$e3u500o zD^@Da)o&(eCGey8f89&RNnuanO9ef1>Pv5fvrpWY4s-rFFY6NuHhpLSzu)Z3|GWCp znoUwNqeVOXDFBr$z}@se8RCkLHwThG5|{^!5GyGIaO!1PXQ3;HT;_@32=0;jzwrVL<9AWP=KVULe?xtop&ha-1JqvrO z^pTj&3062)UaM&{&f%1VmW3TS{TM}b&$`#d?v(W3C3fJa5S@JJuvvmE#Wq|&LNZjQ zW}F#QnE0R+LCiL-HR7memqdDreN~JEn5@u69|{z{uR`&j`~=QZ!*FBY(mLnR2E2i} z@^>!!<2YN&NE)I12Z87)rCd z`7=IU$+Oj5OV~wa9EURLArl2rdO?ikRI~Bk5rL3L>*%hI%rOXc*1d~DyJuZ_w)oX0 z_R`j4vFww|UlW(P!=E~Nn&RU)>xJ!53E_{j66I#U{ic~I_Rtp@ABzEqJLr+K$m^(Q zlrj7wL?K;e@m+X3TGUMK`k}ma(%kVZ>q6+0rANeUg$6yMM+@8H>cI)Ul2P7O*aM769lesR zon^Jqa&Us|oIt&TMee^`gL&pzA>#Ye17fyDttv;odFIDm;`{LXVp$6B4*CdD?2lF0 zfxW@NG%0pvpVnIB&}M~M0a&sic8L$<0XDLq0GoIez-CS zOMJd{S1e18-iZ?75!?H|Lbk0{iaVb9w+~L<=v%%rN|?tSeaML8G~<>|0}Q;N6j=i@ zrzvXJN9M$@oey(z7=_hC>CF;)1*3ebuo3G2AfbUC0XouP?lPr7-4kPUE2O+N6y7qC zxJ6cAXd1OT9f|jnt}jrWc>{Ei`P6n^??7i^*LwRbrAh0VC<@ULXej5Cc3kCzmlr73 z8~!>-glanpaDLIa;l6)x*__i=-T3dSmRkLl6XDd1#*UnlVR&kSmsW-1wA9wRQhX@( zC_x%XLsMBwWK*gHxeagu5<*DGD`t}11Tp9D2};InBQSNGcuo|A6$0K31R2?AT~i~% zZHX;#yqG-2b^W{T|#lt2_e zU<7!|l+%PW5{O%;Ta=IbFN%?D(im?G3sNFTLIvMSa=&BA5+dgLX+>?ZVTZymEpwoi zZnsJ#O(#eYK)@V33lo1WSrgx7da9ge(NCQ{|C#@cOk}!6!QKPHP7Ae~6laEN28UqU zY~W8882J}Q$}fv(eLY&ZeLEyEcl$OH-hTG5D1k$fYM`+B(xc>vag~-O<3a(<8p-`I z{O!yxAagv&F(8v?b)^NamgAn6pgMCq$x^pVev;JJPB9>#cuRlsWtZ<2gD3e_kp|w0 z%llRO@4}sV7?}c!L4VTaNw?%Y`>mKl0}jd9s&cAQhYnh2FRV_FXWd!cnQOBU?jy63T~e1u=2yx}7pEG3XpeNNEUWJ#=KGjIin+h? zXiU}Y!4>(0t@9A$=w6;1RCM(~TyjrFYG0lk7|$qEp8LGoSaOftb;~h&<@r7;=>e|c zu<3}M_z)A#zc9Avo&0xKuI8j`l3z%2VJv%_S><}F8hK+5bbTR;yz=dn>G$4Sxr|%e zfN<8cILLSq$JtnR3@hlL=PrE|;Zs)40Jp|J&(0jFM1UpDb|V+(li$R;RCMub6IHI& z!R=dqFNHS$SP#2(?KxFt(W^FsWbfpXv;S^7I1YVf$_6G6HZ|ZMDDw+{Xl$cjm5!-O znKXTOK#$MM74B#Sn^t0}T)z=|%uejErc{_-9W-d!!4}=j(KoB{*|!fgsqvXwndzpi zd{IeSV)d@lXZ2?4r(bA+%T7;DLtEp|oLkY33YJ2R6YsOdPMaL_FX97*gJqcaKI^7HDhmE4-)Xq`BvThm`f5#GXn+$*$Nu&AGygMf_7#44 za0ZxSF98lP*`{t>>n&NL=_!E`zV(mdw|;TVeckwg?C%#~qZt<=u_9GhGVnA%C1tC5 z^WbMJAh%0XUxGLkIOXzRj8)bTik6T#_^B^=_vPmAzSggkx{`Tf@u#jQ^7CYhvw^LB z)l*c+;&AS)12r@)t`X#G`yw~n+O9e95KW@OV89BGCZv?KmHD%!n*N5#uh z&nw4n_1V-+r9s5C3YXAI_O|EOUUB*M_jlSW@q-?+iMyBofWJXM2`7!#Q7HUpVSEL@ z_)bYjzcT-RwU_H<6iri<6^0z7-n$ap^*!U(g9EHiIXCaHVK@?LKzLJEN?gUfu_bPz zW-4_g<-}D7HmUk!ywO5b!*uN!m|Dpc8*RmO8sVNc16Ti}xjIj{WMr;7>Ne zf7hm{kJt2LqW8~5!hMzZ5C8XkhC=XEUYPffYn25{@MHgEYlc4n!;eLHW<;&rO-EV9_Q_o{fVcj^v3n?@3?-`F;g&WYEF&E;}8c?g5bpM6Be#i~^DHdE~58XK=g2YkHYhrcjT= zeJ{wKvF=b~ue{EF56W*fuqeXx+v;GtcqzXEZT2^NlAT!zmEx&Qo!9hL8OQZori@V? z2CR|y**fpP-!njq#b6bR59LloGH+bD7~V1+_km{UlVlU1L?MRx$({7VuEkP^_`h!2SpA>aG?d1wR)=2Rgp z1h{=sxax!3>e+1{$0~JjeQ`X?kxlC~{v73)G!4l)S2={38rnIu%OY2NhD*3rw24oT za@4+=uBc8|(1$XQN#UsbQk;X4Ar|>%$Tsd^3mfH*UXn)K&CC*)ZeOCbs`cMpP$0ivwk!B)@ z&h-}!y<{IX zH)@yZpr`C->7I$ai&a>q*$!c?mBU@XH=z$*50 zL-?Z%9z|xYcuSpd>`RZCerBuF9sT^YKCX6nJ2)uZCUowR0+fNI7Lk++kh-dZ%416Xc{sjfNWG4DpHE8Ne|Z} zLD?>#0>yV_ibZ&6kFu%hm+A1n@h#yovYx=gf_DHPc+f|rot~s4?F$Ui%PXVB;YA!IX#_U8#~O^l!D7K>13_r{LNg|1^I=^iA-O?b z&wn;u9TC_%|L7=TFl=;?5raF_=V5g*$|z2k`Tgo|pJ@tO2_fOT&Hs2?-u?)gpHE$O zlu9=Avb?reG_|@Y#m|sP9(FC0mthy~v^q@#sq=a?2M_=2v6{LM ztJh|w6k*Pe5Mq z`j+7+i&ZJPD9_Bw2aLkov8RXNmo-VD+(#dNedo@t%-Q9-#K9tq!-t=py{X{@>qP6i9+86wi;1`lfe-dPz#q-bCuD}5Myq|VY3`V97`(r^JOwq52 zs+X+Z?ob(;)?D4Mp+$#kJ{UZnTp0Z7xI=FIFOg>4a>1k~E~ir|dMsK;q?-L~O(D82 z>Q=q6#Xc~Mor9#m@+?s@ueM?K5MOffw&v6_J=O_9Bn!76GKXS|H(vgZ*psG{iE3V2AM}rJb$eK=>j63?ur4mc(*v&VKlQzpkXe+z(9KKn8 zaQzcr&zslHNkIj*CppSe4?R`e24~eM80FyIcc&w5!iQJlHPxEeWyNnYK4dhs*h zjOAem8jPv8#_t{<+?+7hT+8x1H^)?RLrjCJ2w9BcRdjWX6s9xjKp;?X)dl2oX^gs5 zQ?9!vyjzUwF~vvvUflB!PF4ZE^1R@K{_Q=X{sp*_vSiXx^P)s@G8#!gZEO2Cd46!5 zLSofgWrAtDt8nt?{+-i{&+0}ny#meIK~;0jHe+aYrB>mDz|3IzgbP5L9wJwdEUwgI zoJbZhW;(Ef!WCPMU~F0`0#S_R%v459=Kx7Qr*dMNb(ma%Tmdshk3oHQ(6JDZgH{5n z5>f<=`K48~EAB;%U}Xu(0@(cVs6qSPw*w#QKY};YDkrK!z0RV3`9tLZGd|>2Cd|#V zIPweNSwrce@1IGTwb^s?%mC?Q#1TF8*;p80tmEZ#3+iV441mQG=Y;*|8D+X@^a=5Rirz;9-C(098oVEle!=c5B`tz)l zgQ$YWOtoCUD;;(L5?XUnnVzx*OaT?XHK_x0SDW9Pl?L`wv&H}S*!Tylgu6^9gf?4e zkWMpO*1`9N?HY>$66xHlsAFj`&zd+-ENCon9}eJ^TRSm5-+5ay|BT?`GhFQe664PZ zw$&?E$OC4kmi~WcCUf5(I$GB&>J+d$5-Af|L-ixYjTmYYTxac6fKT+1m6a3h3CxaL zOp|DPfa$ZWlb~U8E^=C?be(RR4jpA9m~=tTFnJZh0MHx;cm|4=IPA*FPiFuJ!l;bi zqn$2ftwhrZ8JbpclRqfNkP4wghBTx;8}PO14CaqdKs7)m5^H?SSj0QG^w=xGx|0 zez>zbHmZbV7i%~RIr1}gYw(q9Szc*4CkdPr1Og-ZK?fM5=NTYyKd{Yz1e0Sa+s}GNntBjU?$;!lPM4Blj8oglMO%k1a3m3v>gds!7aq$DfN5 zW5rU3^%vH(-{&4gkP+{^Dj0{we)eKsMhKbGem`A~#m$beGZd8QO11@S!i4Pm5G2IA zueMHc_j0$Y_>cAs?ups(ZU?W$marrtKc@|KazWnyG$8_w+AVIB zI%|%_0`qHP6J`iw1E$#g&pzA2B8x}bhkq^w7g3_aU1q_#%zW-ZRC@MyZs*3SYtRYt ze)cwK+wCqIl2dDP8odQ+tNsbeX|9N$su3QWY5|>#UsYW0*9cEcZ2~)#cqN)D0v2jm zr>0tnZ2cCi_3Q)GWr|DO6RiB&{Hcok?#BEjc=|Y3yPek!u5I*mQzPAOaFJWO@_uJ^ zx53P{>^yr1{?3z~lZTqADv`g!1&h~_Hg~h)cZr*n89{drP;S0_mfId@1yW6hQ zL*|GJ*+Q2TLwmjHX~wG~1A+7tu`BLc(=12GZyhtsujb!|vs*XEnkDL%bBiwHHS;Az zJ)^FMZC%>Fx!qg}XS%!)E%$D{xT%okdHkrre?qm~F7{ol+qoZD7EkUnn_Q>R_uW54 zw7vSmj2-=N$T(8)lx5v>H#-=4T!OzR?pk5>8!?VT&s^B$6s%ZPYK@e1z6s509k+R7 zSc4z6&vW(8=fAP{70Ukp;E<9294dUso7{7*ZIMxH%wu!wYsO>Wip-TXl4O=8*F!|RQ*wavGP z-(_oQv7bG=-cmrBgO@5c;q9PY*^uEReE!#d(;)PlTI~T>6*k!knt~QPItT1oUCm6$dYgDd0E2QN@yf zQP1v+9WC_QUckx;4EW@Fl_(C~+9g{Gt73XJKVKKn{wiH%OAeJt#~AK*(U&WxQOn;; zXwgGfSS;04UW+$~2zW4#R1`cyr8X12`{&3wCQKA-&2Q*_9Zza`Vq(jfAdh@3L&KI4g9%m%lPH^GTSHMqMxl$<2a$@XMS1CHDt*WL zmQxq{3E?pqOBPHS-`u|PAEXUb5%B)!R$|3-s-gEjA(n9qzeDGIO;z)KiQkbvYTZ}m zJgZ92@(rLoyfhc_ZZfAA71TbDxiKZa$9%u^Q1?Qk$dQZdTes?JLGYS8phwtE1DWC^ z-F|Rn#0cF|D8mD)8Eke&)i3ZTtB5a3!P*T63vaG#Zi<(i4mt~igXd_j&84r z0s~!D@?fd|Lx3P$h++~MSmP@}N)($yN@O7^ArSnKWiPxm$jC$5L`Ov_B7_U1OicD9 zkdhP=-~m-2$tXXP6on-Cm+;sF?QKLu_tpo2_C)^*7O;fGaH@nd+~^OTjvFSUfR3wV zf08;7k8&)24YE!x00U$vc}!&>XQHjF)xmsnxInj8cN!9r1nuL9-&(<7i{Dx<_c~G& zXADW?E76$tf2)|CR+sn+J$ZQ%?HfGF5bqm2?G~*&1mb0h=g>P9St&Y_e?%{pb97>0 zG}aQRCS4^pSSt5PSlcR_nKwJFgf|!ol-7clk#!&DBsxo@rkyU81~CpU|7Q7evBo&k z-QG+wMA1^n&4bS}gt_FJHafNmGfBrrbK+khuu&`{(VbWr^0w}Uun3v1=7^v=t!RS8 zmlo8F<<=x_J24lU3eB+{NHApac$M#~& z*5tl#toiAzA$WMqlICv#GJormCShZ0x6&v5+13LfTMcV5==U2pv(+WB@Mg1Ls$CJ| zvlX6}1J_7$Yb_T8uZ~pDCFI*rlvb!E0x>5xzCZGQJiN<%#dW;UwL2s7Ez&yfuXu%k z<7D(5eYX1@Eb{47&DF~zsLda_4x7pWfyd275zp4Rjv9oqM3Z44()>${`*XFBAZF&u7AnNr zXPvXXuO2T9ald-MW3|Prrgl;OXeuc#7AisAlNC4Gr3p8|pnl~=#QmltA=XdS`$1W> z+B>0-Gk_&=ZvW)^aY$>#Yi+yf0J6QC=scGY%HU_S^|QA7jthl2xQ+^ab{LyOC6#O1J&a^{cXZ2xquU-|lQ!_c zscXXDfpXnGzFozQ54G8dk8b8W8V+;AMO!*Qma;)0!rdBn^8ds3?0Na>m_B%|?y!3I zm~6Q~ED|B_HZ_WtaV}jE^3TtU!u1BpC1=BjVJNL}`5mTE9X7u@@~ap85K#SVRuy%5 z6a}q3J>>lsyn>KVTC)sBWJM@O36XkvcH|+_NJA}n4DrcnUx_9S+)-G`W+J60#gTyU zqus}Y*Xv6P4=zQ#aUtg#SBNURDJLB8pLb|>THUJpZ1TvFEiuZ{u4T#|Z@JEWI3ilZ zDaU{QTf8qWl`pJidum{(#hp_oa&sGRn@&moN|cdEQ1K}S2?&e+5rxX?sIh97Vn4x& zzz7{ghg1Yv%yI5fPWRDhZF#pmqdrlZp_E3)YL+GXNWBp39T901QN8%gC=VH4sRih# zHSRBLRe5Y>i%31>^p-T$v{?gKd@?aM5zo-&8#;VaPb~YE7}ZITahp969y${VdSO(~ zgV+1venxn;RuT`c4>R(uH8UNeL13SK&5bugoh(vM#**#q#S2#<_fl``aQe_U`1Kc{ z&!`6pPTvgUGB#c(Nb87O67S8`Yje_u$-H$39j~-1>Fs~jLv9eK4}qJ^!V2u<8Q)=$ z*EMsaO4HSm>r74c(YZA*!z#`D%HK8CtL4#l1@CH+8_F}r6Ga=MTTN{-){zgo2w8wg z@W`)9sm)3*UT`<}F(9?iGQ4WOOsPDMy5q#A^%skr8N4!8BT7_czj)zWb@9TK`{G4y z^@W`dHNEzpS^L!svV5G#X=(3lCDtc72?rJFN^DU3Pw@i-!N?L>9VB|~(&3v*?3Q%E z(PR;om|a2R!$p+MA%I^ znK4Zi_!TV!Xfb3&uuK^wWsO!|kDnl|_0^WR+bOA!`d#ZNtl(0vFrGNrkl5;_Ikg3z z{YFEh7Dcp#v|Wc1Bqw4`LT0H_Ng4U8G*a}@@BSP|NDhS2b8xE9cD!L47Qousz>2iA z0y>ouv~^76Pb^b5w>=6$wn>Gcz4GDfVL8FRmq!5++p5b>+S(8Zo7zrZr_7gTyp3qA z!-T)Ndcg-G^!L!2WzmjjE4%;|XG}BPU5Uk&zZp_MIiH<(+LLM9l|{KsVe1R0e$_C| zFhZWKbdD&YwwSb&Nc{e*e}m6=;jdb+gJ9%Xo~sZc#6x=rP&KFMN>H3S!kCQUXGZ?^ zdxXhp;aKoIWO4-*pm?xjNsliWQKo8covj+;m99$bTBV9LrAm^U1Q!;hfW-f4jlX@l zc+C%^-ZMNV0P--3DoTMz>nX*ZUZ!9u8DJO?`G)uiguYVR*cpWDlva;dz_WV zn=u$;I_f?bIz#R#-D^YOuAxQ>X_&14&#Dr1c(&%_2t|4WX=e{2urSUl@y+1zRJ{eRF| ztF9DQY0|mVNHdUPE`N`Zs$u8;xq)AkZq8cIUDS3Ca{EVzVSDgWnAI-*3P4`8pKC>0 zA}~Xma2YFYPlO>jBI})Ii9B&Puc~}!m3Y{Sns1gJ5oE_#2Ym`P$0pA1C%8A|uAv6! znynuP-#ub3JKl|Se2eh^o!c^Z6uf+x>sf<{UdK=j2+Wll?KtL+|HE~&7@MB_&t&<~ z-MLhiRygivnIp0JAIZ&PH7Q};rmsiMa<dN z<94fmZAe5xaYOs|^V`D|s=rNC_rtuOfNkKLQ8xcBpj$Ra#wd3YL}g1`g>BV!(~^8u z(2iXLTk4bdw3M+IoxW@C2br|IO5!K+Sn>_PgJ&*7WO4ggg*;7+73)L~r4h7vX$+_) zLe-)tN9mv@`^a^qUvTi~$*ARp>X%Y#KAZkojXq1~oVgwdipF~rx}?P4JQkHy>p*x)Xp#E`^Kitj|Dyrqd^j!A)8A$7tY zU+d;{Je|dUS^I}Mep4M76n76KOHxS+RP5>niahm*F;$Edy@m2#=NVv;y?(AZVkLj7 zLA(+UZ1y>pts&=S1bjKrsfP7RZ!~|Ri+l}vh!@UtYPU&>7l-IL(s3;ibl%(o0~z2z zn!AnDrULnwV?}OqkAbp*pV^A2UJe~7lrkM{NYg(Y21}(oWPm!{v$ zygT@_{b22SN1}n$vEJPKeLY~|3#bo*(~i4&zV<|Ql zK7VJ~3K?MPKn6CI7gSE^Cq^Ij#MXM66w3;xz14W54$@RK~5zb>B>r(sARD{R8 zSZ2$5;Q^pr8OxaHvQ`D`tL{+%z~=|bi6q8|M2LR?inRT&h?;Q8ut#&BBV}8}ce}5r zvxfhrMvE)~S=Cn4<%hxrP1q52WqKZOMJnPGojzDlMgqN4r(fp7*<^)wERCbZeDa_1 z-u3%m5ssOfdpku`K0T6tWKfnMf4=bbXs>V2zbU{$WZVSnt#pC~wp@<&Iy6H6!`1x` zR3eG&|6eeb2mDTd00T&?-UKtP`~W|f*#KK$9KdC@ok+6d?MD1lYP3V;@>Tr9Xj#k#hNP5U`xS#j^;{APp zoa1)yb!KL-HJjP9;<{{h)h3RQq;mFruNnV?gBE17$-@>mp&08T>Xp!SjvKBp_fC0N zZIa|ziYoHWvARewf*lTCz6~+5i9^kLpcqiHocaR(Teq~)V&@3mW2udC+hcLK?doDx zlnceXAS(2QJ|pa!@C8MR^66m_>=I+ILavpSDC!ujrQkn-p`g4ddQym^#g0^hP`!N} zROrJ(0IbEw<^*>qlPiJ>li-GNALDOHKr-W%4Dbo7PwLuN1|S%xqRXRzFgOsR<)XkP za6(lJ;zY%*Nmitz%>)*tT#`bN46C;4nGAi;7`jFu>ywm)0QZHrZa?_%q#$k4&n)cc zc9#eUv+OHx%;v*`QeT4Z+cZv^Zp>9DNyfP@4*-x6Q7ig-%D z+LRcD31#kyL5}50?3$npGLvEfw5-?i^G@w-fo4j-O+13t^njq;C2aJE6=|v;J&V4N zjKd^yERlQzVj9x+wO;BxPNNM!qErtB-`W~KN|z-sBVZ`6`V97^F#cLR<<^%Mg=p0H z{CacJ?YD)!4CRdCeY=gHM)6~QDbM8kCQRJ3)1ehd{L8iR=C#Y`%hz;LKLnP^WJIfV zXT*JjEb03=6N5Jrc&SE3s>wJ|daYwmAZdXc+r5R>qK6PdDq=bUMLVF&sDh&i8IcMr_LbJem8^y<8FHp%OQ) zE9tP_ldA7;n$)j;Fa5*X1C+|H*Uj?^1^cQ(Z`>XY>&N&+XHvS4G6pTpOUg7Z?~Kez zt`_QM3wLyFe_IQLC#z0=l>Ud>XR>O$uTx3OeU4Iim9T2)=w{2Qs=PC-F(Ih6qX>C) zoyVFYPH<+~agz)mucLOOeE%0$FV4xyz~nxbj}@KI6~q1PTCnWn%`ih!W<@3DXhoLX z ze~QV?;{l~E61pQJ_J8|;Ilp?Fd|duwNn5bG9VE7`3YmIshos!Pd#&v;-Su2QUSMps zYu){Go~UsS64XEFSvt4!%uqggA)jwxE}edElj?t5y9oW`NaYK&DWJ!hyk-b8GVDno zyrchQ%<)@P)^tE^BW{k?3fx^VLeVfV3p23k(h%=Xp%dL?sShN(3g&)u_3qa!yFwDdrQ>p=D{#rXhee_AV!0COxtX$ce*D)dPo4SQ<1&?Dwn3ZY%DQW%I zo%B<^)+&RfP->0J47{z{8^X?!IoFdn8SwW~B}Vb*B?%ti>N7moBQq)AxOFJ1w;eVQ z31eU0405c9*)ML=!G#O?#q1Ei@}lz*zfJpcHKQ1x$hTI|EXYA+N*?;Af~wQc{iLi- zIuQ!O|8KP&W@|(~&{aR_Eqoec87PbDkcXsk&=_AXZym0!3URLzG#*v)b3O_FaQXJ| z=Gy;@@(SC2k$$|UU(_d69k-R8=!_KILk#&5yy5oGX0y=QdS!2ikiU#kW!M$hzj4tq ze^wmA@vIQFZ6(u(+=Egt>r}Z@^NI62nW7TCkLZ(N>&p-q(r?! zUogJZpfJU%M=g#?Q)esJd(PGKcbJ=d|NUp{GghoQUwJTE?J|>?CrD1GRjy>jdr>aY zJp21=aG8WhWeo4W387SIohJG;O_rW1l>0v(SQBway?pDDU<+#E{(3@pqSd6}h!>Ka zgdY?0^adjib$D6z9f}|y;av0#t?Tg$93bMF95Eg@1`{aBZt0LoIk1kuG2ZW5k;~CD zq}^?gdlJ-ikMmnfha_E8OX4rMwX4?%gQ7dlE=&04`a)Nj;?-i; z^kX`#<6G`r<;sH4U>hwvt{AE}NG>IMzosNa^nNfA&1)wXf;7M%J>47FlV`kzCPPE% zGQ3Q>G%*UHyfnEzhVae9BFT!5#h#faa(m3Y6xfyQC2$6Y5`*G*1TmrC7X#(mR)YU9 zGF1|V%R5%{WX42r*Ukr;w5`%5m#`svj4j*XNV4f2VAuRHBkDCh{Zz`#HYm{C72Y&kNQjl}SKN2TKd=N@~n!8Mwyg|E* zgY{Oq(1c@;>ocSbS-EgaV2V$@?x$8>K)lRo@ufO;_&TCj92XY|$Vuh9r4|q_ec|06MU3 zm5Dj5+PrZO+89YO-Yb zj^Fs!GF_x)bu@=(@(PbAosG6+nvr?}WFi`~G|EUIeo`kBKcNie;+8H%n63EuT5?qH zQv$Q1W9fl)^CiVZU4}k&04~EWPC;>Ze^c>F^%RoxSZXi<(+f4J--q%)EG4c3&gWmd zOAVZL$^YP(?z@Z_=3`bcrJkNDY!z4sMgXG_eQ#EC?%71|Toh zfYvIFH$dxUuEMaWZIXzY{thO9?O;t%_YUnZbM~cBp&cmN= z2_8Z5ytHb%Gd|K6N#Q9xE_PvY$Roy}C6OF`E1cPUxr>2j(a+FOFp~(*S z_SiUTXqjPMLH^D%4<0Q=F$LY;Qt)ure4KwLjTR{Y&FI9RyZ*$WHMZ$XTIX!~<~RrV z;V*`gMZ2)#Yx6X_7ldB%CySj+!pBkiAL|xL%tGD_y|G-|y6|k;{TCB%fl3tONwV}; z2nzdhRMNvQL3!j3N{S}fk&M$cmEmWEAoQy9nElTZ-bP~wo$uJwpANsFJ4(aNtFy!6 z_RP_3FBESPe^d6XEAz2c%C5VF6~vokTdxq9O#u4}b22A8?`L}E!Pd2$CS>LhJOQuQ zov$B3MPU&pnB z8QD?+ro26|HPrc2wDEqp$<_-l2S=JUaeGqGbpLMk=UOYspPlQ!DJAzw=AYM`Z8ZbO zB83JTy@wi+q32n_KXxVNP^m`NsR0@N9>dLn2CX|qVRgcYUk+Vcy<(IaY+Anc9g>#{^JZ*h>ziYUchP2BSG!^eZQMHxOW)e>yB z4fy;t67YQ&6)tAZu9wq!v=GsDxz|!_hy6yN@z2mdebYiyLNMKS5NN;t+(hb%URyzo zn|VqGril5OSY8{Cm)%V-^gb$~HTP=w9FH`+VGaLOrG8U*9Nr<>QUMhjHzULPu~3d1SA1MsY}(+J#|V3AWNMuiH{QhB1<6~)&Bv<;8U@x zuvNM$&xqrRoDqc5bA|_pG?D{DJO>hKTQwDnfJg7fRLunZ5m_+VP9;oygqD|;8-l$B zdlu9a319VSQfj7R#Z;Z0XZD5^BnioPTV{&Fq9h1ERyb=Io+~9u%-Gjj;RF?eo#NhJ zi85|R6i1b@a+!pNGY80K1MV2{i3uqxChT@A>ik0ZNTwz-4Jsx95=&}vNqqF-zj|9{ zc@Ff?SH&ga(O=e&GNtL}=^1`7*zfY`mu`nsZhiLJROJG+8@bC8Fit|tqvuu)j*B3= zzbDjT%xs1GQF2T`~q}($$wR^0&xvJP+@BJ3}Y_#kvA6 zO%5cq)OU78-^eB$WIm`5(Eq7xF z;%}Q){Vr9F)5V^Qf-P3WVL%xnSQFt$d)hlVFsK9uM+3t}lybl%O{}~(6kUNT-@PxD>$|X9?AlvE6;!}; zS)!Cc8i@nUT`HmK$uU_Z6I}to)_jA@o-g5~Md5^PjF*aNxIQa5s)A5+;aS0aEkK1p z!Pbbq?-Ovq$m1x%;H(g-@p_bD4QdTh&TP#oz_1z&QR?A}AVo0iZHys3Q?Y&7NjkVSQRaYGCl}zAf0`wICm}VQMC`p*)4Pe!Ja$_Y_={;xmP@{qS04P6~QINz^ zZA7Quiles>_ys_GU3`B+DwiIo-AWBi?#LX_cIm8qEAr){EOjEySYPM_whSteW{iRG86XZ$>byiNk=^Tb~D9 z@OQ7o!JB4BZ8d>Zmxk;4A$qoUHG?3y2l!AunwEcOtci2N9;%`wmToKUH={8+jMh=vYLv%$*4_CD`A9y?g-iqiKjf}8|5LpYAkh%z6GQwoNV1?^u zX{nbNq!AQIol|>alArzM+9B{))0Z$< zlQdBZ7;}u-JSp$KQ5)_LyCBaQW3f|u1|15mi!?gwo;~FYyu7CsZaMlQ;qsyZ64mu& z05xH9*nRp!;p<4;|2|4KONadJi3jb|JwCbB6I#wSqL?k2@O0(55YE+@^7Mr_Zd6mo zQzo+V*u~#}a!zddG9Nr&P#9Zu^e_noDaKsvkGLEvNzx{oPjrVN9`pAieW?ukUx({nHOVd&t+= z>s>SpK}0L2hLtJK_QMV<#Fq^}qwU9BhpXw@X?#XMJsf{4!(ED#^4xmXMc)mF1=*cq z041JmQkMDcj*lPgzICqs=1M{hCLD619@cR_)or3)2jcDR04dJAc|o~mN!0jw<3x8I52(o}OVj-)=?wfW?DzAEJ@AFU8gCN0 z%X53oF9VGTr`FK2hs=y_p>y`CFJtB!H!P>-@?Ud}%+3C+e9Z;$*KJxl*B4)N=?WeT z5p(t8rE~md{~9ezVU1eR*p8Y4MceRepe|FJmaY#RW;DHtoetjRwp#nkaiubkquEi`--@K~Lw8yzmG_SyF={N6=4 zX-7kS_C|oyO)5$A@|17%IdD?0i4uw|D>;IG-j^fU05%(OMXFbxsjP%-A=?Ur+68Vh zv)_tT#mC4hu{8a(V-ZkgwGf#Zlu^nUOqpUU79^Mh0uNS;^ZH|`(3zPv3xy}ya$zP9 zUY%&eQ6EpL&K0L&Fi}vX@CJSVaEK$UbpSrQIKqqhg*zB+l>mvg>$d?R+ux%Vt4puz z1Dac&vWplH=;KAS>V7{{p&BJ7+CX_Z51kfv%o^n|k+SHu8c3yWl;NUpS6?Rr*zXuy zWsHz1v0NP{0tr#1p#0L4D1mehD(mb@DN((XcE|vVSo_di_}7Upv3qjDfjqsInE@?V z%1L3BtPzW4b2?FU%_zW6QYGBpW9@%|%94=Jj?Ucnu~K;Qt*%SE)d*5yLp1b55d}8F zF7E7L5d{64*zSzaOZv$!L*7GNsl~n=?Ah!#NKN`+dz^0A6p|xzkbPy#EZRrT#iZ}S zgf-Ip?N<7HL^8sYo~0(LU$kkgE#3;k=5K2Zb{QbA(55B_1<}RStul~fF!RIa17NKk zBsWIggo6m+Wte90f58=FT)t`Y8zr22wb;3wtB+7h!8$$8;57Dk0$#J}n?u9~@Wx6UGB?q7=$(-e*VaZ=+@R;MbB}P{GmEMv# zQy$!w0CFxtDO-@$8)lAx0x)P<1{YM0V}NI7p=GDua_+*G$qUtUkU_lE#TzA?hs+R z?^%XvSQzXLne8h9s+iuO*ZyD+kHz8$65V)RWRL^%tr>uFZyRlAr2lQg2~yGY3{el- z;%+7*dmYB>dL;^TmbkK!xJt^zCMR`b1KVsoOIfwS=Dusa3{GAfB=X67Ex!8mwux8@ zrofhqH=rP2!SKrf09k67W*D!VW$3D-BYFutWyi$}TVTr^MI~wr5a$3b5J-kQ#IXSL zc_(X>!Gmt)xurwFAT-qEUWcwaQ1Rw(*{phAu%F&z0#MXq2tcTgkKq9)DS$V($`{n( zSuE~!*xP8RpnFU?XM&)~iCS}sH35p8x~4sx{9$^JT7vIyHfo+i;VFPdmvmj{K>Xb4 zg(B#5F|rq^iI)D`Do+^#VBbZ8)*6gy#*-3#=F^iC#e{Md+JZmP{yM-n6T;F%vU$1r*c+ zdz&f*6qM6`rE+_7fx>ZYC;|r8pn{e%n}U#%$X_!cWlaJnFN@wIl)R3fk_d%QndL9@ zw=Cv6cidm@-ijBa8m}8Ak&{p6OZt@Z(b?3Oa>Tg7QiKcKA;wP1ED01^dyEDQL^3QT zU56xRjr_@^H2-7(^NAJqAC5OJ$WC&H7_)_7yKboEwiQ_$_ZMmL7e@xN)64p(ZCY%% zu1Pj0m?>T-Rz#W|1Gj|~_@B{r9R_8)a>Uxhw;C&N1ru`X@Okd2SdSO{Ny;LolCgPBS|FhEAdrOTfM#cdnRp%f-cN2yFN_R8S=#jjP89FmnTqNk^62iL7?&5QII<1E28Li#W>LhXv@k4T9phDT89O*IwCtX0;TfuA_z=<)=+9rG50u}&Xr!3G`QCpGZ=?D32LyI|h?FWCevR}=fcUQz z(VcC9Lkh=%br(EN>a>nkTbrMqB@P$a@GY?zpFw~O<)dj(2HcMrQY zqi#0bPe;FmgT&b%5#mpR%(prv_cyj5;q>6;+;oi7-o~*%7^R)KyxVaO_}W&qVeAVY-S*c`Ef+s@(oP;e+J0F%$-hrm ztF8I*PGuxf>qtD5_|99)bH&X3to6WF8k%wdK<#MBjAg@bvzD|$d?K&Qctmf{qUg|U_|Gi-(1X~1_H z?ck`~u#hzAk6;MA+~73H9M`Vb^^@W-S(?zMnL@Br{}#fl9a&-Fn>T?o0{A|*i%Ee8 zzM~ByKXET5DuH;KP$p+zxm9oe?B?Fq!!^BtpvxKaO~uUbwKJmbN)oa$yH`@5*jHkS zWX%jbpOF52FAl$Ncq78$U*cJL@{J_`N$*P<#9s@zaA&|sQl+O$4>3z;y8LR-0!>wR z)t5R)yGrIzlDr}E;%QeE*)e!7=(}#Vc|FWAtqnfv<|#IWj#GpfrP`qtdA`&XqJiA< zJ8;V!$uu-X#W25Wc4aFP?BH>+dL0W*ayHUSJQZj_LDs^1^_>MFme_4*Lx9Z5e3Pp9 zhX-}hM6xE;bCF#DWg&B*)+g5`MXr1_D#Dwk&c_;N!@`{RB|*S8tHpdj`=>*~w7ZoQ zdn7Ln2yQd1moo>$XvuRaz$OZ4N`b6!yGZ5ijEL|1uJBUL_<(lh6LNffY+hg%&g zkDF8YlmJp6N^&9|OJXI9bCpD0@xDc>beSsRO>7$-y1xF<@bLh*NF7A9jTvJlRAl@n zVAfJTib-O8+)Y?^76elr$x9ZVBl&Y)f!cRHE_&~NDtGBMtu_R83hvm`aCRF=fu zg0Oo9Gd~4#*-eQrC!_M^R+eeAx<|}yDZ)-Uc-PUoQZS{t0&a^! zMLhJg@@a-G{}o$umi=&F0;rmbUxIKo7GB1=wfrsvtk$*39~AYOGF2%&*>t$NMH}+5 zkk7Y(KridDB*2PBE=ND#G4f|cnlE+r{{A<0xL%neReB90n%gqs9hw#+&|^V4GjJAP zDRA~)0vLosMF6?qU@CXN>&1wXMBDvO9Qrpww_1A@I9E1wUMgi=8AY? zD#~VlGXQW8u)t=lmgdlDP)3%G1HFvkVNJ%qa&2^w(UK+#-(x^G^J9c@HI;xhsuzS! zGvykrH`5h4m`_J=QYsq>EGo5NwtQ65@UtY{mPryy`aX(LnaBB?lz9OElz z>HvcMH8q7!MZ(BWn!Kp|le%j0wuZG%*V(%Y_s2=^DV5J3E|T1|+)`?wAMU`PhI}76 z#bkjZC8J}ooG+;2{?cC@%MCUd=PyW|P0x|?9rxCt1pOsQCkfEY8Krz*<8z^7h!9Hc zQg-~vx-K+ty~lYX_;v{Mph4uD_WH5vTaD25V@&&{2X?zwmZsxtl*X0Ekflck zyYPeLxr-7M2|vO{uwHL8Wz|sFK6kN@dUbs5*eTR^{6c0jjO|lkQS-)pq!S)eTP1i zg!wz~fLCXb2{&_PmE{wT^qA@y1f1w1vs?$bdVXn;Bw=O%1AC-}r6_Eo|qRE<^VN zT#O%ll_sBxLGY9J=W1yIu>tVS#_Dp0X&?faa}7jY&XURUSc!CL`$CD?jZgrDU6NHQ zK|pQ*9B_8JG;w%{z`2Hps7q7xEasU$u1RxHT#pTp(wx+;%7Z#4i1Zh07YFqfps(6| zsB$1Kj447`{khUVU+-!}U2QEruD+p!#yUCQx!fwUQb!3~+4Yorz$Ld#C~d=&XUKUA zFAIV(1}&3y5ch#Zw0ywa~AIhsTWeRM7nKMbfKR43>H z#plZ{06rR%BW_@GZ$vbQeu+>z-ul*>x@J}(0yt`sTVzaVV5maNEDjlC>qsrg1HKuq z^f~0&ZYt39Lh;ZoX>svVhq4hr;G^f+E@|3`uyL8IFVvG;wqudupK9~#6i@80DhSdRFP$zV15zcV})-@^?^Dl zwKxq#bdK|4bzs*rG3&h8cne*QykvH!sLXBvd!Klfs{2U^=@8p?6XNgJYTMp z+h7dX2k0sTeGPn(1)N|kCC{_zx?Z&~g|Zwh+VOaJ15Qv!S$?UdKAI9ZpHi_|aQn|+ zr4q_{oRjonbrpo?Dl(BWTDZ;$13*bwnjRhEl<8WpImTncfe$?10-YK>Z|@UWA*S8Z zZ}E0<&c6MGdtXz1%*B)cU~R0BugerzffWK*4i-P*L&gB?Y-X;(UXyf@#fEf1?rMCY z;PM8CP};d1r^U)Aw&a$Xh- z(kVwku3a+Y3wfT)S^PHp)~t_$9d_q<+7q$;CsAp&O<%F2zoaC8%CeoXox)jKPn(a_QeqsBvz13pJ+#0=f81N$-o=v4No5CvHU$J!`3+CvHRbp1^z`_O`I1aPd=|^+ z!<`3Asq95k7@Hd?U+2h126&Ww(kSf_w)V3JLSO*IHx@MCTs&BmCI&Vz=VwayoMx{Mg$=VQ;u4JZSsG+w-`&Ase@Wdf7p<~sy) zIRpyWH`@JJs?B0x_d5Qtn83*FZr0u$w;hh{D8~x2(GI|H2(8|s2}8pd9McDk^~GaK ztyULScS_>ky;IK#4M&c>Y%clv<|1#^H(Z~+zpt~bf_W;ZXSkW`#UML&0>pRzwxHvj zOW{Bw1w!hvqo8Ey;n5=7tJkxl#uAB*it{Kij9OSJ+QK*Ax=p@?5(Z|=D( z)8`h)-@DA-DBRsnTi3E^Y~rrJ%E~ykys#baTouqK)IWUhCS)S%a_HvoNdlw8%W!yi zr0d)~)!8dJW!w=JE1r@iKKjk#*6n0l;i-Xis{*~J!*5?}6%tEvjEhsx=kY0(E2ZDa za~ksWxye`N#tJ(85xTe-dS5({s1jP>hpu;W$ubU<vsA!#UZ$}N>E^d`aeh8dr_u*|T@7CThRts?MtdgoUyd_Cumm3kF7)j!Ti8#{8 zjn?{^E#am9+E;2Isr_==g^}gh`VboGB?L6vb*y80Xu`wK-7d@Ze#>Jdb|u1i-< z%6BYmP&WEYL9q!p7vs?F6DDZ&Dg?{tnSjH_xLqJV#;}`jMgsJf`>%Eg@b(H}M2t3h zChN>V_Im+PPi{|N&$nfVCPfN%jT1Ej++Z@SD=iCZEH-)@t|%&brn@T&`O@b%prIU9 zc!iBL5h%Noa2+VWpniczubQJP ztwdPXhFCIV7O<|I*J%}Q1v@>nnsS}Sw|#RgyrqA4KRz$9P^=^x95@o}uw^Om(Ly9c z<9R!t0NB()b+s)H6=2gT0&;+h+Ka|mq~4I&LyPEP=vPq{peRWA0_fMlt02T99>~?$ zMOOUlVl`25U1W{oFJCU@umTJ#CTjB^ZF)TO0Fo>4g$zuk*xF$ImS~UT8wLLEElZF( zrC53)lVS-lgboETBYnyWg9-2G*+8ET0iHB}Nc15-ooaqo*RN{);}`KRYAYJ?df z9gZoOD7epD9)m?)K5@$30OB`}M@=es_DmEO;J)>48(~UMsG-kII%R{ww0Rc!5~jMt9u@{ULlJS|y#xs^n{;vW68pbHehRv> zil7V&+M0+&0qZ_Fvh3%yIuuq>Z>L%1syNV3NCX{+AQcodfBn^~c5EC@Ts~dQd+<_- z+Jt{y!SG~1jWO56p-5TcPba88_%bBo{#FaH2M*-UyV3_(QE&yC%K@OgBHq0;Q2mW% znWyY{mknrOjSLx#4=l@jI+*KGy_D=0SdHU`p8X#tqCD5lY%gS`h7a0glJaW|sSQso z+eM53Jvvsc8BxzEV@NgKTRI?potoSaz z>wZcz=#ArZ83I?>FA}~+RBIJQlsq#5DSHtsjZ;;^brE{<+|O4igPO_m1EZcvFMW+x z810^Z4o~^Qs9{kUf(zxMlndCQGIV%3VE>-Z=2vxRN;w%i$Z+_`HSnX}=Ra#nCdlAcrf`zNC21RFAwZTqbbbGrj>Z=ueM6%)FfRCcV0w z-KiGrUGBc0{7GhFo_~^s`qfg;_s=v5w42XulKu}qNAyVZ?(YKRFB*TAU;36X74Q_|nZ~Ywg1+@jn7_MFn9$Y^NuzP#6 z6P=Wt{}s+0?^dKggAyPL;^X{vkA@3xeWD6@Ngo>5+Tet+x;$X75rsMmgUKiKsD+1umec};cV@~utF z_ZzxkrTp!u>TYiD#R`PKo!c{=UH-2k^_}-+F{^u3y13iuwg36``jNl3fw;=CXiKEU zbAas)j}8%o$;s#d(_uj}t%)D2kSAm0RkHt(lIySZj4^GF*o4YVvDy`8*Q|ZZo^6E? z3R*?D%Kq6S8b3R9O_8zw-S686K0Cc-_3Tc>nawGi10aNpSf+Tj)26^N(<+RPMXbK_ zO;QEl1G84a!(*Qx^L!>v>&%_e)dSv_Kh0|6av!`T+|hfy60ET_!40)R*}L-C_44$Y z!)@P-9clSPW`T5h+jem}e#o8bECk!$0g~k|JxQ2e#0t&p%h{U|{x+P9-I?CKDM_rznYvjyON!Drl?vAnyiO za&Q|S{d-4oe$eYrTa?Yd&*zcyh~$0L-*_X&pC1MASh$2A`hEU%Z1NngL^K-{d2o>u zvRUg3xUUB2ZWwXi4%EN0GWg!470Km4s+7B-J_7!iBwZK#X_G>^vXPAv_VwR7EOlfk zzySNHL5Z2c9^XY;?NovW4(O@=^ohc=yqae4ut~&N?n&njx_4`hg=vvWKS)aDEu4hm zr9#g$XjBN$$x{fBoW5jiL~sPVyO=LNfUo5%3B`^YL5WWE#dQptoYWM*Z-rbz>VQpi65lZwKAY>_|~7j7988jqUibYkjMgl zC$N`O@wK2IBept%-|_zUz+a`Ix|ji+q0he`SIT%ltptYrJkSZ`5$O2G^G)|i`6-(+ z!XeP141*9yyg3Hve>XDS?Iif`iG%g`WdC1@|88_ZKjiK;7&8_sgAg^2IR*`miXLaz z+Y@Gf_564;LU{8i>JpJ5OqAYaQIw!~kh{j?RP>H~I|RW3Ea?AUSs!NRRSyEP&v*Vj z5Tw!nsASK0kTPCL3Q7@RYlN3^;2%$hCG-Duzbe-zS5+h9{iHDJwN?LB+5cz`{3shx zeR1)dKFkFtIfC ze=G+AIpEIvy1*slv$Rq%6)>H7kj9`fA4dzkBC9)|Vw6(e|7*4*icwY>+6^gY{MH z6Rw?^G6O?in^c+%yCiBDJqv1K&2T_hvH$s^pzF5*Q7^^}fIzj+fFf1cGiZG$^G@=Z zDW$EU63uD4<1;uxo+Qo6iz}l#o1Z z{j!FDFgeQzy#5jO2{9^pHhhx5V3eo@={z(GrssnI6(k7~-Md4{*i&dPBeWiKn>l&ur75PF`f+ zmem-Q|XOlnLG!mvAEJoX?wkF%ofUr0XCAm{X%eZGZe;w69zBn4&oFFC9JHS3k$l|5f`+J?n23$|+#R z_v!vOAvv48;O%B=lD+`OwYr&XjHesa{*&tI&`@7@M<~-LVPpLc$))csPj41iIXpD7 zP}LmY+vzI=Dy*-P250^?1}!&R}SIzWEOREN0y{7LreEPGOXs=8GOJDFx4k2$T2A_6F zk(MVbx}4=v?u$IH{Sr{UpKw|naN9f0H2u~^FWdLse~N*>>BD%rzFW1nx+{8KQt#Snx_G~FlPcLY=kT6dQGZ-_)_NP(A z$Mk+WO+kCL%&EraT4C7Yi-lg+e@BOwACVk*pX!9_&h3Kge)A0Lrc~(frd=45aBUEP z>fGpr>g;Ap2LJB?x0{TaJxCkivtUM8)?MirRyM{ff^qXIH1U^WR)IZn#X3hCOBXRU z1|V6kPKCD#qiYsfE$_a?a5H?u86v6`Myy-nQ?C#}%?Uv5*AS6Fw!>Lfx0RCASp3q< z5VNvc>{!l;h5n58UgSJXjipgmCN`@=9UF*-G824R+C%?BmAo}wl|H9G2WP+z5Oq$f z6bie#5lwt>RRsrhL=yq7_;~p-HnWR3_v5_Rh^Au&wV2!5oAThyKZ-ai-E-pxa8JBD&BfKW6M2( zEBXDg#j%*-m4Fz$TdgU_Wyv2bMg0~_WPL;_$|U4;?WM#_7XMXYiE+F60mCtMJ+ zj`?zW!X+4RYE}*J-WXm3I#W%G0=0BH>k5NS>uEi035bs4E4{&V<13-hM|$wskORO> zHp)PNSM;x_{ay^>`RCj~jSomc=`sUkTtpdNKu=w+UWIzwh0lm^pzxkOL=NtovNg{5 zNgv$%@e`9=>~TAgWAH(Qi9!@$%b5W4o4A>Gqx|Qq zEH&c@Elb)#CG^vb#8h>L{Kh#l?ILg3i2AzS-0)Jm^Z*W>s%bWZ@uOwC43EP=8{GPe z?d#5(4pyK*I-)*UcYM55C9>y@uDWS8N?_v!Y9N4m4|Ju{M#b}8192ZCy#Y^)C zI-hJ8A_A}(yNB5nr}@iF#58pv%e+SBxr*zV!nUOOuM3=)-605B(t z^7@kJ6JHMW+FT=pLQlZ%v&`V`+IOLN!b;R$34tjP*VE; ze3)v9fFCAVUs-5zqH9J;>2z9VJ~p-+THc3z7&O02S*Nw=u>2gI?@^}y&W&}B!(p%O z+Y-XDwOwky2XtH2Z7bw-xfy#2VFZ8Vs2Xga=|g9-T2oPkx>}R@+!UUL236fyTkB4i zQEa{MvRb*Z-C%e)v2p@xOtD>}_)_J^AJd1;EXlByj4;patj7YIE?ks0@D)}O{cn;_ zZ8zdG!DhH`+soogM6ENje3HMp(hf$s6l&wO?DvfhGRLmkGTx@^3s}pQKp}jWp_^lEKbVLNax|QmGqsWN(@(x38nD-^{%|`Q%t0 zQl|SO`gqW)7Hl=FN4kZ%_$g*syI)V6_rDE2F!tPfu;f^RLWc)0SczD=eSap1}P(k=k)A3zuW# zb=$Hb-LlJ7#^_-9^t>zUZ-* zYj-NeMbfw6aAbCzf$;^VCA8B(v8V}ZBba0tyBI^-V zmsL6{b{c_}sF@ER4Dk}LXchF?3p0Z>k%N;zG-vf|XCh%XV9j|$Mq@|*F4J8I$`DZe z?zzW84lG7>3P3$ORO@{56`Lu2<@BRRPBEwg%`9sir%VUu#8D!)M|aFZ-9p9y301v% zNc{I(3mgWHH-q(zINL1nK{-m>IreiLVK^r_5};z|mQ86OOzkbI)(kz?fL4q(u2h&F z5}dThkobCqH4cLX04W#VfL1Vh4;He%9nH;4h=hYZs~yetrFS8qCk|6l2&$-$qzq_n znqaJAawPcY2vzYdT>lKKatuK#KnfdRdpRGUrh{;{DkTsHYoOe@%NXf7jgzK>)4;U# z644~vk(QH&89wMXe_1ibBOLoi%J(V!c10?m7B`3%Kd3~#jS><1;Pq_?vJfh)VdD6T zeoigvA9DB^L&Tbzga8r3t}V)#`WOf`d8hBGvP#Y53mp{N6lLMt;x7#34{F?~lQKqd zAw6-bFq(12lK#f&l3kkS+#~3%HF4o^DvB-z_Bw?b5j_Q^7y&&6MO!&lhu!^Bu-}Ny zRUidyN_(g>Z&AJXC{+JN zV{BL&rz#~Uaw*=c`I$ow593y>Q#chVqLK2fWvREQP2YRXi6xo2uIuuc-Uo=N2s*(KF%V?(XhVytqSgw@Y#N7I%tEad(G{ zySo*4cZcHA;?{o4d(QWRoZZ>T>?GW5l9}frfN1?(YGMY{zLyvvs!r>KaqQ*u3G;Y) zDn```Q5hHw5hGIh(VDw5ANWeLK5LGSissRyw!x2F_0;Y_K`wb}SSaNk%wx1{{ zdO?deH_QYz4oy*k)HWhM=V>GYpkt;~u?CjG&%V;|kG3uO?RH~|uqNyN6nHEIu!xaj z{)S!p`elGBOh|3?$Bg!+?S6^&pGK^v1$C;?yC&F}ot1L`6m~%*k1>2Bw`hgS_@yV}lk420*f(9yU*vB0hr==82xo4_R15#noY{{K6O-^)Q#qpf^!GqLbrA^IRSs>4W`k5v0hJT`l>T>ir>cLQDuh?8 zHf1ZPWCQ*yhFj6sn!|$%A!kl%Y&q*0+(b+1j||xKT$Bg10-`7b0*d&2)P(zZX%aTK zkqMgs-cF966*0}0Beu8ME4KL~k3o^QxhF=i8kTpi*j9##X)M4b^Vwb{CQ>w)h}qx+ zlgv~hnAeP41;Ik>`qv~_L?RQL|sb3{h zc1wzMf-NX%bTltt_p;TlG2P|++o7F zk|lx(=23FE@I}7)q_EqnPlLpkXK7j-mTX_R#6BcR#sp17v=ul?`<)OWu#YI8XEBV4 zKQBd6#x%H2(4}+I^V*1CM?9Gk>nkZ>0*G&c3$2b57**`DH$iPfXbR}LeRy$9+^`iA z(?fOp>wBe;8FP=2{dd&tFbCy#=EdCOkrv73mzUL}FO7dQJ-^Zy6O$Ru-*eWUEJj8W zYfya?GQf-VX%xv*9JgF+WNx(nE0gK)uTb${5`Z9m68630c=L?t&3Nrr z?NKI^7G&e&cEMu*V*yn=LpYt4_{vKCeII)5Hsro9c3=j)kt+gLG%O&qny)XWQ+tj9 zf|YnKU=9qX2i>jIHyXY#S81P%)ad`)c0MyCFD9+Zh|o}0XLHC1*C4lL4l-|L? zy0k58@?;$Wt0m(!-1yyjC(1QNQGRp>Kvn7GZoHP!xP(TVH=cx(84dgxXDjvb1R)jC z&H(rm#bU2yrYXsWZC5(LVV`PAo#*FdF_}U!qEd!0S@@OQd7GbCtF!B!J+0wpw|5U9X&8dp3eLhPYX0j;j5pJ6EZ=-PTw7V(9hsaE;!a=#7wMztgX| zrA*@rX5=_irhOFO_XTy|pyv$`Re)s>xoRdP4l3YP?(RUonR2c~cLY?5W`Yxk12v8@ zIhvMv55>!(-Kdpl8aJ6knv#)$l6_s|TnFvJV?%Zyepa=|+hk~N3+3snyb>Lk ze>jCD%QT@ml=d_}sI&8Dlv2u{_m<)Wg+zi%u-a~SP89W|cNj#smQDBD=9jsDWasQN z#FWn8Y>StCf+rF!`2*WQsKETr-1nOz6734|Fb~fzDr_lwmAymiEV~` z(X7UVlcqY!aW9H@`3ThK(E_;3F`kk3R|RC1EHLF|Z!v*Fb`3_?%5D((lvAq-qa|AE z@KCaJLG7oPysmV{Hs|m4owvsWuyCjFcL0cVmv*Lu=V!u9FtZ`|eT4;< zS@BAy@XP{GW*-uWA_2g&=IyU!B$`jUwBI2AM1%rh85QM3+wsz~C>NTA`XOTBp;3US z;LCP=s9lD4&8fD9L`36KmnO(i2=M;(UaJU3M&2lYUA)Ni&Q{nChxS*#N{T{iN7|(^ z(*yA2W`WS6CwYK;%{^V}5q$jF5BLTr;3yTP;)?&D+VgX-6QnZmeqqN~QHi_sd5+m!I-@P^-Fn1NLGE zen(|lX|FU0h<4*8XHhQSVax!pMuZNO1MN{n+^o2s1wPlRB*2*oqf=e>(*U4($3_M0 z={105B4Y&{LC-TdBc8|u1Sm&d0nl1pS?V980K6K*_SKo-CN!JmjXF!Bq4?t@T^QH} z5Y6NP;H_otaHD14&O&PKvUv&Mt*Zb_UjVp#2HGged(masdvT@q_W*Dnd~LwJNfgUf z?%?$fjrY#CZUr2<&N4idA2&agt2PNM6j2NS$Na~zo<;GlN5IP%=hv|rxJF;)$GgS~ z&dIdDy+i%=0#R^%DuwYbC4w`e&vPb)iGWJ)j9kqkV%LQWjAkEQwIVL1s{lMePzd*E z{~oXZ%zR8ZOofBOo~XSPQ{BmwC*WQUeq;pt-4z%g@0@beKp3;Ye#Or&4qVxh+Bka` z@f`I_jrq6V?|_5eEWYq1M39o1%N&4-(=2Tes}j#fAsRZ2$@UK6{KFFkMJEI>iao1c;m`tD za_^b6=^FuNGv`cSo20r#OdF%W)&sn5Ujb4&Kr8Q%bVdL`XZWNOQVUpJKhFVP0_PO! zHJAW3S`^i+wRs=H&r;y%z6=gY34v4P3smNR43z6At;F16Q^2mv>=|TX+b(`o@y*!%xgj>YT{-WwE9UYeLOVE5Hnj!yA7d5GS3p zwWlS_)~Tj+eEI1!|C6$auXt+YKHXa1?{y&^<==4QRwKH>jMqHBhy07ax-iT|3zO++ z!`rh|sC^#PRHj?8VZ@gj?V)kYGbyAUmI_N%;RzLkB$jIa`xp&zOoVxNJnhe7k8u?7LPY)J4 zi-%cbbXKld+nDzsxNz4XXxdtT)1r=f@g>l@4=^V)u#?#sJMKp z!H@R>T}Q;*Xmf-cVo-6j4n|?y#LubC?^7BV0T6p}*e7>qcx@*i|2PKiiIb+aTj#^4 zCE#L9-Tz!@l>z*Q4jz7@<& zBEzb*CANPNY;lw6{@GU>FJSOTfIDNZB76uS1bTq*wLd7^kv401 zK5q?Ncl0dSE(^KRI^Q+FCZc}T^tcg5$I95un zj6KghAMmK*8|AFciD!q}bh7qF`L+DvWQ*M%i$haxy%Ob5(qA;5<`>_(o@N-s_50R_ zh^E}FHqj5nHS11DhHbauozPWRT~2QwoWIm);&w_NsJ%*oa@vC2mT#_(x6ib{8OnP# zeu277mg9*%8QZdhoKXymKHDSdUbE@Di2>7qw4xQ!m_8Hg$5PY~)>|~VEN)PYi+D|V z+mMsYjB>>tS~d{=`NFQn;y%(J{ZM|=cPLYM8h@aLnsd#iw9O8a0jAd@ z4FQbi2+2hJ^K9`9^7{~~_7es@XBsM1N)`E zV)vuTd`3q~#@xevi#03+lob1c?&XwJF!OQllarxz)CI)=eT*T9=Abx9fTkt`K&{0E zLe#-H5V^;uWG3a0(^~T$4*oq$y~sI1!~P(jWo4OZ5@|84&hor8PSVbukL6 zQ}uuKA`S=nhr*-Zc6|G}l3^U%cp0exrZ8|ld5m6Tn6Fix$^bUooePkm*SCLR{z;>8 zN~4H^$!;{1hPqH_g)`EwaWk|y5Fo#l+v4m}H?K?!A><(SC`n)q2XI=v)@p-;8?!^c znH5d)0P|jk7Y!cZlo@S4D+9%64e*3EXyEoAnv~y#H z5#aGhDvT(db-nvxg#+)Y66HPO%b z!jvx|+zdLmdxeLZ^Xj_PFvwr$}G-^-Wp*jdkAn{1{)^z(i3h-17V9Voe#oN_Owq!GjxSX8`uROf@W zZ52RDU{0Ie0fxzh9MK&Y6kpR75T(Gwe)~{=V?zR&?HuP3oTWZRMqEW3|MJsr9-7Lm zy7;eAwY7MBV|S#X3H9jXTBcedfi zzj5;8Y@7sQlKHiYcb(5}t_@YbFN3%P=34|%T~a`e8fzR6i=#n z8pkk_3^=&n4Kr<_pZQ5}dPAK7;m3RB6G=v@J2NMroz9FTS6SYllcJ z%*}A3FAjuXEB-UC$OhM_Ze9e3MR7yT_I}v-@;_9OPR0zag4IY|MpQ1S*Kb=-H;)w8 z>3=-1kCwk5dabWI6YhkK*POEWwVq{I7)@zX#0i#R__g{ZfBiiG=7ufYHtqgXow!{% zjF$TOp2RPWdpKD_L`O40WPWhKT+ zF?TvM;8NjTS)4vQ0{CZ!lwYFlDJ2aG4PywS!SJd@syGz7+-s8Iozj``?+ldaQiMBu zs1>So;s@O234eiDpJ0F{@dtVpq4|3;g{8^l(nv|2Fz%y9{& zWQBAFeEhNu7DYRE9MnCGw_xfpP_k!6UW{ zL=+jAIu+|_lB&U0$)#8ne=q@sXFNzGHm*#=g_snvM`?;9wA%hieZL~NOs(FiYSfL8 z6mXSmkuxeRV2^g0mu!Kq?^BzP+jpJq`69c(mDdpYcN6&yy`x?-5)yrV3R3gSveGJaO=%rX=M6`H-xFy3YmlU}($`XvE=kTk2sQXmhZE0Blkd)+q4T!&X~t!E!3b{yzR zT`djZBSpljBJ}K+1Q;sQj+c7va)2e@hbxT?w)puE9A{bLv@1Vz7!KSw?ffD2->N^a&&HRxp3Jr*fK=O%Vi^6sD|kfhOg2mF>rPS_Kz*ax6QOJ_H1VY)Qbz zi61__+ZfOsvy+x+_=eA#vc^#%!^-BIlRa{I1)E-%I|c#UGujtZ3ScHJqMth+!>%G+ z5B>odxvZcp;0c&kWv)-VPO+H(5c(!asTVTnVq0sNM`}g$?7pk6&&6GPI2MS7*$K?) z#=xq20|+*!H^H_xGmp}W=AfXeQKdEK;`X1f0~p?GwwSJ6nE4L{WedMRl^FpHuh;GC zqNqPpypw6|xwrw+@7;IBwGo&=l8`$yRF1dO2_tdx;nLVCG^59jQH<3MtUn`}aKh1CyeaWMIa##1pi? zV*e^%ptm!@FN{M?2}Zew7?lKLjcZYd24!5(vg-56gnu5nwPA+TA1CH_ES<*>4z7)m z{95F-Y5$Uzld$58qr$xl&tMEdr+m|O|CW~67IXr3EwN7S&3gk&L8jgx9vRAv2nTee z(FbSMF602)yS~k_1Pl!&);9UYZv}@CLHF#VT)&TgVklvj_f5EQs*%$%-@z42SBgmO zM&WvtAwhdX6=e;?Zoich|&N*Dft zgSYt?m3I##W}l1xj(!Gzr%bVcIt25Nr(XGuE6}UyABGsq%d40#l$aDlJ5nvPP!AP= ze)i;!prP^7JFrL!&G_jE?onOFZ%6qs`C2x;8%|~VR@~d0X&Y7rqpVvtF9uPXUb>U7 zp;~h}p4kvKzN_c&USjOOP?0LlWjX_K{O{|!jw7{}=Gwt0Sl;)#;03Kzq9Y8QE_!Fi zF8sW_o2eH1<1)T(C|M1!a2TO>zOOGQa}WAwh_;{140@VgxOam-kI15l_IX*A$c!u+ z7FxE;%*2&J;Hs-p#)evPW&De?a;Jj1BJ6_qoRr25;nVHY+j8x>{Ja>zy)t)oi}20= z_p=l~mnV!}VzrW_GD&ZS9Bf;+k z<0ypJGcXsk-MVzlG#O%e@v{OC9a#>0PyK~R@DO~w9{2;5MQ)#A#afon$^DgwoA8A< zYx=+Um^`}ZQD2{IUJ&<|{Mvn1e02FxN8!Wou>vpbOXBl}Gf>h&yMwkn4`7{Lmw8Lw zUhI%q_VkQ57Zv#FZ<;?8efMB*e_S%1Xja?yJLCQXH?r(T6EqaGoQn6`v98c+WOH(9 z{hZcs!7_t1hX%kTwHOK%`Y|hn*W}-QDOIx>y|5U5gmOX13Y^d)Wd?{ZFFs4KZLU{;lN+Mhb}bC)G2>5V2WsSstgnMxq7v`;Z1!<`Wt znVidV+ogNx^J?vk5l7&Bbzv&AGzz{&(Tq!pHe4DG#AUh_}MK$i~%YkuhMQ-UsM)ni4h z59<|r{@3!r)0IL!>bleYT}r%{`Gw+@syj3-L{fMWxrh{jIwZf9;>YHqnb@Lc^r;QP zfT4)nUTE7ocf*Z=h2@fo|6U-oMdvlv!$zxv!{uZ4$CN?h-Y8_b`TE7oqr@}%KA}#o=83RL74bAKMwA~^;5`z|d`D%) z&tycbMVsYh#Vd5+$j8UWOq7X;{Bb{sLt=W9gHVX`J*f|6w4xW`azlmdpg*jAz{{;0 z7v~E!;C6z>fItvN(KpG3$kQq&HYPf{t%I}C9K!fnzBy< zy7+W-k29&<*e4twUaHoeC5P%DHHiwuDIF7M#1WH+c1@gb&J1!W;pi$WnGG187mDL^>tTCP4;8eR;0{y|FBd1|$whY&lZm#Jp0z z;r{GLPb!P2Nk>COSVRZI0#DRZQqE+yD9G2%m`AC1K!J=+^}NuUHf9JNiqIeUil`70 zG~_U;%NB=iR=PP7$Yos{=1i38sQj79p+2J*xnYLw91!xZRlm6f`cuyhBOI$Dd{!xR z!>gc>2GHFC@wuI-)kP@+;7v59F`N{~;$PQ)nQ|AECQ+@#x9OnJFup;LP(Vqo*iiPt z@h|koGjs8MuJ=RE74`d)e)o>4k~=)2qB1aOy0 zln1fX+Z@oPL z3+hmZWAUGf!j*;C>zj*yjwIBzsW_KclN0FsT?{+(3V&W6GIIfagtds%{G|#zhdhmZ zz!H_t^9C_|{I&$9E~HZSL1l}}RPmqhI&G)ZXUm2CmXD%>rndQ&E$}0U1dnu7sdP!FI zkG%jfUBimxvhe%*cT@4(`zG90A2%8vEw;-4%8JF#-pjeKE0|w5FdE3owLDX`ywj=A zO-+5c!@I(IN-b6T{CgD&q2YSQRO&F_ZoIl-??&-(cXL!RjN9EryG%qsNk7qC>r&t_ zzwO5UaJL|a62U^iWt+AyYEHuWXnjuNfPknk7`g2$H0KYr$!w9J$J$bcPGNcd7ao$S z=b`R6?r^k=&pzrt^fl8;t?~0y!_8mr5us1=-zc}^NpsNdtnU#uSeE733cH`5LVP6* zyUG_e0wYdOLjWLYBl}Aqd86owqf65aBTAYtqZOpwOE*IwtLiS>U5U1N8_})KE5ZqF zUv{_Vbdd66kw3oB{#e4I#md&S&fzF~v+JL~_|x}YF{I?7NzVfjjeH~ZM2T$qw!5xo zD{=Z>W#bp3#!X+(9-;;@dFL<0g)>a`Jkqnm0%pxT1H3ZGJHJ!CfahQ8u{~-R<{EjZ zC+1*LA=b&iw$-9tAJt$^-&Wcn?@m}=s9{c323b`D_$BMoA@5qxQw^M9PJQDURj$xX z&y^3G<{DaWR{Tg`<~8a4R&tlxpCfDkW?jv#-9NEC22^c6#+8R(2wId9I}MtaO%us` zJZbE?A=7*!1q&Ld2^<&$&d??!(h*}5ltcV5dRR~q7MA#m`U@%3fF$xt9 z0T~(EA!5K!!QNKWBRv-N4qmn$opQ>>a7U{=E_|n9bUzqmD{(08I7hYW9SIv!qm4S% zYS#7ZU+mN$N>#W`Mj*cIAhxSWFShqE$1^I(Br)YoS_>m#gn^{TquEfZMdU?;{MM#S7cMf1jQf`2VMsC5l@uA_+Te6HO9RHMO8I3 zj~EkSdP0@{RMJ5PhG};DP&kFU_?;s$qViZ$(dYOw;X5OY0%haj(>d2$M?P$Om z=TsT6EaGOT9^cnUw%t8oJH`Ga9mPKwjb+-08EMSC3~n8uSKq>CH&fGj6rK_76T%+*MlK7R7L8)%I!xV>lJ}!a&w`Pud zmn)FL%<_Di^(z2&VVQdry8S5$U8o(&N9LG;0GEed*-#L@WOjQE0!4+|R1)#36nJbw zP&$f(D;7%}w^$%@KhDLCEW37G3q%~2aC3pO)LYY?ljz&mSD@m2J>cVIg8Lf z)rHymE4Jh=Z;bQu}8t~|^?WCg6kEN-WM!%Gpz zr(RACbH~ZbRh(7k`h%2Ca=t1ESv(~JFmsa$Mxo*=P;43*HUN47?#~+dl3jeE%sUI+ zD!nfdD>yr#jDOJtqd;MIKUfqjm#({j*Kd-<;2VWMo+ONl94?Afh=^JgUv6$Q1S!o| z^5|%iSDUK}<7)X^PfSCuEkU4pa@g@4dRVMPW}R;GpwEr096# zq^s8!;-sQ@lH;%>aKTwjE@RgL#E|M!$qLAsXb0Dfhk6unD0<2HG?D1$NDQ3;5-f?kW2rGh7n@Ppa9Z=ijNyv&bOFBVVGcWNvslj zm=l=i0>O&no*^;{e_dXuRg7c}=%Ukx$78Nc2@CWyjW|VQvx+2!gS>z;R~afQ$=tOO zga8Kupx^x${ym!|wb$`>HjvJwmi28ohJ=Ktt z4(D(MVL_HK1~a6^!4`~Z$V&&CkI~>j*vu*w@S5cf!qCDiD`O6Pd|}2*G18Xf4Mbf~ zr~dB85lSv}2Q9`n#v^4U;nnI9+}%ZlunELi;6;-Y6yN6Yg_c-mmXEUi<>5e1HaD?ea5h%FysRy5T4}eqH&v{ETw9!8uFgTj7`bkE{j;`s zlV9l}-?4V@yO~RNp?GoXcZWUbd*;~;t79OKrc zF#FUor}?yKz=5`!p|>2HR9(I7@)SR}xSQc$d$8KBf!3a*`}JXU-&HjhTP(O0)O=Ch(uarcE9 z#ZW77sSF$%0oJ7CqW(tz(;y+A3Q zF5eWP>ROdztf5~CisI0=#V}1D2ShGiDaP3PwFFUjSxn9T0ZXmz)am$<)vFv)Qh4^b z`)L);;f@pLL~Nw>J5DF*{Mc-*sy+gq5Ld;GWllt4QvH=oHTT;_Zq_*(7 z$>fcnE3OQw#&+!~4ftnz6H-x{-soSV6qh9khMxDnN7dV{@v7?=U*SRw9we3dy=4wq ztp)JDCo3kmc+b9tX+96|nqR(I!b`oNeF+9@tq_DNpp)iXJ?tVI&t4ATLO}k@rWm=M zX&=^Ugm4cG=x&WK=^y&c-ey^ryXM79^v`4U4GHOt<0ff0;CatfL!|M+4Ytnq%s4V2 z&`BCgZxm9I1KHQ~1&q?f5CVuPfp^7Gv0Qxsd7=_e4|V z?f3J|`1DMcv&36wlb=hsNPpa87fcE|h~LV$Dw3<{kfxQdIq?pZx(nDN1&lf2=H~H4 zD2$dza%wj2*AAARuH_i#wFJ;TGoUL>uRIZ>TRG9REl^4|AL4!KW8r)lmsl1nrcM?j<=bx?Kp^v7=HSB10Yi683LVd;#)R z@XR&im-1N}BiJO4ESCF*aYj}9hOxjhPBUoJ3q2SYx?Tum8FSee+p}xk@lLU+_>;EU zthoc)uDP$6l!Lw2nk2_OzPtd1m?KZ*!nU~eFaS%ipCoIHK{Vx&e&890i*Z@M2 zX>1n;BqZf)RwVRH;0uzR$DZGg!maAd2sx0{;#V|pPO-&>!-9DL5pWSYJ==8lEp+y( zdH~mCu|5R3z;-n-#A?k|ASlktFmXtlkI3?#;ps!a|Q1EsnxM(ns39ofdr?My8t_~Y*e zA1VkzLV#tSeD!H12bpV(4ic6IvWBR^s5gi%*4wTFLu(lrTKgXPeB=wX@nwoktDNDA z?>5p$!sCd#VAZQduXyhRtqZU{1rLkf2)P!^P#yjVFnzpdi@IY4MD4h&I^kf&FwXGu z$wn5*<^B+4C;>H6$Wcb~a;te`q}fIXilG0L9oux_4bo{$ZVsW>ZH^Pe2I@kOUG{k#^xNs49?lYQ;^F#cb+Z zuUSl)lO>Csy?+yhut}`T@&-iR!W9 z6DKAETXsb9#eHS-12;mM{~8d@jrHP+_?+>qw6UCa_4DbQ z=twl()H(!(t%sYQqLzVkM?}f=3r<7kN=?Sh@`S@)chb6I*0L&5H~1%TBXdqWq;Bbk zbtQQB$i%H1?uIpBNzstWTf@C#>+s3ZklGDvzmBs5;lar_Ve@BgFOWYJN*Z_~=*QT$ z`E!$&rzsPk?ANNp-k#_AqtKO+Zqd+ zwAoJ+8w4c7m0i>M7U~GU4u5PQSh%3nyTkTS%#UfcL}1ByFf?UQd3~W?h1=S|@jU_? zCp;Ktu*%OikIt!GRtqq&M0S57VCgd*+alN~t2|k}r*E4euPgce=t&(nD>vTtiOzTQ zOkX0Y`|uDqrR1w;EwcAtU)~1xGo$7+??j{fH{sxEwq>KJU*LemrwHR;3_;G7Hc zw5`AP-7YtCZV>{m<=$WX+sz?0COT+T^ApnVe$)31L97c8oc#4jf4L)L`+QL!_DTRb zzwaAxVhjy_=>RVA0#1$)70d(fb+Axx#vY)-hF!(9U7_CEitS5lk9g`L85*|DJ~synZjD~ z<#ZXF&Uaasz1HH@J<5A{W2rH=fm1idFS;2Y`~F4{-knG#e9TV$8+ag(hPXAJ8go|q zaWeH%-nu*3Xzo+O$M?t4B~yQj-E+JSSTh*Rp60UY51!`QvIPy>SrdG$1>I6U3JKlQ z{gS5&lmAm3-*5gj=ef9&=yTF7^QZW?an7IOFAQCVU)l|qa%xIh$j7v5K05f_xkFW* zWqilgq29Pp{k5z*?JXkr*A$os)(Fv^zvE1KzU;C$+cGX2Z;-4nime-0uGupU9Ir`@ zn~Vr|doEmS3<~zX#VQgxnB$|UR}UY9SG{}VE}ook@HM>wnWmx+OQ_v}bM-eXyjI3F z8>WG{*Fue0ir+s4ZCdv?GJvUjT`RQC3X3H&U|(n~*=`oDdMC@0^zI3j_voTzSmzR% zd>~E$^&flfs(4xdy>cGnJY+GVH$?y={!u!etNZzy|A-0k$7Dam)hZEpv^wkQDrA#I zEnQr3Fw9ia1k$d0B|sS+bi5WcB0hpRENJaf>Uu_6XuDp8Txk6XXqAN!mg40;z6|W! z!V&(A>E~Aq^9hYGr_2^(Jh*htgDHr9O&NGuRuM}?Su-QK`=`|!v>{L52Xqd)G&&SC z&ChT_5Or2pRnSmVo&gN$n7ry7G|*t9tYvptM=N!fpjpRGcXZ@79Uii*ovh)seo_OY za?|Y}?2C0-w+hBBHMJ|yM}pHyJJm!;iYukz3RP=COhGzLO(}!DVr1rW;NTH#Ods5g zoh-aE-C3sq;~o5uDvOO6+M%wPqH$qLY@e+bl|?a7%B`Hp?Vj z;7$z7v1Zol`d>DwksCR!-l>>0C4 zpXA4HH15DYKg1j$rqtCouF=xjfO-vcbT0jU+0d6CnYU=LR`3DLbqq){(|UE4rtIfQehc{^D$3G8GjPk z*Bg3ewwXvlmIemJ-qI1UkUHCpfR12TK+bn_^CYE+@6{d(sJthou1jyN{jA6ucJgp_cQH=s0SbQm-_ z=p@TiDnx~b{R0esJC^O?Ck$Ty;93}_!9P~5Hp&D33uJT%w4Lf;fSb=ZkodM78d88#pD2Oa!>ZT;))U4SIOLQ+O@D-nct(i&Uv;{MwAp{u27# zfEsaKhnb&cL~>x*e_g;Fk@S*O91N|bk=vC>3$3Pwo3)dRmo7dw7MQ4K7tfH^#R*TH zD;)DtMM4!E=kv^q3fGl9NXvT+e4t6|=vV;|Yn(7hLekjGw_0RB@eWFp=+e<~@qX?W zXv^vaM&^{rsw`(q7Gr@*s1S~Fqo`VsHSxM(oXxSbt!57bAIiid?OstXRyH1G6lA#) zdPJZ^uH7tOE7uH1qdq2nID~5hBdvX#Eqv{*+PtB{>J{&gdwnB)6qA$Nc0?1HW(X_D?}{u}4h9-DhlEOQd%hp1m#0+a94jT@w-f(k&@0 zAq1(hdVhn`*Ye85$QKj|xLG9<0PC>r@2xJ!qNhz@g(%OZ`rO@-r3-4gYA$N$G5&A+YIWXpiInn~Sw$nwIX> zE|(tVt)bGJp>cL|x^UT-Imi9=P5Co>p&W9a3!GdE+DZB0=&ui~FuRs9;ZbE=foYAb zB%iuB+pvxOrZMW6SL9;SxL6lox?Q&CyfSruenR1?tzwfiS)Y3v-8$Fx+TatD9`(F} zwFsB>{`GWW|JBvf!TqWa8e{NZbeEN^^RK7S?!`=kj<@X2wUt|ul~@MrNx`oh+ou!E zeb3Y)hFOB2c#Nr|(=BgCr_aY<=?!KgF6{3ve#hU}d`;m(-?i_6JYng)$ff8M+Q!?; zk@oQJr0T5d8F3KNcJtnuP{f0R(?|BHJijNr)L*q1O1XRD+e+G`jP=}TVOjrDzrL@_ z&`I_&U@utl#5x*F(WuWZALp&EY< z_B`+0>}b2WAWS~osvKu?Tx-3A=43^_$o{%iTG`U06pAo9?u0qf`pWIztzW3-&=QV} z<@=*Wob3&>=hj*1&jFOla=Yin&|w`MdPS;x|f{I?Co*tt}4 z=KS;QuPOUgEfw~m5z?S8jEPp2Mv=seXeYt*eC_*sQ{^YKk79bL>jK-1!)GnhTmgbj z750J0+AlX%FMEd`-yG-*Cd-Z`Ue$fCt@p8@p%ZO2u6+HEmJT8( zrU9)LR-NB(i~hk7cA3)M>W0>shfc3QKumF|;~Bj8beE89*mrS`4-YyHT)cjZ-n;at zS>L6gwmZj$;vhhyxVe%zi4&{*xVRIm`omMrJxoE)yVsv;y^rnr?kj4cz62I>)(^Py zHT~8s6E4?)TKxK}{<1(dum`eEy=t}DJtx|?e^eGhLB=Dn<_Cy5c60;ur?AFsqEr7M)%s5FQLP)d4j9ho9a5Odvti9?!gH`Zl($_At_7I@T z319=ToXARzXu9jtP{XcIp>QNOvlzlH1fday=+!R_UPZ*nC5+ig{+y3sZ>;Jlgh@P} z>}!Nsg^DGCl0H$W9E+s~3VboLNx$>PfGQwBQ>|{`fDCv>nZ`ETNMZ!7D36M*p1eu z+r(kQ&?wQJ@o-DX=VJ6UtG374%9o0Dk>5Kk1(fm$=mfDgM%@%kHu9q_kV~MPfKyZF zb!?p#s60f}7p@SI@?ta0#Unx;nKw90xo-No3%+i;d;!7H3c?WB7}6{s6qQp*U$fBP z`sx28RLl;jiDC)Viw7i0{J>&)XPj-RgMLw*{A;no9nc;{T&o(med!Ps#S^JUC7mf% zhE-?_V+eeiF)o@cfco&*$4bXD(MzxM6f~>G8_>Dh9P$hs)R z?hgEkwMcyXls(0$YAJ7EyHHIqQq@x5=BMb1^iH|8u}x^eTy(Eyx|BCY;e=Xe zgld!3#{qiXAC~MXpfp1ExG31_AGlx(d>LsWZ55z1hVy5IfrAR5@Ar6-`!jQwDUN_s zk0O%Rz+~P-MAY2?rja%@+>!h_R6YGbTwKUQRFMja$;otGOTI11l_p$n3DI3?Bb)3H zpuK6`g^0SYT2JV|J6|5LeYFatgL%e()ApAqmlA|dAd==!)^~-gSdyGd0=!$P6kJsj zP57=$`M^;}#cx_^-~21}MP0#26^lg!NgWFy7rky%s&P{4H9-m}>=fghhtnfGDxRa# zd_l1X7Nm{CpMLS83qF2jmX*l;0fG%@X!cKq@Rars<^7^rznw{S11v+gEy@h={W1?r zOkeep?h<~xvj}tV7v=;Z_e{-ou)l&sN`S2i+^zK8m&zHW{RdT7{!qgv!H)#pwv%N9 zq$l*IC6hlo*!_A~2pWE8F0H5kK4YFh+Fu4a@DF{}O-YS1Y+6}}iiJd#Ml0vg3l9z8 zJuI=x&L;St4&&+PL*ED`A~pUy;Wu6tNA|wN=;ULcwY}pmEUIo48Gg`LR<G>#&D}n zLg~JkD8g}8WY$?Jmf$(twm+>zaA$vS+G+-SXW1t?HXD=dI~;W`6kqa8Rm>J&azJ(F zuw*Q3E<44xKb5h@wzm}3+);(pM7(Uh!K(OMW%b)Z*<4Ag&lJ-<BW!2DIM@L~`cHvtjh{L9e&b_0Jy(w(+|6l4+ty?1m(hOR zdQ@^mTC=?)#w4&Z4_AG#z4TUpSSOoA<`lJC&^uZsFvAvD6WFdSDSLpB`QfS1X3(op zG;}ldsd&hV{13g=B%33fDq0{xNYSsUmI{x1Z#?z^$?qE>U7``4s~b--ooyQTkorp2 z&>S`{7tvo+P)BzKpnmF2801MR3tjnqQI0n7JBQId4C1*7PsG^@z*2X z_s#wmt3GI!;w?uT=lsuZb#@?;N;&q@*3(bJH6-Kk^Mh0dSvDHq*Br9+=@)6g;DOHx zWcsN(elCqcN1umH@5KHTzLed(9#58#eqSVI@S2Fd)y*NJ*k)!HY5zF)dhB;DDB|VS zCj38=t~xHN=j|dT-7F!((zPJnAl*o=bc1wCBc0M9pwv=Q3(~oCcYTo*P^7!N-s|uE z=Q5wU&z+e&GwjSf&pGGzBmB1zNfQgAEdyuc;z0-N$Tvmnb4=u4)ou*Apy72mi%1{J$CEV6bEN?r3!Q z#@ZIgT>MFeL_WEwm&47#kw85O40`WZ}$hr8e9m-TJF5tzuS4*Vg+L;8Exo z>t$K$U$!vgbjB&{D8>6E4e@^bh!x`86vF1wTBMUE`q)UWVU)!j(1CJ0QR9mvtB4$e zS$msUQ}Bz!63fsxq-^vmmpdY-0jb7;_#DS#o@op8cZz9?qOVeIi~~Izoke?yOH7*` zvBHCKL61XYIs5P4UG2^BD|?6YytPOtj~&sik&tES-_kXM{hwB`K2*^mPlL!2E}Oxbxa zH+6zhV~cOnka^G`FY3=Z2OIJvZ4nHXit(_>D0m1fxs7&lUbVo@dO{8l+GkHQETa7p zY2t@!6zG)RF@#Ub@^zW?xuG)Y&(wa)yhn~rtVfps@~Dqj-O|LebIIjUQJ}h=kXOy2 znJMnG^%22J&l7^c_P-M1brF-^dV?<`8zJL}6VyL!fOLAR*m07Qa0`PLU^qQVRFnn6)3t>`gNFuJo}QQ zS5z!erx~DsrJ2x`Nv-B2+$F8sYj;r7fHz><2STr<74+J*Y@4c{hyMoKBoA;U^es#0 z;U)1zICXdF%nNK$$OrL}282pdfUV*7G#{~P>yT~WcFZ4RUwk1MA&I$1*5+ZKQm6eQ zZG{C5h9op?9@#h(TD|*2ASasn3g|#qZ4Etz;_Bb(83vVg_E9f{8N-C?f3$=I_aN$o z@FFh%h7mK&rIuj{7ez_tau1M@%mF_1tSlRXg`tZYOsxHgemBJmZ<;K&pQ$(&?M@Uh zaHGR{s3iCi2WYe#449_wK+BaE^vR?804xCNXZ{i_1YrmnuJ|^< zHgo_{$AuSv`B#RRZ!WvsI^9tn2QXs)S@#my%Pha<0@qeb@JU&c$c@Vo{<7!Fu9lkSI@A&2Y(KSOc& zxEjWLj-qQ4fGk>VWM-@^Eg;kl@=}PF7;Rui*Mfqw^J)@QFEtll(=Js^!wB|Q_{1V4 zpLW-UCcdkKvcR=?s>5+p`ap+@@IY<&y~A1R6#Xs0nnkL^sZ+qLAIaot7^D1GxU_k) zozxY@H-iuSO@qN>e&->WJPs2ivQ(VWGF4sCB8mD1KQNfxb%@gP>aHNbBu>7;&GGc4 z#guj!nEqTbgLZtr_BTDTbA0K5TOvhUnjm~GB-bc zson0@vG~Wm(f*%PVY_5}>5wZh3vJQzA+UjNV(@Ej5CAvSau`w1>0hw?v{4vG!;k^X z<#A~2y|D&aB%Zp(sQ$h9?8Geiz%$zLc%otO(r;wePn0Gw1o_bS6Uz_w&r^fk`&ENC z3*SbfqNWh7dA$8U2ca(Dpx=|$`16@}E~8Z|H7M;1Sz6Oy)rn%=&yV(5^N1Xv9Ssks zIlkBVv9V9KxTe24sB-h!IF8GeM|IMiM_b|lJ;lN=&Y?xyg(GG{`2oJhySD^NZAI*9 z3$0h%3jQj3Y&J!s?sk4xPKPe+DwF3AeAZ=u=0?4rto`RyIv(Qw{`Yc6bnicR=lz+w zjv~&0`r|I+drb)~6F;NZ*%JSmdLF$&t*xwkd^DIH4f=Dic^7-_`w%O3Ie+i59obXy z$S~rk<#)I}^+q^gfy`}vx$476T$439#0e{oPv^)CL>Ma?>$2|s~F1W}*!KM&b7|(I>OTc>R z&-`scEpV&LOy0b_{d_zUZQHmz*CPFEBhgUbmdEN%J@ zw$~P7y|ReFT0xeY_rMw5`UgVXiXM~B?=|%7Nw%e>VgVBH5(S=JzYjOW+w-0R_R#c~X1t%= zUYS$uhwiZgK@NucajdM52uzq5)^R?zUZvws5m6%JmVv3h?+HH3#Qy)=)S|>Ngzo;A z@DdrEEDZH1kN_EsI+2X?-&K&46qbN*8D1j)Iwo#=6ia<}>ba6;xpDZZ*aXjg`Yjeb zq^fG4FVS~C$<#?_kVS4B$2q#C2{j-7(x=|xKdI&4E=z5fAt$AU6^#k*)0vMLbDO_2 zqYN9?9nhQXp)HS+Iq`1{W6(bZJ8ymNB_>6Y0NL9Vk`Gb8mYy-GqCiFzktQM?+mEF5 zm4Ue6>FK~4C)#X)BMh2Ceu}2Wz8=z<2FwNuE;rHF4ZiUdgWvPxb4A*vvfG-DqbxtO zv}A$K6yju7ohC^?eI6a=GCSF5>DkM2XCxy#N3#5;+|t7t?;Cti)8t?qT4U^6*1O=M zenDb6LtP1y@uCpcH8$CwwRBuMgwds`}Pmy&|l34aiQ_tku{}#D;6Y9H<{+Ct?}g% zNzn>rp;r7_Xi?0{vjt8@xbg~a8^c_9Y0a;2$cgJrU!qn=;cF#TXcZ^9pcjMFid4HT z7kDH3eu|a0nrlb2Ml3X}IiT14rZ^)WfHP84{JVfG{qxT;E~=7Qg*o)}guceks_zqw zR6=0A7R`4jKeIqSRs?F;Vi5UxSQUl*%m?5-8$I<<51^z+paQ#J^Ed@2_kZyUYy%V` zHIMG_ur(Xb9ndxFi^?PPHk|LcL21o~aRn=;yf}PYSKUeif+As(=gmVu3vkVdF>Fmy zvNAp#ALny( zWYqmM9OdSi#{qop3*8{msQX1sKa(DgLM7o$gq}CeAZ;2@m}T>wkcl^GuMK(YdtW`Aixz8w9aZAerTQWI zu!SQDS#<*2ZMCwcBTGE&8aPM-h_DRwN`vjJr!lE}lgldksVU@hy|jsCc%UOBS{gKi z*1XqqJpjBwMGPX_x&Nq*qa=-@4P_VO!O*um0`O$4qZ#lf`~hP5X{q^)zF01yaZ zP%ws}z{aGrQbHu(f!oI3Umpl+&=;#pJpjF3-$fs$2VHmOPJ(L{TfHll5K4P;2iy)I zA3cm=9bxUEwEh`zQclISS z6-2W#PY>5fidCg06iL7};wTV66^{O^GQ=pY-wne|ohApYziITtVAGr%nDmuNq3D(G zziDyDRsOT-6$A~@hTswymy7WLXbox*@*-OimO@Dgn^iePj00LO20?GECYNpf3BoI| zPgX$BAM8^nNcrJjT>WN~HU^kU(Q*!A5Y$@W<97MM@v0mK>xA4B+Q8tTUR9AJYiTH? zW~ae&`j`~oi>qz-%JHBzA0U=bTIakNdXEj3%p(=jmB~ZzE#Xxzyjb8R8P)Az{ z5+(oPp<2*y_)bp|^qMD&yKSR5HT&|2$06#NEkHf;*kIgzK*2;AnXtYpBeJD~7d~BlBJFril`)eDqbk$V$xRRTq;l&O9_J z-DjnDgx_)e=2{;;4xl%G$_5o$L8y9`)8ie*?n%##og8G%(tDy6|3hd%f7}Udso6trI!IM_WbU%XO%{t z_i~kY8SYSFuVnzGrSjw-P-yzT@=nr6x00>3|7m(Py?jLU(~9oZId03|Wz?^dVdx|~ z6qP3GOSyZXgkj|!Qh;Hl!KBlZ^Y65B*jL00@5}WY#TK?BR+`bd-jMD8EKnPZnH*X# zvgR+Z?H;gy!lfSgjkPArM^V4y%=axf)Lr{B*Z38c>WGw1j%bzyuw5(8u4Z2cZ*l7U zIiS#?tH^3O_C4>OGRrk`C60AfBMd6TVDqYxex@Uyr5e*>h;RmxpZ9dr`3WTx9;E=LV=5eu z%sZ36iacf%<+mDFB=U3r-`zpr?$PEQ!|T1N0Va{3wDIE}rI$QGlh&n|0+H&_()B{I zMIa_dWp>;A<89*Ou4gv#nM$t99m2LGMd{Wu>^d;DWQ9giWKx7PLG&nck-UGU+OE?v ztlHjeoWKgZrz=r(;x>CNc}bQgjO6^=QDpHOF#0y5-t4m%wV|4Qif!p(9H5@-`(a(i}Xbu)z2)akzWaFbwG|x5Rg7 zyYp*oBF74Iuw1JZGg7R;umFZZQYIahL6Q~0##WkZIQT#~ba_UssMS2^^E%BEjp&Po z2Jyxh3-wH#C<{m9%go`%t-Z_`SptIs82grQ1kv=4&p$HXfMqwW1dvmtIH8#Wf;7@~*@g%tbtD9Z z>lbR(`=;a_d}rvk06s4+iZ_sAam&%rud&8h!Z9&tB1ypvJ}o?_e|i;u7;kBP*eslW6@o~j4ROY&qYQAtlsuN)k7IbYXx zLe32~uj-X^(o6aepPn5cU@-v7Xo^469UAW6n5Ji^axTQ6BQ!)tc2ZcoXV6%;hYJK$ z3*xtP(x-&sd5%~8a6-$>(;Jke_?4_g+FbS$*mP4>qtJk5Q6T#GZXzkBRUhJr; zhHd{)u(p&LrZ6-15*JZCgx|?82MkX0IK_x8%r24}J?D^~4Lrt_o`%h%uW`F3AQ4Xw zX-yZ;WA^Y|i|_pm6&N9c$O_WbS3UamXbCs$H%N75(8MYxS)r%LI6r;Bh!SuW#84Dv zRoU@e>-CcQtE2}2>#G6rh<@7UDD?D^EBBIB557|}FooaC z^;)EUXa~FjRJ5lI-3payU7GDi;TXtgN;KtbncYJ6z(hdG>qW~#(DuYpK@UT6z&{76 z+tDPKl!X0+1ci_oU~z?VS!U{}da)^|Yh;uZ2KAU;R6)WG0j(4?HiL0=3lWG@>$m|7 zgX*-69$ui=LB4-TDaj3zJW_`04(e_?-nB5_qyHgB-0naubw;MVFx_E;rl!pmt zq@x%Sk8#%DIZkGd3m!Z!+%oM5fryA{;m}9%Wl=0YedOES-aP%fBajzxS6%RaRJG)Y$4dT;qdqVEowxNXX#G;sN!=YF-w;kbAF` zlEH_NM_eR)%>lwTDRH@N;n5R^DX;em1XQwuJSviDQ_CuTbmL>|r@mtacOt2U*qi7r zh3oQ9f%HGK?;#~sG7G)}M4#8N5Y3o7%O9o#a1qm*il$MO=XqlntudNlvX(< zHpMGNSBpD`&P+B6$8}R3=+N!mj-P(>3pQc%t*)zhs~;i)a5E=*iM5aR?i?@NuM_JE z=QRyY!}319g@wh;8b@@0ZPi=FGx-1wz;&N^%pfC=6yRCw#qe-DMYV}npmyDyY`PTA zl*AhLsi9QXciJPEe3j^=Kkpr$ZOF9Ir)hnw@-tiSx+l=%_cg~eM(4oDK2`3q?KM7f zPL!KwZT}^~ZVtu_4HqRVWuo>zVoe!_@ZOJ&j$ zSRG7uQlHbtdAaG(g}<@$sX7o2BaWwk*7RzH&1Prkyvf@_WzhXN7d2~dI670f$5^l} z#u@)Etv%wg@G|=(_}NyRnOf>HlV)=6E67R0&&(txH0swv3nlOF1Yt5w&NAn4 zx)Iybck0Nstd{B_+7mrZs>}NI_^gfAC4&TyA4rqpAqdbnf3=!Qw7c35X1cg~q7<2q ztVbMjqQ~uLs6T%Cck&e&@17}7;PftYjzk~-V9Z;uQti8C zyMXM(p&-gvqCCaf|KTde$bCFue45iV_JXn7yuVO_1t<_kO?cRr#m{Uj^h@-t3Duc9 zqMcF0p^{%FOs6iTN%kF_hJ%cb5)lkL;0SqNM@>P=M~LmKGKUhmEu8tV=Y5qfncH}Q zbC_b6(u7)2lG4eT6zh4Fj#{?$El@%W{(0{G+Y&8eV;_^xTIYy#cK-WK?DI@^e&94- zwrIjxIIUV@_x3&(Z!OXN)AjIDs=A--dU3E51Sw`Wr-t9yMc z(>iVz#Z%#b(;7=V-w;J?J@#ctoZrUZ$@*?_P^fKYG+FR{v1wF!y3E|?1**vN4N6gg zQM`9|BZ0_XSz=)xi#Z#uY-U>o*j&1|SNQ2P8GSgX=?uL61o&CMUEV z=i(3Te+@gktYw3_>=d}y_CqN5f7r<17niIQJ5VkS_Di`m$%_4+Hk}BrUNO$nioQHr zx&OJ|>!Dj=TDgMYbKtle%bi(8iiRs#H@a@Cjhm-kfgO z#VlAwt74UHXV=dKkE}GXM(F*!O}=@wlxmUM>M%n*aJI9QDy68mLZ>}ye4Pn+<~SKq6f5$<6~r#4Woo?@`LC5W zAl2C_SVVrm(g7sf?}6n0N*9o96%{H140?7k3xA7eYsCc$y7~3!9do{8mDk<&iJd-@ z08*{5gvHG-TEA$=Odq{}r%rx(w3%w5h)&#M?=4tDQn-4U4daU8g!0C@3wrqVlp5fr z11I|;p!x3C9?IM&E+OUa-k!?b>8*?z{W~RKf9oBkG9^i z4sgC{+{QvLJz&Ooo{>xgj?2)1jdjr9W<#+e07ZYZs4QQ`oJH804McL2#5_STvtWRo z_C1Mr)^o7iVyI0rBeWt>_4ry$CBV@JM$XMr;=n={Z#j2s~;`5 zLU<@T|EyvY*J~MNI*%ijr@K;BF<)YSyVP@iWM(;zCZu-9v8y|N|vx}Q@&q5%t0CS}Ylt8VR5oKbg1q&s7s^oIR3 zlLV%G+U(Yr4Do}yu&!cufMbd|+orM?sHuzeL7i3iy z9|rdW!1*VK-2qrQovW>$=lYu+2AhPJHdw*{XiTcFM;#owxk4etAsuFuj^Y534vj*ob&pQn`_L~l5A#2B{W!4N$rr%9klR> z3rKV z;3cDMD}4y-eQvh?R$E=FljIvYNjuX$Qb3fgPOpvaRe>2v#akKseAs=P`jK&_dyoDm zlqyY*v1I{8*HwZ8!nSt8>)J5HO|WS%wYN(z^iG%cU%o`>n_4=j1HhFC5JD$PUSg|^ z3N_b}4`~72KIJG8+6$Bxu{@*TDxA1V2KowO$PHnyN3(XroG3|V7n;^62Xe?2zh}_>@L!Q##z_mG$)LxJLnk#0l5O^B$ zdL!@Pl#G<@+i7x03K;iaWv{cJQ`Qo-`SCyaP_YwvnfdK4Ci6Z7&`$gANC{Fc;}Fkm zxuey$Ny+S-eL zg`XCj*I8I7F7Y3MXHnu4jNwRp*CELCZYlnvp`AX!sT0HWt?mt0_p2v6A+e$|YOSe1f`GyYpz;-V=QaxFr0~!KccjOY}{| z{N`P~`});G^>vZzHJhdLSE8bkO0!3ym3>e3XO@oYccs^%`2A2=wFj9VJSCQR{EChxH`}J+X!TlNf}c(skc^ zObW}xbK2z>a@iT5yKKMCEci2I$tYMJ6E<2=w`ie%Ru1QnGBTTcM=-4${=!5q`_+rK zGxak=DO1e5ExK0GA^&hM?2WIXwT<*apQ{y3heX2*sv_E?=e3%*UG>U2*|P%TC`mrg zPBOVhJnIHj=!bP(cBEq)&6g*g^OH5Nl9hE`wpn+T_04`-t!f@1Em5nQ@}r_>C#Rd= zrzCEnzMTFBCT#(@=tGx*2S!_WTb7BPS{XJZ2)s0#Vvm5E^|meL`FlDjVl^?x!8mud z66_^zf5Wx4Y8cR3VfeFd_3tmggtJ7qnzv)~A8QHc8@IUAy6yUm&l726YoFC z%+I{R4(Sbzm#Xl)v*t#?zF3p1C3ZsOgM@X_r)_#fX@_}&?3 z7zGe0*H9J!J$Tcv(D+gMTILjy(NF0fmyqdU3 zr<;jS1MLTU5f;{*Bq@~~MNg$dCunV|uoh=+s?IdFdRJ3FvZg(JvU*>HR%YP>X^alo z{iM@Y_+2<~3y8Cga=jP7YaoA&pz{z%s>3L!PP4`^#_xhi&j2M9wv!}IUFJb#Z2it0 z2;tPJ))>%#?=lkx+}k_-+Rx&rk#7Fy8<-0USoN|1t>Xq-r^01Mfk3T{0qn_Rse>qR znq!?`_6m8tu>1eJc}BQK-KMGTXumYhk=7HwxT9^teS^7GogiG@LVT_f2j^xXnE%ZV z%@)731|0f>rXb6IHCoQBzlp8clhTizuHx_L)%#bap6B4Kg~z`R$%F;z$5k?014yj% zH?f+Rr~oT3b4)+(suqA7ZexVN3lyv=WT%O_ur)7BA-$z0y*_j zfSq^0Lyn^p?F-7GRGh7jycTRt;7R~&B~rUGLY2pP(dwonBHX@39|0lnbwn*!LO}Ok zP~gd{BAxt52@SM(V3v%`0<%N`pwF8#EPVo^y=hNRc}C(uYMW)-J_py73B6WlgmeUg zqH8?v#uHbm&<8@XW5Zrgs;ra{==M(iI9o|f9Tg(2G6J1Bw29T+B%I8hBV^Ou(Hb)G*EL$)E0Y4zE7KiH63xKRI7Y*L8UUKmhu;hF-n*8d_tQ5_JHzy zS_JcsF1_{;;P9V<-%2Kgq5Lo2Fk~)^s5?OonjZRT`J85EramGgIU}C|-`lXDP5Pl# zoTqahLiORhqe%FmEdy4TE<{YKhcZLj8+#-b!vE-q@q?WiSU@F`dXqiO0VrW%GV2B$ zA|lld3_UxmC6-BHEdGWNe}Sr07XsJ=8Uh*%5Ax#L8i@CxEYMFq^x~v4t>US5Iy11g zwW?I7K>$_MTUKkVT^lnjxpW|S(?OXLIudV@Hy(knMu2dKYgp~d5UVN+L#L|I;7O%g zaG<~7U@bFqsw1E#HS7@xtFEVkv?`A6DvR!p7h$t>v2u&ww_;(O?{J2=-f)lWWK8M# zG__`-wF*wY?y6L7G2i8>}NGo|8Ay~Qon z2EH;D+hDNi$`fpqhtOOgz{#(?zQrXX`Zr3!eq^T`6FBF$hYQ@E?APm3 ztT(lm8wmuqwvH^G)@aK`9)GPq_4T=^GdloJUmVoieIgpD>br?3i z!#9HvYQvIO_MR6*6kWHCMx(f>PU#0P-k+g%4pfc=h~ZQ0`vyJyFojpr{nEb_ubD3v zy+}zO8jzv8S~7Jerq<8C_O3Sxx?aJ5-tYbWaMIcFeB%8!;Bj3&=rg%AUi{=>$Q$av zRZqK@G*3@1&%b_Sm{$cos|Q`1nwmb#FB;3ctgGOI#b`En2~9emSF+%XS8kb$0`(r7 z6z9Od*#3R!;w;98d;d`V+ttA2vA{;FtBPOiht5wcPdqV;=d|Eq#=1*)ea>3ezp(ud zS(3VwzXMJVtS%}a*7%;4QWo7=Jx|>)nTH|F+jVGla{b*cW?qK*9LdlVFNwE%0j#8B z5~_-BulQtWn7?t%3oI$rc~n%iE*pV~##E`?&vcb$P+)V+++*+OXUL!4 zX6VrDIG)NPm)YOt&sKf%HF}N({@JRLll`LqN6#tiV_eD`uQUD;W%pl0{&n4vvF(CM zCZ1QTMq3f6uC1@?`-iuN*+_YQ3n(9 zg#%|$`x~O$eV+r>r@hrm^^{ILC1<*z*D=dRPkt@4ytn&K*1035gHgWohnLjbYgdSP zn)Smgk;^B%#2im_uwum;G61oZ}V0D<8M4H}>-*PnY?&Z{t<=%b6^GUNrLq;PL8{hwDe@2a6X1xPcU1@RvQH{NImpJgD`W%T%FoTAtua z&mK_T%A+Yy@LjF0VBk#QADle3_D9rGgUMv1p;f6rwk)(f;pVc=gd-|ts7T@@-Y+#S zNQ6*W{IDEfq<@WYtA_!eY1?QpPq18KFfLMk<2m>1V8?0OvIaUyI|mq#*mMArBjJ@o zVj&LFYm(Or`vj6!NKvpS10)X(z?ELm!X%7hK4146$9(4BM#A0`8d`1Asx*lq^NIZ{xFK_V?f{hKHYSc9p>$2UJD!E|cJ1K%GSvOA% zHT3}AaCk`v=!GC}I>@+?5;dBdMMX~c0c74XcA|~S;#hv){X=f@6K^CQRu~N7(N;2rKLd>;Xb``pMz6r4A?x#z2+9 z`IglfLzCnRI~6<9{NEc=3yYaMK$2HNY?v~NP!t8|q(3j}ESDY<-+L=6r2-@4(jz&1 zf8Jo=f{Sd`5MChA7>LtVz}${0`RWc0+toHP8&&EZ`)fIkpIR|_rH2wamL=wlniw$# zlbWIzNrE!LUbLu}De~xsWc#5< zNV=Dntn3$ju#G}`{-a4On0@?9A6U^2MadZ7j~CSzgsfzX7*b?g(i{fsi0_XRz^Shc zQ1$J#(ycHl^w|8CvS`ijg{m1G)CP#G>dUdkG^X9tLE@+U7#h<&>EMD($SkdcB0*k0 zE<{SE6_8fLbn;9tq4wL$qNVaXa3B;|Nm3z5k`hVZBM`8{XoUeI4b5_7#3(=FrVLlZ zH{nG+NWNV_xrA6N%_W5t(K-(iB*~zsTh$EnU?|$?3OYy%|I!bZpXUaI@Pt&9;P!3i zNReH%D8U}IN#TxP#ws+%-;)JcB@HmWxBcKv^C>T*h>AAqf(kcHCK9Y2yp0jMsEo{a zQCos7ku-V)k(A+lm7bC`3W(aJUs4$t6XPH$ec#5gSp0%&Yis>@^OEv{3+eXpYuB_F z>G(EMt^Ea+6w9b^%I}~J#q_T@NEF|nF&69!sAwYqJv|=%k>mQK!OCXn&NYmynWO}NvO_z@>KD0&k_|H%VNg|XsF8zB&Z>hOycIp8xM zfYhBCPrB8b4`8DPvBC5$#Gjn%b7r{s<0w`g4*CwckR*Ji-(zlTW#{On`fAqlV?O17 zdhfnH7@y`-+C1{(%V-RscT^wt4JhF4?u3p7SEK1W1|-b523Z?Pk?se267<7vmtU$? z(7#Msc-MoEV=T^})W`E7Nl0SSpP-M(A}{KYQ$z-T)JN*S9iQaifwXQf?e!+HwN!dW zPxdmy=xeOnh9*0jOK~_L>uAFT>qWl{(ydM^#RJCw)MhWA1>?|G_`3`Fa2r%BY|!C) zRL7C&gZ)hQJQKbpa=yLjiiOY*f1wxsgvXuKMa_UCgYs)d7Yi4%hDM}!y^&-8t`P|3s9M z0f$Z7oD12KiqZ7MDOc4{`cj)fs(!%hu+;mkvR_wif5OC+(kR_epA_nUSAe>f!MwYu zG+}Yn`w(W~lU2wx&3d#A`ezD-uZ#D^IxY0bYLNAw18zeQr3~9+( z02v&c+NC-B;{hjs53gM=_)?JGuBEuZCcFT6QhFMAGB`a;7)h2mq)^WL4ET8y+`&cq zG)AtZp>|<|RKHe4B~?Z!6pFA|#O&g9saeNR^YP?(MTobO+k|1;sDxzI=@5!P1t@yr zwV^*gDJV{mBa1kR1gkZj@&-e_w>cy`9nU@n>*KRo~&+kcP2(_`6~8CpBof~L z9{jHKm-jo7b4Re)y45Mgp{F2?{~rx`;S^}$HpaN8utJvelp!kLGz0Jhw`{y4<**Xp zZ&N?_L*hbGOG;S!rP|BtJ&8c{DNp}ZRQu4R{qXWo1A1PSenR#DCD~wFoxlB-rKl6vlYSB zs3kQkXw-Z&D|$ZiyeoSs_^717YRw>~qG6+vKBX*JjVe={gG&7`$M(CSzE7mc`o$M& zRMJ$&@A0rAH9?>(wI*PsE4V~4#ix`|)8DTQO%l9cDQvv&n8-v5lUg$zkHEzJ&@Lw_M`4L6`k7Nw2G*_5hOl%YOtMJ%gHk4IR<`VaPtjG- zdWDXZf+bJn*zZM_H~sc&O88UD6S1V$w9-k4PR~bF-+|#!{LF1YJyl`=P){vrMT*~Q zxgb73gt@%<6Q~x7kJB%vu#?kTvlF)3vPKN{E$&}epe=@isj#~3iUI=qn7vNo)c76i^-P^QGZv%vpO6aomb0#nV-c>|+(9u*1D zU7gzbHYzN=w1dLOKnhT-qkR)JMn~xImp0K8@=DEs)k@Q7BSb9BJ^VvUR^lYrD|#v^ z<~3pI5~C5qpA;eV7;Fn(bo5Blu zteh0D>9$#GR2j{GdSb8NL;yEH;WS((CihM zqq>QLt>g(3iA#0KOHfOq?kP`0$niN|vU^)0mWk%PX_g+KEyjX-+y=&9?W^*WY)v2g z4-ICGO#hpE0Gi>yef~w9x|MUAFLr19lrT~J$^P}>T%_UO74wY_FX)nBkX!5Canh2##ilf;KCMrtiM3jN_&TZk{1-{b`PNU{{?*Oiy)RQx#I( z$EEu2fYGbszi`w0jNH;@k@P5u9oLxhcel65G3>$a{j-4V(7^!QgQYS(jIA=^*Ku{j zc_FFpg8nT_|7<}CL*nCxI{m@(oyqSFnvVM`@3A}=krePT62ft5`(u&w&pPj_Mmd7*};n{^YW&sD5AAwKBW8-{$zqkG&j!BGG}* zy(%$nv6*;(wqFeY=wNVqg~+DeNX*fvK9PS;>d<_h;a4GlW!Tb+KELTp^H2WeIKQ&G zJB}(;F!z=rh6K77mV z&BtXnFC`7cC9|=t@@`Rkn|K|>V%jCXw?-dr{kxV@^Y3A(_16wd8ei5`J=>f?T6ec) zw_^s=-eyq&ae^B16ahmb*zwNCH@+5T6g}YgD=Liy0n|CN(E{qSOtSNb8#sl(ZRq~d ze>-zuSNUK;gDr?wPQ(WciFi4n%!(SIP2 zyH3UJ^P3<}MG6`Ckqr2lH2`h8NqNWsw^tf{A9qvQOH@e3*q2DrcgD@C(E-$jvT*^~ z398XDiJCmo#*+$=J^{gW`aS{gbmmBX3%NM8rgV-0kpwNeJ`r_AroLhuR*F8j4FjlP zvVAjpdVA}vPtVg^xOWH9>d3t$rv91yrb!YykCKK{xU2NJzw~2}utjQ1w-|Tk5tj`) z)cYHUd`1)-p^SU~5Oh{M4M&D4VrZ7fI|D`j?Y6{upPomFaIc<6`J&knSDO25;^K0E zS=Y}PceE-v5JujDee7GmbmO~QA z_r(M<$g_^5ZODJcJ`Y$YMexpUzq^pty9{QO0c6;CX1AO@`fShtSOF4xF;kZteRMy4 z`-lklmeXKBI4Oz_KSQZoI+jO z=;$e!PNabPN zl|6kyb*D5z0#E8CTm302-dnm}Z!OK|SuhFCgf;6$`yKu!j4tp^?Jq^RWt!*FEe^U+ z6jwl)_!p^TbcW-qtG}Th!xhsi@;Umo#_+oS{IS;#|M4+yIqI;!P1|ZYA2({!!VH+MIb=Mh5gYe=% zAN3r?e2f^I87yMM)|w#In(RvZrv>mG7E)fUM#zJs|KXo=`7Gw+KlwaMZMk$nl+^me z29`eCCRU5hA7#*Y_SiMj;eT46?>Qlny%Qso`=t78h48ozS`ZNJEW)}UfWh5OL>Ev| z04w#A4huqp^!MXIIDB<^s%eiRxSt|}5h*-q+T}L{f+KLk5+OAy%1d0;9gGrk^Bgn!c@c=!MXfy)NUC8iILX6a^ER|K?TD~}`=s!Tj zV8kto)_dmoRT}Glez0?c!ggKbzH20j)TxuvQX?{#s!Pvte%} zX>dvianv$dt8$bGMAs1TFlrQ=xs!e~u+l`-E-;Xl+hDnm0#5v9BeY_WRcRb+i{5*h z0rP0NjL;+=o(MHxP-gnREQ5I&B7 z2mx9J>wHYVk$*vbVcj8dfXBrR+J@T+clLMbAh2`kg zhqRT9M3O&=r2P3T$0WVOCN9G)BE%D#U^h>Hr<+N?Kyov8~;O|8+MPM*O1UH|tj zMThyt?pbqwjK$JvuM<0*ZF z7X`=-?%%#!P4qHVvDVn1{rl>gRO*uqdc@m<88@1?KsV5helB z9LJK2Us>}imO7~ZbzY?Sd-G!kL!@1kQ6w_@}00k3DC2}sQcuV+X!Wb8dUYYzGF z`M%3HIJ+oS(%2umm8VhWu+1fC(QiNo@3rU;9@+}#ZoU;80=CBAiLNd|R`aafooKSx z{ArZCIZZq-`I$dwKY!$V+my)3R(&iGw*Rx_w*+Fo{|0g+RAr0OG6_n(Y%AQ7_%8EH zh4m8CvhwH+_vJ1(!uIwv>8hNCDC6LI~q)=vG28 zH3GCwK{)PuSs~{Lw`Xb;^7k?ZN+I)4_&w`a8VvLqG4ApLdF|o4Nb&W9NFxp<7^Y3d3 z0fyoOfvpE02wIm83@|=xrLwkI#;Q8mH)fev>@_-YTfO5_-#bbY&W9$}z&D*Exg7z` zHHfbe6h8#syR+ApWzL5y1G1D`!Rk%=ekvv|uZ^;bQwT??>Q7Pv)Wg0=Z@}T$E|HoW z4JP7|eLCl*Yh_D~zBo#}!n(Bsu|~u7T`ehAwC)XgKCxz93J`b3nb3d2Zwtt?C)~LMd1tKFf?~%b$Ay{!rn7eU>t@~mngf?f!VJ}B3fdu*XFkVyftET;KXg%D z!@}rImCUS^B&2=`XLKXy5eFWk5}=t_)ts_$dguiCVa4gaUmlQs>tZk?QPv6?&mDGgEu?WQjnp6U|2lE`j4YXd zJ%7W5sRo5~Yd7MIhO?_{kQm9nc9Dt=vgn>rVLPk{#Ap)Zw5%^be8QgR2KE4h$hwzp z@ElA)Jv4;<*wk8S++yo@fjD}w;oF`*WSZ1?tgzI^9Zog|0rLXR12_lqR}hOG`k9f9tL9)-|?vG>!GHuy?i%9C&=dniU>|?;#>u_vGK@QuK3_DbM`?@D`+yc09E_=N^$#`$DD6=r3s}9x z-l(QE4Dewq@d{A~Z~R?BTeYD2nlI5U$+VY|BI<<|qRRIPX92TX5|5qdIbam`z6aTN zv4OZPLUKeoBQzc$g0r$elJl_27T>L4ON2>MQ$`y!y!wP*V=w4~{bJBzge1E{JpA7R zb)be;3~vmZ1X~qRWY{keNB~;41gjQZ7nxFE>`S*cot1@ga8d+%G3XE@*Sw3fM~1`+ zGgoRTj^JA;H-)u5H#CnJWtYuT`Dg(}`-G_+!q=Sz(O~RN&50;RQz|XNI&kVhB*^ z74$dY4%#<3h3gF6mi6U%8D=_%ST5W^oV7CZDxwMC7WUYX4@sivLPY`2+P?&gOR*8h z(yLVf64=$kwnP?#A@8PA=PwINIhMl6BB4GRXKE$)fgez3!ukq!m?-T>g)_}tUftP zwyY&*@OU8vQn-8RxvdX8oG@Jm6bwcdq$+n8yO~HSs6PYC)YCkJUSUx-vqIoiYBv1v z&-jU=JcZ~<{nY`O)cRoPjYKs{RNg0_?BA7~CtYKCUkCzjsamST>I?=Z+}dtt#Ba~P z)P$YuPfqCky>R%tMG7(yHz_~=J+Udwr#rm*TVmK7Wo@}bc|_-o`G$Ybxp8gA%YIFu zR?JB3mkyrmY~Qks(>^oii;lay#Dj|<;U?quyn~F((!_T4KC;C(z6vs)pS}~PM)=+- z<~pEycD(Tyi9gu&QMkHLX=;B1_7kCjcbdzcZOW-{_ujoB6VH#mW~X``<6nDEG%aRs z7yZkg)x`nU^_STWcIWx`K9Ob7^{wfBt9L691HM?gSC zq*tYd4#{`8_df5%``-8e?elCnoSpgYoY_4)o88UK$hB{JVGWR$lBs-tO7yxyJHq zQ{t)ewMWL@^$^gMZwaBPF?9~hE5SV;c@a%_hHaJ$J|VIHqDRdO^>$8rMO3`CXDJwj*Hp=@bxf zo#Ay!u{VtZSJ=A+qOFc?4u!jl8sX+ew?F|aLJ5{}qAi>7De=@^kYE1-Kd#diVvVhK zVh&fqd-kBL8@>V{BfB_uDlR56%Q2%HN~X|fz^+6Y)Ejh~x?Jikl8z&0v1txA;$#Bj zs6>}5IrvMb;~4cX^MlZ~afN=4kUShDmk+Qs`=E>lhdTPY!Xvv^(vbyH7Klm*1A9un zq%L*E+XdXjU*9THNZ(u}O9Z)^aT4*U`G^uwainpsDB@~)^uhRB2s+<^&z=No`{UhQ z2wn(-4rmq|XZ$d_8pJ|B%kTPp#tgjDL!?#NOw12strm&g6EXE88rpCJ;}{5EeaJ#L z%MXjEG!3tKR`uQqyc1NxQr(j?8T#&6m=Uz#fJQiZoV$$LM06no?D{~bz2t&k!p*>F zAnuZ8WdGHqP~{jFdiE;9Vu>*JjgNW>Ecm-1i|>A_l#!Nzw|nNd?}qTk)E0=upKzd? zx41mO4YYX8&$5BlwT>4IFGz;l?bVf5NI>C<&HBj?fnAyL_+_Fx3ShmBX*$Y2V@@xj zl6tXK)QB~W!{IirMrGTi`j4=|cvi<1uFbSJvVLG9+BVBvp@4azR?C2QAJs`cy9TT% zIGDqPB^7o;mmSu(C|r@GIafwGMF-!}t|e zDb3C!_9~LCnufC#RhovZ$^$Z zTT1t8`BlSgDvD=j*3J38F)L;w)#{Wjqig_0EI?rZQ1B(o zv^tU`0~IT4f><_!xK_oC)nUPgkwx=)g#^41cmhe0R9%@INnzGbq4063Y)m1$cQDto zShX6=$1q4tm3dLs6RqzerY7-H6}aOlrrLBVer}?$&mqAzCa!g&xWggtwr1SiihtNJ z!&KVU$5lGM!?X{nuC`aHISw;SQ_(yg*0C6-J-cx|#yYW}KwRBz?OCyU}FWSQ~W6Ik{PN3^&2b0(AJ|A{loFf)(rzsP8=cjJ!j*+ zK2ObZ9m^{9W<$_S@%2`-XPto}MP!61b<3OhTGtl$q87s$Oqnoczhc{LE$eBhYpZ>y zc-+PG<`W>)Tx6KAJJWYVzQuamz+TtJp4grokXUCM$o#RSh}J$SbSwa;>=#SFgd=Zq z%A(%9kj`S1A6Rz2mt|2PYf<-Ba8uJ{zg^vA;GpQbmnkMTU{SRFIuB{x)bgh>+ck?- z&GqGMrsw;6Q%uE-A6@XB8BWR8hrcOJj~h()_>F1JHZHDA_PUCT8MeQ*c#Oy^vNC(q zpz_InknMe5Rmdb>ijygm0M(tq%)C6bC#P}cD-%}2U*=9{K+Mb_YOxRwlPKM~t<*EB zx8H}>yR*?0bQrZjSn{hclcd!SV9@vLRI6j9I&LQxlW)@5vjo?PMBj@{p=MsX9*lda zWG^OU`R3^4xLuj)M9I7^5$>sqKli%CTv&Sz5&h;dEmtF5*E101R9d>wgiUnp*-rY1cir`-OhY0pDjlwnI7svhOm?zqevUG}5@y z9@}}KhQ?b-m1Z{BSxp(3tbseULg?GKJA}~vLWmb{+G!Duz?n*b_^%?1KZ}mVQ>Efy zD_Jmz5;S($zHsV^FeF6aKU@wY?EF@vy)mDG@)-!gYW^Q$fbL41ECWF7ab88?o0b*S zXW%Jv8wm=@4QIfG1Q;n4|+2-*SQu}n_@rAz@z@t%PwO@|1yRUY)S zAesP$5;W1Zc^p>LqUHb;rY0IColwyyvpdeLh< zeL(j$(AY3GCf&4UPWvPY` z;e^+oNPagO%u#@3et4Y3`vO>u>DIA9mbZzcnuY6u<9*W}NE^)+*|-|kwE-c--6^a0 zy`gEAUD*_6NTheaPz;F$5Wj#V`#L&x`$ZY4tv^B-JVk?-W6xtEavfa3(qsl4r#vk_ z9s(bcE|ZYj2D>1YzUROgOz^uz3BZzR*Lgf}O@^k8Xgby_!cAhszKin5DFuv#cp#PL zb71oIKR<@=AiVHbbrzhA`<)S0$dxgx{A(hy^Cl&{)NqELO zwty!L!|C$&6>E16MHa@r;WDz<{sdt@VnUDIy3%+z9tS=t=oyDt>93YQmY?gHlcbWI zRx6QS_)bi~A(_l8R%At?u6EmS(P+<^!1LRVNd$;k*WUAVO=K~XPiZShVT12cHEq{D zI>V${aB)8B1%*@pgnpWM2 z*KpVW8L{cyMpKozoIOie0`;b*Th)7iU#i^-y+g6^{Ll;_F-@g@gv*u1mr(N2$P(u|Lk<;QBQ_<6k zke{iu!-SLgMc(SosoN&hep%a9P!)t)$Li!N5}||G6b!wD6T_&fJ8rjccgTv-MKGth ziOPBzbdUuxKlEF>1cd9;G!+dV;o9%sGJZIbH5>Ko79Dd(o?8G~#%?3OJbxgHOqbftv9Hy^=iZp@mNPi$1!Yqt zJ|vze3@oZkK`%IJw{xvrE% z?eW8r(QXO&Z2;F94JGMlr{=3Orz8K3$DMI@T#5CN@jHc zmuOEpBXpY}KEAEhbQq;V7Uj7{8m$oOS}0MFH%$Iv0`N=CR8 zi7iP_Tr*V>)sp@+V+x5o=2{d2CF2x;oXYxUrT%E)zD5OQZ8##r3*S+7LGz0!;Mw?Y zU|EQExJpdms7L2dT{mHl%*FfNY&>4oNC`M%cr0tiO6&-y@{m-#eXh`eS#^o7qmsLZ zHigBz!X||Iqm$D>9?VF5xrVmAb{ij}kt)Ib?ASwOP-ryon)h4T;%X<1kowvl*}1ZEg`=(|i8L9okfJAJ=gsmwDTKHW6c}{8CtfAwN+p-ho_jp>U9O>cJJ_C?!dXoINYB%wz*6TIO458u z>{z&BVZa&!_*%sKvXIOBz7IyRk}=ZSX*!xM7xqYOe#?`=JO-%Gr*E6WHv{mZ7!|a8 z?@7p7FMFHp-r|*cJ$DQQk8Dvkt`Igbpm>FT35;A55*-w}3A7sRx>1H&oG)J=Hvy!d z*93+9W`!;jN~B#ex>ieH0eBBIaSx3hE^d>t8s!zvqqS%_0*t$voA6p%h8pBN1|Om! z5TSqG5@}`E6KQ)#pWcZpSURQa@DQw_?d7i`qIJl;@{wM38Sq*~a7KXVMbbkZw6q~B ztJM$J7gSVb{g_C(T&YMzWVsS2m1zOp@%u$PZ@Ll&m&Y zbY)*htK=dkM&Hg@p?QJ&LV9|*2|iTNf<^S0b1m`vGMx;KWm)T_5A11we)v^G;TzM# zuAEb_LmX!F6yIy&r4e)PkXV$caWOL3YILeaE`leh){^xZFJB@>FU3<}F`5e4xY4uE zmX%S^RmfBv$?l>`G47z!HpB&59>qpDN)?-^o8*}dco)vDI$nv)l}h79_ibypKp%_X zyQc?HKgzUWL*qpcr(=L~Iv<*q6ZW z&CVdOTWY(=gvSWf4`<9saL8|`J=OGUvzoZ9s6r`PTx^n}@F25$i5c3=`!mkh@ z5H)+g$PTq`tiXe*eVB%aw4al}`mLZCj4hgK-1J^2GT~8hzw>eW`AR9VS+ZLpU!fNOEaMd5y4P+ zn+XSYZ-g+o8oQgtjGb9Oaokywz86;yeBa*t0i#$Ah~8 zr+2rept38dv(-c>wznyCcjV4YkJj;sMAO-76te&|{A^k742@!5fQIgFVvn)lE8%;0 zpl5sVqpTxmirhvFN@50!p3T~XAIw5SPf(kUM_c75CVMzd(^y71zDcFB&L}MVNgnj9 z7@D}-)QH(HSufcggk#P&7x9l*2?JZ*8!_7^&~A}AYWTMM%;_O2Di5=F?bCo9=E#4C z9-0?4oUVsi=yVS~-d>-<6bY^pClg`LZUy5rV}7E>&yQo2sr{bBnbTRq%xKKvUZPyc;ZJh8;DetBSSw83$EIh2zsRw1M+2uXZ?G&AqO@6| zW6apoX@6$S5g=IN(aY|VvxBCiTiS#>KlZlWuo0&RaOl+&O89i>-a(M>E_3dWGlDOK z;~7n1lzqG2*z({GKx^fBA>Y%mRh#MBnmYnm^iT2`_~A70v0GcAurR(u5fF_&0S@;laCS;)9s6y^+J&17?iH zaV7SbNmI}|C7hjgeX|04mMDVF@HfM#C&5panc<(Bx|o}ert{z@{Za1NEwv-!;KTic z!`EH&!6zl;@Z(wXnN#$e0J+99%rXAiF1g&Se@Mvl^_m@z!N~=!94yD~#F+!O`o7=+ zX4d`9OhzBE$gd{e52yO=>k%gM71*B=@MBfeqou5wvnNT%QE#w|C+_f+yz6#W49i$< zv-EhmljEAEYIv1aBkv*n;aT^*VB^WsftZb=rOEZ!F$lr_1UgNG$M*6j+}@7aj8&#_(2KObAA5Mv8--=b zTbG;nKC4zPYf8qdVbG}ZS2ozf(*taSz>;7r#&(k#ql(F!aXHk|?m88$>4Y*J_Ws;X z?>yA{INqE`e&{?j-`gy>OP*eXA)7dk+L?h`wqc<%^OSkp+oA#Ru9BvWk|U<=?(N%i z*uba3$H#1WQLpVLq@zOS$@ivR4!7zbN@4P#7ERya@)@U_hftCDSJw2zsp?Q{O=q|Y z4J15{b77?I4ES}>PK35U{BYj78uzrRU1VvG`2qI0>FlgJ?UWpQ)O5NB58~&+%IRql z5}9{ZqJEU(g330?KzdquU@8z15fNz6dD|RxA@Ks&I<`JA8<-DF5b9;?;w|XvZe!~L z^|tl#adflyzG3a|X6I;s@xs};2`R3hsW9E)xZ#TmM9hV-#4?WRjdWM?Tjd#bNW3pn3MYBr0i(eqrcE82P8 zWweH3(T#{~o1kI&nmFHdn&5MgUDg{^ezn^+Ob%4cSW9mJ$2r%*zR0QkYv2j7K>pu4 zV7jP-e|`G+lq#LZ9X7 zN8e_PqF>7BR zsH2;myO%4>$I;#GMu4k}c$^j)pfBZv?ADz|o%(gQW_`9XjVY>1&J>n}M3lY6^T1t~ zCS7)Zn67?p`|?>BMMj$%=7Z_Z@_uWh^Q%wTFt0UwNp|Hol1@0!H2sD*O{Mr{WG4sBpbW#ha97z07#~;8Me$MxdI>Q%-Jq zBibQ_(O-RJ_Wn=5Z(PE=g;uzgRi)obm*1cB*)O%~P47tyb^XUib#MFeAny>IBsYCN z^q#Xng|rn;VnEl#LCepdRvz|ZUnNbMG;JzVi(BLH3%$`U0W>@J3QO^JJzLfGL>VO@ zt6N3v0`YMH3j#u#oP{px)yB1(rm7ZuHDn2OuKg_Sa{j92=q_P>O zqD0K`O|?N*uY{-P4XtUo?Z)ErW;zs}BG?PW`Y7$aYu-4iIQ0T%y`qqvYC!5BvoJH2|An7ICw$%TNg?;rRZ=N8qxFVF+WyykiQ zrBqqada-PGAX>mzv+ec!0_wKrA7nZmHyqm={2vTGXCJ+~a9Y8nxUv#2GxXlijgHaE zL2;9Cw!e%?!r|?w_tzk39J|8QV;D1BTBgEF+6625=NR#In~QW82Lvhr|6g6_63})2 z93KA|316o4YPJbcAr5w_fDm%%0=Cb7H`!`E*nMwjbFJcgvumi#eAk9C^bWNPWywoQ zVGnXR#xVCZb~v;1;wl_-?b3+)A$e%Mk;Hw@z@ig7lZH#ttW4YUHn*d1e;xOMw8-KF z+$4D{D}HyybT!_PcJ2$QWpc6PYP;Xb5i_5>^gwgfXd?x{c&NJiRAi$Lk-GAY@xkFtX z?HzpnT_n3u6zMHMob!D7H>h}y3s64p9{A0x0K5zc;a? z#YMEg9>?AqnBd%SwGsah4(QK$(Zv}P&2LhD`JXud!T4)#b#caVKDYWikrCqk-C_TK zGp&EZUNp<+)0Mx|WugnP|2ld3C)PzQrY{}bur(D}RKPc9<;m!9Cr1z@PR&m-s31hmcV%JM+$U5(EkHUUu5P0 literal 0 HcmV?d00001 diff --git a/assets/3d_printing_files/go2_stand.STEP b/assets/3d_printing_files/go2_stand.STEP new file mode 100644 index 0000000..68122f9 --- /dev/null +++ b/assets/3d_printing_files/go2_stand.STEP @@ -0,0 +1,46768 @@ +ISO-10303-21; +HEADER; +FILE_DESCRIPTION (( 'STEP AP203' ), + '1' ); +FILE_NAME ('MID360+֧6.24.STEP', + '2025-06-24T06:25:27', + ( 'pjoffice' ), + ( '' ), + 'SwSTEP 2.0', + 'SolidWorks 2025', + '' ); +FILE_SCHEMA (( 'CONFIG_CONTROL_DESIGN' )); +ENDSEC; + +DATA; +#1 = ORIENTED_EDGE ( 'NONE', *, *, #2845, .F. ) ; +#2 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#3 = CARTESIAN_POINT ( 'NONE', ( 41.50181681594300898, 120.8598905339968184, 87.87266037630595861 ) ) ; +#4 = EDGE_CURVE ( 'NONE', #8671, #36222, #15537, .T. ) ; +#5 = CARTESIAN_POINT ( 'NONE', ( -20.00010960551400530, 118.5861297300807138, 87.28009461489128284 ) ) ; +#6 = CARTESIAN_POINT ( 'NONE', ( -15.66647089846898488, 184.8876660487106847, 102.6891680080509133 ) ) ; +#7 = EDGE_LOOP ( 'NONE', ( #6417, #29162, #21440, #27963, #9046 ) ) ; +#8 = VERTEX_POINT ( 'NONE', #20221 ) ; +#9 = CIRCLE ( 'NONE', #26783, 6.499999999827354102 ) ; +#10 = CARTESIAN_POINT ( 'NONE', ( -25.67545716422647573, 209.7076544165666689, 75.74092205266403255 ) ) ; +#11 = CIRCLE ( 'NONE', #3896, 2.500000000063874239 ) ; +#12 = CARTESIAN_POINT ( 'NONE', ( 2.303546409809000384, 189.9846911846000239, 103.9762804151000211 ) ) ; +#13 = LINE ( 'NONE', #34144, #24756 ) ; +#14 = AXIS2_PLACEMENT_3D ( 'NONE', #12949, #31961, #16196 ) ; +#15 = ORIENTED_EDGE ( 'NONE', *, *, #13893, .T. ) ; +#16 = DIRECTION ( 'NONE', ( -1.287855998059750215E-14, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#17 = ORIENTED_EDGE ( 'NONE', *, *, #29026, .F. ) ; +#18 = CARTESIAN_POINT ( 'NONE', ( -20.51978786315646630, 209.7094320854081104, 73.57086927696296641 ) ) ; +#19 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282898364, 148.0700263536679984, 93.85134194391106632 ) ) ; +#20 = CARTESIAN_POINT ( 'NONE', ( -16.17402367319390066, 152.6351915047822558, 181.6236851348978973 ) ) ; +#21 = LINE ( 'NONE', #3875, #3676 ) ; +#22 = VERTEX_POINT ( 'NONE', #3332 ) ; +#23 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265227786, -0.1368326740407717901 ) ) ; +#24 = DIRECTION ( 'NONE', ( -0.7933533411653069800, 0.5930537057989943017, 0.1373964268091564522 ) ) ; +#25 = CARTESIAN_POINT ( 'NONE', ( -25.99976593112455348, 118.8155677978001705, 90.28348901843737906 ) ) ; +#26 = ORIENTED_EDGE ( 'NONE', *, *, #5435, .F. ) ; +#27 = EDGE_CURVE ( 'NONE', #8778, #14326, #3469, .T. ) ; +#28 = CARTESIAN_POINT ( 'NONE', ( -22.49823373578395191, 173.8377602238623751, 102.8790334322490878 ) ) ; +#29 = LINE ( 'NONE', #9440, #37171 ) ; +#30 = CARTESIAN_POINT ( 'NONE', ( -20.49970531958899400, 151.8550384256017480, 95.23695349276246702 ) ) ; +#31 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22396, #12985, #12777, #35225 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33 = DIRECTION ( 'NONE', ( 0.5422127811705124145, 0.2959572644767380356, 0.7863934114289006239 ) ) ; +#32 = DIRECTION ( 'NONE', ( 0.0005884949961155384228, -0.2249510543439099397, 0.9743698870671255730 ) ) ; +#34 = AXIS2_PLACEMENT_3D ( 'NONE', #28971, #25924, #37761 ) ; +#35 = EDGE_CURVE ( 'NONE', #16264, #22006, #22569, .T. ) ; +#36 = AXIS2_PLACEMENT_3D ( 'NONE', #24915, #12607, #9558 ) ; +#37 = ORIENTED_EDGE ( 'NONE', *, *, #39919, .T. ) ; +#38 = VECTOR ( 'NONE', #35966, 1000.000000000000000 ) ; +#39 = CIRCLE ( 'NONE', #17646, 1.650000000000002798 ) ; +#40 = EDGE_CURVE ( 'NONE', #23346, #30982, #3734, .T. ) ; +#41 = EDGE_LOOP ( 'NONE', ( #36460, #3149, #28592, #26769 ) ) ; +#42 = EDGE_CURVE ( 'NONE', #36951, #18050, #10855, .T. ) ; +#43 = VERTEX_POINT ( 'NONE', #673 ) ; +#44 = EDGE_CURVE ( 'NONE', #1155, #29199, #10034, .T. ) ; +#45 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; +#46 = DIRECTION ( 'NONE', ( -0.6772915400549289755, -0.7357147339628467009, 0.000000000000000000 ) ) ; +#47 = CARTESIAN_POINT ( 'NONE', ( -45.16400980236513618, 70.91888486856629470, 322.7789803297500839 ) ) ; +#48 = ORIENTED_EDGE ( 'NONE', *, *, #32583, .F. ) ; +#49 = CARTESIAN_POINT ( 'NONE', ( -19.99814303586761710, 191.9760241014712960, 101.9334704393890405 ) ) ; +#50 = ORIENTED_EDGE ( 'NONE', *, *, #21680, .F. ) ; +#51 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567900 ) ) ; +#52 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13175, #12763, #37700, #31787, #31577, #3945 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.005577396964778614727, 0.006726925734499736992, 0.007876454504220859257 ), + .UNSPECIFIED. ) ; +#53 = CYLINDRICAL_SURFACE ( 'NONE', #24949, 2.000000000000014655 ) ; +#54 = ORIENTED_EDGE ( 'NONE', *, *, #11868, .F. ) ; +#55 = CARTESIAN_POINT ( 'NONE', ( -19.99828015742506793, 192.0076529467379771, 106.9671611953735777 ) ) ; +#56 = CARTESIAN_POINT ( 'NONE', ( 20.50141158344984404, 191.9758728513155575, 106.4093071483684696 ) ) ; +#57 = PLANE ( 'NONE', #21814 ) ; +#58 = CARTESIAN_POINT ( 'NONE', ( 13.46852558400658850, 153.7328115929476269, 98.21571663388800744 ) ) ; +#59 = EDGE_LOOP ( 'NONE', ( #31590, #21771, #20752, #12795 ) ) ; +#60 = CARTESIAN_POINT ( 'NONE', ( 3.063400437118999786, 190.7419505334999883, 106.7647335544999976 ) ) ; +#61 = AXIS2_PLACEMENT_3D ( 'NONE', #26719, #29184, #10775 ) ; +#62 = EDGE_CURVE ( 'NONE', #26666, #11241, #38827, .T. ) ; +#63 = AXIS2_PLACEMENT_3D ( 'NONE', #25666, #25869, #19886 ) ; +#64 = CARTESIAN_POINT ( 'NONE', ( -45.39754466565177182, 131.1270945138005573, 90.46656737203734622 ) ) ; +#65 = CARTESIAN_POINT ( 'NONE', ( 36.18256164553691434, 191.4809836520348085, 103.8379386387424432 ) ) ; +#66 = LINE ( 'NONE', #3323, #4540 ) ; +#67 = AXIS2_PLACEMENT_3D ( 'NONE', #38158, #23026, #10163 ) ; +#68 = ORIENTED_EDGE ( 'NONE', *, *, #307, .F. ) ; +#69 = AXIS2_PLACEMENT_3D ( 'NONE', #8559, #8969, #5060 ) ; +#70 = DIRECTION ( 'NONE', ( 0.0005884949961251572477, -0.2249510543439052768, 0.9743698870671265722 ) ) ; +#71 = DIRECTION ( 'NONE', ( -0.0006039748319391886151, -1.387778780781439522E-14, -0.9999998176071844824 ) ) ; +#72 = VERTEX_POINT ( 'NONE', #38092 ) ; +#73 = ADVANCED_FACE ( 'NONE', ( #10849 ), #25042, .T. ) ; +#74 = CARTESIAN_POINT ( 'NONE', ( 16.59040448417249891, 121.5622698803751121, 177.2309519810485767 ) ) ; +#75 = VERTEX_POINT ( 'NONE', #13165 ) ; +#77 = CARTESIAN_POINT ( 'NONE', ( 35.91265183286542850, 191.6406926546981424, 103.8749735105696033 ) ) ; +#76 = CARTESIAN_POINT ( 'NONE', ( 36.14467970416134790, 192.0930395166764413, 104.3839062667640150 ) ) ; +#78 = ORIENTED_EDGE ( 'NONE', *, *, #16278, .T. ) ; +#79 = ADVANCED_FACE ( 'NONE', ( #35746 ), #31361, .F. ) ; +#80 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971522104 ) ) ; +#81 = VERTEX_POINT ( 'NONE', #19267 ) ; +#82 = CARTESIAN_POINT ( 'NONE', ( 15.59122047669174549, 126.7497335477701910, 179.2034385373662531 ) ) ; +#83 = ADVANCED_FACE ( 'NONE', ( #29652 ), #25240, .F. ) ; +#84 = CARTESIAN_POINT ( 'NONE', ( -30.44899458943609005, 184.9287475678549981, 105.4443921870966250 ) ) ; +#85 = CARTESIAN_POINT ( 'NONE', ( 6.034202834021533235, 137.3564637335765610, 91.35735362699509210 ) ) ; +#86 = ORIENTED_EDGE ( 'NONE', *, *, #40303, .T. ) ; +#87 = AXIS2_PLACEMENT_3D ( 'NONE', #27595, #15294, #40024 ) ; +#88 = EDGE_CURVE ( 'NONE', #10727, #39550, #14097, .T. ) ; +#89 = VERTEX_POINT ( 'NONE', #9485 ) ; +#90 = EDGE_CURVE ( 'NONE', #21775, #20721, #2367, .T. ) ; +#91 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971537369 ) ) ; +#92 = CARTESIAN_POINT ( 'NONE', ( 41.20424435709291089, 166.0101408972543595, 183.1539072767900791 ) ) ; +#93 = CARTESIAN_POINT ( 'NONE', ( -14.62254490296892406, 128.1170529630574606, 179.5121082275731794 ) ) ; +#94 = EDGE_LOOP ( 'NONE', ( #19904, #14870, #20319, #19242 ) ) ; +#95 = ORIENTED_EDGE ( 'NONE', *, *, #10616, .T. ) ; +#96 = CARTESIAN_POINT ( 'NONE', ( -5.671191585905537735, 123.8351953472891864, 91.20138000056049066 ) ) ; +#97 = CARTESIAN_POINT ( 'NONE', ( 20.48673967653602901, 211.0896571907997554, 75.54495990469186495 ) ) ; +#98 = CARTESIAN_POINT ( 'NONE', ( 15.92170649585048281, 184.2627309268899580, 102.1837104338655848 ) ) ; +#99 = ORIENTED_EDGE ( 'NONE', *, *, #11923, .T. ) ; +#100 = ORIENTED_EDGE ( 'NONE', *, *, #32571, .T. ) ; +#101 = CARTESIAN_POINT ( 'NONE', ( 22.50136996952335267, 157.6320572232312998, 99.11047108320519783 ) ) ; +#102 = CARTESIAN_POINT ( 'NONE', ( -37.26202794485465120, 111.6171511925439148, 151.2319588935870058 ) ) ; +#103 = DIRECTION ( 'NONE', ( -0.0006039748319387582953, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#104 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #39047, #23329 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#105 = ORIENTED_EDGE ( 'NONE', *, *, #19721, .F. ) ; +#106 = CARTESIAN_POINT ( 'NONE', ( -36.67432554227874419, 115.9022888061950880, 89.74328836332526294 ) ) ; +#107 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#108 = CARTESIAN_POINT ( 'NONE', ( -5.668235839012205624, 187.2935674832718007, 105.4622348357629136 ) ) ; +#109 = CARTESIAN_POINT ( 'NONE', ( 31.81423252379520505, 154.4985393321093454, 201.1972645548150354 ) ) ; +#110 = DIRECTION ( 'NONE', ( 0.7933533411653070910, -0.5930537057989940797, -0.1373964268091563690 ) ) ; +#111 = ORIENTED_EDGE ( 'NONE', *, *, #24435, .F. ) ; +#112 = CARTESIAN_POINT ( 'NONE', ( -38.04444379205944671, 118.4867705051282627, 87.71485106921780073 ) ) ; +#113 = CARTESIAN_POINT ( 'NONE', ( 38.53174385238651922, 78.67361070814361312, 289.9170220609951230 ) ) ; +#114 = CARTESIAN_POINT ( 'NONE', ( -37.82318234731999951, 118.8138069173000133, 87.38894521921000091 ) ) ; +#115 = CARTESIAN_POINT ( 'NONE', ( 36.55562030122000294, 115.8243310143000144, 89.83301026034000358 ) ) ; +#116 = CIRCLE ( 'NONE', #14483, 6.499999999988752997 ) ; +#117 = AXIS2_PLACEMENT_3D ( 'NONE', #18312, #14872, #30813 ) ; +#118 = CARTESIAN_POINT ( 'NONE', ( -29.41044142705827014, 181.8648675259495633, 101.6574994283702296 ) ) ; +#119 = EDGE_LOOP ( 'NONE', ( #38155, #24800, #1408, #26406, #5637, #19732 ) ) ; +#120 = CARTESIAN_POINT ( 'NONE', ( -45.48423345424451014, 77.14301703112153064, 297.5860163668562564 ) ) ; +#121 = EDGE_CURVE ( 'NONE', #19053, #25286, #32870, .T. ) ; +#122 = ORIENTED_EDGE ( 'NONE', *, *, #5340, .T. ) ; +#123 = EDGE_CURVE ( 'NONE', #11575, #21267, #882, .T. ) ; +#124 = EDGE_CURVE ( 'NONE', #1239, #14482, #30688, .T. ) ; +#125 = CARTESIAN_POINT ( 'NONE', ( -38.20440139773999988, 118.7296188347000054, 90.14784475465999947 ) ) ; +#126 = EDGE_CURVE ( 'NONE', #8868, #31885, #31773, .T. ) ; +#127 = VERTEX_POINT ( 'NONE', #36587 ) ; +#128 = FACE_OUTER_BOUND ( 'NONE', #13493, .T. ) ; +#129 = EDGE_CURVE ( 'NONE', #26891, #35621, #22863, .T. ) ; +#130 = CARTESIAN_POINT ( 'NONE', ( -31.19629630738960913, 110.6131156702000027, 90.28662662050363963 ) ) ; +#131 = CARTESIAN_POINT ( 'NONE', ( -33.38621112099523458, 163.6246645812861971, 189.1270109278173095 ) ) ; +#132 = CARTESIAN_POINT ( 'NONE', ( -22.34218834335725390, 158.3009385975264536, 96.21306774085992686 ) ) ; +#133 = VERTEX_POINT ( 'NONE', #17959 ) ; +#134 = FACE_OUTER_BOUND ( 'NONE', #39381, .T. ) ; +#135 = ORIENTED_EDGE ( 'NONE', *, *, #31023, .F. ) ; +#136 = ORIENTED_EDGE ( 'NONE', *, *, #21942, .F. ) ; +#137 = EDGE_LOOP ( 'NONE', ( #21578, #37363, #29502, #27008 ) ) ; +#138 = EDGE_CURVE ( 'NONE', #36900, #25308, #19809, .T. ) ; +#139 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#140 = DIRECTION ( 'NONE', ( -0.0005884949961178167653, 0.2249510557410934197, -0.9743698867445601541 ) ) ; +#141 = ORIENTED_EDGE ( 'NONE', *, *, #24667, .F. ) ; +#142 = CARTESIAN_POINT ( 'NONE', ( 19.98041095528421707, 209.2225623532448253, 73.04692467823424806 ) ) ; +#143 = CIRCLE ( 'NONE', #21702, 2.000000000000011546 ) ; +#144 = ORIENTED_EDGE ( 'NONE', *, *, #19370, .T. ) ; +#145 = PLANE ( 'NONE', #32036 ) ; +#146 = VECTOR ( 'NONE', #7172, 1000.000000000000114 ) ; +#147 = EDGE_CURVE ( 'NONE', #36039, #25299, #36173, .T. ) ; +#148 = AXIS2_PLACEMENT_3D ( 'NONE', #18417, #9999, #12866 ) ; +#149 = CARTESIAN_POINT ( 'NONE', ( -30.07826481366596738, 134.2402275243734096, 93.74179301315371049 ) ) ; +#150 = CARTESIAN_POINT ( 'NONE', ( -3.632612936599522779, 143.5564359001282071, 95.77751706023541090 ) ) ; +#151 = CARTESIAN_POINT ( 'NONE', ( -30.07174127556133669, 134.7161224726260116, 93.44441010718954033 ) ) ; +#152 = ORIENTED_EDGE ( 'NONE', *, *, #23533, .F. ) ; +#153 = CARTESIAN_POINT ( 'NONE', ( 28.34188046507999914, 125.4821649217000044, 88.94658904128002064 ) ) ; +#154 = DIRECTION ( 'NONE', ( 0.7942820423213359238, 0.5918950211223032998, 0.1370267171630252800 ) ) ; +#155 = DIRECTION ( 'NONE', ( 0.0004161288024547937867, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#156 = CARTESIAN_POINT ( 'NONE', ( 25.49923630764208227, 118.3473981419666785, 87.75233666297712887 ) ) ; +#157 = CARTESIAN_POINT ( 'NONE', ( 4.379475180782625543, 135.5225349930722416, 90.93811872962228904 ) ) ; +#158 = ORIENTED_EDGE ( 'NONE', *, *, #31069, .F. ) ; +#159 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -3.519737327345223780E-16, 0.0006039748319385488274 ) ) ; +#160 = PLANE ( 'NONE', #23809 ) ; +#161 = CARTESIAN_POINT ( 'NONE', ( -15.94429972368852866, 121.8869921648800698, 174.4792395813007886 ) ) ; +#162 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#163 = ORIENTED_EDGE ( 'NONE', *, *, #23583, .F. ) ; +#164 = ORIENTED_EDGE ( 'NONE', *, *, #13285, .T. ) ; +#165 = CARTESIAN_POINT ( 'NONE', ( 38.36929107696393970, 118.9352448211023017, 90.24632071806664158 ) ) ; +#166 = CARTESIAN_POINT ( 'NONE', ( 12.31450649940180142, 135.1704657886633356, 91.19412197989161939 ) ) ; +#167 = CARTESIAN_POINT ( 'NONE', ( 25.78894422189694779, 212.1706022175659712, 73.04292820630129768 ) ) ; +#168 = CARTESIAN_POINT ( 'NONE', ( -25.49895059653205109, 190.9802068742214658, 106.3202087131623585 ) ) ; +#169 = ORIENTED_EDGE ( 'NONE', *, *, #6235, .F. ) ; +#170 = EDGE_CURVE ( 'NONE', #29017, #39184, #16528, .T. ) ; +#171 = EDGE_CURVE ( 'NONE', #3824, #585, #35482, .T. ) ; +#172 = VECTOR ( 'NONE', #30008, 1000.000000000000114 ) ; +#173 = EDGE_CURVE ( 'NONE', #20721, #921, #36791, .T. ) ; +#174 = CARTESIAN_POINT ( 'NONE', ( -12.63885758284349237, 182.0021742443144035, 102.1105035275109572 ) ) ; +#175 = AXIS2_PLACEMENT_3D ( 'NONE', #10239, #35133, #38619 ) ; +#176 = FACE_OUTER_BOUND ( 'NONE', #9445, .T. ) ; +#177 = DIRECTION ( 'NONE', ( -0.7933533175743878729, -0.5930761747309520882, -0.1372995428259456974 ) ) ; +#178 = FACE_OUTER_BOUND ( 'NONE', #34083, .T. ) ; +#179 = ADVANCED_FACE ( 'NONE', ( #39644 ), #21261, .T. ) ; +#180 = DIRECTION ( 'NONE', ( -0.0005884949961184574203, 0.2249510543439044719, -0.9743698870671267942 ) ) ; +#181 = CARTESIAN_POINT ( 'NONE', ( 36.36530821653990131, 191.8372400467440002, 104.3548065722559812 ) ) ; +#182 = CARTESIAN_POINT ( 'NONE', ( 36.51035386448999986, 190.9807345362999911, 106.6672906836000010 ) ) ; +#183 = ORIENTED_EDGE ( 'NONE', *, *, #24382, .T. ) ; +#184 = ORIENTED_EDGE ( 'NONE', *, *, #16639, .T. ) ; +#185 = EDGE_CURVE ( 'NONE', #5998, #16791, #35473, .T. ) ; +#186 = CARTESIAN_POINT ( 'NONE', ( -3.723721742435894377, 136.4323261788989612, 91.15305474119872997 ) ) ; +#187 = CARTESIAN_POINT ( 'NONE', ( 37.96521291183479008, 190.3639829187772250, 106.6578906949923464 ) ) ; +#188 = LINE ( 'NONE', #12660, #32996 ) ; +#189 = VERTEX_POINT ( 'NONE', #23509 ) ; +#190 = CARTESIAN_POINT ( 'NONE', ( 37.73070576671000254, 118.1925768933000001, 87.57314476239000101 ) ) ; +#191 = EDGE_CURVE ( 'NONE', #10943, #662, #35954, .T. ) ; +#192 = CARTESIAN_POINT ( 'NONE', ( -6.036264379394199686, 174.7922271991594414, 102.5762947721396898 ) ) ; +#193 = LINE ( 'NONE', #9610, #25563 ) ; +#194 = CARTESIAN_POINT ( 'NONE', ( -36.32955808867194492, 191.7831307432306289, 104.4004776953238576 ) ) ; +#195 = CONICAL_SURFACE ( 'NONE', #27637, 2.749999999928335992, 0.7853981634201930850 ) ; +#196 = EDGE_LOOP ( 'NONE', ( #3440, #31934, #12454, #39404 ) ) ; +#197 = CARTESIAN_POINT ( 'NONE', ( -23.36033136076990502, 129.9689112135512232, 92.23847830418463900 ) ) ; +#198 = CARTESIAN_POINT ( 'NONE', ( 25.61340328942235089, 212.6007637392172001, 76.04305467133100649 ) ) ; +#199 = PLANE ( 'NONE', #28726 ) ; +#200 = FACE_OUTER_BOUND ( 'NONE', #18567, .T. ) ; +#201 = ORIENTED_EDGE ( 'NONE', *, *, #5666, .F. ) ; +#202 = CARTESIAN_POINT ( 'NONE', ( 12.64191830251873583, 177.0167639429040776, 103.4528965672968326 ) ) ; +#203 = VECTOR ( 'NONE', #4844, 1000.000000000000227 ) ; +#204 = CARTESIAN_POINT ( 'NONE', ( 1.446531013058000026, 188.9112451455999917, 103.4032447082000061 ) ) ; +#205 = DIRECTION ( 'NONE', ( -6.938893903797542002E-15, 0.9743700557921584071, 0.2249510932971567068 ) ) ; +#206 = VERTEX_POINT ( 'NONE', #7964 ) ; +#207 = DIRECTION ( 'NONE', ( -0.6087613186456907188, 0.7729176985478710682, 0.1789074850089337476 ) ) ; +#208 = ORIENTED_EDGE ( 'NONE', *, *, #28907, .F. ) ; +#209 = DIRECTION ( 'NONE', ( -0.7871416011357068587, 0.6167723240884886993, 0.000000000000000000 ) ) ; +#210 = EDGE_CURVE ( 'NONE', #14771, #34948, #20641, .T. ) ; +#211 = EDGE_CURVE ( 'NONE', #5370, #12877, #14316, .T. ) ; +#212 = CARTESIAN_POINT ( 'NONE', ( -12.62960812168191183, 177.0992617944713743, 103.6047656994513204 ) ) ; +#213 = DIRECTION ( 'NONE', ( -0.7075227810178097432, 0.1590644159616022568, -0.6885564798298096090 ) ) ; +#214 = CARTESIAN_POINT ( 'NONE', ( -2.833334676081999959, 208.8581063077000124, 73.25715202902999579 ) ) ; +#215 = CARTESIAN_POINT ( 'NONE', ( -1.997901840931525230, 189.7491732284025261, 105.9548322323222607 ) ) ; +#216 = AXIS2_PLACEMENT_3D ( 'NONE', #15180, #36225, #14975 ) ; +#217 = EDGE_LOOP ( 'NONE', ( #30516, #18788, #9334, #5463 ) ) ; +#218 = FACE_BOUND ( 'NONE', #19523, .T. ) ; +#219 = DIRECTION ( 'NONE', ( -0.7933533416835715224, 0.5930537051408173443, 0.1373964266575322113 ) ) ; +#220 = CARTESIAN_POINT ( 'NONE', ( 42.89008714222951113, 113.2528206432904341, 125.5033208068462329 ) ) ; +#221 = ADVANCED_FACE ( 'NONE', ( #17345 ), #33103, .T. ) ; +#222 = AXIS2_PLACEMENT_3D ( 'NONE', #22583, #28311, #35005 ) ; +#223 = FACE_OUTER_BOUND ( 'NONE', #32828, .T. ) ; +#224 = ORIENTED_EDGE ( 'NONE', *, *, #25103, .T. ) ; +#225 = CONICAL_SURFACE ( 'NONE', #864, 2.503000005669923311, 0.7853981634067779272 ) ; +#226 = ORIENTED_EDGE ( 'NONE', *, *, #37023, .F. ) ; +#227 = DIRECTION ( 'NONE', ( 0.0005884949961236880453, -0.2249510543439056931, 0.9743698870671265722 ) ) ; +#228 = ORIENTED_EDGE ( 'NONE', *, *, #26833, .F. ) ; +#229 = LINE ( 'NONE', #9050, #27668 ) ; +#230 = CARTESIAN_POINT ( 'NONE', ( 15.99992735094624763, 169.9186965180942650, 98.87215626859075712 ) ) ; +#231 = ADVANCED_FACE ( 'NONE', ( #39237 ), #11242, .T. ) ; +#232 = CARTESIAN_POINT ( 'NONE', ( -3.536105410441011010, 136.6754134117661863, 94.28792821396773149 ) ) ; +#233 = DIRECTION ( 'NONE', ( -0.1782640835105696875, -0.3528946327679918782, 0.9185245204640325456 ) ) ; +#234 = CARTESIAN_POINT ( 'NONE', ( -38.02513973112999679, 119.2109743768000101, 87.30192654314001288 ) ) ; +#235 = CARTESIAN_POINT ( 'NONE', ( 25.50040748627628773, 118.8155663766999481, 89.75240507814876878 ) ) ; +#236 = ORIENTED_EDGE ( 'NONE', *, *, #33905, .T. ) ; +#237 = DIRECTION ( 'NONE', ( 0.4298642588094122585, -0.3871440406461976180, -0.8156814395279384788 ) ) ; +#238 = EDGE_LOOP ( 'NONE', ( #19592, #19335, #38778, #3267 ) ) ; +#239 = CARTESIAN_POINT ( 'NONE', ( -82.80843920860921514, 105.1411378422745315, 24.32376295616780482 ) ) ; +#240 = CARTESIAN_POINT ( 'NONE', ( 38.49879497324275235, 78.38483656737932392, 291.5352916277676627 ) ) ; +#241 = ORIENTED_EDGE ( 'NONE', *, *, #17146, .T. ) ; +#242 = CARTESIAN_POINT ( 'NONE', ( -14.99990248618953181, 136.4138140789638953, 91.32664213178384216 ) ) ; +#243 = CARTESIAN_POINT ( 'NONE', ( 1.306454471753598190, 188.7206452512837700, 103.2217284838431794 ) ) ; +#244 = AXIS2_PLACEMENT_3D ( 'NONE', #25224, #25423, #22753 ) ; +#245 = DIRECTION ( 'NONE', ( 0.0005884949961193586092, -0.2249510543439039167, 0.9743698870671270162 ) ) ; +#246 = EDGE_CURVE ( 'NONE', #39374, #22073, #23759, .T. ) ; +#247 = ORIENTED_EDGE ( 'NONE', *, *, #28931, .F. ) ; +#248 = CARTESIAN_POINT ( 'NONE', ( 20.45872449161620210, 118.1119902764347245, 87.71370651214481029 ) ) ; +#249 = LINE ( 'NONE', #22554, #33049 ) ; +#250 = ORIENTED_EDGE ( 'NONE', *, *, #22389, .F. ) ; +#251 = EDGE_CURVE ( 'NONE', #10727, #19810, #20465, .T. ) ; +#252 = CARTESIAN_POINT ( 'NONE', ( 2.563028759935935597, 191.4135359453850072, 104.3558246061316339 ) ) ; +#253 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; +#254 = DIRECTION ( 'NONE', ( 3.538835890992693415E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#255 = ORIENTED_EDGE ( 'NONE', *, *, #14656, .F. ) ; +#256 = EDGE_CURVE ( 'NONE', #35304, #1023, #21922, .T. ) ; +#257 = EDGE_CURVE ( 'NONE', #14938, #3287, #29232, .T. ) ; +#258 = FACE_OUTER_BOUND ( 'NONE', #8621, .T. ) ; +#259 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24376, #25173, #2696, #36821 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.001089237863740169726, 0.001154390576975604810 ), + .UNSPECIFIED. ) ; +#260 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927775713126, 0.0005734119022076485583 ) ) ; +#261 = ORIENTED_EDGE ( 'NONE', *, *, #3575, .F. ) ; +#262 = EDGE_CURVE ( 'NONE', #11101, #410, #18365, .T. ) ; +#263 = CARTESIAN_POINT ( 'NONE', ( 22.49999922077099157, 184.9675253677782791, 102.3424519572667037 ) ) ; +#264 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.271205131337280331E-14, -1.000000000000000000 ) ) ; +#266 = CARTESIAN_POINT ( 'NONE', ( 36.11364262193256280, 191.5260145455536929, 103.8483746271915322 ) ) ; +#265 = CARTESIAN_POINT ( 'NONE', ( -38.93740081958814159, 183.0561992808241882, 105.0172067937131999 ) ) ; +#267 = VERTEX_POINT ( 'NONE', #27817 ) ; +#268 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971581778 ) ) ; +#269 = VECTOR ( 'NONE', #25372, 1000.000000000000000 ) ; +#270 = CARTESIAN_POINT ( 'NONE', ( -23.36013622322097305, 127.9076955631128811, 92.27576111919179880 ) ) ; +#271 = ORIENTED_EDGE ( 'NONE', *, *, #10804, .F. ) ; +#272 = CARTESIAN_POINT ( 'NONE', ( -20.35185535331545736, 209.7097377694403804, 75.73747142885962091 ) ) ; +#273 = CARTESIAN_POINT ( 'NONE', ( 14.17154134345668126, 176.0476639716964939, 102.8539302333655172 ) ) ; +#275 = VERTEX_POINT ( 'NONE', #2664 ) ; +#274 = VECTOR ( 'NONE', #26596, 1000.000000000000227 ) ; +#276 = EDGE_LOOP ( 'NONE', ( #29220, #16061, #26642 ) ) ; +#277 = CARTESIAN_POINT ( 'NONE', ( -22.49964039505865898, 137.3544959182434582, 178.0533373668075399 ) ) ; +#278 = DIRECTION ( 'NONE', ( 0.0002393071182785117587, 0.2252352986010041080, -0.9743043687658491381 ) ) ; +#279 = CARTESIAN_POINT ( 'NONE', ( 2.621271904897064520, 209.6171333383382205, 73.39025471814052537 ) ) ; +#280 = CARTESIAN_POINT ( 'NONE', ( 35.99530537726000290, 191.7686035531999948, 104.0424034760000040 ) ) ; +#281 = EDGE_LOOP ( 'NONE', ( #15248, #10667, #27731, #33068 ) ) ; +#282 = VERTEX_POINT ( 'NONE', #6699 ) ; +#283 = ORIENTED_EDGE ( 'NONE', *, *, #16458, .F. ) ; +#284 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22030, #27973, #40406, #6458, #3390, #29163, #26701, #29361, #38351, #26101 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998142042, 0.3749999999997213340, 0.4374999999997243871, 0.4999999999997274402, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#285 = CARTESIAN_POINT ( 'NONE', ( -13.49823340920320724, 160.0628909777703655, 99.69670533858855777 ) ) ; +#286 = CARTESIAN_POINT ( 'NONE', ( 20.64817629877472172, 129.1121636414192153, 89.44834173347469175 ) ) ; +#287 = CARTESIAN_POINT ( 'NONE', ( -28.26178469267999915, 125.5769036415000102, 89.17499484335999682 ) ) ; +#288 = VERTEX_POINT ( 'NONE', #37784 ) ; +#289 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #3040, #15521, #21864, #1578 ), + ( #11001, #7106, #35490, #7509 ), + ( #19969, #4644, #19577, #4441 ), + ( #38583, #10796, #39193, #35299 ), + ( #26541, #26741, #32854, #35697 ), + ( #7709, #7915, #14063, #32466 ), + ( #20172, #16894, #10400, #32270 ), + ( #29406, #4837, #1372, #29809 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.07039365576733999652, 0.000000000000000000, 0.3333209167664999972, 0.6666601135059000427, 1.000000000000000000, 1.073358129890999990 ), + ( -1.157058506089999943E-06, 0.9997056213035999672 ), + .UNSPECIFIED. ) ; +#290 = FACE_OUTER_BOUND ( 'NONE', #29891, .T. ) ; +#291 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -0.000000000000000000, 0.0006039748319387908213 ) ) ; +#292 = ORIENTED_EDGE ( 'NONE', *, *, #20209, .T. ) ; +#293 = ADVANCED_FACE ( 'NONE', ( #40444 ), #30866, .T. ) ; +#294 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #5334, #17791 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#295 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319383846792 ) ) ; +#296 = ORIENTED_EDGE ( 'NONE', *, *, #22800, .F. ) ; +#297 = CARTESIAN_POINT ( 'NONE', ( -29.43062942139435023, 161.0139814470911688, 187.1134349459278496 ) ) ; +#298 = CIRCLE ( 'NONE', #25167, 51.40509898897000340 ) ; +#299 = ADVANCED_FACE ( 'NONE', ( #28207 ), #9403, .F. ) ; +#300 = CARTESIAN_POINT ( 'NONE', ( -1.042992686386000178, 188.5885128006999878, 106.1192851443999956 ) ) ; +#301 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5638, #8928, #6037, #30385 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#302 = AXIS2_PLACEMENT_3D ( 'NONE', #2191, #27750, #8527 ) ; +#303 = CARTESIAN_POINT ( 'NONE', ( -34.02846521710866057, 93.66177618440443098, 291.5790962755415308 ) ) ; +#304 = EDGE_LOOP ( 'NONE', ( #10614, #37478, #8917, #6655 ) ) ; +#305 = DIRECTION ( 'NONE', ( 0.0005884949961247682359, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#307 = EDGE_CURVE ( 'NONE', #27317, #25168, #40047, .T. ) ; +#306 = CARTESIAN_POINT ( 'NONE', ( 33.24619400733308794, 82.58330910283459048, 291.0120781237818619 ) ) ; +#308 = EDGE_CURVE ( 'NONE', #37286, #37740, #1403, .T. ) ; +#309 = CARTESIAN_POINT ( 'NONE', ( -37.83067437562999658, 118.4147154292000010, 87.61792235453000899 ) ) ; +#310 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; +#311 = ADVANCED_FACE ( 'NONE', ( #2843 ), #10711, .F. ) ; +#312 = EDGE_CURVE ( 'NONE', #12152, #38835, #15709, .T. ) ; +#313 = ORIENTED_EDGE ( 'NONE', *, *, #35780, .T. ) ; +#314 = CARTESIAN_POINT ( 'NONE', ( 15.50029468041032388, 127.6324160061002857, 89.62297635135885798 ) ) ; +#315 = VERTEX_POINT ( 'NONE', #9390 ) ; +#316 = CARTESIAN_POINT ( 'NONE', ( 22.99270477044632344, 214.0899081099834689, 76.04459013870678064 ) ) ; +#317 = CARTESIAN_POINT ( 'NONE', ( 5.675840488321574284, 188.3446150673902650, 103.1322824216947396 ) ) ; +#318 = CARTESIAN_POINT ( 'NONE', ( -38.37514916663999998, 118.5434696222999946, 89.84850653638000040 ) ) ; +#319 = ORIENTED_EDGE ( 'NONE', *, *, #126, .F. ) ; +#320 = ORIENTED_EDGE ( 'NONE', *, *, #18623, .T. ) ; +#321 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971557076 ) ) ; +#322 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265227786, -0.1368326740407717901 ) ) ; +#323 = CARTESIAN_POINT ( 'NONE', ( 25.53747175047978857, 190.9172658757476313, 106.2799836673595024 ) ) ; +#324 = CARTESIAN_POINT ( 'NONE', ( -15.49852918879845554, 137.6306203023815158, 94.00257520767851815 ) ) ; +#325 = CARTESIAN_POINT ( 'NONE', ( 29.05533563819800236, 110.6131156702000027, 90.25023614458406485 ) ) ; +#326 = VERTEX_POINT ( 'NONE', #34307 ) ; +#327 = CIRCLE ( 'NONE', #30403, 4.999999999999990230 ) ; +#328 = VERTEX_POINT ( 'NONE', #8995 ) ; +#329 = ORIENTED_EDGE ( 'NONE', *, *, #7732, .F. ) ; +#330 = CARTESIAN_POINT ( 'NONE', ( -6.036418464817404406, 177.2878155064289558, 101.0168780376782109 ) ) ; +#331 = EDGE_CURVE ( 'NONE', #5120, #21171, #6300, .T. ) ; +#332 = VECTOR ( 'NONE', #39259, 1000.000000000000000 ) ; +#333 = CARTESIAN_POINT ( 'NONE', ( 15.66679300288561727, 160.6640684447974365, 97.07785643563907740 ) ) ; +#334 = AXIS2_PLACEMENT_3D ( 'NONE', #33895, #40031, #15305 ) ; +#335 = ORIENTED_EDGE ( 'NONE', *, *, #16182, .F. ) ; +#336 = CARTESIAN_POINT ( 'NONE', ( -23.36258586059182463, 135.1577092718124504, 91.20172337759686343 ) ) ; +#337 = AXIS2_PLACEMENT_3D ( 'NONE', #2937, #2552, #15427 ) ; +#338 = LINE ( 'NONE', #37553, #10692 ) ; +#339 = ORIENTED_EDGE ( 'NONE', *, *, #26267, .F. ) ; +#340 = CARTESIAN_POINT ( 'NONE', ( 6.035817316619340289, 176.7425654431414443, 103.0192746799617822 ) ) ; +#341 = CARTESIAN_POINT ( 'NONE', ( 39.06393364112003042, 183.1686747597475744, 104.4829110299670418 ) ) ; +#342 = ORIENTED_EDGE ( 'NONE', *, *, #9160, .T. ) ; +#343 = CARTESIAN_POINT ( 'NONE', ( 28.30037992548000148, 125.1369368826999988, 88.52587847348999617 ) ) ; +#344 = ADVANCED_FACE ( 'NONE', ( #12645 ), #31064, .T. ) ; +#345 = DIRECTION ( 'NONE', ( -0.7069397808361403968, 0.6508952239913371463, 0.2767156548817158446 ) ) ; +#346 = CARTESIAN_POINT ( 'NONE', ( -22.18332052414608668, 128.5026941233560649, 175.4939087089999532 ) ) ; +#347 = DIRECTION ( 'NONE', ( -0.0005884949961209497843, 0.2249510543439031118, -0.9743698870671271273 ) ) ; +#348 = CARTESIAN_POINT ( 'NONE', ( 4.504851336039020104, 135.4216444545554339, 90.91475058518872743 ) ) ; +#349 = VERTEX_POINT ( 'NONE', #5911 ) ; +#350 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#351 = ADVANCED_FACE ( 'NONE', ( #3037 ), #25140, .F. ) ; +#352 = DIRECTION ( 'NONE', ( 0.0004270958050665225100, 0.7071067811865940911, 0.7071066522025566403 ) ) ; +#353 = DIRECTION ( 'NONE', ( 0.9999998268367519261, 0.0001323825254113870128, -0.0005734120100192159576 ) ) ; +#354 = EDGE_CURVE ( 'NONE', #36048, #5125, #32620, .T. ) ; +#355 = CARTESIAN_POINT ( 'NONE', ( 12.64386512242256266, 130.3482773188944748, 92.81742853362089818 ) ) ; +#356 = ORIENTED_EDGE ( 'NONE', *, *, #16875, .F. ) ; +#357 = EDGE_LOOP ( 'NONE', ( #38792, #27046, #18775, #35953 ) ) ; +#358 = CARTESIAN_POINT ( 'NONE', ( 16.21976467472907757, 122.6436220881636814, 172.0961230653717564 ) ) ; +#359 = CARTESIAN_POINT ( 'NONE', ( -40.82578792912735821, 120.4063655703290436, 90.55449113282519136 ) ) ; +#360 = AXIS2_PLACEMENT_3D ( 'NONE', #12528, #31160, #8887 ) ; +#361 = CARTESIAN_POINT ( 'NONE', ( 20.95020508879656163, 128.6695385774041256, 92.42488413635012989 ) ) ; +#362 = EDGE_CURVE ( 'NONE', #20220, #18693, #23368, .T. ) ; +#363 = CARTESIAN_POINT ( 'NONE', ( 14.55294048017762698, 182.5605668518259392, 101.7915615195478409 ) ) ; +#364 = VECTOR ( 'NONE', #37833, 1000.000000000000000 ) ; +#365 = AXIS2_PLACEMENT_3D ( 'NONE', #31960, #21952, #16195 ) ; +#366 = CARTESIAN_POINT ( 'NONE', ( -25.50667448668442816, 190.9437958018905022, 106.3169387399151304 ) ) ; +#367 = VERTEX_POINT ( 'NONE', #773 ) ; +#368 = AXIS2_PLACEMENT_3D ( 'NONE', #34656, #38343, #10354 ) ; +#369 = CONICAL_SURFACE ( 'NONE', #17333, 2.502996077826407983, 0.7853981633816121688 ) ; +#370 = CARTESIAN_POINT ( 'NONE', ( -19.70083802979191034, 149.6495827129742793, 180.8771180990181904 ) ) ; +#371 = CARTESIAN_POINT ( 'NONE', ( -15.66646722745994680, 127.6691331963593399, 89.47923018327796285 ) ) ; +#372 = VERTEX_POINT ( 'NONE', #29202 ) ; +#373 = CARTESIAN_POINT ( 'NONE', ( 28.53094770716555217, 124.6122665164779164, 91.48361085109841895 ) ) ; +#374 = FACE_OUTER_BOUND ( 'NONE', #37509, .T. ) ; +#375 = FACE_OUTER_BOUND ( 'NONE', #12336, .T. ) ; +#376 = CARTESIAN_POINT ( 'NONE', ( 36.67803170103999832, 191.3755374097000015, 106.3641529334000069 ) ) ; +#377 = CARTESIAN_POINT ( 'NONE', ( 4.035676232316198764, 143.6517845923164600, 95.38087260498555509 ) ) ; +#378 = CARTESIAN_POINT ( 'NONE', ( 36.67231531969000002, 191.2361342563999926, 106.4435789431999950 ) ) ; +#379 = ORIENTED_EDGE ( 'NONE', *, *, #27117, .F. ) ; +#380 = CARTESIAN_POINT ( 'NONE', ( -5.386563737826397968, 134.9999922083646027, 90.82337864291790197 ) ) ; +#381 = CARTESIAN_POINT ( 'NONE', ( 22.50029346827053089, 158.6816162529845826, 96.78702253161689839 ) ) ; +#382 = CYLINDRICAL_SURFACE ( 'NONE', #31791, 4.999999999999990230 ) ; +#383 = ORIENTED_EDGE ( 'NONE', *, *, #7035, .F. ) ; +#384 = CARTESIAN_POINT ( 'NONE', ( -30.40330716480172057, 177.7873404760022993, 100.7167276284103821 ) ) ; +#385 = AXIS2_PLACEMENT_3D ( 'NONE', #13264, #16710, #38204 ) ; +#386 = ORIENTED_EDGE ( 'NONE', *, *, #6638, .F. ) ; +#387 = VECTOR ( 'NONE', #20369, 1000.000000000000227 ) ; +#388 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#389 = DIRECTION ( 'NONE', ( -0.6188015000093128881, 0.7855473910504855439, 0.000000000000000000 ) ) ; +#390 = EDGE_CURVE ( 'NONE', #4391, #12087, #16705, .T. ) ; +#391 = ORIENTED_EDGE ( 'NONE', *, *, #16628, .T. ) ; +#392 = CIRCLE ( 'NONE', #5623, 2.500000000000002220 ) ; +#393 = FACE_OUTER_BOUND ( 'NONE', #13748, .T. ) ; +#394 = ADVANCED_FACE ( 'NONE', ( #31675 ), #28990, .T. ) ; +#395 = EDGE_CURVE ( 'NONE', #34749, #23829, #38108, .T. ) ; +#396 = CARTESIAN_POINT ( 'NONE', ( -37.29428432633125112, 118.1868522465356364, 122.8630558711557796 ) ) ; +#397 = VECTOR ( 'NONE', #24823, 1000.000000000000114 ) ; +#398 = EDGE_CURVE ( 'NONE', #7038, #1494, #16113, .T. ) ; +#399 = CARTESIAN_POINT ( 'NONE', ( -15.49970617728509481, 174.4013312752846900, 100.4391564138297497 ) ) ; +#400 = CARTESIAN_POINT ( 'NONE', ( 20.50045376188424129, 118.3470799342523350, 87.75520690767631038 ) ) ; +#401 = EDGE_LOOP ( 'NONE', ( #16276, #95, #15037, #35711 ) ) ; +#402 = CARTESIAN_POINT ( 'NONE', ( 9.175045684063999119, 135.1076161457999945, 91.09600681774000464 ) ) ; +#403 = CARTESIAN_POINT ( 'NONE', ( 1.764841773357460175, 189.4098073068830104, 103.8140057643769723 ) ) ; +#404 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510153906202348, 0.9743700737782995391 ) ) ; +#405 = EDGE_CURVE ( 'NONE', #479, #31729, #16501, .T. ) ; +#406 = CARTESIAN_POINT ( 'NONE', ( -36.53787773711000142, 191.3244119832000081, 103.9585308249000093 ) ) ; +#407 = VERTEX_POINT ( 'NONE', #28793 ) ; +#408 = EDGE_LOOP ( 'NONE', ( #679, #32778, #36283, #17693 ) ) ; +#409 = DIRECTION ( 'NONE', ( -0.9914448496661262267, 0.1271494159038595306, 0.02949806952699914747 ) ) ; +#410 = VERTEX_POINT ( 'NONE', #22471 ) ; +#411 = EDGE_CURVE ( 'NONE', #31583, #5720, #1518, .T. ) ; +#412 = CARTESIAN_POINT ( 'NONE', ( -20.18663680212400990, 209.7095168387737942, 73.23727984573439187 ) ) ; +#413 = CARTESIAN_POINT ( 'NONE', ( 20.00050118914248998, 195.5086344217266401, 105.4811071159344920 ) ) ; +#414 = AXIS2_PLACEMENT_3D ( 'NONE', #37315, #24462, #36702 ) ; +#415 = CIRCLE ( 'NONE', #1729, 6.000000000000007994 ) ; +#416 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#417 = CONICAL_SURFACE ( 'NONE', #7597, 9.999999999999664269, 0.7853981633973083909 ) ; +#418 = FACE_OUTER_BOUND ( 'NONE', #23180, .T. ) ; +#419 = CARTESIAN_POINT ( 'NONE', ( -2.570582216233999961, 209.1916834252999990, 73.46146492376000481 ) ) ; +#420 = CARTESIAN_POINT ( 'NONE', ( -36.80923119322000048, 190.7095693884000411, 106.6535541835999936 ) ) ; +#421 = ORIENTED_EDGE ( 'NONE', *, *, #13929, .F. ) ; +#422 = AXIS2_PLACEMENT_3D ( 'NONE', #39753, #38787, #21168 ) ; +#423 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#424 = CARTESIAN_POINT ( 'NONE', ( -20.01841854128525711, 211.0875725380936103, 76.07063535483980843 ) ) ; +#425 = CARTESIAN_POINT ( 'NONE', ( 33.97195405289492953, 127.1809089859550994, 297.5380268206066035 ) ) ; +#426 = VECTOR ( 'NONE', #350, 999.9999999999998863 ) ; +#427 = FACE_OUTER_BOUND ( 'NONE', #39627, .T. ) ; +#428 = ORIENTED_EDGE ( 'NONE', *, *, #14466, .T. ) ; +#429 = ORIENTED_EDGE ( 'NONE', *, *, #6211, .F. ) ; +#430 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927782437076, 0.0005734119022074447283 ) ) ; +#431 = PLANE ( 'NONE', #27250 ) ; +#432 = ORIENTED_EDGE ( 'NONE', *, *, #31159, .F. ) ; +#433 = CARTESIAN_POINT ( 'NONE', ( 43.54015349051805117, 114.1160320780469704, 121.8918845946140124 ) ) ; +#434 = FACE_OUTER_BOUND ( 'NONE', #8446, .T. ) ; +#435 = CARTESIAN_POINT ( 'NONE', ( -38.36175615046000331, 118.8220069778000010, 87.72134297774999823 ) ) ; +#436 = DIRECTION ( 'NONE', ( 0.7730662169443226484, 0.5272861007345267526, 0.3526159273084130130 ) ) ; +#437 = FACE_OUTER_BOUND ( 'NONE', #8419, .T. ) ; +#438 = EDGE_LOOP ( 'NONE', ( #24862, #21064, #20177, #39906 ) ) ; +#439 = CARTESIAN_POINT ( 'NONE', ( 44.64373491923319648, 189.2041368418193201, 103.8203288493235164 ) ) ; +#440 = VECTOR ( 'NONE', #15444, 1000.000000000000114 ) ; +#441 = EDGE_LOOP ( 'NONE', ( #38871, #28206, #5259, #6281 ) ) ; +#442 = EDGE_CURVE ( 'NONE', #28499, #3536, #37467, .T. ) ; +#443 = CARTESIAN_POINT ( 'NONE', ( -18.98889543208580122, 125.5955304196095312, 175.3358149539526778 ) ) ; +#444 = EDGE_CURVE ( 'NONE', #17419, #72, #28596, .T. ) ; +#445 = AXIS2_PLACEMENT_3D ( 'NONE', #8077, #33200, #39549 ) ; +#446 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; +#447 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #19934, #29772, #17470, #23031 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.624050982390370379, 4.624081416319758553 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999228146308, 0.9999999999228146308, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#448 = CIRCLE ( 'NONE', #33069, 2.000000000000011546 ) ; +#449 = CYLINDRICAL_SURFACE ( 'NONE', #28212, 10.00000000000000533 ) ; +#450 = ORIENTED_EDGE ( 'NONE', *, *, #23332, .F. ) ; +#451 = CARTESIAN_POINT ( 'NONE', ( -19.99846415485538031, 193.1625704610679577, 106.8253906829090454 ) ) ; +#452 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #7019, #18804 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#453 = CARTESIAN_POINT ( 'NONE', ( 2.588293688821421856, 189.6472944346019176, 103.4348881448569273 ) ) ; +#454 = CARTESIAN_POINT ( 'NONE', ( 13.47054187644548406, 153.6079216790072621, 98.01583170369502795 ) ) ; +#455 = CIRCLE ( 'NONE', #18704, 6.500001104192627110 ) ; +#456 = VERTEX_POINT ( 'NONE', #13259 ) ; +#457 = LINE ( 'NONE', #28281, #15295 ) ; +#458 = CARTESIAN_POINT ( 'NONE', ( 5.668109638569153397, 183.4506315909706302, 105.0813282954734262 ) ) ; +#459 = ORIENTED_EDGE ( 'NONE', *, *, #2690, .F. ) ; +#460 = CARTESIAN_POINT ( 'NONE', ( 41.39926400812499452, 120.5685452915470108, 90.54227133756512558 ) ) ; +#461 = CARTESIAN_POINT ( 'NONE', ( 36.16642383351802437, 191.4912202370425405, 103.8403116878715764 ) ) ; +#462 = CARTESIAN_POINT ( 'NONE', ( 16.28421033156310216, 151.2599356526419285, 184.6951526137606265 ) ) ; +#463 = ORIENTED_EDGE ( 'NONE', *, *, #38612, .F. ) ; +#464 = CARTESIAN_POINT ( 'NONE', ( 2.711028266378750828, 208.9737166860216462, 73.44859438967698395 ) ) ; +#465 = CARTESIAN_POINT ( 'NONE', ( -4.139449305539524282, 124.8489201536050075, 88.47906534633457909 ) ) ; +#466 = DIRECTION ( 'NONE', ( -0.9999998268368063270, -0.0001323825921995365950, 0.0005734118997056624183 ) ) ; +#467 = ADVANCED_FACE ( 'NONE', ( #32267 ), #13847, .T. ) ; +#468 = VERTEX_POINT ( 'NONE', #35694 ) ; +#469 = VECTOR ( 'NONE', #2521, 1000.000000000000114 ) ; +#470 = DIRECTION ( 'NONE', ( 0.0005884949961247070869, -0.2249510543439059984, 0.9743698870671263501 ) ) ; +#471 = CARTESIAN_POINT ( 'NONE', ( 36.04524237818177568, 209.7096540190999860, 73.53673375003081958 ) ) ; +#472 = AXIS2_PLACEMENT_3D ( 'NONE', #1170, #1783, #13650 ) ; +#474 = CARTESIAN_POINT ( 'NONE', ( 35.59539200389620817, 192.0921221148306302, 103.8968606314943202 ) ) ; +#473 = CARTESIAN_POINT ( 'NONE', ( -38.36106832263448752, 118.8212171802660606, 87.72011982685570786 ) ) ; +#475 = ORIENTED_EDGE ( 'NONE', *, *, #17363, .T. ) ; +#476 = CARTESIAN_POINT ( 'NONE', ( -15.10714331244187214, 129.6097141051087362, 89.58480571958619976 ) ) ; +#477 = CARTESIAN_POINT ( 'NONE', ( 3.166350703034567449, 184.1264558197564156, 102.1599558388959537 ) ) ; +#478 = ORIENTED_EDGE ( 'NONE', *, *, #11877, .F. ) ; +#479 = VERTEX_POINT ( 'NONE', #7506 ) ; +#480 = CARTESIAN_POINT ( 'NONE', ( -13.46986788395000012, 174.3879284816999871, 152.4718672074000381 ) ) ; +#481 = CARTESIAN_POINT ( 'NONE', ( 26.00170599668673788, 118.1131156702000169, 87.24902382708054915 ) ) ; +#482 = PLANE ( 'NONE', #32390 ) ; +#483 = CARTESIAN_POINT ( 'NONE', ( 8.470678213537377488, 151.0674926792860049, 95.03763680969706229 ) ) ; +#484 = CARTESIAN_POINT ( 'NONE', ( -2.300490056545999806, 191.0208375971999999, 106.1810267846999949 ) ) ; +#485 = ORIENTED_EDGE ( 'NONE', *, *, #27419, .F. ) ; +#486 = EDGE_LOOP ( 'NONE', ( #38539, #28194, #8804, #34851 ) ) ; +#487 = ORIENTED_EDGE ( 'NONE', *, *, #24736, .F. ) ; +#488 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971576227 ) ) ; +#489 = EDGE_CURVE ( 'NONE', #22792, #8531, #16957, .T. ) ; +#490 = CARTESIAN_POINT ( 'NONE', ( 20.11108698654291516, 128.1535755644673031, 89.22735858623562422 ) ) ; +#491 = EDGE_CURVE ( 'NONE', #25299, #18476, #6907, .T. ) ; +#492 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386880390 ) ) ; +#493 = EDGE_LOOP ( 'NONE', ( #20538, #32260, #32848, #15873 ) ) ; +#494 = DIRECTION ( 'NONE', ( -0.0005884949961224280940, 0.2249510543439061094, -0.9743698870671263501 ) ) ; +#495 = ORIENTED_EDGE ( 'NONE', *, *, #34696, .F. ) ; +#496 = VECTOR ( 'NONE', #31484, 1000.000000000000114 ) ; +#497 = CARTESIAN_POINT ( 'NONE', ( 36.06588537441000142, 194.9391275604999976, 107.7152975676000040 ) ) ; +#498 = EDGE_LOOP ( 'NONE', ( #36671, #21549, #16809, #24710, #13730, #17370, #35163, #30337, #29356, #27134, #28658, #1797, #27624, #26608, #27772, #16640, #34868, #35558, #34400, #29870, #19344, #31943, #30587 ) ) ; +#499 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#500 = CARTESIAN_POINT ( 'NONE', ( -2.503680010063999983, 189.6842172410000273, 106.3860591883999973 ) ) ; +#501 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; +#502 = ORIENTED_EDGE ( 'NONE', *, *, #7788, .F. ) ; +#503 = CARTESIAN_POINT ( 'NONE', ( 22.78196627740044278, 153.3599009982148118, 97.61084599868732425 ) ) ; +#504 = FACE_OUTER_BOUND ( 'NONE', #32385, .T. ) ; +#505 = DIRECTION ( 'NONE', ( 7.930164461882003851E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; +#506 = CARTESIAN_POINT ( 'NONE', ( 42.83827273200019903, 189.3718331974772582, 106.4258958018896095 ) ) ; +#507 = EDGE_CURVE ( 'NONE', #13220, #26074, #4031, .T. ) ; +#508 = CARTESIAN_POINT ( 'NONE', ( -37.83650503347710270, 190.7637522520328162, 106.4538665319802959 ) ) ; +#509 = EDGE_LOOP ( 'NONE', ( #2105, #12513, #10717, #17166, #22728, #20104 ) ) ; +#510 = DIRECTION ( 'NONE', ( 0.0006039748319375823696, 6.916865751211140412E-15, 0.9999998176071847045 ) ) ; +#511 = CARTESIAN_POINT ( 'NONE', ( -28.25689436368393714, 186.9042180597057836, 103.3333805992548093 ) ) ; +#512 = ORIENTED_EDGE ( 'NONE', *, *, #20286, .T. ) ; +#513 = ORIENTED_EDGE ( 'NONE', *, *, #8641, .F. ) ; +#514 = LINE ( 'NONE', #18919, #29035 ) ; +#515 = ADVANCED_FACE ( 'NONE', ( #35094 ), #8765, .F. ) ; +#516 = VECTOR ( 'NONE', #28278, 1000.000000000000000 ) ; +#517 = CARTESIAN_POINT ( 'NONE', ( 29.20104124293241910, 162.9684951647539322, 100.3384403448970659 ) ) ; +#518 = PLANE ( 'NONE', #29405 ) ; +#519 = CARTESIAN_POINT ( 'NONE', ( -3.777786845789887327, 174.7331624351747905, 102.8264155123936376 ) ) ; +#520 = VERTEX_POINT ( 'NONE', #17505 ) ; +#521 = DIRECTION ( 'NONE', ( -0.0009686424659220778562, 0.2252351993847904188, -0.9743039395844949047 ) ) ; +#522 = VECTOR ( 'NONE', #15662, 1000.000000000000000 ) ; +#523 = ORIENTED_EDGE ( 'NONE', *, *, #12901, .T. ) ; +#524 = ORIENTED_EDGE ( 'NONE', *, *, #17371, .F. ) ; +#525 = ORIENTED_EDGE ( 'NONE', *, *, #30357, .T. ) ; +#526 = CARTESIAN_POINT ( 'NONE', ( 37.28362348802268400, 145.4126454253283214, 281.4614046043920439 ) ) ; +#527 = EDGE_CURVE ( 'NONE', #39304, #31792, #27729, .T. ) ; +#528 = CARTESIAN_POINT ( 'NONE', ( 19.44287702427785547, 124.8277558452613363, 177.7399537498035045 ) ) ; +#529 = VERTEX_POINT ( 'NONE', #10998 ) ; +#530 = CARTESIAN_POINT ( 'NONE', ( 76.10748482112096269, 155.8105762428847925, 98.14442178571833608 ) ) ; +#532 = ADVANCED_FACE ( 'NONE', ( #20584 ), #30204, .T. ) ; +#531 = CARTESIAN_POINT ( 'NONE', ( 21.72426698684031976, 130.1004708904147265, 89.67586055015539159 ) ) ; +#533 = EDGE_CURVE ( 'NONE', #20299, #20347, #26950, .T. ) ; +#534 = EDGE_LOOP ( 'NONE', ( #25263, #15716, #6651, #33569 ) ) ; +#535 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#536 = EDGE_CURVE ( 'NONE', #8692, #10027, #22362, .T. ) ; +#537 = EDGE_CURVE ( 'NONE', #19831, #17075, #39384, .T. ) ; +#538 = DIRECTION ( 'NONE', ( -0.0005884949961193586092, 0.2249510543439039167, -0.9743698870671270162 ) ) ; +#539 = ORIENTED_EDGE ( 'NONE', *, *, #6576, .F. ) ; +#540 = PLANE ( 'NONE', #5303 ) ; +#541 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12398, #28162, #8952, #31212, #30415, #21211, #15081, #33866, #15278, #24700, #24904, #21627, #34067, #6257, #131, #12593, #22227, #22022, #3983, #35251, #32024, #4179 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), + ( 5.594315114139762021E-17, 0.001939686057088096547, 0.002909529085632069686, 0.003879372114176043041, 0.005819058171264075187, 0.007758744228352106899, 0.009698430285440139478, 0.01066827331398415533, 0.01163811634252817293, 0.01357780239961627056, 0.01551748845670436645 ), + .UNSPECIFIED. ) ; +#542 = FACE_OUTER_BOUND ( 'NONE', #30780, .T. ) ; +#543 = CARTESIAN_POINT ( 'NONE', ( 16.00202263909956457, 151.2883905618018048, 97.64994197610543836 ) ) ; +#544 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999901590, 132.9679238121798619, 90.36185680190951075 ) ) ; +#545 = CARTESIAN_POINT ( 'NONE', ( 20.96422822264385033, 158.7934676277431265, 96.30062105744464418 ) ) ; +#546 = ORIENTED_EDGE ( 'NONE', *, *, #2807, .F. ) ; +#547 = LINE ( 'NONE', #31856, #21347 ) ; +#548 = AXIS2_PLACEMENT_3D ( 'NONE', #23737, #20660, #33122 ) ; +#549 = CARTESIAN_POINT ( 'NONE', ( 0.7260690469630617372, 189.0066063905518092, 103.6849890980020206 ) ) ; +#550 = CARTESIAN_POINT ( 'NONE', ( 20.50029379647860495, 189.2267361095769331, 103.8400967508667492 ) ) ; +#551 = AXIS2_PLACEMENT_3D ( 'NONE', #36766, #21651, #5891 ) ; +#552 = CARTESIAN_POINT ( 'NONE', ( -26.00132979581089288, 118.1159538331455252, 87.28348844368876769 ) ) ; +#553 = AXIS2_PLACEMENT_3D ( 'NONE', #5804, #28106, #9484 ) ; +#554 = LINE ( 'NONE', #19154, #5533 ) ; +#555 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923101038, 127.7447309815698873, 89.13696229017300254 ) ) ; +#556 = LINE ( 'NONE', #13642, #33299 ) ; +#557 = CARTESIAN_POINT ( 'NONE', ( 12.63829599803258041, 181.4182578506842560, 104.2633634328516905 ) ) ; +#558 = EDGE_CURVE ( 'NONE', #23378, #27940, #11387, .T. ) ; +#559 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825957230524654, 0.0005734119015252938864 ) ) ; +#560 = ORIENTED_EDGE ( 'NONE', *, *, #39768, .F. ) ; +#561 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20914, #2315, #27676, #5778 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0009062002059386310747, 0.0009636043971113295633 ), + .UNSPECIFIED. ) ; +#562 = CARTESIAN_POINT ( 'NONE', ( -19.00260255556003131, 149.1275189729910267, 180.7566863177478638 ) ) ; +#563 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971575394 ) ) ; +#564 = ORIENTED_EDGE ( 'NONE', *, *, #4497, .F. ) ; +#565 = CARTESIAN_POINT ( 'NONE', ( 21.46292357967359976, 116.1138482125577838, 87.75460328546795097 ) ) ; +#566 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; +#567 = ADVANCED_FACE ( 'NONE', ( #17908 ), #5242, .F. ) ; +#568 = CARTESIAN_POINT ( 'NONE', ( -25.02200516277000375, 130.2733187283999996, 91.28345564459999650 ) ) ; +#569 = CARTESIAN_POINT ( 'NONE', ( 36.06505882652250250, 192.7068426039909923, 106.3467840092589967 ) ) ; +#570 = CARTESIAN_POINT ( 'NONE', ( 3.931141971386352463, 143.6293547669063173, 95.48310455860253398 ) ) ; +#571 = CARTESIAN_POINT ( 'NONE', ( 35.47021744578000124, 192.2039990837999994, 107.0420568499000069 ) ) ; +#572 = VERTEX_POINT ( 'NONE', #8124 ) ; +#574 = AXIS2_PLACEMENT_3D ( 'NONE', #8141, #27180, #13869 ) ; +#573 = LINE ( 'NONE', #37996, #19898 ) ; +#575 = EDGE_CURVE ( 'NONE', #24174, #13536, #14673, .T. ) ; +#576 = CARTESIAN_POINT ( 'NONE', ( 20.04381349576867066, 126.7748930407473722, 91.94483827613792926 ) ) ; +#577 = EDGE_CURVE ( 'NONE', #29516, #37526, #38988, .T. ) ; +#578 = AXIS2_PLACEMENT_3D ( 'NONE', #24274, #40378, #36718 ) ; +#579 = CARTESIAN_POINT ( 'NONE', ( -23.35979081385350398, 130.6186769843367017, 90.16484899944724418 ) ) ; +#580 = ORIENTED_EDGE ( 'NONE', *, *, #14785, .F. ) ; +#581 = CARTESIAN_POINT ( 'NONE', ( -17.34531841520229634, 127.5687170461390565, 172.4105396402263466 ) ) ; +#582 = AXIS2_PLACEMENT_3D ( 'NONE', #18653, #9286, #39940 ) ; +#583 = EDGE_CURVE ( 'NONE', #22996, #1259, #2416, .T. ) ; +#584 = AXIS2_PLACEMENT_3D ( 'NONE', #36881, #14813, #24230 ) ; +#585 = VERTEX_POINT ( 'NONE', #17710 ) ; +#586 = ADVANCED_FACE ( 'NONE', ( #4642 ), #33574, .T. ) ; +#587 = CARTESIAN_POINT ( 'NONE', ( 20.00000279695219874, 118.8155797008581374, 87.25566994753728522 ) ) ; +#588 = CARTESIAN_POINT ( 'NONE', ( -3.169796603587565986, 128.7385212851464757, 89.37646504162516692 ) ) ; +#589 = CARTESIAN_POINT ( 'NONE', ( 38.22623376675434059, 118.8155667128057615, 90.24469678293085906 ) ) ; +#590 = CARTESIAN_POINT ( 'NONE', ( 27.30442999513742919, 110.6131156702000027, 88.75129337409590846 ) ) ; +#591 = DIRECTION ( 'NONE', ( -0.0001358647734255411942, -0.9743700647848254626, -0.2249510133161850278 ) ) ; +#592 = CARTESIAN_POINT ( 'NONE', ( -35.69795641737000125, 111.2706431035999941, 87.53934500879000780 ) ) ; +#593 = CYLINDRICAL_SURFACE ( 'NONE', #15667, 2.000000000000011546 ) ; +#594 = DIRECTION ( 'NONE', ( -0.0005884949961246487568, 0.2249510543439061372, -0.9743698870671263501 ) ) ; +#595 = EDGE_LOOP ( 'NONE', ( #8672, #24429, #20056, #22752 ) ) ; +#596 = CARTESIAN_POINT ( 'NONE', ( 23.72263521211007031, 115.9590670243358232, 152.9217693425221682 ) ) ; +#597 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34553, #4704, #4086, #7164 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#598 = CARTESIAN_POINT ( 'NONE', ( 18.99695336057541795, 148.4229678448664060, 183.7014091461406622 ) ) ; +#599 = CARTESIAN_POINT ( 'NONE', ( 21.25891437287570440, 136.8714408223384567, 91.75249562560091476 ) ) ; +#600 = EDGE_LOOP ( 'NONE', ( #32369, #12113, #22331, #7773, #33819, #36917, #10893, #22939, #13959, #36294, #16984, #37697, #23156, #9020, #9923, #6852, #1017, #26161, #30987, #37503, #17151, #36365, #24213, #3389, #26066, #22005, #27886, #13770, #25460 ) ) ; +#601 = CARTESIAN_POINT ( 'NONE', ( -37.62510914575000953, 190.9293338957000117, 103.6056530092999992 ) ) ; +#602 = ORIENTED_EDGE ( 'NONE', *, *, #7262, .F. ) ; +#603 = CARTESIAN_POINT ( 'NONE', ( 13.81047920904208226, 150.0053730344457676, 180.1700289459587907 ) ) ; +#604 = VERTEX_POINT ( 'NONE', #17097 ) ; +#605 = VECTOR ( 'NONE', #11678, 1000.000000000000227 ) ; +#606 = DIRECTION ( 'NONE', ( -0.0005884949961249829080, 0.2249510543439062205, -0.9743698870671264611 ) ) ; +#607 = VECTOR ( 'NONE', #20837, 1000.000000000000114 ) ; +#608 = AXIS2_PLACEMENT_3D ( 'NONE', #16548, #29043, #35344 ) ; +#609 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20952, #17247, #14219, #11334 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#610 = AXIS2_PLACEMENT_3D ( 'NONE', #5756, #18407, #40091 ) ; +#611 = CARTESIAN_POINT ( 'NONE', ( -16.04896084364859021, 152.7188673256511890, 181.6067879991456664 ) ) ; +#612 = CARTESIAN_POINT ( 'NONE', ( -15.83179463202705861, 160.1070185153170087, 99.53409605412225858 ) ) ; +#613 = CARTESIAN_POINT ( 'NONE', ( 5.995984845311999933, 151.9652147202999970, 28.07991271570000080 ) ) ; +#614 = CARTESIAN_POINT ( 'NONE', ( -2.996716101987999981, 209.7033295502000101, 72.92379390556999397 ) ) ; +#615 = CARTESIAN_POINT ( 'NONE', ( 38.31102854718000117, 118.7287393711000050, 90.10199935446000552 ) ) ; +#616 = ORIENTED_EDGE ( 'NONE', *, *, #10432, .T. ) ; +#617 = EDGE_CURVE ( 'NONE', #349, #13580, #36535, .T. ) ; +#618 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16049, #714, #19708, #10139, #4166, #1114, #32210, #12798 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 4 ), + ( 0.000000000000000000, 0.0003628416619586385971, 0.0007256833239172771942, 0.001451366647834552437 ), + .UNSPECIFIED. ) ; +#619 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989946348, -0.1373964268091547314 ) ) ; +#620 = ADVANCED_FACE ( 'NONE', ( #7707 ), #31317, .T. ) ; +#621 = CARTESIAN_POINT ( 'NONE', ( 19.70892818629356569, 149.4293184409359014, 181.7720440811204412 ) ) ; +#622 = CARTESIAN_POINT ( 'NONE', ( -3.668404234881370574, 185.3449489777972019, 105.0111528741126676 ) ) ; +#623 = EDGE_CURVE ( 'NONE', #30537, #14528, #38910, .T. ) ; +#624 = EDGE_CURVE ( 'NONE', #28651, #36967, #2290, .T. ) ; +#625 = CARTESIAN_POINT ( 'NONE', ( 35.80519753165925323, 112.4664341929300093, 89.99614522430350405 ) ) ; +#626 = VERTEX_POINT ( 'NONE', #40290 ) ; +#627 = ORIENTED_EDGE ( 'NONE', *, *, #36499, .T. ) ; +#628 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #36202, #18194, #20675, #24166, #5118, #1665, #30282 ), + ( #20457, #14554, #8824, #39465, #5747, #36622, #30089 ), + ( #23959, #23750, #11683, #36417, #33134, #8423, #2078 ), + ( #2278, #29887, #14150, #26623, #32929, #4926, #20881 ), + ( #21088, #5329, #17995, #39064, #8206, #33338, #17787 ), + ( #26825, #14760, #27244, #36820, #39675, #39879, #11075 ), + ( #33744, #39271, #11271, #33536, #23540, #30499, #8623 ), + ( #2486, #21299, #17383, #35990, #27457, #11890, #24374 ), + ( #7995, #204, #19001, #9621, #12677, #31490, #15159 ), + ( #15547, #34338, #3064, #25170, #27646, #12474, #28040 ), + ( #18785, #6731, #2873, #15351, #34520, #34728, #403 ), + ( #3264, #21897, #37818, #27846, #24774, #5942, #30700 ), + ( #3457, #12288, #37228, #12, #18397, #34143, #28426 ), + ( #40078, #30900, #40276, #24973, #2695, #6335, #12089 ), + ( #37426, #24575, #28237, #6528, #15931, #9226, #31290 ), + ( #37030, #21698, #6137, #31097, #9422, #15737, #37623 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 3, 4 ), + ( 3.467946620240000122E-12, 0.01041366078304999977, 0.02083069311681999894, 0.04166475778438000210, 0.08333288711950000149, 0.1250010164545999891, 0.1666691457896999906, 0.2500022395825000077, 0.3333353333754000003, 0.4166684271682000174, 0.5000015209610999545, 0.6666677085469000508, 0.8333338961324999739, 0.9999999601867000099 ), + ( 0.1894117542789000019, 0.8184388841219000232, 0.8247291554203299846 ), + .UNSPECIFIED. ) ; +#629 = VERTEX_POINT ( 'NONE', #2880 ) ; +#630 = DIRECTION ( 'NONE', ( 0.0006039748319383109534, 1.233022124494217175E-14, 0.9999998176071845934 ) ) ; +#631 = EDGE_CURVE ( 'NONE', #17579, #24155, #37040, .T. ) ; +#632 = DIRECTION ( 'NONE', ( -2.449021403759176867E-15, 0.9743700557921586292, 0.2249510932971564847 ) ) ; +#633 = ORIENTED_EDGE ( 'NONE', *, *, #16949, .T. ) ; +#634 = CARTESIAN_POINT ( 'NONE', ( 0.5444273898015001834, 211.0000000000005116, 73.55817535311000199 ) ) ; +#635 = EDGE_CURVE ( 'NONE', #16566, #34518, #24587, .T. ) ; +#636 = VECTOR ( 'NONE', #11508, 1000.000000000000227 ) ; +#637 = CARTESIAN_POINT ( 'NONE', ( -32.36931359533516428, 158.3297460257155649, 186.4994859931237841 ) ) ; +#638 = DIRECTION ( 'NONE', ( 1.387778780753341559E-14, -0.9743700557921585181, -0.2249510932971562904 ) ) ; +#639 = CARTESIAN_POINT ( 'NONE', ( -35.62084758004493068, 207.7152267789312816, 77.23343464428440086 ) ) ; +#640 = CARTESIAN_POINT ( 'NONE', ( 114.5937281169188253, 50.54601443099469549, 171.8750556891886276 ) ) ; +#641 = EDGE_LOOP ( 'NONE', ( #33141, #841, #4462, #16740 ) ) ; +#642 = CARTESIAN_POINT ( 'NONE', ( -31.91335489949009130, 137.9985878559502623, 92.04483278691883186 ) ) ; +#643 = AXIS2_PLACEMENT_3D ( 'NONE', #17508, #17713, #30414 ) ; +#644 = AXIS2_PLACEMENT_3D ( 'NONE', #34495, #25543, #6499 ) ; +#645 = VERTEX_POINT ( 'NONE', #5953 ) ; +#646 = CARTESIAN_POINT ( 'NONE', ( 19.98261053240618779, 208.0209216810735882, 76.90620748650613336 ) ) ; +#647 = CONICAL_SURFACE ( 'NONE', #22118, 5.500000000083335117, 0.7853981634365208020 ) ; +#648 = FACE_OUTER_BOUND ( 'NONE', #15019, .T. ) ; +#649 = ADVANCED_FACE ( 'NONE', ( #26764 ), #8358, .F. ) ; +#650 = VERTEX_POINT ( 'NONE', #36561 ) ; +#651 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971542088 ) ) ; +#652 = CARTESIAN_POINT ( 'NONE', ( -22.49999922076347758, 151.9675441756866690, 94.75098345857674076 ) ) ; +#653 = PLANE ( 'NONE', #18143 ) ; +#654 = VERTEX_POINT ( 'NONE', #39210 ) ; +#655 = ORIENTED_EDGE ( 'NONE', *, *, #22684, .F. ) ; +#656 = CARTESIAN_POINT ( 'NONE', ( -23.02059183176825741, 214.0904033191889084, 73.07235108223721909 ) ) ; +#657 = CARTESIAN_POINT ( 'NONE', ( 13.46793942647703801, 157.6314446051065943, 99.11578051374280562 ) ) ; +#658 = ORIENTED_EDGE ( 'NONE', *, *, #19905, .F. ) ; +#659 = CARTESIAN_POINT ( 'NONE', ( -26.01326056281665089, 211.0902258159713085, 76.07393268928584007 ) ) ; +#660 = LINE ( 'NONE', #24831, #1306 ) ; +#661 = CARTESIAN_POINT ( 'NONE', ( -25.87425499709999954, 120.4547996877000031, 90.43191455909000354 ) ) ; +#662 = VERTEX_POINT ( 'NONE', #36142 ) ; +#663 = CARTESIAN_POINT ( 'NONE', ( 13.85666887114530077, 150.2803490827782298, 180.5372210466468061 ) ) ; +#664 = CARTESIAN_POINT ( 'NONE', ( -38.04444379205944671, 118.4867705051282627, 87.71485106921780073 ) ) ; +#665 = CARTESIAN_POINT ( 'NONE', ( 35.84002668644952649, 165.7685787144644678, 188.2286130183017008 ) ) ; +#666 = CONICAL_SURFACE ( 'NONE', #37250, 5.249999999955947239, 0.7853981633862021638 ) ; +#667 = CONICAL_SURFACE ( 'NONE', #25502, 22.50000000000906653, 0.7853981633972855203 ) ; +#668 = ORIENTED_EDGE ( 'NONE', *, *, #4798, .F. ) ; +#669 = CARTESIAN_POINT ( 'NONE', ( 25.50032466477000170, 120.2211198582999998, 89.96472687520000022 ) ) ; +#670 = ADVANCED_FACE ( 'NONE', ( #14702 ), #13874, .T. ) ; +#671 = CIRCLE ( 'NONE', #28105, 2.999999999962116526 ) ; +#672 = CARTESIAN_POINT ( 'NONE', ( -8.473032270639919261, 161.1929806888288397, 98.41182820864784730 ) ) ; +#673 = CARTESIAN_POINT ( 'NONE', ( 23.37116632637657077, 177.1196686977561399, 103.6090577849978445 ) ) ; +#674 = EDGE_CURVE ( 'NONE', #16466, #19730, #8144, .T. ) ; +#675 = EDGE_CURVE ( 'NONE', #38540, #14950, #7938, .T. ) ; +#677 = CARTESIAN_POINT ( 'NONE', ( -9.889664841446476728, 153.3280908470186148, 95.05747415439600445 ) ) ; +#676 = CARTESIAN_POINT ( 'NONE', ( 20.00176513869433137, 118.9456690639568990, 90.18052439326532976 ) ) ; +#678 = FACE_OUTER_BOUND ( 'NONE', #24613, .T. ) ; +#679 = ORIENTED_EDGE ( 'NONE', *, *, #3309, .F. ) ; +#680 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#681 = EDGE_CURVE ( 'NONE', #31532, #35965, #31669, .T. ) ; +#682 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971575672 ) ) ; +#683 = ORIENTED_EDGE ( 'NONE', *, *, #38650, .T. ) ; +#684 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #20340, #5005, #1534, #36078 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.441567807838093351, 5.011884969131253698 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8048507809858624906, 0.8048507809858624906, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#685 = ORIENTED_EDGE ( 'NONE', *, *, #2582, .T. ) ; +#686 = CARTESIAN_POINT ( 'NONE', ( -13.47069009286630603, 153.6544384493914492, 96.33233530911239484 ) ) ; +#687 = EDGE_CURVE ( 'NONE', #38882, #38531, #37490, .T. ) ; +#688 = CARTESIAN_POINT ( 'NONE', ( -46.14362517609952619, 125.4997054666571472, 91.73359335677182003 ) ) ; +#689 = CARTESIAN_POINT ( 'NONE', ( -43.57128771414367918, 121.9172130293124212, 88.19101713714755419 ) ) ; +#690 = ORIENTED_EDGE ( 'NONE', *, *, #38385, .T. ) ; +#691 = EDGE_LOOP ( 'NONE', ( #31999, #16217, #22925, #7696 ) ) ; +#692 = CARTESIAN_POINT ( 'NONE', ( -29.78271044658185218, 126.9386829446179377, 89.49016549083705740 ) ) ; +#693 = DIRECTION ( 'NONE', ( -0.7933533411653341805, -0.5931840316264885837, -0.1368326740407639630 ) ) ; +#694 = CARTESIAN_POINT ( 'NONE', ( 0.1948172102453834542, 3.621363614364748935E-12, 322.5584319246983682 ) ) ; +#695 = EDGE_CURVE ( 'NONE', #10631, #6854, #27713, .T. ) ; +#696 = ORIENTED_EDGE ( 'NONE', *, *, #38303, .T. ) ; +#697 = LINE ( 'NONE', #31592, #13485 ) ; +#698 = CIRCLE ( 'NONE', #1361, 2.000000000000011546 ) ; +#699 = ORIENTED_EDGE ( 'NONE', *, *, #30882, .T. ) ; +#700 = CARTESIAN_POINT ( 'NONE', ( -37.79509714950135901, 117.7323670804173474, 89.71823316337903975 ) ) ; +#701 = AXIS2_PLACEMENT_3D ( 'NONE', #25935, #961, #23055 ) ; +#702 = CARTESIAN_POINT ( 'NONE', ( -28.46737701140906651, 131.0177979894622808, 89.91795673199465000 ) ) ; +#703 = EDGE_LOOP ( 'NONE', ( #2605, #10511, #16063, #38102 ) ) ; +#704 = CARTESIAN_POINT ( 'NONE', ( 20.00176513865781303, 118.9456690639568990, 90.18052439326535819 ) ) ; +#705 = CARTESIAN_POINT ( 'NONE', ( -1.744169957438999941, 188.5358409586000050, 106.4260139966000054 ) ) ; +#706 = CARTESIAN_POINT ( 'NONE', ( 21.72592390767327686, 135.1711755393868941, 93.92543662762206225 ) ) ; +#707 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35200, #38286, #13962, #32763, #19671, #7204, #38890, #1070, #4534, #26040, #22571, #10698, #1690, #35803, #19865, #14178, #13555, #38679 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000370259, 0.1875000000000689726, 0.2187500000000849598, 0.2500000000001009193, 0.5000000000000535127, 0.6250000000000375255, 0.6875000000000295319, 0.7187500000000210942, 0.7500000000000125455, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#708 = EDGE_LOOP ( 'NONE', ( #22990, #9936 ) ) ; +#709 = CARTESIAN_POINT ( 'NONE', ( 2.781572041167127640, 209.6623637130746545, 73.22349110528780614 ) ) ; +#710 = ORIENTED_EDGE ( 'NONE', *, *, #33726, .T. ) ; +#711 = VERTEX_POINT ( 'NONE', #27183 ) ; +#712 = DIRECTION ( 'NONE', ( -0.0005884949961263054178, 0.2249510543439064703, -0.9743698870671262391 ) ) ; +#713 = CARTESIAN_POINT ( 'NONE', ( -13.78572884413053323, 125.0559276006693921, 174.4126573023246465 ) ) ; +#714 = CARTESIAN_POINT ( 'NONE', ( 19.39902400086316092, 126.2415996759917505, 175.5115058955111351 ) ) ; +#715 = CARTESIAN_POINT ( 'NONE', ( 21.71477686248909933, 151.2531533811763325, 202.9610808053989217 ) ) ; +#716 = ORIENTED_EDGE ( 'NONE', *, *, #32049, .F. ) ; +#717 = FACE_OUTER_BOUND ( 'NONE', #37574, .T. ) ; +#718 = ADVANCED_FACE ( 'NONE', ( #26564 ), #17730, .F. ) ; +#719 = CONICAL_SURFACE ( 'NONE', #37390, 2.499999999965141662, 0.7853981634008656565 ) ; +#720 = ADVANCED_FACE ( 'NONE', ( #11020 ), #19842, .F. ) ; +#721 = CARTESIAN_POINT ( 'NONE', ( -36.07808061111000342, 112.9804154865999948, 89.64438889024999924 ) ) ; +#722 = VECTOR ( 'NONE', #9071, 1000.000000000000114 ) ; +#723 = VERTEX_POINT ( 'NONE', #29424 ) ; +#724 = AXIS2_PLACEMENT_3D ( 'NONE', #4283, #32713, #19425 ) ; +#725 = CARTESIAN_POINT ( 'NONE', ( -22.46513725335000089, 140.5903658354843344, 152.9217693939943388 ) ) ; +#726 = VERTEX_POINT ( 'NONE', #1395 ) ; +#727 = DIRECTION ( 'NONE', ( 0.0005884949961257676535, -0.2249510543438813792, 0.9743698870671319012 ) ) ; +#728 = AXIS2_PLACEMENT_3D ( 'NONE', #21683, #34318, #34122 ) ; +#729 = CARTESIAN_POINT ( 'NONE', ( -26.91923286534074933, 123.7406455964028567, 88.23695837583139223 ) ) ; +#730 = CARTESIAN_POINT ( 'NONE', ( 23.36598296845494360, 177.6947003474286930, 100.7482006756413284 ) ) ; +#731 = FACE_BOUND ( 'NONE', #27312, .T. ) ; +#732 = EDGE_LOOP ( 'NONE', ( #34050, #35652, #23725, #5148 ) ) ; +#733 = ORIENTED_EDGE ( 'NONE', *, *, #4734, .T. ) ; +#734 = VERTEX_POINT ( 'NONE', #8562 ) ; +#735 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#736 = CARTESIAN_POINT ( 'NONE', ( 1.875840786765911039, 189.4897504644060575, 105.8774097022063643 ) ) ; +#737 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971542088 ) ) ; +#738 = CARTESIAN_POINT ( 'NONE', ( -25.75976792568999940, 210.3999399800999868, 75.82533471885000154 ) ) ; +#739 = ORIENTED_EDGE ( 'NONE', *, *, #12362, .T. ) ; +#740 = CARTESIAN_POINT ( 'NONE', ( -44.78294139341442559, 188.5432348633073047, 105.7511144607040876 ) ) ; +#741 = CARTESIAN_POINT ( 'NONE', ( 36.18941359597000940, 191.5903931521000061, 103.9682770481999938 ) ) ; +#742 = ORIENTED_EDGE ( 'NONE', *, *, #25799, .F. ) ; +#743 = DIRECTION ( 'NONE', ( 0.0005884949961251158311, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#744 = DIRECTION ( 'NONE', ( -0.0005884949961251545372, 0.2249510543439063315, -0.9743698870671262391 ) ) ; +#745 = ORIENTED_EDGE ( 'NONE', *, *, #12498, .F. ) ; +#746 = LINE ( 'NONE', #38170, #20322 ) ; +#747 = DIRECTION ( 'NONE', ( 0.0005884949949860971558, -0.2249510543438488497, 0.9743698870671402279 ) ) ; +#748 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825867343808962, 0.0005734119035994554754 ) ) ; +#749 = AXIS2_PLACEMENT_3D ( 'NONE', #27685, #25015, #24617 ) ; +#750 = CARTESIAN_POINT ( 'NONE', ( -25.92937993143591413, 117.3625828949747785, 90.28344553495060154 ) ) ; +#751 = CARTESIAN_POINT ( 'NONE', ( 5.695423016759590951, 134.9205841030388626, 90.79835259162844352 ) ) ; +#752 = EDGE_LOOP ( 'NONE', ( #18976, #37690, #34170, #524 ) ) ; +#753 = CARTESIAN_POINT ( 'NONE', ( -14.78542059478467330, 183.3574060367851359, 102.5063981592711571 ) ) ; +#754 = CIRCLE ( 'NONE', #35338, 2.500000000003740563 ) ; +#755 = CARTESIAN_POINT ( 'NONE', ( 1.038435199333894943, 189.0574318112943217, 103.7007315583379210 ) ) ; +#756 = CARTESIAN_POINT ( 'NONE', ( -1.198528310954169340, 138.2140671179444666, 181.3494557296553182 ) ) ; +#757 = ADVANCED_FACE ( 'NONE', ( #33478 ), #30965, .T. ) ; +#758 = CARTESIAN_POINT ( 'NONE', ( 12.63825265581525059, 130.2405143122917366, 92.64486568747496165 ) ) ; +#759 = CARTESIAN_POINT ( 'NONE', ( 5.668109638568658681, 126.1283174451533711, 91.84742690372624452 ) ) ; +#760 = CARTESIAN_POINT ( 'NONE', ( 20.45340480371016767, 105.2139170030256281, 87.75543103923976673 ) ) ; +#761 = CARTESIAN_POINT ( 'NONE', ( -43.16067970895235106, 137.0136042933273472, 338.0369414682852494 ) ) ; +#762 = LINE ( 'NONE', #13252, #15106 ) ; +#763 = EDGE_CURVE ( 'NONE', #12730, #23821, #24372, .T. ) ; +#764 = CARTESIAN_POINT ( 'NONE', ( -20.49851155431899841, 191.4731498523730693, 106.4361349872459641 ) ) ; +#765 = DIRECTION ( 'NONE', ( 5.259792451068736282E-12, 0.9743043966640311249, 0.2252353050503814180 ) ) ; +#766 = ORIENTED_EDGE ( 'NONE', *, *, #14407, .F. ) ; +#767 = ADVANCED_FACE ( 'NONE', ( #36360, #1809 ), #32684, .F. ) ; +#768 = EDGE_CURVE ( 'NONE', #10259, #4372, #17894, .T. ) ; +#769 = EDGE_CURVE ( 'NONE', #17683, #5306, #24325, .T. ) ; +#770 = DIRECTION ( 'NONE', ( -0.0004161288024551938573, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#771 = FACE_OUTER_BOUND ( 'NONE', #3554, .T. ) ; +#772 = EDGE_LOOP ( 'NONE', ( #6568, #9921, #33003 ) ) ; +#773 = CARTESIAN_POINT ( 'NONE', ( 43.53560975226982777, 121.3918131887250524, 90.46069063649885322 ) ) ; +#774 = CARTESIAN_POINT ( 'NONE', ( -25.99205882618559116, 191.8000695062693524, 103.9294257625771110 ) ) ; +#775 = FACE_OUTER_BOUND ( 'NONE', #29670, .T. ) ; +#776 = CARTESIAN_POINT ( 'NONE', ( 36.19056359025920955, 192.0351720573459886, 106.4168301014839955 ) ) ; +#777 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#778 = DIRECTION ( 'NONE', ( -0.0005884949961246307591, 0.2249510543439059429, -0.9743698870671264611 ) ) ; +#779 = ORIENTED_EDGE ( 'NONE', *, *, #37023, .T. ) ; +#780 = ORIENTED_EDGE ( 'NONE', *, *, #13425, .T. ) ; +#781 = CIRCLE ( 'NONE', #30831, 2.000000000000011546 ) ; +#782 = PLANE ( 'NONE', #14722 ) ; +#783 = CIRCLE ( 'NONE', #15190, 47.50000000000481037 ) ; +#784 = CARTESIAN_POINT ( 'NONE', ( 35.91066480312174036, 115.4548871365115161, 87.24609515033561991 ) ) ; +#785 = DIRECTION ( 'NONE', ( -0.0005884949961257719903, 0.2249510543439054711, -0.9743698870671265722 ) ) ; +#786 = ORIENTED_EDGE ( 'NONE', *, *, #24400, .F. ) ; +#787 = DIRECTION ( 'NONE', ( 0.9914448496661263377, 0.1271951663094869900, 0.02930016617724658101 ) ) ; +#788 = ORIENTED_EDGE ( 'NONE', *, *, #5292, .F. ) ; +#789 = FACE_OUTER_BOUND ( 'NONE', #21421, .T. ) ; +#790 = FACE_OUTER_BOUND ( 'NONE', #32863, .T. ) ; +#791 = FACE_OUTER_BOUND ( 'NONE', #38364, .T. ) ; +#792 = LINE ( 'NONE', #16138, #25333 ) ; +#793 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; +#794 = CARTESIAN_POINT ( 'NONE', ( -30.06407215524082943, 177.1126099298436714, 103.6397089757105192 ) ) ; +#795 = CARTESIAN_POINT ( 'NONE', ( 44.93984957629947274, 145.3877245808612031, 285.0133094889154677 ) ) ; +#796 = VERTEX_POINT ( 'NONE', #27783 ) ; +#797 = CARTESIAN_POINT ( 'NONE', ( 15.50147165697079465, 137.9484461010407870, 94.05722786790197176 ) ) ; +#798 = CARTESIAN_POINT ( 'NONE', ( -30.07079256068832152, 177.3114379493538308, 101.0139105263539818 ) ) ; +#799 = CARTESIAN_POINT ( 'NONE', ( 6.034204648359921208, 177.7921235470974466, 100.6958268401488539 ) ) ; +#800 = ORIENTED_EDGE ( 'NONE', *, *, #36871, .F. ) ; +#801 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#802 = VERTEX_POINT ( 'NONE', #17934 ) ; +#803 = ORIENTED_EDGE ( 'NONE', *, *, #23864, .F. ) ; +#804 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#805 = ORIENTED_EDGE ( 'NONE', *, *, #34404, .F. ) ; +#806 = AXIS2_PLACEMENT_3D ( 'NONE', #907, #12794, #34828 ) ; +#807 = EDGE_CURVE ( 'NONE', #5625, #8723, #8793, .T. ) ; +#808 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6625, #35021, #7232, #9723 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.009024888469274735397 ), + .UNSPECIFIED. ) ; +#809 = CARTESIAN_POINT ( 'NONE', ( 13.85658554618334293, 150.4134353313125985, 179.9607612785380581 ) ) ; +#810 = DIRECTION ( 'NONE', ( -0.0005559617639789404386, 0.3907311284894095516, -0.9205046855589108512 ) ) ; +#811 = EDGE_CURVE ( 'NONE', #35987, #5120, #12421, .T. ) ; +#812 = ADVANCED_FACE ( 'NONE', ( #25116 ), #35503, .F. ) ; +#813 = CARTESIAN_POINT ( 'NONE', ( -16.78108589029219644, 152.4450255530118739, 181.9531753362896325 ) ) ; +#814 = EDGE_CURVE ( 'NONE', #4354, #18466, #16429, .T. ) ; +#815 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 0.000000000000000000 ) ) ; +#816 = EDGE_CURVE ( 'NONE', #1746, #24020, #6276, .T. ) ; +#817 = LINE ( 'NONE', #23106, #37997 ) ; +#818 = CARTESIAN_POINT ( 'NONE', ( -2.458395782143000030, 209.7031701907000070, 73.44000010378999832 ) ) ; +#819 = CARTESIAN_POINT ( 'NONE', ( 38.30818804999999827, 118.7293481547999932, 90.10350194488999875 ) ) ; +#820 = ORIENTED_EDGE ( 'NONE', *, *, #31967, .F. ) ; +#821 = CARTESIAN_POINT ( 'NONE', ( -12.63662704360879729, 174.7913534257970696, 102.5800794996181367 ) ) ; +#822 = LINE ( 'NONE', #34545, #16252 ) ; +#823 = DIRECTION ( 'NONE', ( 4.799828776013770619E-10, -0.9743700559000059158, -0.2249510928300180457 ) ) ; +#825 = ORIENTED_EDGE ( 'NONE', *, *, #583, .F. ) ; +#824 = CARTESIAN_POINT ( 'NONE', ( -20.50031106545476689, 193.6217541318450799, 103.8231728181809785 ) ) ; +#826 = ORIENTED_EDGE ( 'NONE', *, *, #22963, .T. ) ; +#827 = ORIENTED_EDGE ( 'NONE', *, *, #12133, .T. ) ; +#828 = CARTESIAN_POINT ( 'NONE', ( 25.86791385122951681, 191.4731423800313337, 104.0134104725774193 ) ) ; +#829 = CARTESIAN_POINT ( 'NONE', ( 21.57097971548348880, 115.4710243950989224, 87.25475596080617890 ) ) ; +#830 = CARTESIAN_POINT ( 'NONE', ( 5.666417568496214585, 124.0425428568022710, 91.06625163005953993 ) ) ; +#831 = AXIS2_PLACEMENT_3D ( 'NONE', #17862, #30364, #91 ) ; +#832 = ORIENTED_EDGE ( 'NONE', *, *, #15867, .F. ) ; +#833 = CYLINDRICAL_SURFACE ( 'NONE', #36116, 5.000000000000007994 ) ; +#834 = AXIS2_PLACEMENT_3D ( 'NONE', #11891, #26826, #8827 ) ; +#835 = CARTESIAN_POINT ( 'NONE', ( -38.36863212317000205, 118.8178900763000030, 90.09766773322999711 ) ) ; +#836 = CARTESIAN_POINT ( 'NONE', ( -38.37945905963000115, 118.8393537648999967, 87.72095146696000256 ) ) ; +#837 = FACE_OUTER_BOUND ( 'NONE', #10537, .T. ) ; +#838 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971557076 ) ) ; +#839 = ORIENTED_EDGE ( 'NONE', *, *, #34963, .F. ) ; +#840 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; +#841 = ORIENTED_EDGE ( 'NONE', *, *, #5013, .T. ) ; +#842 = FACE_OUTER_BOUND ( 'NONE', #38123, .T. ) ; +#843 = FACE_OUTER_BOUND ( 'NONE', #732, .T. ) ; +#844 = VERTEX_POINT ( 'NONE', #15684 ) ; +#845 = CARTESIAN_POINT ( 'NONE', ( -37.62305393521922525, 212.3970732061812896, 73.58122755549422322 ) ) ; +#846 = DIRECTION ( 'NONE', ( 0.0005884949961292186690, -0.2249510543439060262, 0.9743698870671263501 ) ) ; +#847 = DIRECTION ( 'NONE', ( 0.7933535325932937754, -0.5931614258681804364, -0.1369295263402622864 ) ) ; +#848 = EDGE_CURVE ( 'NONE', #38719, #14771, #30439, .T. ) ; +#849 = EDGE_CURVE ( 'NONE', #25128, #21097, #31129, .T. ) ; +#850 = ORIENTED_EDGE ( 'NONE', *, *, #16275, .F. ) ; +#851 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#852 = LINE ( 'NONE', #7191, #10889 ) ; +#853 = VERTEX_POINT ( 'NONE', #15297 ) ; +#854 = EDGE_CURVE ( 'NONE', #25248, #12222, #13478, .T. ) ; +#855 = FACE_OUTER_BOUND ( 'NONE', #40097, .T. ) ; +#856 = PLANE ( 'NONE', #15052 ) ; +#857 = VECTOR ( 'NONE', #17204, 1000.000000000000000 ) ; +#858 = EDGE_CURVE ( 'NONE', #14434, #13079, #8104, .T. ) ; +#859 = ORIENTED_EDGE ( 'NONE', *, *, #24577, .T. ) ; +#860 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25539, #38388, #3827, #9993 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#861 = CONICAL_SURFACE ( 'NONE', #34165, 4.999999999930255790, 0.7853981633830142695 ) ; +#862 = CARTESIAN_POINT ( 'NONE', ( 40.54493956983929337, 220.4002260892000038, 73.03401595479815001 ) ) ; +#863 = EDGE_CURVE ( 'NONE', #23346, #11066, #33681, .T. ) ; +#864 = AXIS2_PLACEMENT_3D ( 'NONE', #14431, #36912, #34036 ) ; +#865 = ORIENTED_EDGE ( 'NONE', *, *, #34601, .T. ) ; +#866 = ORIENTED_EDGE ( 'NONE', *, *, #9089, .F. ) ; +#867 = CARTESIAN_POINT ( 'NONE', ( 26.00511610745047264, 120.0889745669351782, 90.43625461076925376 ) ) ; +#868 = DIRECTION ( 'NONE', ( -0.0005884949961218496721, 0.2249510543439063315, -0.9743698870671264611 ) ) ; +#870 = CARTESIAN_POINT ( 'NONE', ( -8.192072165922381188, 151.6568654278863733, 94.67061599110682835 ) ) ; +#869 = CARTESIAN_POINT ( 'NONE', ( 36.06386299210247870, 192.3813622508035905, 104.3665697773190715 ) ) ; +#871 = ORIENTED_EDGE ( 'NONE', *, *, #33176, .T. ) ; +#872 = DIRECTION ( 'NONE', ( -0.0006540525280306910220, 0.2250342908583061741, -0.9743506248539022252 ) ) ; +#873 = CARTESIAN_POINT ( 'NONE', ( 39.01961099979754266, 175.8196705488005023, 136.1591049921323986 ) ) ; +#874 = EDGE_LOOP ( 'NONE', ( #4772, #37592, #29615, #33870 ) ) ; +#875 = ORIENTED_EDGE ( 'NONE', *, *, #34263, .F. ) ; +#876 = DIRECTION ( 'NONE', ( 0.7066518122933521662, -3.184449828924648418E-15, -0.7075614575303836862 ) ) ; +#877 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23234, #35878, #29974, #27133, #4411, #20553, #5017, #32631, #16869, #17480, #26310, #26714, #35666, #14439 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000590639, 0.3750000000000573985, 0.5000000000000557332, 0.6250000000000540679, 0.6875000000000532907, 0.7500000000000525135, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#878 = LINE ( 'NONE', #28908, #23317 ) ; +#879 = CARTESIAN_POINT ( 'NONE', ( -2.557262702658000375, 190.9632190922000063, 106.4318435757000003 ) ) ; +#880 = EDGE_LOOP ( 'NONE', ( #11826, #12243, #12769, #25971 ) ) ; +#881 = VECTOR ( 'NONE', #29482, 1000.000000000000000 ) ; +#882 = CIRCLE ( 'NONE', #3502, 8.499999999972331466 ) ; +#883 = ORIENTED_EDGE ( 'NONE', *, *, #24759, .F. ) ; +#884 = ORIENTED_EDGE ( 'NONE', *, *, #19167, .T. ) ; +#885 = DIRECTION ( 'NONE', ( 0.0006039748319395907457, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#886 = FACE_OUTER_BOUND ( 'NONE', #18879, .T. ) ; +#887 = AXIS2_PLACEMENT_3D ( 'NONE', #19343, #35459, #38165 ) ; +#888 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#889 = ORIENTED_EDGE ( 'NONE', *, *, #27357, .T. ) ; +#890 = CARTESIAN_POINT ( 'NONE', ( -20.45570291159294030, 122.4774857238997043, 183.8048636542243059 ) ) ; +#891 = ORIENTED_EDGE ( 'NONE', *, *, #13113, .F. ) ; +#893 = ADVANCED_FACE ( 'NONE', ( #5689 ), #36969, .F. ) ; +#892 = CARTESIAN_POINT ( 'NONE', ( -37.13539223219807894, 116.7950545578066794, 89.73131408846597878 ) ) ; +#894 = ADVANCED_FACE ( 'NONE', ( #5884 ), #18339, .T. ) ; +#895 = EDGE_CURVE ( 'NONE', #1429, #37610, #27074, .T. ) ; +#896 = EDGE_LOOP ( 'NONE', ( #16759, #29679, #37111, #39920 ) ) ; +#897 = FACE_OUTER_BOUND ( 'NONE', #16698, .T. ) ; +#898 = EDGE_CURVE ( 'NONE', #7054, #22555, #13333, .T. ) ; +#899 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555688 ) ) ; +#900 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7965, #11047, #11444, #36588 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#901 = VERTEX_POINT ( 'NONE', #28969 ) ; +#902 = CARTESIAN_POINT ( 'NONE', ( -30.24155573443220746, 159.9839851041407996, 186.8751258489507165 ) ) ; +#903 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425149360, 185.2313152530017248, 105.5040075785468048 ) ) ; +#904 = CARTESIAN_POINT ( 'NONE', ( -22.78222448785095011, 163.9594641391059042, 100.5986201911018298 ) ) ; +#905 = ADVANCED_FACE ( 'NONE', ( #9971 ), #16680, .F. ) ; +#906 = VERTEX_POINT ( 'NONE', #38366 ) ; +#907 = CARTESIAN_POINT ( 'NONE', ( 25.50773672857076235, 191.9759150222000130, 101.9060413065578530 ) ) ; +#908 = ORIENTED_EDGE ( 'NONE', *, *, #18787, .T. ) ; +#909 = LINE ( 'NONE', #1111, #34236 ) ; +#910 = CARTESIAN_POINT ( 'NONE', ( -43.16067970895235106, 137.0136042933273472, 338.0369414682852494 ) ) ; +#911 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319356122658 ) ) ; +#912 = EDGE_CURVE ( 'NONE', #16019, #21171, #35273, .T. ) ; +#913 = AXIS2_PLACEMENT_3D ( 'NONE', #25178, #804, #3460 ) ; +#914 = AXIS2_PLACEMENT_3D ( 'NONE', #34086, #27985, #7277 ) ; +#915 = CARTESIAN_POINT ( 'NONE', ( 0.06247583203485999881, 188.8062377635999951, 103.4410994233000025 ) ) ; +#916 = ORIENTED_EDGE ( 'NONE', *, *, #15721, .T. ) ; +#917 = DIRECTION ( 'NONE', ( -0.0006039748319392586546, -1.665208279866278382E-14, -0.9999998176071847045 ) ) ; +#918 = VECTOR ( 'NONE', #35489, 1000.000000000000114 ) ; +#919 = CARTESIAN_POINT ( 'NONE', ( -35.82625367234000890, 112.3689870599999949, 89.91154723993000175 ) ) ; +#920 = ORIENTED_EDGE ( 'NONE', *, *, #5292, .T. ) ; +#921 = VERTEX_POINT ( 'NONE', #19743 ) ; +#922 = CARTESIAN_POINT ( 'NONE', ( 11.82534515883345527, 158.5331529580515735, 96.24604232593732434 ) ) ; +#923 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#924 = CARTESIAN_POINT ( 'NONE', ( 23.69085248748276840, 130.8248087875101362, 90.01295625239652054 ) ) ; +#925 = CARTESIAN_POINT ( 'NONE', ( 3.064236136099508290, 190.8512031035150471, 106.7914583158460573 ) ) ; +#926 = ORIENTED_EDGE ( 'NONE', *, *, #39072, .F. ) ; +#927 = LINE ( 'NONE', #38154, #22617 ) ; +#928 = ORIENTED_EDGE ( 'NONE', *, *, #16160, .F. ) ; +#929 = VERTEX_POINT ( 'NONE', #29180 ) ; +#930 = ORIENTED_EDGE ( 'NONE', *, *, #19926, .F. ) ; +#931 = CARTESIAN_POINT ( 'NONE', ( -6.035163149060575272, 177.6449902918727162, 100.7936898218632393 ) ) ; +#932 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#933 = CARTESIAN_POINT ( 'NONE', ( 19.24557514809682957, 124.8328511027356456, 177.9395134564782381 ) ) ; +#934 = ORIENTED_EDGE ( 'NONE', *, *, #31296, .F. ) ; +#935 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#936 = DIRECTION ( 'NONE', ( 0.7856637144487862434, -0.6186538028643614462, 0.000000000000000000 ) ) ; +#937 = CARTESIAN_POINT ( 'NONE', ( -34.28801115370752228, 89.15625349133107136, 280.9732277762227000 ) ) ; +#938 = CARTESIAN_POINT ( 'NONE', ( -43.86701283492332948, 121.7474466771614914, 90.64158096768842654 ) ) ; +#939 = AXIS2_PLACEMENT_3D ( 'NONE', #35478, #37983, #9983 ) ; +#940 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971545141 ) ) ; +#941 = ORIENTED_EDGE ( 'NONE', *, *, #27660, .F. ) ; +#942 = CARTESIAN_POINT ( 'NONE', ( 28.24084398341999957, 125.5722885917000013, 89.14071976869000480 ) ) ; +#943 = CIRCLE ( 'NONE', #40138, 6.499999999990746957 ) ; +#944 = VECTOR ( 'NONE', #12893, 1000.000000000000114 ) ; +#945 = DIRECTION ( 'NONE', ( -0.6773442687123379935, -0.7356661890032381024, 0.000000000000000000 ) ) ; +#946 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#947 = EDGE_CURVE ( 'NONE', #35304, #20063, #16576, .T. ) ; +#948 = AXIS2_PLACEMENT_3D ( 'NONE', #27763, #31014, #3186 ) ; +#949 = ADVANCED_FACE ( 'NONE', ( #1151 ), #10373, .T. ) ; +#950 = FACE_OUTER_BOUND ( 'NONE', #24854, .T. ) ; +#951 = CARTESIAN_POINT ( 'NONE', ( 3.533886511882771142, 137.1968222802559012, 91.32516919190832994 ) ) ; +#952 = ORIENTED_EDGE ( 'NONE', *, *, #14768, .F. ) ; +#953 = CARTESIAN_POINT ( 'NONE', ( 45.16550232355236005, 181.2351781714976937, 101.8091835899543440 ) ) ; +#954 = CARTESIAN_POINT ( 'NONE', ( 0.7291628089563826354, 189.0068906503063886, 103.6850538576102139 ) ) ; +#955 = CARTESIAN_POINT ( 'NONE', ( -1.692498771449036932, 188.7201307904135774, 106.3023338887167171 ) ) ; +#956 = CARTESIAN_POINT ( 'NONE', ( 3.334663580956577000, 183.4889149388049816, 104.9205407821583123 ) ) ; +#957 = ORIENTED_EDGE ( 'NONE', *, *, #36269, .F. ) ; +#958 = CARTESIAN_POINT ( 'NONE', ( -26.12986736251000153, 191.7563640120999935, 103.7886991103000014 ) ) ; +#959 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8128, #26744, #14271, #35699, #11003, #22874, #17102, #976, #17304, #35301 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000002350897, 0.3750000000003276823, 0.4375000000003435585, 0.5000000000003593792, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#960 = CARTESIAN_POINT ( 'NONE', ( 24.01770307888959621, 118.3486789263952517, 189.6358675532988229 ) ) ; +#961 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#962 = DIRECTION ( 'NONE', ( -0.9914447019871281963, 0.1270494721559694284, 0.02993049492647828144 ) ) ; +#963 = EDGE_LOOP ( 'NONE', ( #29866, #34587, #739, #1128 ) ) ; +#964 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #20966, #17256 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#965 = CIRCLE ( 'NONE', #25804, 4.999999999999990230 ) ; +#966 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; +#967 = CARTESIAN_POINT ( 'NONE', ( -45.39258384773165034, 124.3433029335535878, 88.43811771986804615 ) ) ; +#968 = VECTOR ( 'NONE', #4303, 1000.000000000000114 ) ; +#969 = CIRCLE ( 'NONE', #3588, 6.000000588931215795 ) ; +#970 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319387907129 ) ) ; +#971 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36827, #5753, #17596, #14560 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#972 = FACE_BOUND ( 'NONE', #9002, .T. ) ; +#973 = DIRECTION ( 'NONE', ( 0.0002393071182782299474, 0.2252352986010034697, -0.9743043687658493601 ) ) ; +#974 = CARTESIAN_POINT ( 'NONE', ( -13.46970022169197989, 176.3366686086323227, 152.9217692962739079 ) ) ; +#975 = VECTOR ( 'NONE', #27436, 999.9999999999998863 ) ; +#976 = CARTESIAN_POINT ( 'NONE', ( -5.667187237236853470, 130.2293307052626687, 92.64134285576068351 ) ) ; +#977 = CARTESIAN_POINT ( 'NONE', ( 13.50156854163491005, 188.0558794582128996, 103.3088726825072001 ) ) ; +#978 = VERTEX_POINT ( 'NONE', #15879 ) ; +#979 = CARTESIAN_POINT ( 'NONE', ( -2.689544897498777232, 209.6680443742787077, 75.89346469953468954 ) ) ; +#980 = CARTESIAN_POINT ( 'NONE', ( 18.98507725696123671, 148.2474724526778687, 184.5421123104517278 ) ) ; +#981 = DIRECTION ( 'NONE', ( 0.6087611427424929333, 0.7731004630501246977, 0.1781166615410725018 ) ) ; +#982 = VERTEX_POINT ( 'NONE', #10176 ) ; +#983 = CARTESIAN_POINT ( 'NONE', ( 26.87666215091000055, 135.1099595320999924, 91.08585649840999565 ) ) ; +#984 = ORIENTED_EDGE ( 'NONE', *, *, #30565, .T. ) ; +#985 = DIRECTION ( 'NONE', ( 0.0006039748319386881474, 1.110222822128452674E-14, 0.9999998176071845934 ) ) ; +#986 = DIRECTION ( 'NONE', ( 0.0005884951729871207987, -0.2249510544218079611, 0.9743698870490344888 ) ) ; +#987 = CARTESIAN_POINT ( 'NONE', ( 25.99875258092378161, 117.7155965479965687, 87.25208169694612081 ) ) ; +#988 = EDGE_LOOP ( 'NONE', ( #17595, #16179, #35857, #39446, #26286, #13976, #8313, #4701, #28650, #18373, #38755, #31568 ) ) ; +#989 = CARTESIAN_POINT ( 'NONE', ( -14.42373142009429365, 182.0239085154369150, 104.5930275125517852 ) ) ; +#990 = CARTESIAN_POINT ( 'NONE', ( 24.50320502934976830, 213.7111511448713088, 76.04368778216444014 ) ) ; +#991 = ADVANCED_FACE ( 'NONE', ( #6674 ), #19549, .F. ) ; +#992 = ADVANCED_FACE ( 'NONE', ( #542 ), #13629, .T. ) ; +#993 = CARTESIAN_POINT ( 'NONE', ( -12.63680864157205086, 130.5439919522491721, 90.20625573009445475 ) ) ; +#994 = CARTESIAN_POINT ( 'NONE', ( -38.38796632900000105, 191.2261826337999935, 104.0807279818999973 ) ) ; +#995 = VECTOR ( 'NONE', #25432, 1000.000000000000000 ) ; +#996 = ORIENTED_EDGE ( 'NONE', *, *, #38160, .F. ) ; +#997 = DIRECTION ( 'NONE', ( 0.0005884949961162573573, -0.2249510543439059151, 0.9743698870671263501 ) ) ; +#998 = CARTESIAN_POINT ( 'NONE', ( 42.78873758771006663, 120.8665316288775102, 92.29373204621693105 ) ) ; +#999 = CONICAL_SURFACE ( 'NONE', #40172, 22.50000000000898837, 0.7853981633973132759 ) ; +#1000 = CARTESIAN_POINT ( 'NONE', ( -40.45487666593005827, 220.4002261020000049, 76.08293836150286893 ) ) ; +#1001 = AXIS2_PLACEMENT_3D ( 'NONE', #6931, #28422, #31898 ) ; +#1002 = CARTESIAN_POINT ( 'NONE', ( -36.44734101958000849, 191.1363885723000067, 103.6637415026000042 ) ) ; +#1003 = ORIENTED_EDGE ( 'NONE', *, *, #18303, .F. ) ; +#1004 = AXIS2_PLACEMENT_3D ( 'NONE', #18866, #31367, #25245 ) ; +#1005 = ORIENTED_EDGE ( 'NONE', *, *, #34200, .T. ) ; +#1006 = DIRECTION ( 'NONE', ( -2.081668171217371032E-15, 0.9743700557921590732, 0.2249510932971540700 ) ) ; +#1007 = LINE ( 'NONE', #24331, #24282 ) ; +#1008 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8362, #16921, #14290, #11025 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1009 = CARTESIAN_POINT ( 'NONE', ( 14.07223717073995672, 122.5303360716178105, 176.5193168095456713 ) ) ; +#1010 = CARTESIAN_POINT ( 'NONE', ( 32.56862209515505668, 137.3592834573111929, 91.34514006402139330 ) ) ; +#1011 = CARTESIAN_POINT ( 'NONE', ( -12.63649281426050663, 129.9703308633319807, 92.23232912533514138 ) ) ; +#1012 = CARTESIAN_POINT ( 'NONE', ( 25.93424969579000106, 190.6798797952000086, 106.6095218724999967 ) ) ; +#1013 = EDGE_CURVE ( 'NONE', #28881, #10321, #31673, .T. ) ; +#1014 = CARTESIAN_POINT ( 'NONE', ( 38.16410284748000237, 119.4654676515000062, 87.14306831961999933 ) ) ; +#1015 = CARTESIAN_POINT ( 'NONE', ( -3.046821091270000004, 209.4711209118999875, 72.92944012904000317 ) ) ; +#1016 = CARTESIAN_POINT ( 'NONE', ( 38.15391655548999950, 118.9232721861999948, 90.39751939907000633 ) ) ; +#1017 = ORIENTED_EDGE ( 'NONE', *, *, #40315, .F. ) ; +#1018 = AXIS2_PLACEMENT_3D ( 'NONE', #24305, #5258, #36747 ) ; +#1019 = DIRECTION ( 'NONE', ( -0.1843855713908465477, -0.08049128666858569592, 0.9795525069302342125 ) ) ; +#1020 = DIRECTION ( 'NONE', ( 1.156372029607614051E-16, 0.9743043966640312359, 0.2252353050503803356 ) ) ; +#1021 = VERTEX_POINT ( 'NONE', #12832 ) ; +#1022 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20394, #27176, #26965, #17521 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1023 = VERTEX_POINT ( 'NONE', #25922 ) ; +#1024 = CARTESIAN_POINT ( 'NONE', ( 25.66576336802040359, 118.8155664474191724, 87.58560832463771817 ) ) ; +#1025 = VECTOR ( 'NONE', #1639, 1000.000000000000114 ) ; +#1026 = EDGE_CURVE ( 'NONE', #39304, #1429, #6173, .T. ) ; +#1027 = DIRECTION ( 'NONE', ( 0.5968393679912002980, 0.8023607473050164973, 0.000000000000000000 ) ) ; +#1028 = CARTESIAN_POINT ( 'NONE', ( -6.831231556254691917, 155.4618032185357492, 100.6797548176731993 ) ) ; +#1029 = VECTOR ( 'NONE', #30178, 1000.000000000000000 ) ; +#1030 = EDGE_LOOP ( 'NONE', ( #33987, #10661, #36469, #4591 ) ) ; +#1031 = CARTESIAN_POINT ( 'NONE', ( -14.76234657499968783, 188.0332833685391734, 103.0727436135631194 ) ) ; +#1032 = EDGE_CURVE ( 'NONE', #13945, #16868, #22247, .T. ) ; +#1033 = CARTESIAN_POINT ( 'NONE', ( -38.72644908288000209, 118.7070105194000007, 89.71289965706000658 ) ) ; +#1034 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 135.6474414654788347, 90.98047230848234790 ) ) ; +#1035 = LINE ( 'NONE', #7370, #24335 ) ; +#1036 = ORIENTED_EDGE ( 'NONE', *, *, #17518, .T. ) ; +#1037 = CARTESIAN_POINT ( 'NONE', ( 19.70863784699480448, 149.1560517737245561, 182.9541186021026817 ) ) ; +#1038 = ORIENTED_EDGE ( 'NONE', *, *, #30182, .T. ) ; +#1039 = CARTESIAN_POINT ( 'NONE', ( 31.79572357098799174, 220.4002260771000294, 76.03930080927051449 ) ) ; +#1040 = CARTESIAN_POINT ( 'NONE', ( -25.50006284340070906, 118.1130153187805689, 89.78316558933853742 ) ) ; +#1041 = EDGE_CURVE ( 'NONE', #23754, #39643, #27745, .T. ) ; +#1042 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10861, #38439, #10653, #13315, #35755, #14130, #10260, #11057, #26394, #7765, #16956 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999876765, 0.3749999999999565348, 0.4374999999999233946, 0.4687499999999067968, 0.4999999999998901989, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1043 = EDGE_CURVE ( 'NONE', #35217, #8772, #31851, .T. ) ; +#1044 = FACE_OUTER_BOUND ( 'NONE', #4555, .T. ) ; +#1045 = CARTESIAN_POINT ( 'NONE', ( 17.30417074659255761, 152.9391053872499526, 180.9092052391793004 ) ) ; +#1046 = DIRECTION ( 'NONE', ( -0.0005884949961227338390, 0.2249510543439056653, -0.9743698870671265722 ) ) ; +#1047 = EDGE_CURVE ( 'NONE', #27481, #31227, #27695, .T. ) ; +#1048 = ORIENTED_EDGE ( 'NONE', *, *, #21134, .T. ) ; +#1049 = CARTESIAN_POINT ( 'NONE', ( -0.6157399968410001145, 188.8694429141000057, 103.5223704861000158 ) ) ; +#1050 = ADVANCED_FACE ( 'NONE', ( #17070 ), #35525, .F. ) ; +#1051 = DIRECTION ( 'NONE', ( -0.6319268263561552690, -0.7750280550608716901, 0.000000000000000000 ) ) ; +#1052 = CARTESIAN_POINT ( 'NONE', ( 32.66389061773956826, 141.7118122376935219, 282.5421777876526335 ) ) ; +#1053 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #23744, #1865 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1054 = ORIENTED_EDGE ( 'NONE', *, *, #10117, .T. ) ; +#1055 = CARTESIAN_POINT ( 'NONE', ( 24.00841289415539848, 118.3368870854502717, 189.6331392867438979 ) ) ; +#1056 = CARTESIAN_POINT ( 'NONE', ( -24.52910917930924484, 213.7107200543937608, 76.07243698009752109 ) ) ; +#1057 = AXIS2_PLACEMENT_3D ( 'NONE', #24137, #5096, #11053 ) ; +#1058 = ORIENTED_EDGE ( 'NONE', *, *, #18855, .T. ) ; +#1059 = DIRECTION ( 'NONE', ( 0.5988683521957600675, -0.8008474865655350605, 0.000000000000000000 ) ) ; +#1060 = CIRCLE ( 'NONE', #26563, 4.999999999999990230 ) ; +#1061 = ORIENTED_EDGE ( 'NONE', *, *, #38829, .T. ) ; +#1062 = CARTESIAN_POINT ( 'NONE', ( 22.50176470574832877, 126.7597147172538570, 91.98302937056051576 ) ) ; +#1063 = CARTESIAN_POINT ( 'NONE', ( 20.50029383489984980, 127.3219018132126479, 89.54826866284827247 ) ) ; +#1064 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218858604, 138.4701267047078659, 297.5295786860737053 ) ) ; +#1065 = EDGE_CURVE ( 'NONE', #30696, #29413, #13049, .T. ) ; +#1066 = VERTEX_POINT ( 'NONE', #17684 ) ; +#1067 = ORIENTED_EDGE ( 'NONE', *, *, #30273, .T. ) ; +#1068 = CARTESIAN_POINT ( 'NONE', ( 26.00304017342149621, 120.1091259005509926, 90.45343346466181345 ) ) ; +#1069 = LINE ( 'NONE', #31360, #32580 ) ; +#1071 = CARTESIAN_POINT ( 'NONE', ( -37.29404342678407858, 118.1039676111839754, 123.2219287228025735 ) ) ; +#1070 = CARTESIAN_POINT ( 'NONE', ( 20.48158208153664361, 208.7639276185600750, 75.71837906042235034 ) ) ; +#1072 = ORIENTED_EDGE ( 'NONE', *, *, #3432, .T. ) ; +#1073 = CARTESIAN_POINT ( 'NONE', ( -2.937322199011638268, 191.1124755427409809, 103.7764892006471058 ) ) ; +#1074 = EDGE_CURVE ( 'NONE', #7652, #39292, #10973, .T. ) ; +#1075 = VECTOR ( 'NONE', #11856, 1000.000000000000114 ) ; +#1076 = FACE_OUTER_BOUND ( 'NONE', #19236, .T. ) ; +#1077 = ORIENTED_EDGE ( 'NONE', *, *, #1641, .T. ) ; +#1078 = CIRCLE ( 'NONE', #9592, 5.000000000000007994 ) ; +#1079 = CIRCLE ( 'NONE', #4344, 7.499999999930377470 ) ; +#1080 = ORIENTED_EDGE ( 'NONE', *, *, #25991, .F. ) ; +#1081 = CARTESIAN_POINT ( 'NONE', ( 38.92749941854999918, 118.9318509131999946, 89.81972100347999799 ) ) ; +#1082 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971548471 ) ) ; +#1083 = EDGE_CURVE ( 'NONE', #34462, #12345, #14026, .T. ) ; +#1084 = DIRECTION ( 'NONE', ( -0.0005884949961248158324, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#1085 = CARTESIAN_POINT ( 'NONE', ( 5.669618588597917785, 187.4181796362739476, 105.6527527589996254 ) ) ; +#1086 = CARTESIAN_POINT ( 'NONE', ( -2.557265678393000119, 190.9742781186000116, 106.4347167855000009 ) ) ; +#1087 = ORIENTED_EDGE ( 'NONE', *, *, #19759, .T. ) ; +#1088 = VECTOR ( 'NONE', #12974, 1000.000000000000227 ) ; +#1089 = EDGE_CURVE ( 'NONE', #37866, #2346, #11401, .T. ) ; +#1090 = ORIENTED_EDGE ( 'NONE', *, *, #11398, .F. ) ; +#1091 = ORIENTED_EDGE ( 'NONE', *, *, #30837, .T. ) ; +#1092 = CYLINDRICAL_SURFACE ( 'NONE', #33710, 6.000000000000001776 ) ; +#1093 = CARTESIAN_POINT ( 'NONE', ( 20.00153785277168339, 160.0757089691884971, 99.67622395206049646 ) ) ; +#1094 = FACE_OUTER_BOUND ( 'NONE', #8198, .T. ) ; +#1095 = ORIENTED_EDGE ( 'NONE', *, *, #21134, .F. ) ; +#1096 = EDGE_CURVE ( 'NONE', #37155, #19698, #19870, .T. ) ; +#1097 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#1098 = VERTEX_POINT ( 'NONE', #32635 ) ; +#1099 = CARTESIAN_POINT ( 'NONE', ( 20.16688071201305732, 174.4873282160424139, 100.0954865458536887 ) ) ; +#1100 = ORIENTED_EDGE ( 'NONE', *, *, #7043, .F. ) ; +#1101 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1102 = CARTESIAN_POINT ( 'NONE', ( -23.36052865740974838, 181.6105241605473282, 104.1608863659234885 ) ) ; +#1103 = ORIENTED_EDGE ( 'NONE', *, *, #12151, .F. ) ; +#1104 = CARTESIAN_POINT ( 'NONE', ( 25.02588108245754484, 153.6585318740197010, 181.6250235156477402 ) ) ; +#1105 = DIRECTION ( 'NONE', ( 0.0005884949961231158034, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1106 = LINE ( 'NONE', #19702, #11746 ) ; +#1107 = DIRECTION ( 'NONE', ( 0.0005884949961256949035, -0.2249510543439057209, 0.9743698870671265722 ) ) ; +#1108 = AXIS2_PLACEMENT_3D ( 'NONE', #4558, #693, #28716 ) ; +#1109 = EDGE_LOOP ( 'NONE', ( #17306, #7928, #21301, #122 ) ) ; +#1110 = ORIENTED_EDGE ( 'NONE', *, *, #39682, .T. ) ; +#1111 = CARTESIAN_POINT ( 'NONE', ( -3.631498268106390537, 112.1323247865684607, 152.4707203835916687 ) ) ; +#1112 = CARTESIAN_POINT ( 'NONE', ( 20.06100899634295587, 211.8492643960386488, 73.04638773564751375 ) ) ; +#1113 = AXIS2_PLACEMENT_3D ( 'NONE', #12392, #24895, #3574 ) ; +#1114 = CARTESIAN_POINT ( 'NONE', ( 19.39305163340773674, 125.4565983441243162, 175.2227004938931429 ) ) ; +#1115 = CARTESIAN_POINT ( 'NONE', ( -25.49166336760104912, 196.1181869298516744, 103.6951339797178804 ) ) ; +#1116 = VERTEX_POINT ( 'NONE', #1551 ) ; +#1117 = CARTESIAN_POINT ( 'NONE', ( -39.71549914202294218, 121.2606343799488826, 123.5760462896040934 ) ) ; +#1118 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29860, #39241, #36176, #8179, #39438, #2462, #20644, #17560, #21063, #33106, #20849, #27429 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2492599143486034785, 0.4985198286972069570, 0.7477797430458104078, 0.8724097002201126605, 0.9970396573944148022 ), + .UNSPECIFIED. ) ; +#1119 = CARTESIAN_POINT ( 'NONE', ( -38.38756031713000283, 118.2000217570000018, 89.55403246576000242 ) ) ; +#1120 = VERTEX_POINT ( 'NONE', #17482 ) ; +#1121 = ORIENTED_EDGE ( 'NONE', *, *, #32048, .F. ) ; +#1122 = EDGE_CURVE ( 'NONE', #35790, #8868, #8685, .T. ) ; +#1123 = CARTESIAN_POINT ( 'NONE', ( 8.046776639317595681, 161.2737771581006996, 96.88104755365348808 ) ) ; +#1124 = ADVANCED_FACE ( 'NONE', ( #14854 ), #2280, .F. ) ; +#1125 = CARTESIAN_POINT ( 'NONE', ( -27.65251932003710422, 124.5980834872316194, 88.43535643343921038 ) ) ; +#1126 = EDGE_CURVE ( 'NONE', #14712, #19860, #36433, .T. ) ; +#1127 = CARTESIAN_POINT ( 'NONE', ( -13.49986562384761690, 124.0034607844170722, 91.10007752827642946 ) ) ; +#1128 = ORIENTED_EDGE ( 'NONE', *, *, #13655, .F. ) ; +#1129 = ADVANCED_FACE ( 'NONE', ( #28090 ), #23169, .F. ) ; +#1130 = ORIENTED_EDGE ( 'NONE', *, *, #30388, .F. ) ; +#1131 = CARTESIAN_POINT ( 'NONE', ( 13.50000077932746834, 151.9719590241109870, 94.73025978658517943 ) ) ; +#1132 = VERTEX_POINT ( 'NONE', #38068 ) ; +#1133 = ORIENTED_EDGE ( 'NONE', *, *, #10008, .F. ) ; +#1134 = ORIENTED_EDGE ( 'NONE', *, *, #8058, .T. ) ; +#1135 = CARTESIAN_POINT ( 'NONE', ( 1.541641309182932407, 189.2503461931255515, 105.8091309696538360 ) ) ; +#1136 = DIRECTION ( 'NONE', ( 0.0001358647752415049960, 0.9743700647852354679, 0.2249510133144081714 ) ) ; +#1137 = LINE ( 'NONE', #22636, #16996 ) ; +#1138 = VERTEX_POINT ( 'NONE', #22948 ) ; +#1139 = EDGE_CURVE ( 'NONE', #7358, #34014, #4723, .T. ) ; +#1140 = VECTOR ( 'NONE', #9060, 1000.000000000000114 ) ; +#1141 = ORIENTED_EDGE ( 'NONE', *, *, #26637, .T. ) ; +#1142 = CARTESIAN_POINT ( 'NONE', ( -25.50961619573916295, 207.5944492561152117, 74.07776327504342362 ) ) ; +#1143 = CARTESIAN_POINT ( 'NONE', ( 38.53687076957470481, 218.5902260770998282, 61.03522658939011336 ) ) ; +#1144 = CARTESIAN_POINT ( 'NONE', ( -38.54589056617000153, 119.0161585872999979, 90.15889641821000566 ) ) ; +#1145 = CARTESIAN_POINT ( 'NONE', ( -44.77736910497013412, 122.8593275267315619, 91.09968955831281789 ) ) ; +#1146 = VECTOR ( 'NONE', #24084, 1000.000000000000000 ) ; +#1147 = EDGE_CURVE ( 'NONE', #3990, #1116, #13938, .T. ) ; +#1148 = CARTESIAN_POINT ( 'NONE', ( -45.92960031148149369, 125.5172539323009886, 88.65860258904321256 ) ) ; +#1149 = CARTESIAN_POINT ( 'NONE', ( 36.04619750388000199, 209.7096540190999860, 75.11813308473999484 ) ) ; +#1150 = ORIENTED_EDGE ( 'NONE', *, *, #34677, .T. ) ; +#1151 = FACE_OUTER_BOUND ( 'NONE', #16523, .T. ) ; +#1152 = CARTESIAN_POINT ( 'NONE', ( 25.18370408048160769, 116.8541948698079835, 87.75240084223993620 ) ) ; +#1153 = CARTESIAN_POINT ( 'NONE', ( -24.95545957861278197, 159.0476773995373208, 180.5017353223074110 ) ) ; +#1154 = PLANE ( 'NONE', #18984 ) ; +#1155 = VERTEX_POINT ( 'NONE', #29477 ) ; +#1156 = EDGE_CURVE ( 'NONE', #37208, #29757, #29031, .T. ) ; +#1157 = CARTESIAN_POINT ( 'NONE', ( -22.78469271946612196, 158.3009118758265004, 96.21332883968871386 ) ) ; +#1158 = CARTESIAN_POINT ( 'NONE', ( 0.8736985995922892378, 189.0243393747963125, 103.6919201171674132 ) ) ; +#1159 = CARTESIAN_POINT ( 'NONE', ( -2.915934786403184820, 190.5310171364556879, 106.7211489447119135 ) ) ; +#1160 = CARTESIAN_POINT ( 'NONE', ( -2.438441566312121278, 191.9759150222000130, 101.9229200979920620 ) ) ; +#1161 = CARTESIAN_POINT ( 'NONE', ( -25.87265514998000171, 191.7182740471999978, 104.0421947181999940 ) ) ; +#1162 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927784831808, -0.0005734119022074042876 ) ) ; +#1163 = CARTESIAN_POINT ( 'NONE', ( -3.501640554245670334, 183.5236249414575127, 104.7616159400518541 ) ) ; +#1164 = CARTESIAN_POINT ( 'NONE', ( -3.893460981304297963, 148.9599728392922771, 129.9645419182680541 ) ) ; +#1165 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971553745 ) ) ; +#1166 = ORIENTED_EDGE ( 'NONE', *, *, #19596, .T. ) ; +#1167 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#1168 = VECTOR ( 'NONE', #6521, 999.9999999999998863 ) ; +#1169 = AXIS2_PLACEMENT_3D ( 'NONE', #5667, #24495, #36955 ) ; +#1170 = CARTESIAN_POINT ( 'NONE', ( 39.05618840313393747, 127.6228071286297734, 91.65913731599329139 ) ) ; +#1171 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1172 = VERTEX_POINT ( 'NONE', #13538 ) ; +#1173 = CARTESIAN_POINT ( 'NONE', ( -34.95638759933999751, 226.4002260771000010, 73.57961695570000416 ) ) ; +#1174 = CARTESIAN_POINT ( 'NONE', ( -37.35285048055809654, 145.6614909859866884, 280.9747434382983329 ) ) ; +#1175 = DIRECTION ( 'NONE', ( 0.0006039748319385826545, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#1176 = CARTESIAN_POINT ( 'NONE', ( 20.41970764888255729, 118.1111884937556908, 89.83743835591825189 ) ) ; +#1177 = EDGE_CURVE ( 'NONE', #901, #21181, #38658, .T. ) ; +#1178 = CARTESIAN_POINT ( 'NONE', ( -39.39119571213127102, 179.7048915881142648, 119.1251828874389389 ) ) ; +#1179 = EDGE_CURVE ( 'NONE', #9277, #25509, #18559, .T. ) ; +#1180 = CARTESIAN_POINT ( 'NONE', ( 35.68878940061000549, 192.8595724163999989, 106.6974279695000121 ) ) ; +#1181 = ORIENTED_EDGE ( 'NONE', *, *, #19909, .F. ) ; +#1182 = ORIENTED_EDGE ( 'NONE', *, *, #21145, .F. ) ; +#1183 = FACE_OUTER_BOUND ( 'NONE', #17663, .T. ) ; +#1184 = CARTESIAN_POINT ( 'NONE', ( -2.849114641686540050, 209.7153547210247666, 76.06022791818580231 ) ) ; +#1185 = CARTESIAN_POINT ( 'NONE', ( -15.99823432472775941, 127.0706064849903782, 92.07805732825173095 ) ) ; +#1186 = EDGE_CURVE ( 'NONE', #26180, #33812, #25777, .T. ) ; +#1187 = CARTESIAN_POINT ( 'NONE', ( 20.48253891412411321, 207.4083879957671002, 77.06951181954761410 ) ) ; +#1188 = VERTEX_POINT ( 'NONE', #19653 ) ; +#1189 = CARTESIAN_POINT ( 'NONE', ( 9.150602861467000082, 130.7229476589999990, 90.08374091371000247 ) ) ; +#1190 = ORIENTED_EDGE ( 'NONE', *, *, #17562, .T. ) ; +#1191 = EDGE_CURVE ( 'NONE', #32568, #10330, #4513, .T. ) ; +#1192 = CARTESIAN_POINT ( 'NONE', ( -5.039516421625153342, 130.9623293100809747, 89.89100093531286007 ) ) ; +#1193 = FACE_OUTER_BOUND ( 'NONE', #23968, .T. ) ; +#1194 = ORIENTED_EDGE ( 'NONE', *, *, #16495, .F. ) ; +#1195 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673442394, 160.6295158081618411, 97.24216643309391372 ) ) ; +#1196 = AXIS2_PLACEMENT_3D ( 'NONE', #34674, #9566, #28372 ) ; +#1197 = CARTESIAN_POINT ( 'NONE', ( -45.74740226047678959, 185.6973914029000809, 105.7298533567153669 ) ) ; +#1198 = CARTESIAN_POINT ( 'NONE', ( 22.99423289560478167, 177.7941910958035976, 100.6860584427342218 ) ) ; +#1199 = VECTOR ( 'NONE', #32180, 1000.000000000000114 ) ; +#1200 = CARTESIAN_POINT ( 'NONE', ( -48.16156435861396545, 130.6626959207983703, 336.5737388819031821 ) ) ; +#1201 = VERTEX_POINT ( 'NONE', #13331 ) ; +#1202 = EDGE_CURVE ( 'NONE', #7538, #22666, #23804, .T. ) ; +#1203 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971542920 ) ) ; +#1204 = CARTESIAN_POINT ( 'NONE', ( -4.387522495294643221, 177.1923504851183395, 100.5636504583834920 ) ) ; +#1205 = CARTESIAN_POINT ( 'NONE', ( 3.535852102820259191, 167.8277681301466941, 101.4758341492079410 ) ) ; +#1206 = CARTESIAN_POINT ( 'NONE', ( -37.95565868480999683, 191.5245969965999961, 104.5544014840999978 ) ) ; +#1207 = ORIENTED_EDGE ( 'NONE', *, *, #18754, .F. ) ; +#1208 = LINE ( 'NONE', #17136, #37489 ) ; +#1209 = CARTESIAN_POINT ( 'NONE', ( 38.56885418974432866, 118.4610218664272452, 89.66265752007532797 ) ) ; +#1210 = CARTESIAN_POINT ( 'NONE', ( -2.770499765333565456, 191.4885340689822613, 104.0342591781858061 ) ) ; +#1211 = DIRECTION ( 'NONE', ( -0.6982900371914135818, 0.000000000000000000, -0.7158149369489396063 ) ) ; +#1212 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #9486, #25440 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1213 = DIRECTION ( 'NONE', ( 0.5987319960704027277, 0.8009494346596114367, 0.000000000000000000 ) ) ; +#1214 = DIRECTION ( 'NONE', ( 0.0004270746993296993988, 0.7071067811864992780, 0.7071066522153991452 ) ) ; +#1215 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552144553, 153.0051697192221241, 291.5584375788738498 ) ) ; +#1216 = AXIS2_PLACEMENT_3D ( 'NONE', #13921, #26403, #638 ) ; +#1217 = CARTESIAN_POINT ( 'NONE', ( 28.46561332783693743, 183.4529609800732146, 105.0712386042130646 ) ) ; +#1218 = CARTESIAN_POINT ( 'NONE', ( 38.39577698277999929, 118.8040257133999944, 90.10298124054000368 ) ) ; +#1219 = EDGE_LOOP ( 'NONE', ( #13416, #313, #14610, #3967 ) ) ; +#1220 = FACE_OUTER_BOUND ( 'NONE', #40208, .T. ) ; +#1221 = CIRCLE ( 'NONE', #27393, 5.499999999682917640 ) ; +#1222 = CARTESIAN_POINT ( 'NONE', ( 13.76437287213889604, 149.5973107319868802, 180.3792966454857094 ) ) ; +#1223 = CARTESIAN_POINT ( 'NONE', ( 45.29457532323036162, 180.8691996123082220, 102.9219678205533910 ) ) ; +#1224 = EDGE_CURVE ( 'NONE', #38924, #22051, #9190, .T. ) ; +#1225 = EDGE_CURVE ( 'NONE', #15470, #8707, #19840, .T. ) ; +#1226 = VECTOR ( 'NONE', #20632, 1000.000000000000114 ) ; +#1228 = VERTEX_POINT ( 'NONE', #13732 ) ; +#1227 = CARTESIAN_POINT ( 'NONE', ( -20.50078406871936920, 194.1847361021935683, 103.1282549620370759 ) ) ; +#1229 = ORIENTED_EDGE ( 'NONE', *, *, #6904, .T. ) ; +#1230 = ORIENTED_EDGE ( 'NONE', *, *, #13104, .F. ) ; +#1231 = ORIENTED_EDGE ( 'NONE', *, *, #31118, .T. ) ; +#1232 = DIRECTION ( 'NONE', ( 0.0005884949961248703678, -0.2249510543439058319, 0.9743698870671263501 ) ) ; +#1233 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971561239 ) ) ; +#1234 = ORIENTED_EDGE ( 'NONE', *, *, #16406, .T. ) ; +#1235 = CARTESIAN_POINT ( 'NONE', ( -15.03332272964733463, 187.8566649671956554, 103.0321316980956254 ) ) ; +#1236 = CARTESIAN_POINT ( 'NONE', ( -13.50000254341547468, 188.3456888787851540, 103.1410290439362001 ) ) ; +#1237 = CARTESIAN_POINT ( 'NONE', ( -38.46629707384001051, 119.1630541435999930, 87.59461058415000423 ) ) ; +#1238 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319414569829 ) ) ; +#1239 = VERTEX_POINT ( 'NONE', #4312 ) ; +#1240 = CARTESIAN_POINT ( 'NONE', ( -19.46385895993763882, 125.8676358703096696, 177.6266660728926183 ) ) ; +#1241 = CARTESIAN_POINT ( 'NONE', ( 25.99030105615392827, 209.7097546603872900, 73.04280869622928662 ) ) ; +#1242 = CYLINDRICAL_SURFACE ( 'NONE', #28694, 2.500000000000000888 ) ; +#1243 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; +#1244 = ORIENTED_EDGE ( 'NONE', *, *, #38617, .F. ) ; +#1245 = AXIS2_PLACEMENT_3D ( 'NONE', #34468, #19347, #32239 ) ; +#1246 = EDGE_CURVE ( 'NONE', #13095, #5536, #28398, .T. ) ; +#1247 = CARTESIAN_POINT ( 'NONE', ( -0.4376680304626999751, 188.6124753596999994, 103.1978087006000067 ) ) ; +#1248 = CARTESIAN_POINT ( 'NONE', ( -0.4555724317109230981, 208.9999999999988631, 73.55877932794840035 ) ) ; +#1249 = DIRECTION ( 'NONE', ( -0.0002393071182785117045, -0.2252352986010040525, 0.9743043687658490271 ) ) ; +#1250 = VECTOR ( 'NONE', #38324, 1000.000000000000114 ) ; +#1251 = ORIENTED_EDGE ( 'NONE', *, *, #7446, .T. ) ; +#1252 = ORIENTED_EDGE ( 'NONE', *, *, #36781, .F. ) ; +#1253 = CARTESIAN_POINT ( 'NONE', ( -19.99931527105535878, 118.1256151686936420, 90.27945241601419468 ) ) ; +#1254 = DIRECTION ( 'NONE', ( 0.0006039748319379876444, 1.544770086762009064E-14, 0.9999998176071845934 ) ) ; +#1255 = ORIENTED_EDGE ( 'NONE', *, *, #5400, .F. ) ; +#1256 = AXIS2_PLACEMENT_3D ( 'NONE', #38670, #7394, #29897 ) ; +#1257 = EDGE_CURVE ( 'NONE', #13611, #38012, #4103, .T. ) ; +#1258 = ORIENTED_EDGE ( 'NONE', *, *, #9270, .F. ) ; +#1259 = VERTEX_POINT ( 'NONE', #19450 ) ; +#1260 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14050, #8323, #39782, #1990 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.002947668951464836248, 0.009586839455661846573 ), + .UNSPECIFIED. ) ; +#1261 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1262 = CARTESIAN_POINT ( 'NONE', ( -20.00062605139820704, 196.5784656963837733, 103.8871944330217048 ) ) ; +#1263 = ADVANCED_FACE ( 'NONE', ( #31952 ), #23142, .F. ) ; +#1264 = ORIENTED_EDGE ( 'NONE', *, *, #37564, .F. ) ; +#1265 = EDGE_LOOP ( 'NONE', ( #17541, #39004, #30215, #34853 ) ) ; +#1266 = CARTESIAN_POINT ( 'NONE', ( 25.83357363015789687, 120.1280924554769740, 90.26901784129513828 ) ) ; +#1267 = CARTESIAN_POINT ( 'NONE', ( -25.20351987054574394, 212.3494581010839397, 75.57404532580622458 ) ) ; +#1268 = ADVANCED_FACE ( 'NONE', ( #22749 ), #16385, .F. ) ; +#1269 = EDGE_CURVE ( 'NONE', #39173, #30729, #1815, .T. ) ; +#1270 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19151, #16293, #19750, #6682 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1272 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#1271 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 1.238758140229869926E-30, -0.0006039748319385906776 ) ) ; +#1273 = ADVANCED_FACE ( 'NONE', ( #5532 ), #628, .F. ) ; +#1274 = ORIENTED_EDGE ( 'NONE', *, *, #29674, .F. ) ; +#1275 = CARTESIAN_POINT ( 'NONE', ( -2.198820561365330217, 189.3382245203125365, 103.3664250168511387 ) ) ; +#1276 = VECTOR ( 'NONE', #26107, 1000.000000000000114 ) ; +#1277 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#1278 = VECTOR ( 'NONE', #32982, 1000.000000000000114 ) ; +#1279 = CARTESIAN_POINT ( 'NONE', ( -20.51990970300121830, 210.6301663998115146, 73.57089453299630577 ) ) ; +#1280 = ORIENTED_EDGE ( 'NONE', *, *, #19274, .T. ) ; +#1281 = CIRCLE ( 'NONE', #31337, 2.499999999988501198 ) ; +#1282 = ORIENTED_EDGE ( 'NONE', *, *, #2745, .F. ) ; +#1283 = CARTESIAN_POINT ( 'NONE', ( 37.28562273942550576, 118.1774615424172339, 122.8329667304428909 ) ) ; +#1284 = CARTESIAN_POINT ( 'NONE', ( -22.50000104909151943, 127.7435495815598614, 89.15524414322925395 ) ) ; +#1285 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501096727, 179.0628333272140367, 104.0826189413666043 ) ) ; +#1286 = ORIENTED_EDGE ( 'NONE', *, *, #33213, .F. ) ; +#1287 = ORIENTED_EDGE ( 'NONE', *, *, #9048, .F. ) ; +#1288 = FACE_OUTER_BOUND ( 'NONE', #38470, .T. ) ; +#1289 = VERTEX_POINT ( 'NONE', #22097 ) ; +#1290 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #13567, #38103, #38300, #10105 ), + ( #4137, #7621, #13366, #10315 ), + ( #22777, #4548, #17008, #35213 ), + ( #7411, #29109, #1081, #23989 ), + ( #33369, #24200, #36852, #23780 ), + ( #17420, #8861, #33161, #36652 ), + ( #33570, #30530, #5776, #17623 ), + ( #39094, #36446, #2112, #11106 ), + ( #23569, #14582, #17816, #36024 ), + ( #2721, #18421, #24805, #13475 ), + ( #12121, #40309, #10415, #34171 ), + ( #40107, #28067, #25002, #28263 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.03178433120621999841, 0.000000000000000000, 0.04166546341146999677, 0.08333232016817999910, 0.1666660336816999932, 0.2499997471950000105, 0.3333334607083999757, 0.6666667335578000397, 1.000000000000000000, 1.093460235121999968 ), + ( 0.0007981880968812000250, 0.9999999654241999991 ), + .UNSPECIFIED. ) ; +#1291 = CARTESIAN_POINT ( 'NONE', ( -35.43460945665400175, 192.7871044595100045, 106.8782972701939968 ) ) ; +#1292 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10596, #9996, #13654, #12860 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1293 = ORIENTED_EDGE ( 'NONE', *, *, #7424, .T. ) ; +#1294 = CARTESIAN_POINT ( 'NONE', ( -20.90347901032547639, 150.8128521043120429, 179.9383906111355031 ) ) ; +#1295 = ORIENTED_EDGE ( 'NONE', *, *, #31159, .T. ) ; +#1296 = CARTESIAN_POINT ( 'NONE', ( 27.38172910116941949, 155.9316580491613706, 179.7942429727659146 ) ) ; +#1297 = CIRCLE ( 'NONE', #20905, 59.40509898896999630 ) ; +#1298 = CONICAL_SURFACE ( 'NONE', #16962, 2.502994014014904955, 0.7853981633916174987 ) ; +#1299 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1300 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#1301 = CARTESIAN_POINT ( 'NONE', ( -20.46828127178381962, 162.3883493913741347, 152.4706590458624760 ) ) ; +#1302 = EDGE_CURVE ( 'NONE', #4671, #7229, #22299, .T. ) ; +#1303 = CIRCLE ( 'NONE', #15051, 2.500000000086348706 ) ; +#1304 = ORIENTED_EDGE ( 'NONE', *, *, #7600, .T. ) ; +#1305 = EDGE_LOOP ( 'NONE', ( #20097, #33483, #32804, #5597, #31459 ) ) ; +#1306 = VECTOR ( 'NONE', #6786, 1000.000000000000000 ) ; +#1307 = CARTESIAN_POINT ( 'NONE', ( 5.659931281361317623, 181.6896837046558346, 101.5959228839198687 ) ) ; +#1308 = CARTESIAN_POINT ( 'NONE', ( -20.01829689993581596, 209.7096928646539880, 76.07061354826153377 ) ) ; +#1309 = CARTESIAN_POINT ( 'NONE', ( 45.12699821176128978, 130.9347303581116364, 89.85432989627193479 ) ) ; +#1310 = ADVANCED_FACE ( 'NONE', ( #9827 ), #34237, .F. ) ; +#1311 = DIRECTION ( 'NONE', ( 0.0006039748319392047697, 1.158053700410192562E-15, 0.9999998176071845934 ) ) ; +#1312 = ORIENTED_EDGE ( 'NONE', *, *, #37295, .F. ) ; +#1313 = EDGE_CURVE ( 'NONE', #2172, #30753, #19864, .T. ) ; +#1314 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 5.991633438574710639E-15, -0.0006039748319372744562 ) ) ; +#1315 = EDGE_CURVE ( 'NONE', #19509, #36951, #36147, .T. ) ; +#1316 = CARTESIAN_POINT ( 'NONE', ( -37.56814571527999647, 118.0504501373000039, 90.15109701891999805 ) ) ; +#1317 = EDGE_CURVE ( 'NONE', #8891, #34551, #35517, .T. ) ; +#1318 = VERTEX_POINT ( 'NONE', #598 ) ; +#1319 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672796982, 173.9550015251411992, 102.3712056567855058 ) ) ; +#1320 = ADVANCED_FACE ( 'NONE', ( #16737 ), #29432, .T. ) ; +#1321 = VERTEX_POINT ( 'NONE', #13090 ) ; +#1322 = CARTESIAN_POINT ( 'NONE', ( 39.72744467449597039, 107.0407412472234370, 185.0027118236955062 ) ) ; +#1323 = LINE ( 'NONE', #20330, #18963 ) ; +#1324 = CARTESIAN_POINT ( 'NONE', ( 37.43237754270795392, 168.1027941077541925, 183.6367509868652519 ) ) ; +#1325 = ORIENTED_EDGE ( 'NONE', *, *, #28213, .F. ) ; +#1326 = ORIENTED_EDGE ( 'NONE', *, *, #40323, .T. ) ; +#1327 = DIRECTION ( 'NONE', ( 0.0005884949961246214349, -0.2249510543438803523, 0.9743698870671323453 ) ) ; +#1328 = ORIENTED_EDGE ( 'NONE', *, *, #20901, .T. ) ; +#1329 = ORIENTED_EDGE ( 'NONE', *, *, #25236, .F. ) ; +#1331 = CIRCLE ( 'NONE', #32690, 2.250000000041461945 ) ; +#1330 = CARTESIAN_POINT ( 'NONE', ( 22.78222448925487953, 163.9654955388074029, 100.5724953333896536 ) ) ; +#1332 = CIRCLE ( 'NONE', #31389, 5.000000000044655835 ) ; +#1333 = CARTESIAN_POINT ( 'NONE', ( 19.71701219870257304, 124.6133069866743455, 177.2811646003819135 ) ) ; +#1334 = VECTOR ( 'NONE', #30355, 1000.000000000000000 ) ; +#1335 = ORIENTED_EDGE ( 'NONE', *, *, #24900, .F. ) ; +#1336 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#1337 = AXIS2_PLACEMENT_3D ( 'NONE', #29058, #13320, #12504 ) ; +#1338 = CARTESIAN_POINT ( 'NONE', ( 37.12346960361000470, 117.3680689878000010, 87.58200843903000532 ) ) ; +#1339 = CARTESIAN_POINT ( 'NONE', ( 36.03638591485000831, 191.4347906147000060, 103.6972876298000017 ) ) ; +#1340 = CARTESIAN_POINT ( 'NONE', ( 3.045988519791387628, 209.1419319775010877, 76.13893608185537687 ) ) ; +#1341 = ORIENTED_EDGE ( 'NONE', *, *, #29907, .F. ) ; +#1342 = CARTESIAN_POINT ( 'NONE', ( -40.95517856246386401, 220.4002260740000168, 75.58324044005986764 ) ) ; +#1343 = ORIENTED_EDGE ( 'NONE', *, *, #4217, .T. ) ; +#1344 = CARTESIAN_POINT ( 'NONE', ( 0.5883234961168344324, 188.6054712616331699, 103.1955722014524355 ) ) ; +#1345 = CARTESIAN_POINT ( 'NONE', ( 5.667815391071374442, 128.0240139252287861, 91.77193103160428223 ) ) ; +#1346 = CARTESIAN_POINT ( 'NONE', ( -21.44693686545786449, 130.1487540525002657, 89.71308199639462089 ) ) ; +#1347 = DIRECTION ( 'NONE', ( 0.0006039748319391886151, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#1348 = ORIENTED_EDGE ( 'NONE', *, *, #22580, .T. ) ; +#1349 = DIRECTION ( 'NONE', ( -0.0005559617641590978683, 0.3907311285029293479, -0.9205046855531719974 ) ) ; +#1350 = CARTESIAN_POINT ( 'NONE', ( 1.084497557541584056, 189.0692846685636539, 103.7040743146856698 ) ) ; +#1351 = FACE_OUTER_BOUND ( 'NONE', #4289, .T. ) ; +#1352 = EDGE_CURVE ( 'NONE', #21410, #3576, #33010, .T. ) ; +#1354 = EDGE_CURVE ( 'NONE', #21126, #19429, #38172, .T. ) ; +#1353 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39129, #13792, #19902, #4377, #29337, #26277, #11135, #26476, #23599, #20731 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1355 = CARTESIAN_POINT ( 'NONE', ( 20.50100932471902482, 118.1127835883590365, 89.75563873136169946 ) ) ; +#1356 = EDGE_CURVE ( 'NONE', #12793, #34762, #3293, .T. ) ; +#1357 = CARTESIAN_POINT ( 'NONE', ( -25.87951586735999854, 191.5803385735999882, 104.0212822168000031 ) ) ; +#1358 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971537369 ) ) ; +#1359 = CARTESIAN_POINT ( 'NONE', ( -23.67442327598790541, 213.5252042271739867, 73.57279381178021538 ) ) ; +#1360 = EDGE_CURVE ( 'NONE', #8220, #20950, #10629, .T. ) ; +#1361 = AXIS2_PLACEMENT_3D ( 'NONE', #29124, #4357, #7423 ) ; +#1362 = FACE_OUTER_BOUND ( 'NONE', #3551, .T. ) ; +#1363 = VERTEX_POINT ( 'NONE', #32493 ) ; +#1364 = EDGE_CURVE ( 'NONE', #18267, #13786, #12522, .T. ) ; +#1365 = AXIS2_PLACEMENT_3D ( 'NONE', #9551, #33873, #25302 ) ; +#1366 = VECTOR ( 'NONE', #16081, 1000.000000000000000 ) ; +#1367 = FACE_OUTER_BOUND ( 'NONE', #14627, .T. ) ; +#1368 = EDGE_CURVE ( 'NONE', #30529, #23353, #39220, .T. ) ; +#1369 = LINE ( 'NONE', #24078, #27614 ) ; +#1370 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927779942056, 0.0005734119022074188159 ) ) ; +#1371 = CARTESIAN_POINT ( 'NONE', ( 3.666638755409086681, 184.0129645450027738, 102.6466012127862371 ) ) ; +#1372 = CARTESIAN_POINT ( 'NONE', ( 36.59177244347999647, 191.2969789047999996, 106.4552055056999933 ) ) ; +#1373 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606776115838874, 137.3532831589803322, 178.0585834212922123 ) ) ; +#1374 = PLANE ( 'NONE', #10301 ) ; +#1375 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#1376 = CARTESIAN_POINT ( 'NONE', ( 37.33707104902199347, 104.0050695705055546, 184.3033154091657480 ) ) ; +#1377 = ORIENTED_EDGE ( 'NONE', *, *, #17243, .F. ) ; +#1378 = ORIENTED_EDGE ( 'NONE', *, *, #28879, .F. ) ; +#1379 = ADVANCED_FACE ( 'NONE', ( #14497 ), #20829, .T. ) ; +#1380 = CARTESIAN_POINT ( 'NONE', ( -2.614686376829999936, 209.2342314638000005, 75.76577055027999563 ) ) ; +#1381 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5159, #38906, #23579, #23790 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1382 = DIRECTION ( 'NONE', ( 0.7947985590179719173, -0.5913221741348984040, -0.1365039814779490934 ) ) ; +#1383 = CARTESIAN_POINT ( 'NONE', ( 13.51396216897000002, 163.2545600168000135, 28.07991271570000080 ) ) ; +#1384 = ORIENTED_EDGE ( 'NONE', *, *, #8405, .T. ) ; +#1385 = DIRECTION ( 'NONE', ( -0.0004161288024570960900, -0.5299192578740949955, -0.8480479980348919478 ) ) ; +#1386 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #27789, #30031 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1387 = AXIS2_PLACEMENT_3D ( 'NONE', #29828, #38600, #14284 ) ; +#1388 = VERTEX_POINT ( 'NONE', #39824 ) ; +#1389 = AXIS2_PLACEMENT_3D ( 'NONE', #20504, #13781, #4156 ) ; +#1390 = AXIS2_PLACEMENT_3D ( 'NONE', #38484, #13559, #26043 ) ; +#1391 = DIRECTION ( 'NONE', ( 0.0006039748319388572829, 3.099784637799882324E-15, 0.9999998176071847045 ) ) ; +#1392 = CARTESIAN_POINT ( 'NONE', ( -8.717675269239875870E-13, 155.6803346353160578, 98.67347229710807710 ) ) ; +#1393 = VERTEX_POINT ( 'NONE', #11842 ) ; +#1394 = CARTESIAN_POINT ( 'NONE', ( 36.23356337170621799, 191.9704930452380438, 106.3944001953638860 ) ) ; +#1395 = CARTESIAN_POINT ( 'NONE', ( -37.17455842349777129, 80.91246596882704978, 284.1870184124936145 ) ) ; +#1396 = CARTESIAN_POINT ( 'NONE', ( 4.035676231532755232, 174.7936433537611265, 102.5705385171684298 ) ) ; +#1397 = FACE_OUTER_BOUND ( 'NONE', #26232, .T. ) ; +#1398 = CARTESIAN_POINT ( 'NONE', ( -30.45076008202071804, 127.0987129668839373, 89.01436241067176525 ) ) ; +#1399 = EDGE_LOOP ( 'NONE', ( #22723, #37355, #27529, #9228 ) ) ; +#1400 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319378609011 ) ) ; +#1401 = CARTESIAN_POINT ( 'NONE', ( -30.07067142585793462, 177.4371639094459283, 100.9353481595662885 ) ) ; +#1402 = CARTESIAN_POINT ( 'NONE', ( -3.168142195203446754, 126.1261981506732468, 91.85226338672082136 ) ) ; +#1403 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24541, #24944, #15904, #34493 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1404 = ADVANCED_FACE ( 'NONE', ( #17940 ), #33282, .T. ) ; +#1405 = CARTESIAN_POINT ( 'NONE', ( -23.37153626856268218, 181.6857280266875421, 101.6124992246220842 ) ) ; +#1406 = ORIENTED_EDGE ( 'NONE', *, *, #15378, .F. ) ; +#1407 = EDGE_CURVE ( 'NONE', #5782, #38340, #24323, .T. ) ; +#1408 = ORIENTED_EDGE ( 'NONE', *, *, #14742, .F. ) ; +#1409 = CARTESIAN_POINT ( 'NONE', ( 30.02141571457803337, 185.4797026207797899, 105.5350675521475381 ) ) ; +#1410 = EDGE_CURVE ( 'NONE', #10753, #12419, #14037, .T. ) ; +#1411 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18806, #3090, #37046, #25383 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1412 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1413 = CARTESIAN_POINT ( 'NONE', ( 36.53073584806749352, 115.3012705596803613, 89.70707320453416855 ) ) ; +#1414 = CARTESIAN_POINT ( 'NONE', ( 2.462157221798171314, 209.5677243469951634, 73.55701709285500556 ) ) ; +#1415 = EDGE_CURVE ( 'NONE', #22040, #8707, #36885, .T. ) ; +#1416 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1417 = AXIS2_PLACEMENT_3D ( 'NONE', #17177, #21084, #33335 ) ; +#1418 = CARTESIAN_POINT ( 'NONE', ( 41.04644941596783525, 217.7719116456999870, 75.53371351155776381 ) ) ; +#1419 = CARTESIAN_POINT ( 'NONE', ( 25.92670928620000126, 190.7418989758000123, 106.6263904082999971 ) ) ; +#1420 = CARTESIAN_POINT ( 'NONE', ( -15.91646557088323100, 147.2350097630058201, 179.8259003790471979 ) ) ; +#1421 = CARTESIAN_POINT ( 'NONE', ( 36.04678030622115159, 205.1071296091856482, 76.08307765920791610 ) ) ; +#1422 = VERTEX_POINT ( 'NONE', #2438 ) ; +#1423 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173459745, 127.6315666250176548, 89.64029552920665367 ) ) ; +#1424 = CARTESIAN_POINT ( 'NONE', ( -28.35193061917324897, 125.4776039296643120, 88.98093332774035957 ) ) ; +#1425 = CARTESIAN_POINT ( 'NONE', ( 35.54675198585685791, 209.7096512551739238, 76.03703539298859937 ) ) ; +#1426 = CARTESIAN_POINT ( 'NONE', ( 21.44870233977301410, 176.2493420812517968, 103.4092482268179936 ) ) ; +#1427 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#1428 = ORIENTED_EDGE ( 'NONE', *, *, #173, .F. ) ; +#1429 = VERTEX_POINT ( 'NONE', #20408 ) ; +#1430 = EDGE_LOOP ( 'NONE', ( #37144, #22256, #6075, #28590, #2549, #26712, #13131, #33626, #10219, #40165, #4400, #1207, #29926 ) ) ; +#1431 = CARTESIAN_POINT ( 'NONE', ( -26.00855467233698093, 208.9309408413571987, 76.19155773393745790 ) ) ; +#1432 = PLANE ( 'NONE', #2368 ) ; +#1433 = CARTESIAN_POINT ( 'NONE', ( -2.693126113164496793, 209.6623431126212722, 73.22679707159588247 ) ) ; +#1434 = CARTESIAN_POINT ( 'NONE', ( 16.00000031304551129, 127.7446264382961232, 89.13542822417404921 ) ) ; +#1435 = ORIENTED_EDGE ( 'NONE', *, *, #9653, .T. ) ; +#1436 = ORIENTED_EDGE ( 'NONE', *, *, #2240, .F. ) ; +#1437 = CARTESIAN_POINT ( 'NONE', ( -16.49964056687395697, 137.3541725157726887, 178.0547363146727093 ) ) ; +#1438 = CARTESIAN_POINT ( 'NONE', ( -35.78508929150346773, 160.5808268139875565, 188.4031816783294744 ) ) ; +#1439 = CARTESIAN_POINT ( 'NONE', ( 20.50153854971994960, 118.8155953598612484, 89.75541792533370256 ) ) ; +#1440 = CARTESIAN_POINT ( 'NONE', ( -30.07171558059459215, 177.1876876956736169, 101.0912387261568028 ) ) ; +#1441 = CARTESIAN_POINT ( 'NONE', ( -36.09965786878999694, 116.0947685687000046, 87.39754037820000576 ) ) ; +#1442 = ORIENTED_EDGE ( 'NONE', *, *, #26926, .T. ) ; +#1443 = CARTESIAN_POINT ( 'NONE', ( -38.91441614853255260, 170.2396169009835489, 164.5533723942515394 ) ) ; +#1444 = ORIENTED_EDGE ( 'NONE', *, *, #18163, .F. ) ; +#1445 = DIRECTION ( 'NONE', ( -0.0005884949961184506983, 0.2249510543501584692, -0.9743698870656828381 ) ) ; +#1446 = CARTESIAN_POINT ( 'NONE', ( -23.00127433123727982, 118.1131156702009548, 87.78148031792997585 ) ) ; +#1447 = LINE ( 'NONE', #13933, #1932 ) ; +#1448 = CARTESIAN_POINT ( 'NONE', ( -12.63866240555081255, 181.1745339601329476, 104.4280621927508008 ) ) ; +#1449 = ORIENTED_EDGE ( 'NONE', *, *, #10745, .T. ) ; +#1450 = CARTESIAN_POINT ( 'NONE', ( -2.088909101511000177, 189.3888656793000109, 103.5213134137000139 ) ) ; +#1451 = CARTESIAN_POINT ( 'NONE', ( 25.49191818104053198, 208.7356988742139663, 75.68967923392696662 ) ) ; +#1452 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#1453 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#1454 = VERTEX_POINT ( 'NONE', #20202 ) ; +#1455 = EDGE_CURVE ( 'NONE', #31222, #12675, #9615, .T. ) ; +#1456 = ORIENTED_EDGE ( 'NONE', *, *, #6142, .T. ) ; +#1457 = CARTESIAN_POINT ( 'NONE', ( -20.00089539691495233, 118.1272453392662527, 87.27993277136866368 ) ) ; +#1458 = DIRECTION ( 'NONE', ( 0.0006039748319385504537, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#1459 = EDGE_CURVE ( 'NONE', #34038, #4088, #29684, .T. ) ; +#1460 = ORIENTED_EDGE ( 'NONE', *, *, #23387, .T. ) ; +#1461 = ORIENTED_EDGE ( 'NONE', *, *, #21562, .T. ) ; +#1462 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16618, #31987, #7220, #16424 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 4.318577332577606880E-07, 6.344312035917670865E-05 ), + .UNSPECIFIED. ) ; +#1463 = ORIENTED_EDGE ( 'NONE', *, *, #35373, .T. ) ; +#1464 = ORIENTED_EDGE ( 'NONE', *, *, #30144, .F. ) ; +#1465 = ADVANCED_FACE ( 'NONE', ( #1609 ), #1817, .F. ) ; +#1466 = CARTESIAN_POINT ( 'NONE', ( -28.25571791307000069, 186.4543155771000045, 105.2821207260000023 ) ) ; +#1467 = CARTESIAN_POINT ( 'NONE', ( 37.96499143901794326, 190.9636352903536363, 106.2831835502989719 ) ) ; +#1468 = CARTESIAN_POINT ( 'NONE', ( 16.16445611536306259, 152.0055496971487514, 180.9366119946107858 ) ) ; +#1469 = ORIENTED_EDGE ( 'NONE', *, *, #34319, .F. ) ; +#1470 = DIRECTION ( 'NONE', ( 0.6087613505916679157, -0.7729391288194348286, -0.1788147677504891564 ) ) ; +#1471 = AXIS2_PLACEMENT_3D ( 'NONE', #11355, #23842, #8300 ) ; +#1472 = ORIENTED_EDGE ( 'NONE', *, *, #10336, .T. ) ; +#1473 = CARTESIAN_POINT ( 'NONE', ( 25.83309271880579416, 120.1166353669539291, 90.25644155803026081 ) ) ; +#1474 = CARTESIAN_POINT ( 'NONE', ( -26.00831778362747215, 205.1071295951792592, 76.12055741643118267 ) ) ; +#1475 = VECTOR ( 'NONE', #12424, 1000.000000000000114 ) ; +#1477 = CARTESIAN_POINT ( 'NONE', ( -42.99989013480271183, 189.1985352993988556, 106.4377309217844072 ) ) ; +#1476 = CARTESIAN_POINT ( 'NONE', ( -12.63633279611100591, 183.4482084008280367, 105.0918242824060513 ) ) ; +#1478 = ORIENTED_EDGE ( 'NONE', *, *, #31513, .T. ) ; +#1479 = EDGE_CURVE ( 'NONE', #12315, #13881, #31051, .T. ) ; +#1480 = AXIS2_PLACEMENT_3D ( 'NONE', #13691, #38029, #10638 ) ; +#1481 = ORIENTED_EDGE ( 'NONE', *, *, #30432, .F. ) ; +#1482 = CARTESIAN_POINT ( 'NONE', ( -36.03459587967929423, 192.0647978141948897, 104.4267888369482904 ) ) ; +#1483 = CARTESIAN_POINT ( 'NONE', ( 25.50924446128380296, 191.7417201544551517, 104.3989876494856190 ) ) ; +#1484 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25659, #37908, #16020, #7215 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1485 = ORIENTED_EDGE ( 'NONE', *, *, #7914, .T. ) ; +#1486 = CARTESIAN_POINT ( 'NONE', ( -35.57348742053811463, 114.4243515753128975, 87.28926978703593420 ) ) ; +#1487 = CARTESIAN_POINT ( 'NONE', ( -46.27971317312926658, 126.2404065528360775, 91.90467990004428600 ) ) ; +#1488 = LINE ( 'NONE', #36449, #22201 ) ; +#1489 = EDGE_LOOP ( 'NONE', ( #30427, #7866, #24975, #16004 ) ) ; +#1490 = EDGE_CURVE ( 'NONE', #18185, #26876, #25780, .T. ) ; +#1491 = ORIENTED_EDGE ( 'NONE', *, *, #4941, .F. ) ; +#1492 = CARTESIAN_POINT ( 'NONE', ( -12.63608108984827183, 177.6170740679187077, 100.8143728218807240 ) ) ; +#1493 = CARTESIAN_POINT ( 'NONE', ( -23.36111095637491886, 134.5088611855341583, 93.57062850653878172 ) ) ; +#1494 = VERTEX_POINT ( 'NONE', #11419 ) ; +#1495 = LINE ( 'NONE', #8037, #29155 ) ; +#1496 = CONICAL_SURFACE ( 'NONE', #11973, 2.500003536218122768, 0.7853981633752317171 ) ; +#1497 = VERTEX_POINT ( 'NONE', #8570 ) ; +#1498 = ADVANCED_FACE ( 'NONE', ( #36367 ), #27095, .T. ) ; +#1499 = LINE ( 'NONE', #2129, #12435 ) ; +#1500 = EDGE_CURVE ( 'NONE', #4088, #29586, #14709, .T. ) ; +#1501 = EDGE_LOOP ( 'NONE', ( #35487, #27362, #37177, #36310 ) ) ; +#1502 = CARTESIAN_POINT ( 'NONE', ( 39.17245388525562788, 118.9831901207053022, 89.68900349796480498 ) ) ; +#1503 = CIRCLE ( 'NONE', #37425, 4.500000000025920599 ) ; +#1504 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825866425532276, 0.0005734119036248240715 ) ) ; +#1505 = CARTESIAN_POINT ( 'NONE', ( -41.44647100807553386, 120.2182348193094015, 89.99828044825905238 ) ) ; +#1506 = CARTESIAN_POINT ( 'NONE', ( 44.64373491923319648, 189.2041368418193201, 103.8203288493235164 ) ) ; +#1507 = ORIENTED_EDGE ( 'NONE', *, *, #34488, .F. ) ; +#1508 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 67.27946979429630403, 312.5857197240632104 ) ) ; +#1509 = CARTESIAN_POINT ( 'NONE', ( 15.50147166113565866, 173.9550007122092836, 102.3699975097636496 ) ) ; +#1510 = CARTESIAN_POINT ( 'NONE', ( 3.046672840550818329, 207.8686389444351050, 77.27521480614490201 ) ) ; +#1511 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19835, #22944, #16782, #32343 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1512 = ORIENTED_EDGE ( 'NONE', *, *, #40323, .F. ) ; +#1513 = DIRECTION ( 'NONE', ( -0.0005884949961251572477, 0.2249510543439052768, -0.9743698870671265722 ) ) ; +#1515 = CARTESIAN_POINT ( 'NONE', ( -38.20586753382468004, 218.5902260770999987, 73.08157946901140178 ) ) ; +#1514 = FACE_OUTER_BOUND ( 'NONE', #31287, .T. ) ; +#1516 = ORIENTED_EDGE ( 'NONE', *, *, #3159, .T. ) ; +#1517 = EDGE_CURVE ( 'NONE', #39006, #20649, #2256, .T. ) ; +#1518 = CIRCLE ( 'NONE', #24417, 2.250000000000011102 ) ; +#1519 = VERTEX_POINT ( 'NONE', #21455 ) ; +#1520 = CARTESIAN_POINT ( 'NONE', ( -27.19780697399936642, 110.6131156702000027, 87.78421117711411625 ) ) ; +#1521 = CARTESIAN_POINT ( 'NONE', ( 36.46845686390152252, 264.8832191855225915, 206.0097772883433720 ) ) ; +#1522 = CARTESIAN_POINT ( 'NONE', ( 37.96499143901794326, 190.9636352903536363, 106.2831835502989719 ) ) ; +#1523 = CARTESIAN_POINT ( 'NONE', ( 39.05501141534195853, 128.0727083965270197, 89.71040118434773092 ) ) ; +#1525 = VERTEX_POINT ( 'NONE', #5890 ) ; +#1524 = CIRCLE ( 'NONE', #33519, 2.499999999952864371 ) ; +#1526 = ORIENTED_EDGE ( 'NONE', *, *, #39576, .T. ) ; +#1527 = FACE_OUTER_BOUND ( 'NONE', #35468, .T. ) ; +#1528 = ORIENTED_EDGE ( 'NONE', *, *, #16494, .T. ) ; +#1529 = ORIENTED_EDGE ( 'NONE', *, *, #23163, .F. ) ; +#1530 = CARTESIAN_POINT ( 'NONE', ( 30.50895605381732523, 153.0051697192226641, 335.7848420411070833 ) ) ; +#1531 = CIRCLE ( 'NONE', #18508, 2.500000000021232349 ) ; +#1532 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8807, #35971, #14532, #21073 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 2.072238197984719300E-05, 0.0007937364710496124746 ), + .UNSPECIFIED. ) ; +#1533 = CARTESIAN_POINT ( 'NONE', ( 39.61232211476462339, 114.7578009829419159, 151.0282930554255927 ) ) ; +#1534 = CARTESIAN_POINT ( 'NONE', ( 34.04100125716845326, 108.7218726133717723, 175.0403703967984939 ) ) ; +#1535 = ORIENTED_EDGE ( 'NONE', *, *, #38424, .T. ) ; +#1536 = EDGE_CURVE ( 'NONE', #16952, #10330, #21239, .T. ) ; +#1537 = VERTEX_POINT ( 'NONE', #40224 ) ; +#1538 = CARTESIAN_POINT ( 'NONE', ( -20.47540048824957992, 211.0902980118789571, 75.61425432729411966 ) ) ; +#1539 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772234801672, 136.6775772631780796, 180.9814965275865575 ) ) ; +#1540 = CARTESIAN_POINT ( 'NONE', ( 37.52439582013000319, 118.3551633538000090, 87.34611301001000072 ) ) ; +#1541 = CARTESIAN_POINT ( 'NONE', ( 36.36513335903000410, 191.2465653387999964, 103.6487651568999979 ) ) ; +#1542 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19208, #612, #38031, #10030 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1543 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -5.029098237799274788E-18, 0.0006039748319384018096 ) ) ; +#1544 = EDGE_CURVE ( 'NONE', #33925, #27579, #34001, .T. ) ; +#1545 = CARTESIAN_POINT ( 'NONE', ( -22.83746502234654940, 149.9685939482776007, 190.2127349222744783 ) ) ; +#1546 = ORIENTED_EDGE ( 'NONE', *, *, #39115, .T. ) ; +#1547 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452352341, 0.1781166614240801416 ) ) ; +#1548 = FACE_OUTER_BOUND ( 'NONE', #1751, .T. ) ; +#1549 = CYLINDRICAL_SURFACE ( 'NONE', #11742, 2.000000000000000444 ) ; +#1550 = ORIENTED_EDGE ( 'NONE', *, *, #8651, .T. ) ; +#1551 = CARTESIAN_POINT ( 'NONE', ( -42.72903334360638894, 77.14301703112133168, 281.5709244913558109 ) ) ; +#1552 = DIRECTION ( 'NONE', ( -0.0005884949961215159547, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#1553 = ADVANCED_FACE ( 'NONE', ( #27790 ), #160, .T. ) ; +#1554 = CARTESIAN_POINT ( 'NONE', ( 38.11757776978107159, 119.1971814748143146, 87.25517274288121428 ) ) ; +#1555 = EDGE_CURVE ( 'NONE', #20125, #31008, #12620, .T. ) ; +#1556 = CARTESIAN_POINT ( 'NONE', ( 45.03146303534695960, 186.3613416546399719, 106.7606159694749408 ) ) ; +#1557 = ADVANCED_FACE ( 'NONE', ( #36764 ), #8979, .T. ) ; +#1558 = ORIENTED_EDGE ( 'NONE', *, *, #10939, .F. ) ; +#1559 = CARTESIAN_POINT ( 'NONE', ( 37.68445503166663713, 212.3970731212107239, 28.08071801548966562 ) ) ; +#1560 = ADVANCED_FACE ( 'NONE', ( #15691 ), #3413, .F. ) ; +#1561 = CARTESIAN_POINT ( 'NONE', ( 1.762914848455207739, 189.4001637137704677, 103.7992039644048106 ) ) ; +#1562 = CIRCLE ( 'NONE', #30942, 22.50000000000000000 ) ; +#1563 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#1564 = ORIENTED_EDGE ( 'NONE', *, *, #11161, .F. ) ; +#1565 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#1566 = AXIS2_PLACEMENT_3D ( 'NONE', #26387, #23112, #16547 ) ; +#1567 = CARTESIAN_POINT ( 'NONE', ( -26.12781411639000240, 191.8675859534999972, 103.7979175393000162 ) ) ; +#1568 = CARTESIAN_POINT ( 'NONE', ( -5.960622341254478762, 149.1452448442896923, 94.08941484461983862 ) ) ; +#1569 = CARTESIAN_POINT ( 'NONE', ( 17.36823235697561074, 148.6268409572465430, 177.2656691734900107 ) ) ; +#1570 = CIRCLE ( 'NONE', #28985, 6.000000000011024071 ) ; +#1571 = CARTESIAN_POINT ( 'NONE', ( -30.06407784565124430, 177.7873364699197793, 100.7165267053679969 ) ) ; +#1572 = ORIENTED_EDGE ( 'NONE', *, *, #26073, .F. ) ; +#1573 = LINE ( 'NONE', #10791, #6311 ) ; +#1574 = EDGE_CURVE ( 'NONE', #9665, #468, #27993, .T. ) ; +#1575 = CARTESIAN_POINT ( 'NONE', ( 37.42082352723856076, 132.6200669550715929, 336.9739440566017379 ) ) ; +#1576 = CARTESIAN_POINT ( 'NONE', ( 17.99676327751897276, 132.8602135917374767, 90.82840093797520353 ) ) ; +#1577 = CARTESIAN_POINT ( 'NONE', ( 5.667003785789049175, 181.2013499400138130, 104.4023232969187944 ) ) ; +#1578 = CARTESIAN_POINT ( 'NONE', ( 38.05634169542999956, 191.1278539811999906, 106.1815489157999934 ) ) ; +#1579 = CARTESIAN_POINT ( 'NONE', ( 31.01176814742588661, 177.6154148053649351, 100.6399422860269937 ) ) ; +#1580 = DIRECTION ( 'NONE', ( 0.0006039748319383107366, 1.234791622901071989E-14, 0.9999998176071845934 ) ) ; +#1581 = LINE ( 'NONE', #35700, #10853 ) ; +#1582 = ORIENTED_EDGE ( 'NONE', *, *, #38078, .F. ) ; +#1583 = CIRCLE ( 'NONE', #9516, 1.749999999975493381 ) ; +#1584 = CARTESIAN_POINT ( 'NONE', ( 26.84904664283360276, 120.0929502244215428, 171.5090809722007350 ) ) ; +#1585 = CIRCLE ( 'NONE', #14688, 59.40509898896999630 ) ; +#1586 = LINE ( 'NONE', #5051, #18350 ) ; +#1587 = AXIS2_PLACEMENT_3D ( 'NONE', #1248, #25620, #25824 ) ; +#1588 = EDGE_CURVE ( 'NONE', #26442, #6684, #12427, .T. ) ; +#1589 = CARTESIAN_POINT ( 'NONE', ( -17.34531841451655509, 148.6239897228831239, 177.2780028082611068 ) ) ; +#1590 = ORIENTED_EDGE ( 'NONE', *, *, #27546, .F. ) ; +#1591 = FACE_OUTER_BOUND ( 'NONE', #1961, .T. ) ; +#1592 = CONICAL_SURFACE ( 'NONE', #2254, 5.999999999897309699, 0.7853981633778843729 ) ; +#1593 = DIRECTION ( 'NONE', ( 1.249000902683486815E-14, 0.9743700557921588512, 0.2249510932971550692 ) ) ; +#1594 = EDGE_LOOP ( 'NONE', ( #10058, #4390, #33919, #16483 ) ) ; +#1595 = EDGE_CURVE ( 'NONE', #38340, #39475, #24727, .T. ) ; +#1596 = CARTESIAN_POINT ( 'NONE', ( -16.04815223297914528, 152.0446744236089671, 184.5300512474807704 ) ) ; +#1597 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971551247 ) ) ; +#1598 = VERTEX_POINT ( 'NONE', #9572 ) ; +#1599 = CARTESIAN_POINT ( 'NONE', ( 36.30316923674414653, 191.8403127940163415, 106.3905535285534683 ) ) ; +#1600 = ADVANCED_FACE ( 'NONE', ( #30646 ), #21650, .T. ) ; +#1601 = CARTESIAN_POINT ( 'NONE', ( 20.00000522920557700, 138.5176112521621690, 91.62015419223651236 ) ) ; +#1602 = CYLINDRICAL_SURFACE ( 'NONE', #2883, 2.000000000000014655 ) ; +#1603 = CARTESIAN_POINT ( 'NONE', ( -12.63048181974366990, 130.3451622633888576, 92.83206449613362565 ) ) ; +#1604 = LINE ( 'NONE', #23484, #11780 ) ; +#1605 = DIRECTION ( 'NONE', ( -0.0005884949961234174284, 0.2249510543439059151, -0.9743698870671263501 ) ) ; +#1606 = ADVANCED_FACE ( 'NONE', ( #9371 ), #36921, .F. ) ; +#1607 = ORIENTED_EDGE ( 'NONE', *, *, #40327, .T. ) ; +#1608 = CARTESIAN_POINT ( 'NONE', ( 17.25779205791675253, 152.0580948532353034, 184.5595410583348439 ) ) ; +#1609 = FACE_OUTER_BOUND ( 'NONE', #9086, .T. ) ; +#1610 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1611 = ORIENTED_EDGE ( 'NONE', *, *, #16778, .T. ) ; +#1612 = CARTESIAN_POINT ( 'NONE', ( -25.49734528616909301, 118.8155664120999973, 94.28318532642107641 ) ) ; +#1613 = VERTEX_POINT ( 'NONE', #2642 ) ; +#1614 = LINE ( 'NONE', #26374, #40113 ) ; +#1615 = AXIS2_PLACEMENT_3D ( 'NONE', #20107, #23598, #24012 ) ; +#1616 = CARTESIAN_POINT ( 'NONE', ( 21.44693881909371669, 176.9241929811547038, 100.4861407201621120 ) ) ; +#1617 = DIRECTION ( 'NONE', ( -0.8142022563027235815, 0.000000000000000000, -0.5805813343809409499 ) ) ; +#1618 = AXIS2_PLACEMENT_3D ( 'NONE', #19511, #7436, #10136 ) ; +#1619 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; +#1620 = AXIS2_PLACEMENT_3D ( 'NONE', #18712, #36952, #8747 ) ; +#1621 = CARTESIAN_POINT ( 'NONE', ( 8.271042397109361843, 124.3676236163658899, 88.36049928470526993 ) ) ; +#1622 = CARTESIAN_POINT ( 'NONE', ( 25.38728234211000157, 191.0564470040000060, 106.1766889295000169 ) ) ; +#1623 = LINE ( 'NONE', #1420, #30995 ) ; +#1624 = CARTESIAN_POINT ( 'NONE', ( 3.293163761662359690, 183.3573071469507454, 101.9823041688293301 ) ) ; +#1625 = ORIENTED_EDGE ( 'NONE', *, *, #24351, .F. ) ; +#1626 = CARTESIAN_POINT ( 'NONE', ( 16.38737785140941483, 122.7247190552318585, 172.1149118660857766 ) ) ; +#1627 = FACE_OUTER_BOUND ( 'NONE', #17426, .T. ) ; +#1628 = CARTESIAN_POINT ( 'NONE', ( 18.98506067126258046, 148.2070439170772431, 184.7168109706149721 ) ) ; +#1629 = DIRECTION ( 'NONE', ( 0.0006039748319371618076, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#1631 = VERTEX_POINT ( 'NONE', #34093 ) ; +#1630 = CARTESIAN_POINT ( 'NONE', ( -48.01998785487717214, 140.9756894717409921, 337.4478224868454390 ) ) ; +#1632 = ORIENTED_EDGE ( 'NONE', *, *, #7968, .T. ) ; +#1633 = VERTEX_POINT ( 'NONE', #34286 ) ; +#1634 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #1014, #19805, #4275, #29244 ), + ( #13698, #4479, #26790, #8383 ), + ( #24339, #33705, #23926, #30664 ), + ( #23712, #24125, #15126, #17552 ), + ( #23505, #35950, #2246, #30056 ), + ( #14514, #20423, #26997, #17755 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 4 ), + ( 4, 4 ), + ( -0.4155779329647000253, 0.000000000000000000, 1.000000000000000000, 1.415577932946999962 ), + ( -2.649034374246999819E-06, 1.000000498574000085 ), + .UNSPECIFIED. ) ; +#1635 = ORIENTED_EDGE ( 'NONE', *, *, #21232, .T. ) ; +#1636 = DIRECTION ( 'NONE', ( -0.0005884949961222158072, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#1637 = EDGE_CURVE ( 'NONE', #1066, #6048, #15476, .T. ) ; +#1638 = EDGE_CURVE ( 'NONE', #29169, #315, #15885, .T. ) ; +#1639 = DIRECTION ( 'NONE', ( -0.0005884949961259294164, 0.2255194585872565272, -0.9742384859325513569 ) ) ; +#1640 = CARTESIAN_POINT ( 'NONE', ( 5.666479358130328770, 124.0060029548555747, 91.08908426695600724 ) ) ; +#1641 = EDGE_CURVE ( 'NONE', #16629, #28767, #11431, .T. ) ; +#1642 = EDGE_CURVE ( 'NONE', #27747, #26044, #969, .T. ) ; +#1643 = EDGE_LOOP ( 'NONE', ( #39936, #1550, #8615, #26290 ) ) ; +#1644 = VECTOR ( 'NONE', #26638, 1000.000000000000114 ) ; +#1645 = CARTESIAN_POINT ( 'NONE', ( -39.38652048934942940, 144.7445250280709388, 291.5823324066636815 ) ) ; +#1646 = CARTESIAN_POINT ( 'NONE', ( -38.89126635191712467, 161.9501278596379450, 193.0760327218276871 ) ) ; +#1647 = CARTESIAN_POINT ( 'NONE', ( 13.00945118851879201, 131.0224190692395041, 89.89397262767793961 ) ) ; +#1648 = CARTESIAN_POINT ( 'NONE', ( 20.33240943743538054, 194.1236379049751406, 102.8213690648429548 ) ) ; +#1649 = AXIS2_PLACEMENT_3D ( 'NONE', #49, #31942, #3106 ) ; +#1650 = VECTOR ( 'NONE', #23242, 1000.000000000000227 ) ; +#1651 = CARTESIAN_POINT ( 'NONE', ( -35.29591335509000771, 113.4357239256000014, 87.14400150545999679 ) ) ; +#1652 = ORIENTED_EDGE ( 'NONE', *, *, #4773, .T. ) ; +#1653 = AXIS2_PLACEMENT_3D ( 'NONE', #11224, #26369, #25973 ) ; +#1654 = EDGE_CURVE ( 'NONE', #11739, #21377, #31707, .T. ) ; +#1655 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; +#1656 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11659, #30471, #33312, #33107 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1657 = ORIENTED_EDGE ( 'NONE', *, *, #24759, .T. ) ; +#1658 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; +#1659 = CARTESIAN_POINT ( 'NONE', ( 5.669252811192786012, 130.1726803172889788, 92.54178110873570517 ) ) ; +#1660 = DIRECTION ( 'NONE', ( 0.0006039748319383109534, 1.233022124494217175E-14, 0.9999998176071845934 ) ) ; +#1661 = DIRECTION ( 'NONE', ( 0.0005884949961230158400, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1662 = ADVANCED_FACE ( 'NONE', ( #6681 ), #7285, .T. ) ; +#1663 = VERTEX_POINT ( 'NONE', #16688 ) ; +#1664 = CARTESIAN_POINT ( 'NONE', ( -1.066844550517989987, 188.6634431852420164, 103.2086216232000027 ) ) ; +#1665 = CARTESIAN_POINT ( 'NONE', ( 0.5626216234312498843, 189.0102564277180477, 103.6972895962819763 ) ) ; +#1666 = CARTESIAN_POINT ( 'NONE', ( 26.00516268442190793, 120.3264862181168269, 90.49568530838079994 ) ) ; +#1667 = VERTEX_POINT ( 'NONE', #25729 ) ; +#1668 = ORIENTED_EDGE ( 'NONE', *, *, #3138, .T. ) ; +#1669 = CARTESIAN_POINT ( 'NONE', ( -19.73768723704201378, 124.3505960279316014, 178.1528323905962452 ) ) ; +#1670 = CARTESIAN_POINT ( 'NONE', ( 2.561557522426483491, 191.9759150222000130, 101.9199002238076162 ) ) ; +#1671 = ORIENTED_EDGE ( 'NONE', *, *, #18153, .T. ) ; +#1672 = ORIENTED_EDGE ( 'NONE', *, *, #35442, .F. ) ; +#1673 = EDGE_CURVE ( 'NONE', #28941, #31885, #10125, .T. ) ; +#1674 = ORIENTED_EDGE ( 'NONE', *, *, #28442, .T. ) ; +#1675 = LINE ( 'NONE', #34979, #25682 ) ; +#1676 = CONICAL_SURFACE ( 'NONE', #15486, 2.502997276898424772, 0.7853981634249621591 ) ; +#1677 = ORIENTED_EDGE ( 'NONE', *, *, #29348, .F. ) ; +#1678 = CARTESIAN_POINT ( 'NONE', ( -26.88272198619890929, 189.0093189843405810, 103.3053996347941563 ) ) ; +#1679 = VECTOR ( 'NONE', #1020, 1000.000000000000114 ) ; +#1680 = CARTESIAN_POINT ( 'NONE', ( -27.86327580912480073, 186.6948185159119760, 105.3339871752620240 ) ) ; +#1681 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#1682 = VECTOR ( 'NONE', #5234, 1000.000000000000227 ) ; +#1683 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700556569576676, 0.2249510938827756212 ) ) ; +#1684 = CARTESIAN_POINT ( 'NONE', ( 33.79593125840131762, 218.5902260770999987, 76.03809273397367008 ) ) ; +#1685 = AXIS2_PLACEMENT_3D ( 'NONE', #34781, #19251, #31761 ) ; +#1686 = ORIENTED_EDGE ( 'NONE', *, *, #13023, .T. ) ; +#1687 = AXIS2_PLACEMENT_3D ( 'NONE', #27779, #11623, #27387 ) ; +#1688 = CARTESIAN_POINT ( 'NONE', ( 27.65192971970000002, 123.9789225586000043, 91.33799792313000410 ) ) ; +#1689 = CARTESIAN_POINT ( 'NONE', ( -15.10714331244187214, 129.6097141051087362, 89.58480571958619976 ) ) ; +#1691 = CARTESIAN_POINT ( 'NONE', ( -30.06407784565124430, 177.7873364699197793, 100.7165267053679969 ) ) ; +#1690 = CARTESIAN_POINT ( 'NONE', ( 20.48207276949980127, 207.8589230177659601, 76.36517592881708083 ) ) ; +#1692 = ORIENTED_EDGE ( 'NONE', *, *, #687, .F. ) ; +#1693 = CYLINDRICAL_SURFACE ( 'NONE', #148, 2.000000000000001332 ) ; +#1694 = ORIENTED_EDGE ( 'NONE', *, *, #9777, .T. ) ; +#1695 = CARTESIAN_POINT ( 'NONE', ( -36.00652865386367552, 192.1144112819058023, 104.4280603975805235 ) ) ; +#1696 = DIRECTION ( 'NONE', ( -0.5668486650917774483, -0.8238218701100766816, 0.0003423623896884662554 ) ) ; +#1697 = EDGE_CURVE ( 'NONE', #9728, #723, #23856, .T. ) ; +#1698 = ADVANCED_FACE ( 'NONE', ( #17489 ), #29581, .F. ) ; +#1699 = VERTEX_POINT ( 'NONE', #4817 ) ; +#1700 = LINE ( 'NONE', #36026, #20439 ) ; +#1701 = CYLINDRICAL_SURFACE ( 'NONE', #37611, 1.999999999999996891 ) ; +#1702 = DIRECTION ( 'NONE', ( -0.0005884949961247390709, 0.2249510543439058041, -0.9743698870671265722 ) ) ; +#1703 = CARTESIAN_POINT ( 'NONE', ( 39.06422788861904394, 183.0561992322088543, 104.9700959750892366 ) ) ; +#1704 = CARTESIAN_POINT ( 'NONE', ( 36.42052453417999658, 191.8205691569000066, 104.3714196691999945 ) ) ; +#1705 = ORIENTED_EDGE ( 'NONE', *, *, #24149, .T. ) ; +#1706 = ORIENTED_EDGE ( 'NONE', *, *, #7178, .F. ) ; +#1707 = CARTESIAN_POINT ( 'NONE', ( -12.63072017624268106, 177.7897717398484474, 100.7065154983451407 ) ) ; +#1708 = CARTESIAN_POINT ( 'NONE', ( -59.73339157710076819, 246.2640820602804013, 199.3617278787578755 ) ) ; +#1709 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16202, #9892, #35192, #31965 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1710 = CIRCLE ( 'NONE', #8248, 2.249999999984614973 ) ; +#1711 = VECTOR ( 'NONE', #27959, 1000.000000000000227 ) ; +#1712 = CARTESIAN_POINT ( 'NONE', ( 15.83961671131613613, 186.7686801668171483, 102.7623040876351723 ) ) ; +#1713 = ORIENTED_EDGE ( 'NONE', *, *, #1798, .T. ) ; +#1714 = CARTESIAN_POINT ( 'NONE', ( -48.18209110666130357, 82.27946979429619034, 302.5876467172398634 ) ) ; +#1715 = VECTOR ( 'NONE', #11009, 1000.000000000000227 ) ; +#1716 = AXIS2_PLACEMENT_3D ( 'NONE', #6774, #18833, #34571 ) ; +#1717 = CARTESIAN_POINT ( 'NONE', ( 3.064242058871999852, 190.8511667218000127, 106.7914563315000009 ) ) ; +#1718 = ORIENTED_EDGE ( 'NONE', *, *, #7086, .T. ) ; +#1719 = CARTESIAN_POINT ( 'NONE', ( -40.98386719339310957, 220.4002260739994199, 28.08353656469164150 ) ) ; +#1720 = ADVANCED_FACE ( 'NONE', ( #23651 ), #9482, .F. ) ; +#1721 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971519328 ) ) ; +#1722 = CARTESIAN_POINT ( 'NONE', ( 20.00028792540915035, 151.9820690596619102, 94.72877128701482263 ) ) ; +#1723 = VERTEX_POINT ( 'NONE', #23445 ) ; +#1724 = CARTESIAN_POINT ( 'NONE', ( 3.534086375177905914, 137.3581944094399603, 91.36238397499714381 ) ) ; +#1725 = CARTESIAN_POINT ( 'NONE', ( 28.46393509241999809, 182.0672870804658601, 102.1824291493838359 ) ) ; +#1726 = VERTEX_POINT ( 'NONE', #20360 ) ; +#1727 = CONICAL_SURFACE ( 'NONE', #414, 5.250000000012863488, 0.7853981634080012819 ) ; +#1728 = FACE_OUTER_BOUND ( 'NONE', #19275, .T. ) ; +#1729 = AXIS2_PLACEMENT_3D ( 'NONE', #17464, #8496, #30162 ) ; +#1730 = AXIS2_PLACEMENT_3D ( 'NONE', #35295, #32460, #17094 ) ; +#1732 = CARTESIAN_POINT ( 'NONE', ( 13.46612284730906950, 158.3062971533392158, 96.19268454968825210 ) ) ; +#1731 = DIRECTION ( 'NONE', ( -0.6087613503636615242, -0.7731003948486159238, -0.1781162479627431405 ) ) ; +#1733 = EDGE_LOOP ( 'NONE', ( #25016, #28531, #11838, #826, #10425, #31844, #3411, #24731 ) ) ; +#1734 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1735 = ORIENTED_EDGE ( 'NONE', *, *, #20374, .F. ) ; +#1736 = LINE ( 'NONE', #23413, #17276 ) ; +#1737 = CARTESIAN_POINT ( 'NONE', ( 37.20222003302175295, 191.1065312683467994, 106.3012689043733729 ) ) ; +#1738 = VECTOR ( 'NONE', #1349, 1000.000000000000227 ) ; +#1739 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178539432571E-05, -0.0002331579774923554001 ) ) ; +#1740 = ADVANCED_FACE ( 'NONE', ( #2186 ), #32835, .T. ) ; +#1741 = EDGE_LOOP ( 'NONE', ( #19569, #17634, #19280, #10149 ) ) ; +#1742 = EDGE_CURVE ( 'NONE', #10482, #24364, #33640, .T. ) ; +#1743 = EDGE_LOOP ( 'NONE', ( #26143, #15422, #26768, #25960 ) ) ; +#1744 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001011, 118.9382625071999939, 90.21260570929000266 ) ) ; +#1745 = ORIENTED_EDGE ( 'NONE', *, *, #25624, .F. ) ; +#1746 = VERTEX_POINT ( 'NONE', #26936 ) ; +#1747 = ORIENTED_EDGE ( 'NONE', *, *, #37374, .T. ) ; +#1748 = CARTESIAN_POINT ( 'NONE', ( -76.10925030609094222, 156.2403276578085354, 96.28296423947058713 ) ) ; +#1749 = CARTESIAN_POINT ( 'NONE', ( 2.711028262986999948, 208.9737165866999931, 73.44859440743999812 ) ) ; +#1750 = CARTESIAN_POINT ( 'NONE', ( -15.74985326587000145, 145.0241313536000121, 93.40046917799001847 ) ) ; +#1751 = EDGE_LOOP ( 'NONE', ( #22994, #11975, #15487, #4511 ) ) ; +#1752 = DIRECTION ( 'NONE', ( -0.6087614115774880874, -0.7729348350621346730, -0.1788331191967951483 ) ) ; +#1753 = CARTESIAN_POINT ( 'NONE', ( -36.08413483559999690, 192.4673174437999990, 104.5417621097000165 ) ) ; +#1754 = CARTESIAN_POINT ( 'NONE', ( 36.48506658101999989, 191.6574214057999939, 104.2272696579999973 ) ) ; +#1755 = CARTESIAN_POINT ( 'NONE', ( -25.50167171021992729, 120.6339921492297691, 88.03071599454854379 ) ) ; +#1756 = EDGE_LOOP ( 'NONE', ( #9880, #9265, #18210, #21821 ) ) ; +#1757 = CARTESIAN_POINT ( 'NONE', ( 22.78039439248025388, 158.5567501843645175, 96.58697503864370049 ) ) ; +#1758 = LINE ( 'NONE', #35462, #17587 ) ; +#1759 = EDGE_LOOP ( 'NONE', ( #24890, #13185, #25553, #34734 ) ) ; +#1760 = CIRCLE ( 'NONE', #40278, 40.49999999999691624 ) ; +#1761 = CARTESIAN_POINT ( 'NONE', ( -6.036405711824646581, 134.8430548843712131, 93.35330002513178727 ) ) ; +#1762 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#1763 = VECTOR ( 'NONE', #5679, 1000.000000000000114 ) ; +#1764 = CARTESIAN_POINT ( 'NONE', ( -20.68588240384768540, 105.5805168953082926, 90.28027859384218345 ) ) ; +#1765 = FACE_OUTER_BOUND ( 'NONE', #17434, .T. ) ; +#1766 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #24992, #16165, #13109, #15953 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.841034667652916568, 4.841107087194696845 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999995629507143, 0.9999999995629507143, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#1767 = AXIS2_PLACEMENT_3D ( 'NONE', #1939, #5398, #36891 ) ; +#1768 = ORIENTED_EDGE ( 'NONE', *, *, #251, .F. ) ; +#1769 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425095181, 127.0691889891074879, 92.07622024688510010 ) ) ; +#1770 = CARTESIAN_POINT ( 'NONE', ( 1.556177609192770150, 189.2631122045734458, 103.7597856918706043 ) ) ; +#1771 = CARTESIAN_POINT ( 'NONE', ( 30.39613569156224315, 134.9224406131777982, 90.78386258933660713 ) ) ; +#1772 = VECTOR ( 'NONE', #18026, 1000.000000000000227 ) ; +#1773 = ORIENTED_EDGE ( 'NONE', *, *, #29619, .T. ) ; +#1774 = DIRECTION ( 'NONE', ( -0.7933533411653076461, -0.5931840316265235558, -0.1368326740407657394 ) ) ; +#1775 = ORIENTED_EDGE ( 'NONE', *, *, #30553, .T. ) ; +#1776 = ORIENTED_EDGE ( 'NONE', *, *, #3338, .T. ) ; +#1777 = CARTESIAN_POINT ( 'NONE', ( -26.12781721057000084, 191.8495054948000131, 103.7969297097000094 ) ) ; +#1778 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825791858209745, 0.0005734119053476003985 ) ) ; +#1779 = CARTESIAN_POINT ( 'NONE', ( -20.07746641892443407, 128.4445336449384740, 89.31880444343536851 ) ) ; +#1780 = CYLINDRICAL_SURFACE ( 'NONE', #38877, 1.999999999999999112 ) ; +#1781 = ORIENTED_EDGE ( 'NONE', *, *, #23518, .F. ) ; +#1782 = ADVANCED_FACE ( 'NONE', ( #8316 ), #20556, .T. ) ; +#1783 = DIRECTION ( 'NONE', ( -0.0005884949961230898910, 0.2249510543439054988, -0.9743698870671265722 ) ) ; +#1784 = EDGE_CURVE ( 'NONE', #38161, #711, #5559, .T. ) ; +#1785 = CARTESIAN_POINT ( 'NONE', ( -23.39847246861572927, 115.1132396649264962, 87.28191638308530287 ) ) ; +#1786 = CARTESIAN_POINT ( 'NONE', ( -16.42123257736666275, 122.1227050838390653, 174.6864616558028445 ) ) ; +#1787 = AXIS2_PLACEMENT_3D ( 'NONE', #24210, #18032, #11309 ) ; +#1788 = CARTESIAN_POINT ( 'NONE', ( -38.21276943808967275, 153.0051697192222093, 297.5816245847972255 ) ) ; +#1789 = FACE_OUTER_BOUND ( 'NONE', #23420, .T. ) ; +#1790 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490108596958, 156.2427122712026062, 96.23754757949618011 ) ) ; +#1791 = DIRECTION ( 'NONE', ( 0.0006039748319369173200, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#1792 = ADVANCED_FACE ( 'NONE', ( #3164 ), #33844, .F. ) ; +#1793 = CARTESIAN_POINT ( 'NONE', ( -29.78212191064955761, 126.7137319910847708, 90.46453513447823980 ) ) ; +#1794 = EDGE_CURVE ( 'NONE', #5370, #20125, #40300, .T. ) ; +#1795 = CARTESIAN_POINT ( 'NONE', ( -38.57808178432087942, 119.0279670604091820, 87.73290398861043116 ) ) ; +#1796 = AXIS2_PLACEMENT_3D ( 'NONE', #38585, #39197, #5045 ) ; +#1797 = ORIENTED_EDGE ( 'NONE', *, *, #40436, .T. ) ; +#1798 = EDGE_CURVE ( 'NONE', #33715, #35551, #23732, .T. ) ; +#1799 = CARTESIAN_POINT ( 'NONE', ( 3.655560249847248144, 144.1901243002204751, 93.06410108720389474 ) ) ; +#1800 = EDGE_CURVE ( 'NONE', #23221, #37342, #16890, .T. ) ; +#1801 = CARTESIAN_POINT ( 'NONE', ( -31.70566062302000887, 225.9002260770971873, 73.07765350693868811 ) ) ; +#1802 = ORIENTED_EDGE ( 'NONE', *, *, #2451, .T. ) ; +#1803 = CARTESIAN_POINT ( 'NONE', ( 5.659931281361317623, 181.6896837046558346, 101.5959228839198687 ) ) ; +#1804 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927782063840, 0.0005734119022076108281 ) ) ; +#1805 = EDGE_LOOP ( 'NONE', ( #15677, #28919, #3361, #5002 ) ) ; +#1806 = CARTESIAN_POINT ( 'NONE', ( 24.52696613582132557, 213.0893819282258050, 73.54350799898485036 ) ) ; +#1807 = EDGE_LOOP ( 'NONE', ( #22407, #15989, #4038 ) ) ; +#1808 = DIRECTION ( 'NONE', ( -0.7075229308291650643, 0.000000000000000000, -0.7066903864854172657 ) ) ; +#1809 = FACE_OUTER_BOUND ( 'NONE', #21480, .T. ) ; +#1810 = DIRECTION ( 'NONE', ( -0.7947985590179719173, 0.5913221741348984040, 0.1365039814779489546 ) ) ; +#1811 = CARTESIAN_POINT ( 'NONE', ( 39.71700394620562946, 182.4828400535788546, 106.8893805178791894 ) ) ; +#1812 = CARTESIAN_POINT ( 'NONE', ( -4.036264725700203115, 136.7920597759830628, 93.80205530682346193 ) ) ; +#1813 = ORIENTED_EDGE ( 'NONE', *, *, #33990, .F. ) ; +#1814 = DIRECTION ( 'NONE', ( -0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; +#1815 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1870, #17589, #14345, #27035 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1816 = EDGE_CURVE ( 'NONE', #16566, #18505, #15353, .T. ) ; +#1817 = PLANE ( 'NONE', #4204 ) ; +#1818 = AXIS2_PLACEMENT_3D ( 'NONE', #14542, #14339, #35984 ) ; +#1819 = CARTESIAN_POINT ( 'NONE', ( -13.47107783232944378, 153.8044057555319739, 95.68275536702104489 ) ) ; +#1820 = VERTEX_POINT ( 'NONE', #24680 ) ; +#1821 = CARTESIAN_POINT ( 'NONE', ( 25.53747175047978857, 190.9172658757476313, 106.2799836673595024 ) ) ; +#1822 = CARTESIAN_POINT ( 'NONE', ( -41.76265597088985970, 120.7057567815182182, 90.62417689729259962 ) ) ; +#1823 = AXIS2_PLACEMENT_3D ( 'NONE', #1523, #26485, #23824 ) ; +#1824 = CARTESIAN_POINT ( 'NONE', ( 4.034499241564549976, 175.2435454650956217, 100.6217987443190509 ) ) ; +#1825 = FACE_OUTER_BOUND ( 'NONE', #26481, .T. ) ; +#1826 = CARTESIAN_POINT ( 'NONE', ( 36.05502599160040234, 113.1256265659911264, 89.73543636218946062 ) ) ; +#1827 = CARTESIAN_POINT ( 'NONE', ( 2.510969621544003605, 209.3808403806999934, 73.56099024588000646 ) ) ; +#1828 = EDGE_CURVE ( 'NONE', #10693, #14260, #7128, .T. ) ; +#1829 = CARTESIAN_POINT ( 'NONE', ( 13.50147201671756214, 126.2418300118542902, 91.35575004871967053 ) ) ; +#1830 = CARTESIAN_POINT ( 'NONE', ( 5.659153654835778369, 124.3673852322629187, 88.36203164978959990 ) ) ; +#1831 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825905884072336, 0.0005734119027128889391 ) ) ; +#1832 = ADVANCED_FACE ( 'NONE', ( #30596 ), #32333, .F. ) ; +#1833 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1978, #24056, #17073, #39170 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1834 = CARTESIAN_POINT ( 'NONE', ( -35.69795641737000125, 112.9281708400999946, 87.53934500879000780 ) ) ; +#1835 = CARTESIAN_POINT ( 'NONE', ( 3.467344452005765909, 182.9186892984050701, 101.8809360402982094 ) ) ; +#1836 = VERTEX_POINT ( 'NONE', #36930 ) ; +#1837 = ADVANCED_FACE ( 'NONE', ( #33647 ), #10130, .F. ) ; +#1838 = CARTESIAN_POINT ( 'NONE', ( 44.97084429314561049, 114.9968340379079166, 129.9902062988158491 ) ) ; +#1839 = CARTESIAN_POINT ( 'NONE', ( -44.46004285478915108, 188.8078265508242168, 105.8352584314367135 ) ) ; +#1840 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825996983, 153.3598638654817989, 97.61100683840648173 ) ) ; +#1841 = FACE_OUTER_BOUND ( 'NONE', #12286, .T. ) ; +#1842 = ADVANCED_FACE ( 'NONE', ( #11793 ), #27743, .F. ) ; +#1843 = CYLINDRICAL_SURFACE ( 'NONE', #1057, 2.000000000000001332 ) ; +#1844 = ORIENTED_EDGE ( 'NONE', *, *, #8927, .F. ) ; +#1845 = VERTEX_POINT ( 'NONE', #12569 ) ; +#1846 = ADVANCED_FACE ( 'NONE', ( #24273 ), #4885, .F. ) ; +#1847 = EDGE_LOOP ( 'NONE', ( #37, #29008, #34458, #6440 ) ) ; +#1848 = CARTESIAN_POINT ( 'NONE', ( -23.35923118230594042, 177.6405394001936315, 100.8049717976453508 ) ) ; +#1849 = VECTOR ( 'NONE', #847, 1000.000000000000227 ) ; +#1850 = PLANE ( 'NONE', #8544 ) ; +#1851 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#1852 = VECTOR ( 'NONE', #28308, 1000.000000000000114 ) ; +#1853 = ORIENTED_EDGE ( 'NONE', *, *, #9315, .F. ) ; +#1854 = DIRECTION ( 'NONE', ( 0.0004161288024546937149, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#1855 = CARTESIAN_POINT ( 'NONE', ( -13.49694790808628042, 187.4862234950086588, 105.7766966278750971 ) ) ; +#1856 = CARTESIAN_POINT ( 'NONE', ( 19.99905349769186458, 193.8169544161346494, 102.6908434160864800 ) ) ; +#1857 = CARTESIAN_POINT ( 'NONE', ( -37.63347317150000038, 118.2019778077000041, 87.61857096769999487 ) ) ; +#1858 = ORIENTED_EDGE ( 'NONE', *, *, #1898, .F. ) ; +#1859 = CARTESIAN_POINT ( 'NONE', ( -19.40391524180801852, 125.1988234544515137, 176.6053550468570563 ) ) ; +#1860 = ORIENTED_EDGE ( 'NONE', *, *, #26133, .F. ) ; +#1861 = CARTESIAN_POINT ( 'NONE', ( -15.99864732207169027, 174.8804197950794901, 100.0369119330590593 ) ) ; +#1862 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971549027 ) ) ; +#1863 = CARTESIAN_POINT ( 'NONE', ( -20.50069624036807880, 196.1175417876341385, 103.6936179443737842 ) ) ; +#1864 = LINE ( 'NONE', #30276, #25443 ) ; +#1865 = CARTESIAN_POINT ( 'NONE', ( 28.46460725226640065, 186.8972851080696387, 105.8632825901553218 ) ) ; +#1866 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#1867 = ORIENTED_EDGE ( 'NONE', *, *, #36044, .T. ) ; +#1868 = ORIENTED_EDGE ( 'NONE', *, *, #763, .T. ) ; +#1869 = CARTESIAN_POINT ( 'NONE', ( -2.551856185010000111, 190.4600180632000104, 103.9472556680999986 ) ) ; +#1870 = CARTESIAN_POINT ( 'NONE', ( 39.53379105069361543, 120.3902222971681368, 87.42331650858173475 ) ) ; +#1871 = DIRECTION ( 'NONE', ( -0.0005884949961373456316, 0.2249510543438897892, -0.9743698870671301249 ) ) ; +#1872 = VERTEX_POINT ( 'NONE', #8727 ) ; +#1873 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498900786, 134.9773540766985604, 93.88293913757411246 ) ) ; +#1874 = ORIENTED_EDGE ( 'NONE', *, *, #26487, .T. ) ; +#1875 = ORIENTED_EDGE ( 'NONE', *, *, #27403, .F. ) ; +#1876 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15344, #21497, #40268, #34135, #33738, #33528, #5521, #11883, #18187, #27838, #30690, #3058, #12277, #2689, #37615, #15153, #27640 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000005668521, 0.1875000000008565093, 0.2187500000009763579, 0.2343750000010360601, 0.2500000000010957346, 0.3750000000009479639, 0.4375000000008490431, 0.4687500000008210654, 0.5000000000007931433, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1877 = AXIS2_PLACEMENT_3D ( 'NONE', #18183, #24763, #24560 ) ; +#1878 = EDGE_CURVE ( 'NONE', #23153, #3788, #6428, .T. ) ; +#1879 = EDGE_CURVE ( 'NONE', #14192, #36762, #38196, .T. ) ; +#1880 = VECTOR ( 'NONE', #2439, 1000.000000000000227 ) ; +#1881 = ORIENTED_EDGE ( 'NONE', *, *, #362, .F. ) ; +#1882 = AXIS2_PLACEMENT_3D ( 'NONE', #2339, #36675, #27306 ) ; +#1883 = ADVANCED_FACE ( 'NONE', ( #2965 ), #35556, .F. ) ; +#1884 = EDGE_LOOP ( 'NONE', ( #23826, #31130, #8831, #15200 ) ) ; +#1885 = CARTESIAN_POINT ( 'NONE', ( 3.066237086918227384, 190.8104827972501596, 106.7820556061583517 ) ) ; +#1886 = DIRECTION ( 'NONE', ( 9.251858538558595218E-16, -0.9743700557921587402, -0.2249510932971549027 ) ) ; +#1887 = VECTOR ( 'NONE', #9433, 1000.000000000000114 ) ; +#1888 = LINE ( 'NONE', #23155, #14993 ) ; +#1889 = EDGE_LOOP ( 'NONE', ( #17118, #22770, #25889, #13226 ) ) ; +#1890 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1891 = ORIENTED_EDGE ( 'NONE', *, *, #10254, .F. ) ; +#1892 = ADVANCED_FACE ( 'NONE', ( #24877 ), #7504, .F. ) ; +#1893 = CARTESIAN_POINT ( 'NONE', ( 25.92039983084000099, 121.8646700609999982, 90.50868154741999660 ) ) ; +#1894 = DIRECTION ( 'NONE', ( 0.0005884949961255130828, -0.2249510543439061094, 0.9743698870671263501 ) ) ; +#1896 = FACE_OUTER_BOUND ( 'NONE', #17446, .T. ) ; +#1895 = CARTESIAN_POINT ( 'NONE', ( -12.63767699503999964, 177.1899956627526365, 101.0812418394431518 ) ) ; +#1897 = ORIENTED_EDGE ( 'NONE', *, *, #6812, .F. ) ; +#1898 = EDGE_CURVE ( 'NONE', #39827, #17225, #11059, .T. ) ; +#1899 = ORIENTED_EDGE ( 'NONE', *, *, #444, .F. ) ; +#1900 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#1901 = VERTEX_POINT ( 'NONE', #15837 ) ; +#1902 = CARTESIAN_POINT ( 'NONE', ( -36.68630558007769338, 117.4611287568297939, 87.28994190131942332 ) ) ; +#1903 = EDGE_CURVE ( 'NONE', #4191, #20872, #25172, .T. ) ; +#1904 = AXIS2_PLACEMENT_3D ( 'NONE', #22440, #9763, #31641 ) ; +#1905 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35639, #16112, #11138, #23604 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1906 = LINE ( 'NONE', #39300, #13505 ) ; +#1907 = CARTESIAN_POINT ( 'NONE', ( 16.16705078777268056, 152.4576016466090778, 178.9883717186631031 ) ) ; +#1908 = CARTESIAN_POINT ( 'NONE', ( 36.32604205261999653, 191.7173161736999987, 104.1914432412000195 ) ) ; +#1909 = ORIENTED_EDGE ( 'NONE', *, *, #21663, .F. ) ; +#1910 = VERTEX_POINT ( 'NONE', #25881 ) ; +#1911 = CONICAL_SURFACE ( 'NONE', #12350, 6.499999999869967127, 0.7853981633308297905 ) ; +#1912 = EDGE_LOOP ( 'NONE', ( #31595, #3027, #3584, #27622 ) ) ; +#1913 = VECTOR ( 'NONE', #12959, 1000.000000000000000 ) ; +#1914 = DIRECTION ( 'NONE', ( 0.7855473026356885047, 0.6188014303620751333, -0.0004744508866335521804 ) ) ; +#1915 = VECTOR ( 'NONE', #33904, 1000.000000000000114 ) ; +#1916 = CARTESIAN_POINT ( 'NONE', ( 15.97824167254727890, 186.2916992871397781, 102.6521006286546083 ) ) ; +#1917 = VERTEX_POINT ( 'NONE', #28533 ) ; +#1918 = CARTESIAN_POINT ( 'NONE', ( -35.64467888793660677, 191.6889051035020088, 106.9474356354359941 ) ) ; +#1919 = DIRECTION ( 'NONE', ( -0.1843855713908465477, -0.08049128666858569592, 0.9795525069302342125 ) ) ; +#1920 = ORIENTED_EDGE ( 'NONE', *, *, #21800, .F. ) ; +#1921 = CARTESIAN_POINT ( 'NONE', ( 3.668109984895000508, 124.1793125683000056, 91.39867154092999613 ) ) ; +#1922 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#1923 = CARTESIAN_POINT ( 'NONE', ( -5.668109638569103659, 126.1268167267171378, 91.85392722789381992 ) ) ; +#1924 = DIRECTION ( 'NONE', ( 1.734723475976797036E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#1925 = ADVANCED_FACE ( 'NONE', ( #35234 ), #19221, .F. ) ; +#1926 = ORIENTED_EDGE ( 'NONE', *, *, #8645, .T. ) ; +#1927 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; +#1928 = EDGE_CURVE ( 'NONE', #34430, #36179, #19427, .T. ) ; +#1929 = EDGE_CURVE ( 'NONE', #34340, #14392, #17951, .T. ) ; +#1930 = CARTESIAN_POINT ( 'NONE', ( 17.99823451501000093, 132.2978359559000410, 93.26432565574999956 ) ) ; +#1931 = CARTESIAN_POINT ( 'NONE', ( 25.67581203438339799, 191.9371493622001594, 104.2389531613646909 ) ) ; +#1932 = VECTOR ( 'NONE', #15830, 1000.000000000000227 ) ; +#1933 = EDGE_LOOP ( 'NONE', ( #24863, #21164, #1329 ) ) ; +#1934 = ADVANCED_FACE ( 'NONE', ( #7640 ), #13392, .F. ) ; +#1935 = VECTOR ( 'NONE', #39229, 1000.000000000000114 ) ; +#1936 = AXIS2_PLACEMENT_3D ( 'NONE', #568, #10204, #12862 ) ; +#1937 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.702666754117757870E-16, 0.0006039748319385827629 ) ) ; +#1939 = CARTESIAN_POINT ( 'NONE', ( 39.36767498017007227, 125.1708217663776423, 106.4887638017983704 ) ) ; +#1938 = CARTESIAN_POINT ( 'NONE', ( 15.99998378901094576, 184.9656665294078266, 102.3459542884652365 ) ) ; +#1940 = ORIENTED_EDGE ( 'NONE', *, *, #16823, .F. ) ; +#1941 = EDGE_CURVE ( 'NONE', #22242, #35941, #28428, .T. ) ; +#1942 = VERTEX_POINT ( 'NONE', #27086 ) ; +#1943 = ORIENTED_EDGE ( 'NONE', *, *, #28656, .T. ) ; +#1944 = CARTESIAN_POINT ( 'NONE', ( 3.073788346373000024, 209.7471523734000129, 76.19157238271999688 ) ) ; +#1945 = CARTESIAN_POINT ( 'NONE', ( 37.04254647716739157, 191.1764927423541565, 106.3114722328703010 ) ) ; +#1946 = LINE ( 'NONE', #14413, #26298 ) ; +#1947 = CARTESIAN_POINT ( 'NONE', ( -38.81665153276784963, 106.4214194585135544, 168.3324293193781784 ) ) ; +#1948 = VERTEX_POINT ( 'NONE', #20506 ) ; +#1949 = EDGE_LOOP ( 'NONE', ( #32841, #11567, #39473, #17013, #23360 ) ) ; +#1950 = CARTESIAN_POINT ( 'NONE', ( 13.88399914228467757, 136.0347715473272672, 91.56378953181273062 ) ) ; +#1951 = VERTEX_POINT ( 'NONE', #32787 ) ; +#1952 = VERTEX_POINT ( 'NONE', #35623 ) ; +#1953 = ORIENTED_EDGE ( 'NONE', *, *, #12137, .T. ) ; +#1954 = CARTESIAN_POINT ( 'NONE', ( 37.96340687623389698, 191.0388351520254560, 103.7347888148996446 ) ) ; +#1955 = LINE ( 'NONE', #14421, #7363 ) ; +#1956 = EDGE_CURVE ( 'NONE', #17689, #18171, #4910, .T. ) ; +#1957 = MANIFOLD_SOLID_BREP ( '\X2\570689d2\X0\12', #39407 ) ; +#1958 = CARTESIAN_POINT ( 'NONE', ( -2.480274637552000172, 189.0000000000000000, 32.65999473746001058 ) ) ; +#1959 = CARTESIAN_POINT ( 'NONE', ( -2.913189425919000097, 209.5191065594000008, 76.06629948724000201 ) ) ; +#1960 = EDGE_LOOP ( 'NONE', ( #27625, #36394, #34968, #4517, #16647, #38599, #15194, #17030, #38398, #13864 ) ) ; +#1961 = EDGE_LOOP ( 'NONE', ( #37045, #30897, #19780, #13910 ) ) ; +#1962 = CARTESIAN_POINT ( 'NONE', ( 14.55306318046054592, 176.9232825744718411, 100.4900915860747403 ) ) ; +#1963 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -1.540743955509789367E-33, 0.0006039748319385908944 ) ) ; +#1964 = CARTESIAN_POINT ( 'NONE', ( -36.35858970950000213, 191.9077732178000133, 104.5549816818000011 ) ) ; +#1965 = CARTESIAN_POINT ( 'NONE', ( 36.54974486126000244, 191.8647094490000029, 104.5085210141999994 ) ) ; +#1966 = CARTESIAN_POINT ( 'NONE', ( -26.00926449878999946, 121.0814862561000069, 87.62239126132999445 ) ) ; +#1967 = CONICAL_SURFACE ( 'NONE', #24837, 2.749999999872844381, 0.7853981633697728615 ) ; +#1968 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#1969 = EDGE_LOOP ( 'NONE', ( #19302, #18667, #40148, #18441 ) ) ; +#1970 = CARTESIAN_POINT ( 'NONE', ( 42.94150479285965361, 103.2019334172786529, 168.6346152762044710 ) ) ; +#1971 = CARTESIAN_POINT ( 'NONE', ( -26.75653968529694282, 131.0179918129932730, 89.91699612660660534 ) ) ; +#1972 = AXIS2_PLACEMENT_3D ( 'NONE', #26297, #35452, #29165 ) ; +#1973 = VERTEX_POINT ( 'NONE', #32979 ) ; +#1974 = VECTOR ( 'NONE', #24903, 1000.000000000000114 ) ; +#1975 = CARTESIAN_POINT ( 'NONE', ( -6.037294616552872029, 134.7461518313687066, 93.41385221303204389 ) ) ; +#1976 = AXIS2_PLACEMENT_3D ( 'NONE', #37774, #38186, #38378 ) ; +#1977 = CARTESIAN_POINT ( 'NONE', ( -35.93878493987466527, 193.8169247290984458, 102.7246158654606347 ) ) ; +#1978 = CARTESIAN_POINT ( 'NONE', ( -14.55306118018871508, 176.9194272080598296, 100.5067835523781667 ) ) ; +#1979 = CARTESIAN_POINT ( 'NONE', ( -21.44517133412774967, 181.8810903885702999, 104.7353468333731428 ) ) ; +#1980 = ORIENTED_EDGE ( 'NONE', *, *, #3474, .F. ) ; +#1981 = CARTESIAN_POINT ( 'NONE', ( 30.07038983360635243, 136.6834034282913422, 94.27269756974730797 ) ) ; +#1982 = CARTESIAN_POINT ( 'NONE', ( 2.243938541402742182, 189.9166128731624212, 103.9479121654673435 ) ) ; +#1983 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#1984 = VERTEX_POINT ( 'NONE', #11318 ) ; +#1985 = CARTESIAN_POINT ( 'NONE', ( -22.49862694078846559, 157.6261014233649576, 99.13627282167615817 ) ) ; +#1986 = ORIENTED_EDGE ( 'NONE', *, *, #35543, .T. ) ; +#1987 = EDGE_CURVE ( 'NONE', #7212, #13591, #38881, .T. ) ; +#1988 = CARTESIAN_POINT ( 'NONE', ( 3.166350953592421025, 126.8041585549839709, 88.92605846951083493 ) ) ; +#1989 = EDGE_CURVE ( 'NONE', #28826, #2748, #8159, .T. ) ; +#1990 = CARTESIAN_POINT ( 'NONE', ( -45.27486310239934397, 116.8517531720308540, 123.7677792994715560 ) ) ; +#1991 = DIRECTION ( 'NONE', ( -0.7066795775298636562, -1.911073989161491327E-16, 0.7075337269008548091 ) ) ; +#1992 = CARTESIAN_POINT ( 'NONE', ( -20.51880467302672173, 211.0905570380611493, 75.57084890002228406 ) ) ; +#1993 = CARTESIAN_POINT ( 'NONE', ( 6.030824592693510233, 134.9998097734520570, 90.92594956691499419 ) ) ; +#1994 = ORIENTED_EDGE ( 'NONE', *, *, #3019, .T. ) ; +#1995 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #25417, #34964 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#1996 = CARTESIAN_POINT ( 'NONE', ( -6.040934757040731462, 134.9721311960137200, 90.89113414393979440 ) ) ; +#1997 = CIRCLE ( 'NONE', #39189, 9.499999999982289722 ) ; +#1998 = CARTESIAN_POINT ( 'NONE', ( -26.00135273745824449, 117.7151665234863600, 87.28348845754496210 ) ) ; +#1999 = CARTESIAN_POINT ( 'NONE', ( -19.99829785685910011, 119.7153791177249502, 90.38236254249699186 ) ) ; +#2000 = AXIS2_PLACEMENT_3D ( 'NONE', #19223, #16170, #38044 ) ; +#2001 = CARTESIAN_POINT ( 'NONE', ( 19.71713340877300169, 124.4083419986981909, 178.1703837097148551 ) ) ; +#2002 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971522104 ) ) ; +#2003 = VECTOR ( 'NONE', #27728, 1000.000000000000227 ) ; +#2004 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971552635 ) ) ; +#2005 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455648501747, -31.54510897440487938, 136.4474729010642875 ) ) ; +#2006 = ORIENTED_EDGE ( 'NONE', *, *, #34992, .T. ) ; +#2007 = VERTEX_POINT ( 'NONE', #24006 ) ; +#2008 = CARTESIAN_POINT ( 'NONE', ( -30.07185925050865904, 175.2389475684547051, 100.6413366228390345 ) ) ; +#2009 = EDGE_CURVE ( 'NONE', #40324, #26903, #39351, .T. ) ; +#2010 = LINE ( 'NONE', #4847, #7908 ) ; +#2011 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28614, #38005, #22692, #12463 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2012 = EDGE_LOOP ( 'NONE', ( #27721, #39508, #16212, #10953 ) ) ; +#2013 = CARTESIAN_POINT ( 'NONE', ( -18.69575332400200907, 125.9675347290306036, 174.7275314831792912 ) ) ; +#2014 = CARTESIAN_POINT ( 'NONE', ( 3.869973094273203351, 136.7573060621185448, 93.95941861830546316 ) ) ; +#2015 = ORIENTED_EDGE ( 'NONE', *, *, #2178, .T. ) ; +#2016 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #13516, #3891, #20234, #10461 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.197186637354022753, 1.570796326794899667 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9884017699607163809, 0.9884017699607163809, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#2017 = CARTESIAN_POINT ( 'NONE', ( 23.64497629418776015, 213.5251522717376531, 73.54403244452512922 ) ) ; +#2018 = EDGE_LOOP ( 'NONE', ( #12154, #34064, #13154, #2370 ) ) ; +#2019 = CARTESIAN_POINT ( 'NONE', ( 75.24011746878784379, 195.1293300889719546, 195.0257767563242055 ) ) ; +#2020 = EDGE_CURVE ( 'NONE', #29127, #11548, #29735, .T. ) ; +#2021 = CARTESIAN_POINT ( 'NONE', ( -29.94659852274795497, 109.6131156702000027, 89.78587174317453901 ) ) ; +#2022 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#2023 = LINE ( 'NONE', #35928, #9015 ) ; +#2024 = CARTESIAN_POINT ( 'NONE', ( 33.37602094669033193, 84.06324503389978986, 284.1448219155665242 ) ) ; +#2025 = PLANE ( 'NONE', #21050 ) ; +#2026 = ORIENTED_EDGE ( 'NONE', *, *, #14707, .F. ) ; +#2027 = CARTESIAN_POINT ( 'NONE', ( 60.86545082361659809, 245.5374438537401147, 206.6753669249971495 ) ) ; +#2028 = VECTOR ( 'NONE', #28916, 1000.000000000000000 ) ; +#2029 = DIRECTION ( 'NONE', ( 0.6087614810001803489, -0.7729390313185899863, -0.1788147452386047165 ) ) ; +#2030 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#2031 = AXIS2_PLACEMENT_3D ( 'NONE', #6507, #21485, #6317 ) ; +#2032 = AXIS2_PLACEMENT_3D ( 'NONE', #26114, #13822, #21123 ) ; +#2033 = DIRECTION ( 'NONE', ( 0.7933533411653066469, 0.5931840316265238888, 0.1368326740407706521 ) ) ; +#2034 = EDGE_CURVE ( 'NONE', #30287, #23153, #14095, .T. ) ; +#2035 = ORIENTED_EDGE ( 'NONE', *, *, #27069, .F. ) ; +#2036 = CARTESIAN_POINT ( 'NONE', ( 3.168113141152071321, 127.9133523189982498, 92.26104312719712652 ) ) ; +#2037 = EDGE_CURVE ( 'NONE', #28262, #21459, #7637, .T. ) ; +#2038 = CARTESIAN_POINT ( 'NONE', ( 21.74144897322905479, 115.9285972877331830, 89.75488417657916784 ) ) ; +#2040 = ADVANCED_FACE ( 'NONE', ( #17026 ), #24531, .F. ) ; +#2039 = CARTESIAN_POINT ( 'NONE', ( 6.032898680163828686, 134.3314735182171944, 93.66704928364619320 ) ) ; +#2041 = LINE ( 'NONE', #23919, #607 ) ; +#2042 = CARTESIAN_POINT ( 'NONE', ( 21.59709472431439181, 115.2762503876805624, 188.9250028067568508 ) ) ; +#2043 = CARTESIAN_POINT ( 'NONE', ( -25.88585013892983966, 209.7107922446395207, 73.19837119205239162 ) ) ; +#2044 = CARTESIAN_POINT ( 'NONE', ( 0.5459373230907974550, 209.0000000000000000, 76.05817508704146235 ) ) ; +#2045 = CARTESIAN_POINT ( 'NONE', ( 20.48026842689764848, 209.2780769040354869, 73.54613605110799313 ) ) ; +#2046 = DIRECTION ( 'NONE', ( 0.0005559617617595236224, -0.3907311284869797730, 0.9205046855599435807 ) ) ; +#2047 = ORIENTED_EDGE ( 'NONE', *, *, #331, .F. ) ; +#2048 = DIRECTION ( 'NONE', ( -0.7933532411131101192, -0.5932638852154232811, -0.1364866195435442964 ) ) ; +#2049 = CARTESIAN_POINT ( 'NONE', ( -34.02993892823075583, 92.27472273181228957, 297.5790982599829704 ) ) ; +#2050 = CYLINDRICAL_SURFACE ( 'NONE', #33237, 2.000000000000014655 ) ; +#2051 = DIRECTION ( 'NONE', ( 0.0006039748319386405509, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#2053 = ORIENTED_EDGE ( 'NONE', *, *, #22665, .F. ) ; +#2052 = DIRECTION ( 'NONE', ( 0.0005884949961190483105, -0.2249510543439053878, 0.9743698870671265722 ) ) ; +#2054 = ORIENTED_EDGE ( 'NONE', *, *, #25083, .T. ) ; +#2055 = ORIENTED_EDGE ( 'NONE', *, *, #24760, .T. ) ; +#2056 = VECTOR ( 'NONE', #30544, 1000.000000000000000 ) ; +#2057 = CARTESIAN_POINT ( 'NONE', ( -2.902524173895590920, 190.6910093414263372, 103.6791650777964833 ) ) ; +#2058 = VERTEX_POINT ( 'NONE', #20313 ) ; +#2059 = CARTESIAN_POINT ( 'NONE', ( -23.36087230894777989, 177.4951561493269878, 100.8958181500985205 ) ) ; +#2060 = LINE ( 'NONE', #17768, #4606 ) ; +#2061 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425095181, 127.0691889891074879, 92.07622024688510010 ) ) ; +#2062 = ORIENTED_EDGE ( 'NONE', *, *, #29330, .F. ) ; +#2063 = LINE ( 'NONE', #17978, #24448 ) ; +#2064 = CARTESIAN_POINT ( 'NONE', ( -39.39285454264343400, 114.3643166784735712, 151.6767146082210047 ) ) ; +#2065 = CARTESIAN_POINT ( 'NONE', ( -20.01777344647963730, 205.1071326358727163, 76.11698016271346035 ) ) ; +#2066 = CARTESIAN_POINT ( 'NONE', ( -38.17491265577000092, 118.4147068048000193, 87.83922331386000337 ) ) ; +#2067 = VERTEX_POINT ( 'NONE', #16831 ) ; +#2068 = CARTESIAN_POINT ( 'NONE', ( -42.84327062420202026, 120.8099927651375936, 92.42850709477329474 ) ) ; +#2069 = ORIENTED_EDGE ( 'NONE', *, *, #28702, .T. ) ; +#2070 = DIRECTION ( 'NONE', ( 0.5987319960703996191, 0.8009494346596138792, 0.000000000000000000 ) ) ; +#2071 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30910, #37237, #36633, #39688 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2072 = DIRECTION ( 'NONE', ( 0.7066897571212915619, 0.1533500351137353224, -0.6907049687894724066 ) ) ; +#2073 = CARTESIAN_POINT ( 'NONE', ( -45.58628251432046596, 77.27946979429611929, 297.5860780019314120 ) ) ; +#2074 = CARTESIAN_POINT ( 'NONE', ( -20.16504595039701897, 190.8883395378736907, 106.6429623803627891 ) ) ; +#2075 = ORIENTED_EDGE ( 'NONE', *, *, #16204, .F. ) ; +#2076 = EDGE_CURVE ( 'NONE', #6998, #21074, #11128, .T. ) ; +#2077 = LINE ( 'NONE', #23958, #40228 ) ; +#2078 = CARTESIAN_POINT ( 'NONE', ( 0.5945138864921091226, 189.0183369199829713, 103.6969883959349801 ) ) ; +#2079 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091565633 ) ) ; +#2080 = CARTESIAN_POINT ( 'NONE', ( 26.00099507788276298, 120.2141150864606089, 90.46974490087802678 ) ) ; +#2081 = EDGE_CURVE ( 'NONE', #39778, #13439, #7844, .T. ) ; +#2082 = ORIENTED_EDGE ( 'NONE', *, *, #34054, .T. ) ; +#2083 = CIRCLE ( 'NONE', #23603, 7.500000000039277914 ) ; +#2084 = CARTESIAN_POINT ( 'NONE', ( -2.454301921840380096, 209.0000005845445230, 75.66282330657800514 ) ) ; +#2085 = ORIENTED_EDGE ( 'NONE', *, *, #15330, .T. ) ; +#2086 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #7451, #19718 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 0.9999998458841763416 ), + .UNSPECIFIED. ) ; +#2087 = ADVANCED_FACE ( 'NONE', ( #38916 ), #999, .T. ) ; +#2088 = EDGE_CURVE ( 'NONE', #32344, #30574, #7534, .T. ) ; +#2089 = CONICAL_SURFACE ( 'NONE', #6637, 4.500002634206803798, 0.7853981634336496542 ) ; +#2090 = EDGE_CURVE ( 'NONE', #21377, #11739, #30407, .T. ) ; +#2091 = CIRCLE ( 'NONE', #22979, 4.500000000005264233 ) ; +#2092 = ORIENTED_EDGE ( 'NONE', *, *, #32395, .F. ) ; +#2093 = ORIENTED_EDGE ( 'NONE', *, *, #22489, .F. ) ; +#2094 = CARTESIAN_POINT ( 'NONE', ( 3.027911450587273290, 190.4527856945552458, 106.6994978557500531 ) ) ; +#2095 = DIRECTION ( 'NONE', ( -0.0006039748319387576447, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#2096 = CARTESIAN_POINT ( 'NONE', ( -14.16859888750098406, 182.3077195333686120, 104.3162949350999185 ) ) ; +#2097 = CARTESIAN_POINT ( 'NONE', ( -41.70913856584510881, 120.6942229597581644, 90.62148178139578647 ) ) ; +#2098 = VERTEX_POINT ( 'NONE', #14202 ) ; +#2099 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.110223024625155594E-14, -1.000000000000000000 ) ) ; +#2100 = EDGE_LOOP ( 'NONE', ( #13564, #24934, #16974, #28888, #15211, #34512, #20267, #11906, #13227, #18932, #31618 ) ) ; +#2101 = CARTESIAN_POINT ( 'NONE', ( 26.06404824249079866, 120.9045055373159983, 90.63257663708037626 ) ) ; +#2102 = FACE_OUTER_BOUND ( 'NONE', #9994, .T. ) ; +#2104 = FACE_OUTER_BOUND ( 'NONE', #10167, .T. ) ; +#2103 = CARTESIAN_POINT ( 'NONE', ( -35.94780537806290965, 112.9281708400999946, 87.78949595528006000 ) ) ; +#2105 = ORIENTED_EDGE ( 'NONE', *, *, #32297, .F. ) ; +#2106 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971560406 ) ) ; +#2107 = EDGE_CURVE ( 'NONE', #7231, #25578, #11572, .T. ) ; +#2108 = ORIENTED_EDGE ( 'NONE', *, *, #30357, .F. ) ; +#2109 = CARTESIAN_POINT ( 'NONE', ( 36.44436247437651133, 190.8511614233640330, 106.7712946021073606 ) ) ; +#2110 = CONICAL_SURFACE ( 'NONE', #5361, 3.499999999893422586, 0.7853981634347139140 ) ; +#2111 = ORIENTED_EDGE ( 'NONE', *, *, #40007, .T. ) ; +#2112 = CARTESIAN_POINT ( 'NONE', ( 39.23603512625999912, 119.1639279199000043, 89.84421601804000090 ) ) ; +#2114 = VECTOR ( 'NONE', #12197, 1000.000000000000114 ) ; +#2113 = CARTESIAN_POINT ( 'NONE', ( -35.98614470123553843, 115.9822958763201655, 87.28951902169316668 ) ) ; +#2115 = CIRCLE ( 'NONE', #26279, 2.249999999963666397 ) ; +#2116 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386905326 ) ) ; +#2117 = CARTESIAN_POINT ( 'NONE', ( 3.534086375177905914, 137.3581944094399603, 91.36238397499714381 ) ) ; +#2118 = ORIENTED_EDGE ( 'NONE', *, *, #15549, .T. ) ; +#2119 = ORIENTED_EDGE ( 'NONE', *, *, #16309, .T. ) ; +#2120 = EDGE_CURVE ( 'NONE', #11382, #1948, #39121, .T. ) ; +#2121 = ORIENTED_EDGE ( 'NONE', *, *, #31154, .T. ) ; +#2122 = CARTESIAN_POINT ( 'NONE', ( -35.94659742830589266, 112.4664344042326576, 89.78949559119494950 ) ) ; +#2123 = DIRECTION ( 'NONE', ( 0.6087614115774879764, -0.7730004600455407937, -0.1785492440296699013 ) ) ; +#2124 = CARTESIAN_POINT ( 'NONE', ( 14.13092599226599155, 188.2870105248598236, 103.1138703412405846 ) ) ; +#2125 = ORIENTED_EDGE ( 'NONE', *, *, #11073, .F. ) ; +#2126 = ADVANCED_FACE ( 'NONE', ( #18044, #8470 ), #15597, .F. ) ; +#2127 = CARTESIAN_POINT ( 'NONE', ( 30.06790063874939634, 135.1133124594595643, 91.08871632618496506 ) ) ; +#2128 = ADVANCED_FACE ( 'NONE', ( #28095 ), #9517, .F. ) ; +#2129 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 151.1459109378392327, 96.08716200003422614 ) ) ; +#2130 = EDGE_LOOP ( 'NONE', ( #4325, #31033, #31887, #27472 ) ) ; +#2131 = CARTESIAN_POINT ( 'NONE', ( 5.667748567169940799, 130.5464144240118287, 90.19576013559581895 ) ) ; +#2132 = EDGE_CURVE ( 'NONE', #28309, #22653, #31556, .T. ) ; +#2133 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; +#2134 = DIRECTION ( 'NONE', ( -0.0005884949961240271837, 0.2249510543439050270, -0.9743698870671266832 ) ) ; +#2135 = CARTESIAN_POINT ( 'NONE', ( 5.505231156190700581, 148.7676655288644838, 93.99531868697803816 ) ) ; +#2136 = ORIENTED_EDGE ( 'NONE', *, *, #21192, .F. ) ; +#2137 = AXIS2_PLACEMENT_3D ( 'NONE', #24109, #36760, #39618 ) ; +#2138 = CARTESIAN_POINT ( 'NONE', ( 35.80370676812943742, 112.9281706819409692, 87.49619306724476075 ) ) ; +#2139 = LINE ( 'NONE', #10540, #16885 ) ; +#2140 = AXIS2_PLACEMENT_3D ( 'NONE', #1195, #10817, #17318 ) ; +#2141 = CIRCLE ( 'NONE', #18423, 2.000000000000000000 ) ; +#2142 = ORIENTED_EDGE ( 'NONE', *, *, #14080, .T. ) ; +#2143 = CYLINDRICAL_SURFACE ( 'NONE', #31272, 2.000000000000001332 ) ; +#2145 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2144 = CYLINDRICAL_SURFACE ( 'NONE', #22033, 6.000000000000001776 ) ; +#2146 = ORIENTED_EDGE ( 'NONE', *, *, #23311, .T. ) ; +#2147 = ORIENTED_EDGE ( 'NONE', *, *, #9702, .T. ) ; +#2148 = ORIENTED_EDGE ( 'NONE', *, *, #34626, .F. ) ; +#2149 = CARTESIAN_POINT ( 'NONE', ( 20.00006507825687407, 169.9346765372802963, 98.87342171090897125 ) ) ; +#2150 = DIRECTION ( 'NONE', ( -0.7066795775300234173, -3.556109467271558380E-18, 0.7075337269006952701 ) ) ; +#2151 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; +#2152 = CARTESIAN_POINT ( 'NONE', ( 15.05197310825490398, 136.6013035982805661, 91.18072662319218580 ) ) ; +#2153 = ORIENTED_EDGE ( 'NONE', *, *, #138, .T. ) ; +#2154 = ORIENTED_EDGE ( 'NONE', *, *, #38231, .T. ) ; +#2155 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35300, #32271, #9998, #4034 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2156 = PLANE ( 'NONE', #7618 ) ; +#2157 = ORIENTED_EDGE ( 'NONE', *, *, #15545, .T. ) ; +#2158 = ORIENTED_EDGE ( 'NONE', *, *, #20715, .F. ) ; +#2159 = ORIENTED_EDGE ( 'NONE', *, *, #33764, .T. ) ; +#2160 = CARTESIAN_POINT ( 'NONE', ( -20.00025820447960001, 138.1823733798348428, 91.56700283718186029 ) ) ; +#2161 = CARTESIAN_POINT ( 'NONE', ( 2.621867308820999831, 209.6150350132000426, 73.39025393530999963 ) ) ; +#2162 = VECTOR ( 'NONE', #23463, 1000.000000000000114 ) ; +#2163 = ORIENTED_EDGE ( 'NONE', *, *, #37508, .T. ) ; +#2164 = ADVANCED_FACE ( 'NONE', ( #33994 ), #12144, .F. ) ; +#2165 = ORIENTED_EDGE ( 'NONE', *, *, #38076, .F. ) ; +#2166 = FACE_OUTER_BOUND ( 'NONE', #5977, .T. ) ; +#2167 = EDGE_CURVE ( 'NONE', #7762, #34936, #22219, .T. ) ; +#2168 = CARTESIAN_POINT ( 'NONE', ( -36.07647867781999906, 191.8527882484000315, 104.2980684900999933 ) ) ; +#2170 = CONICAL_SURFACE ( 'NONE', #23059, 17.00000000000409273, 0.7853981633973132759 ) ; +#2169 = CARTESIAN_POINT ( 'NONE', ( 37.33863555023999936, 190.9616902955000057, 103.5698611074000013 ) ) ; +#2171 = EDGE_CURVE ( 'NONE', #9488, #14192, #25026, .T. ) ; +#2172 = VERTEX_POINT ( 'NONE', #2917 ) ; +#2173 = CARTESIAN_POINT ( 'NONE', ( -26.00150954189000174, 120.7873587952999941, 87.55495400204000589 ) ) ; +#2174 = VERTEX_POINT ( 'NONE', #18248 ) ; +#2175 = PLANE ( 'NONE', #27839 ) ; +#2176 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775999513 ) ) ; +#2177 = VERTEX_POINT ( 'NONE', #2329 ) ; +#2178 = EDGE_CURVE ( 'NONE', #21459, #23019, #15404, .T. ) ; +#2179 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3884, #1227, #16951, #35148, #16360, #28846, #824, #10854, #8598, #21065, #36796, #17963, #21266, #36178, #5304 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 1, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2080554551301270760, 0.2600693189126438987, 0.3120831826951607213, 0.4161109102601944221, 0.6241663653902360664, 0.7281940929552587205, 0.8322218205202811525 ), + .UNSPECIFIED. ) ; +#2180 = CARTESIAN_POINT ( 'NONE', ( -16.52242372029886042, 151.4997482901518424, 184.4407432091828412 ) ) ; +#2181 = CARTESIAN_POINT ( 'NONE', ( -6.063496305472453329, 163.0526542675453925, 100.2081181894236011 ) ) ; +#2182 = CARTESIAN_POINT ( 'NONE', ( -15.85326334123286784, 125.9778002666185017, 88.74676275371332679 ) ) ; +#2183 = ORIENTED_EDGE ( 'NONE', *, *, #39860, .T. ) ; +#2185 = ADVANCED_FACE ( 'NONE', ( #36668 ), #30545, .T. ) ; +#2184 = CARTESIAN_POINT ( 'NONE', ( -45.18718350925745852, 79.77698873149398651, 284.4103241537512190 ) ) ; +#2186 = FACE_OUTER_BOUND ( 'NONE', #12611, .T. ) ; +#2187 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; +#2188 = VERTEX_POINT ( 'NONE', #6191 ) ; +#2189 = DIRECTION ( 'NONE', ( -0.0004161288024660041661, 0.8480480897817621599, -0.5299191110483975065 ) ) ; +#2190 = ORIENTED_EDGE ( 'NONE', *, *, #8875, .F. ) ; +#2191 = CARTESIAN_POINT ( 'NONE', ( -6.635715103306525878E-14, 155.6803346354327289, 98.67347229705578115 ) ) ; +#2192 = CARTESIAN_POINT ( 'NONE', ( -2.455538055765680738, 209.0000002601700544, 73.61629604161946361 ) ) ; +#2193 = CARTESIAN_POINT ( 'NONE', ( -20.38954068182721713, 129.0978827080468534, 89.46983047235534059 ) ) ; +#2194 = CARTESIAN_POINT ( 'NONE', ( 17.25788849119799195, 152.5371962406647413, 182.4889206688251306 ) ) ; +#2195 = AXIS2_PLACEMENT_3D ( 'NONE', #20480, #30111, #36646 ) ; +#2196 = CARTESIAN_POINT ( 'NONE', ( -89.80707058824756928, 73.37406685903091841, 291.6127851554912240 ) ) ; +#2197 = ORIENTED_EDGE ( 'NONE', *, *, #5892, .F. ) ; +#2198 = VECTOR ( 'NONE', #10051, 1000.000000000000000 ) ; +#2199 = CARTESIAN_POINT ( 'NONE', ( 15.99998568644542907, 127.1172274350850557, 88.99058172675916012 ) ) ; +#2200 = AXIS2_PLACEMENT_3D ( 'NONE', #11977, #21591, #33833 ) ; +#2201 = DIRECTION ( 'NONE', ( 0.0005884949961193429967, -0.2249510543439072197, 0.9743698870671261281 ) ) ; +#2202 = CARTESIAN_POINT ( 'NONE', ( 5.666635157737871964, 181.3283579457949770, 104.3229600593109723 ) ) ; +#2203 = DIRECTION ( 'NONE', ( 0.0005884949521151187956, -0.2249510543284071740, 0.9743698870707311332 ) ) ; +#2204 = CARTESIAN_POINT ( 'NONE', ( 31.71706711663377476, 177.1986094558884020, 100.5432891884866393 ) ) ; +#2205 = CARTESIAN_POINT ( 'NONE', ( 44.72966403672144509, 167.5186349756792765, 188.6353666065691925 ) ) ; +#2206 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971560961 ) ) ; +#2207 = CARTESIAN_POINT ( 'NONE', ( -35.43806428669827824, 192.3002664666033468, 103.9163745585288297 ) ) ; +#2208 = EDGE_LOOP ( 'NONE', ( #19528, #38681, #10561 ) ) ; +#2209 = ORIENTED_EDGE ( 'NONE', *, *, #14999, .F. ) ; +#2210 = LINE ( 'NONE', #39601, #30858 ) ; +#2211 = LINE ( 'NONE', #20392, #13777 ) ; +#2212 = ORIENTED_EDGE ( 'NONE', *, *, #37778, .F. ) ; +#2213 = CARTESIAN_POINT ( 'NONE', ( -20.49970533150650454, 174.4001369415204863, 100.4419005550919906 ) ) ; +#2214 = EDGE_CURVE ( 'NONE', #189, #9198, #5613, .T. ) ; +#2215 = CARTESIAN_POINT ( 'NONE', ( -20.37991618439152930, 116.5981088392802718, 90.28009379790530886 ) ) ; +#2216 = EDGE_CURVE ( 'NONE', #4989, #12211, #2532, .T. ) ; +#2217 = VERTEX_POINT ( 'NONE', #30749 ) ; +#2218 = CARTESIAN_POINT ( 'NONE', ( 13.50164015316000032, 187.2961052448821704, 105.4512426002658003 ) ) ; +#2219 = CARTESIAN_POINT ( 'NONE', ( 25.67720680875275008, 191.4606997587383148, 106.5440792307656750 ) ) ; +#2220 = CARTESIAN_POINT ( 'NONE', ( -0.4376666143244844487, 188.6124751099401351, 103.1978086576974221 ) ) ; +#2221 = ORIENTED_EDGE ( 'NONE', *, *, #30441, .T. ) ; +#2222 = DIRECTION ( 'NONE', ( -0.6087614810001754639, 0.7729390313185934280, 0.1788147452386056047 ) ) ; +#2223 = CONICAL_SURFACE ( 'NONE', #25087, 2.500000004635095419, 0.7853981633778834848 ) ; +#2224 = VECTOR ( 'NONE', #970, 1000.000000000000227 ) ; +#2225 = CARTESIAN_POINT ( 'NONE', ( 2.012984916457277468E-13, 155.6803346353121356, 98.67347229714482637 ) ) ; +#2226 = CARTESIAN_POINT ( 'NONE', ( 17.99794026751098386, 132.4103114830794254, 92.77714071224164627 ) ) ; +#2227 = AXIS2_PLACEMENT_3D ( 'NONE', #26207, #16767, #32919 ) ; +#2228 = DIRECTION ( 'NONE', ( 0.0005884949961231939744, -0.2249510543439056098, 0.9743698870671265722 ) ) ; +#2229 = CARTESIAN_POINT ( 'NONE', ( -3.668796569719823264, 185.4948906969666211, 104.3615670296347560 ) ) ; +#2230 = EDGE_LOOP ( 'NONE', ( #7577, #33234, #3497, #14273, #7207, #5262, #7868, #24348, #1325, #36443, #36692, #35364, #36420, #23391, #15085, #36180, #15646, #31204, #2359, #19113, #10680, #21162, #14416, #20925, #1853, #6398, #15758, #21228, #14330, #21736, #14581, #9397, #28739, #36442, #6985, #24752, #1436, #8689, #31144, #20285, #9946, #16459, #6404, #36649, #29302, #21214, #40379, #3887, #14196, #30835, #39125, #37256, #33222, #20032, #34801, #24052, #18175, #38553, #9426, #17252, #36372, #20255, #18588, #40462, #2614, #9427, #5165, #26758, #27703, #26828, #16453, #36200, #3998, #18988, #20754, #6622, #39689, #26090, #18789, #4332, #12667, #6072, #9855, #10313, #24525, #11576, #30280, #39563, #6018, #39085, #255, #26525 ) ) ; +#2231 = FACE_OUTER_BOUND ( 'NONE', #39019, .T. ) ; +#2232 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561517 ) ) ; +#2233 = CARTESIAN_POINT ( 'NONE', ( 28.25950385170297352, 125.5846682600628412, 89.14251585184922533 ) ) ; +#2234 = DIRECTION ( 'NONE', ( -0.0006039748319384393230, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#2235 = EDGE_LOOP ( 'NONE', ( #24633, #32521, #356, #12081 ) ) ; +#2236 = LINE ( 'NONE', #18355, #31644 ) ; +#2237 = CARTESIAN_POINT ( 'NONE', ( -42.44123101563632616, 121.4084042097561422, 91.21054638067076326 ) ) ; +#2238 = CARTESIAN_POINT ( 'NONE', ( 6.034558854670474481, 134.6330650579004100, 93.47859313952841376 ) ) ; +#2239 = CARTESIAN_POINT ( 'NONE', ( 30.07009376553777713, 136.7965748649584441, 93.78249831157448568 ) ) ; +#2240 = EDGE_CURVE ( 'NONE', #8264, #10957, #32487, .T. ) ; +#2241 = CARTESIAN_POINT ( 'NONE', ( 19.98059076253610300, 209.7097557544199162, 73.04669817794425057 ) ) ; +#2242 = LINE ( 'NONE', #12050, #1226 ) ; +#2243 = CARTESIAN_POINT ( 'NONE', ( 3.166350703034567449, 184.1264558197564156, 102.1599558388959537 ) ) ; +#2244 = CARTESIAN_POINT ( 'NONE', ( -25.50991579498579398, 209.7152486954105086, 73.57374465072240355 ) ) ; +#2245 = FACE_OUTER_BOUND ( 'NONE', #8397, .T. ) ; +#2246 = CARTESIAN_POINT ( 'NONE', ( 37.97817678914999817, 118.4650513228999955, 87.57063408596999921 ) ) ; +#2247 = DATE_AND_TIME ( #14726, #30341 ) ; +#2248 = LINE ( 'NONE', #39642, #34999 ) ; +#2249 = CIRCLE ( 'NONE', #13997, 9.500000000005877965 ) ; +#2250 = DIRECTION ( 'NONE', ( 0.0004161288024529937943, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#2251 = CARTESIAN_POINT ( 'NONE', ( 42.50830921456510936, 147.1394519918483468, 291.5328699816350309 ) ) ; +#2252 = LINE ( 'NONE', #30670, #17561 ) ; +#2253 = CARTESIAN_POINT ( 'NONE', ( 22.50216366289214065, 153.7345681062837457, 98.21065990825610470 ) ) ; +#2254 = AXIS2_PLACEMENT_3D ( 'NONE', #10203, #38391, #9797 ) ; +#2255 = CARTESIAN_POINT ( 'NONE', ( 37.28139524443679420, 185.5739301951794289, 107.6056048166977916 ) ) ; +#2256 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #18347, #31045, #6090, #22048 ), + .UNSPECIFIED., .F., .F. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 5.967414621972016775, 6.106579042305979144 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9983867564016686291, 0.9983867564016686291, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#2257 = ORIENTED_EDGE ( 'NONE', *, *, #7291, .T. ) ; +#2258 = ORIENTED_EDGE ( 'NONE', *, *, #26685, .T. ) ; +#2259 = CARTESIAN_POINT ( 'NONE', ( -2.558442632295163666, 189.7708140492636630, 103.4665133998351649 ) ) ; +#2260 = ORIENTED_EDGE ( 'NONE', *, *, #34479, .F. ) ; +#2261 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 137.0112424259995976, 291.5876487235603918 ) ) ; +#2262 = CARTESIAN_POINT ( 'NONE', ( 16.77620139486186801, 151.9520352481422663, 184.1071290740507322 ) ) ; +#2263 = DIRECTION ( 'NONE', ( -0.0002393071182786170347, -0.2252352986010032754, 0.9743043687658493601 ) ) ; +#2264 = ADVANCED_FACE ( 'NONE', ( #2739, #27697, #40128 ), #29086, .T. ) ; +#2265 = EDGE_CURVE ( 'NONE', #25353, #37130, #22154, .T. ) ; +#2266 = ORIENTED_EDGE ( 'NONE', *, *, #25673, .T. ) ; +#2267 = LINE ( 'NONE', #20865, #4823 ) ; +#2268 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 108.4362817545589905, 169.8438797714867405 ) ) ; +#2269 = DIRECTION ( 'NONE', ( -0.9914446239183341003, -0.1273125500237936858, -0.02879361578322678708 ) ) ; +#2270 = CARTESIAN_POINT ( 'NONE', ( -1.962318082198259761, 162.0965106997445844, 100.1559487201849521 ) ) ; +#2271 = ORIENTED_EDGE ( 'NONE', *, *, #17043, .T. ) ; +#2272 = CARTESIAN_POINT ( 'NONE', ( -21.21399076556896546, 136.5867924462192207, 91.71243192711530412 ) ) ; +#2273 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #40183, #5231, #21412, #8937 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2274 = CARTESIAN_POINT ( 'NONE', ( -19.32822035155621165, 147.9764759943865897, 183.5528329745226017 ) ) ; +#2275 =( GEOMETRIC_REPRESENTATION_CONTEXT ( 3 ) GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT ( ( #20372 ) ) GLOBAL_UNIT_ASSIGNED_CONTEXT ( ( #20638, #36787, #34108 ) ) REPRESENTATION_CONTEXT ( 'NONE', 'WORKASPACE' ) ); +#2276 = EDGE_LOOP ( 'NONE', ( #17915, #21348, #22739, #29294, #6079, #20237, #20126, #4371, #11098, #8130, #36486, #8137, #38867, #5564 ) ) ; +#2277 = CARTESIAN_POINT ( 'NONE', ( -27.24093993282000170, 187.8262165483999979, 103.4208887112000070 ) ) ; +#2278 = CARTESIAN_POINT ( 'NONE', ( 0.6561006408056999639, 188.6069392329000038, 103.1942120530000011 ) ) ; +#2279 = CONICAL_SURFACE ( 'NONE', #7475, 8.000000000029075409, 0.7853981633973019516 ) ; +#2280 = CONICAL_SURFACE ( 'NONE', #25138, 2.500000015113073903, 0.7853981633586051281 ) ; +#2281 = CARTESIAN_POINT ( 'NONE', ( -3.893460976669078200, 148.9599728450052396, 129.9645419195898342 ) ) ; +#2282 = CARTESIAN_POINT ( 'NONE', ( -35.53841825476909122, 192.0417956556318586, 106.9432359204027847 ) ) ; +#2283 = CIRCLE ( 'NONE', #337, 1.999999999960905495 ) ; +#2284 = ORIENTED_EDGE ( 'NONE', *, *, #26823, .T. ) ; +#2285 = CARTESIAN_POINT ( 'NONE', ( -5.668109638568818553, 183.4491308723886789, 105.0878286196073645 ) ) ; +#2286 = VERTEX_POINT ( 'NONE', #34973 ) ; +#2287 = EDGE_CURVE ( 'NONE', #23892, #33001, #25631, .T. ) ; +#2288 = EDGE_LOOP ( 'NONE', ( #10688, #35256, #7808, #24465 ) ) ; +#2289 = EDGE_LOOP ( 'NONE', ( #28848, #31206, #24233, #30254, #8907, #3948, #21695, #7325, #33408 ) ) ; +#2290 = LINE ( 'NONE', #39686, #38785 ) ; +#2291 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568178 ) ) ; +#2292 = CARTESIAN_POINT ( 'NONE', ( 39.05126608408746591, 77.57947994969133276, 289.7423654207750019 ) ) ; +#2293 = VERTEX_POINT ( 'NONE', #25830 ) ; +#2294 = DIRECTION ( 'NONE', ( -0.7066795775021792458, 8.805378661621471798E-15, 0.7075337269285059127 ) ) ; +#2295 = VERTEX_POINT ( 'NONE', #659 ) ; +#2296 = ADVANCED_FACE ( 'NONE', ( #855 ), #38079, .F. ) ; +#2297 = CARTESIAN_POINT ( 'NONE', ( 28.53370192849249776, 124.6069703449200006, 91.48759531593780991 ) ) ; +#2298 = PLANE ( 'NONE', #31955 ) ; +#2300 = CARTESIAN_POINT ( 'NONE', ( -28.94810864222802849, 110.6131156702000027, 87.28526822420690223 ) ) ; +#2299 = LINE ( 'NONE', #14786, #21278 ) ; +#2301 = CIRCLE ( 'NONE', #12743, 2.000000000070082162 ) ; +#2302 = ORIENTED_EDGE ( 'NONE', *, *, #37094, .F. ) ; +#2303 = EDGE_CURVE ( 'NONE', #37835, #25286, #19786, .T. ) ; +#2304 = VECTOR ( 'NONE', #2588, 1000.000000000000114 ) ; +#2305 = ORIENTED_EDGE ( 'NONE', *, *, #18740, .F. ) ; +#2306 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418800025, 218.5902260770999987, 73.08022052563953253 ) ) ; +#2307 = AXIS2_PLACEMENT_3D ( 'NONE', #18173, #30875, #40456 ) ; +#2308 = EDGE_CURVE ( 'NONE', #7061, #15824, #31549, .T. ) ; +#2309 = ADVANCED_FACE ( 'NONE', ( #19662 ), #3511, .F. ) ; +#2310 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20149, #38752, #23237, #20352 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2311 = ORIENTED_EDGE ( 'NONE', *, *, #25348, .F. ) ; +#2312 = EDGE_CURVE ( 'NONE', #12419, #10753, #35587, .T. ) ; +#2313 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971557631 ) ) ; +#2314 = EDGE_CURVE ( 'NONE', #13097, #8665, #31349, .T. ) ; +#2315 = CARTESIAN_POINT ( 'NONE', ( -14.60099755400268506, 128.1392381506334175, 179.4895675734404392 ) ) ; +#2316 = CARTESIAN_POINT ( 'NONE', ( -30.17967533865709129, 185.9478674444400497, 102.6005990038461988 ) ) ; +#2317 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971578725 ) ) ; +#2318 = VERTEX_POINT ( 'NONE', #13544 ) ; +#2319 = ORIENTED_EDGE ( 'NONE', *, *, #1798, .F. ) ; +#2320 = ORIENTED_EDGE ( 'NONE', *, *, #29307, .T. ) ; +#2321 = CARTESIAN_POINT ( 'NONE', ( -2.180037377191725412, 189.9716679226577014, 103.9664554834080832 ) ) ; +#2322 = CARTESIAN_POINT ( 'NONE', ( -37.28964217851551410, 124.9030048851708585, 93.64309515347763124 ) ) ; +#2323 = DIRECTION ( 'NONE', ( 0.0005884949961232894926, -0.2249510543439051935, 0.9743698870671265722 ) ) ; +#2324 = ORIENTED_EDGE ( 'NONE', *, *, #4402, .F. ) ; +#2325 = CARTESIAN_POINT ( 'NONE', ( -35.94898838659999996, 191.8605118499999946, 106.6098996716000045 ) ) ; +#2326 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3463, #15944, #25375, #22311, #26584, #22908 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2327 = CARTESIAN_POINT ( 'NONE', ( 2.957254264836670199, 190.0891094935151955, 106.6212271850417892 ) ) ; +#2328 = CARTESIAN_POINT ( 'NONE', ( -12.92592855545641228, 126.1600735973864289, 178.8056805775503335 ) ) ; +#2329 = CARTESIAN_POINT ( 'NONE', ( -5.668553076709809346, 181.6128662714581310, 104.1507415746884391 ) ) ; +#2330 = VECTOR ( 'NONE', #18409, 1000.000000000000114 ) ; +#2331 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971541810 ) ) ; +#2332 = LINE ( 'NONE', #14809, #6498 ) ; +#2333 = ORIENTED_EDGE ( 'NONE', *, *, #8742, .F. ) ; +#2334 = VECTOR ( 'NONE', #37320, 1000.000000000000114 ) ; +#2335 = CARTESIAN_POINT ( 'NONE', ( -21.96624583357523619, 177.4045611624641765, 100.6232602709462043 ) ) ; +#2336 = DIRECTION ( 'NONE', ( 1.156504871743948528E-16, 0.9743043966640312359, 0.2252353050503803078 ) ) ; +#2337 = ORIENTED_EDGE ( 'NONE', *, *, #24428, .T. ) ; +#2338 = ADVANCED_FACE ( 'NONE', ( #15993 ), #3722, .F. ) ; +#2339 = CARTESIAN_POINT ( 'NONE', ( 5.667815391071213682, 183.5631071180958998, 104.5941433521421686 ) ) ; +#2340 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35572, #32350, #4317, #1253 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2341 = ORIENTED_EDGE ( 'NONE', *, *, #31171, .T. ) ; +#2343 = DIRECTION ( 'NONE', ( -0.0005884949961237706615, 0.2249510543439053323, -0.9743698870671265722 ) ) ; +#2342 = CARTESIAN_POINT ( 'NONE', ( -29.90873775226999953, 109.6131156702000027, 152.4718672074000381 ) ) ; +#2344 = EDGE_LOOP ( 'NONE', ( #29913, #5816, #33576, #2751 ) ) ; +#2346 = VERTEX_POINT ( 'NONE', #28484 ) ; +#2345 = EDGE_CURVE ( 'NONE', #14103, #2188, #28681, .T. ) ; +#2347 = CYLINDRICAL_SURFACE ( 'NONE', #11924, 6.000000000278002510 ) ; +#2348 = VERTEX_POINT ( 'NONE', #460 ) ; +#2349 = CARTESIAN_POINT ( 'NONE', ( -21.58773827856466454, 112.4042505803199532, 201.3497749872313420 ) ) ; +#2350 = ADVANCED_FACE ( 'NONE', ( #13344 ), #12948, .T. ) ; +#2351 = AXIS2_PLACEMENT_3D ( 'NONE', #30371, #14845, #24258 ) ; +#2352 = DIRECTION ( 'NONE', ( 0.5634794340701355653, -0.8261300910752492621, 0.000000000000000000 ) ) ; +#2353 = CARTESIAN_POINT ( 'NONE', ( 14.94854772523675557, 136.6910697646424069, 91.37256421016206787 ) ) ; +#2354 = EDGE_LOOP ( 'NONE', ( #5341, #15112, #13293, #1341 ) ) ; +#2355 = VECTOR ( 'NONE', #29045, 1000.000000000000227 ) ; +#2356 = ORIENTED_EDGE ( 'NONE', *, *, #17380, .F. ) ; +#2357 = CARTESIAN_POINT ( 'NONE', ( -3.668109984895000508, 187.1813567023000076, 105.9482730532999994 ) ) ; +#2358 = ORIENTED_EDGE ( 'NONE', *, *, #25724, .T. ) ; +#2359 = ORIENTED_EDGE ( 'NONE', *, *, #23409, .F. ) ; +#2360 = ORIENTED_EDGE ( 'NONE', *, *, #24337, .F. ) ; +#2361 = ADVANCED_FACE ( 'NONE', ( #16585 ), #35189, .F. ) ; +#2362 = CARTESIAN_POINT ( 'NONE', ( 21.25891409511187291, 128.8498498509368915, 89.90056508924928380 ) ) ; +#2363 = CARTESIAN_POINT ( 'NONE', ( 30.31667092456163459, 126.5682557959073335, 91.76305689627588436 ) ) ; +#2364 = LINE ( 'NONE', #14636, #18039 ) ; +#2365 = CARTESIAN_POINT ( 'NONE', ( 3.002302857372999956, 209.4500945363000142, 73.06113814329000888 ) ) ; +#2366 = VERTEX_POINT ( 'NONE', #6386 ) ; +#2367 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6595, #25644, #22168, #37896 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2368 = AXIS2_PLACEMENT_3D ( 'NONE', #35354, #38841, #39046 ) ; +#2369 = EDGE_LOOP ( 'NONE', ( #14562, #23434, #21178, #33610 ) ) ; +#2370 = ORIENTED_EDGE ( 'NONE', *, *, #10778, .T. ) ; +#2371 = LINE ( 'NONE', #14230, #25890 ) ; +#2372 = CARTESIAN_POINT ( 'NONE', ( -35.30527578227999896, 192.3918037269000081, 103.7496537549999971 ) ) ; +#2373 = VERTEX_POINT ( 'NONE', #3321 ) ; +#2374 = CARTESIAN_POINT ( 'NONE', ( -26.00179438729000125, 120.8350387973000153, 87.56562579824000636 ) ) ; +#2375 = ORIENTED_EDGE ( 'NONE', *, *, #31610, .T. ) ; +#2376 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927790623616, 0.0005734119022072373204 ) ) ; +#2377 = DIRECTION ( 'NONE', ( -0.1782640835105696875, -0.3528946327679918782, 0.9185245204640325456 ) ) ; +#2378 = ORIENTED_EDGE ( 'NONE', *, *, #39307, .F. ) ; +#2379 = CARTESIAN_POINT ( 'NONE', ( 0.7432696594355128195, 188.6192524948516223, 103.1986602668173276 ) ) ; +#2380 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#2381 = CARTESIAN_POINT ( 'NONE', ( 38.73751167838227616, 119.2159698917354120, 90.26423455750220626 ) ) ; +#2382 = ORIENTED_EDGE ( 'NONE', *, *, #24612, .F. ) ; +#2383 = CARTESIAN_POINT ( 'NONE', ( -21.27837344614222559, 182.7516671288082364, 101.8573217206271693 ) ) ; +#2384 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2385 = FACE_OUTER_BOUND ( 'NONE', #21956, .T. ) ; +#2386 = VECTOR ( 'NONE', #9307, 1000.000000000000227 ) ; +#2387 = ORIENTED_EDGE ( 'NONE', *, *, #2460, .F. ) ; +#2388 = CARTESIAN_POINT ( 'NONE', ( -28.94720267997999841, 103.6131156702000027, 88.78526795067999444 ) ) ; +#2389 = ORIENTED_EDGE ( 'NONE', *, *, #23872, .F. ) ; +#2390 = DIRECTION ( 'NONE', ( 0.9999998268368246457, 0.0001323826181902279108, -0.0005734118615388824605 ) ) ; +#2391 = CIRCLE ( 'NONE', #12166, 2.749999999949217511 ) ; +#2392 = CARTESIAN_POINT ( 'NONE', ( -2.421792290688875138, 209.3823634036505439, 73.56388561843570528 ) ) ; +#2393 = CARTESIAN_POINT ( 'NONE', ( -14.16977587005254158, 182.7576216332787737, 102.3675551592481696 ) ) ; +#2394 = DIRECTION ( 'NONE', ( 0.0005884949961267937424, -0.2249510543439074417, 0.9743698870671260170 ) ) ; +#2395 = CARTESIAN_POINT ( 'NONE', ( -22.49823373577851271, 184.2867149872474783, 105.2913651576170651 ) ) ; +#2396 = EDGE_CURVE ( 'NONE', #31197, #2940, #12946, .T. ) ; +#2397 = EDGE_LOOP ( 'NONE', ( #9377, #8025, #8488, #29693, #28155, #36909 ) ) ; +#2398 = AXIS2_PLACEMENT_3D ( 'NONE', #10486, #7594, #23355 ) ; +#2399 = ADVANCED_FACE ( 'NONE', ( #17946 ), #14714, .F. ) ; +#2400 = ADVANCED_FACE ( 'NONE', ( #39631 ), #30655, .F. ) ; +#2401 = VECTOR ( 'NONE', #18140, 1000.000000000000114 ) ; +#2402 = ADVANCED_FACE ( 'NONE', ( #5486 ), #17543, .T. ) ; +#2403 = DIRECTION ( 'NONE', ( -0.5988974202702721517, 0.8008257488327987783, 0.000000000000000000 ) ) ; +#2404 = CARTESIAN_POINT ( 'NONE', ( 22.31312662366504540, 116.2335386298891393, 182.3227435278615474 ) ) ; +#2405 = CARTESIAN_POINT ( 'NONE', ( -23.78120603611477790, 115.1892833753767036, 87.28214754456956825 ) ) ; +#2406 = DIRECTION ( 'NONE', ( 0.0001358647752772932629, 0.9743700647730598741, 0.2249510133671457635 ) ) ; +#2407 = ADVANCED_FACE ( 'NONE', ( #27411 ), #6410, .F. ) ; +#2408 = CARTESIAN_POINT ( 'NONE', ( -22.99976245438101330, 118.1131156702000169, 90.28469153849982831 ) ) ; +#2409 = CARTESIAN_POINT ( 'NONE', ( 32.42164055602032136, 176.1828832701569638, 100.3083647338347646 ) ) ; +#2410 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#2411 = CARTESIAN_POINT ( 'NONE', ( 22.21137596932447522, 115.2160762028210428, 90.25436972469280761 ) ) ; +#2412 = ORIENTED_EDGE ( 'NONE', *, *, #14675, .F. ) ; +#2414 = ADVANCED_FACE ( 'NONE', ( #5900 ), #31055, .F. ) ; +#2413 = CARTESIAN_POINT ( 'NONE', ( 14.55485738440738963, 181.8858882541513537, 104.7147121319332825 ) ) ; +#2415 = CARTESIAN_POINT ( 'NONE', ( -19.99971477990169788, 118.1214470234825029, 90.27986416578403350 ) ) ; +#2416 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11807, #14266, #26739, #20792, #20378, #23665 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2417 = FACE_OUTER_BOUND ( 'NONE', #4445, .T. ) ; +#2418 = AXIS2_PLACEMENT_3D ( 'NONE', #27308, #24642, #36472 ) ; +#2419 = EDGE_LOOP ( 'NONE', ( #30600, #18884, #37995, #19455 ) ) ; +#2420 = CARTESIAN_POINT ( 'NONE', ( -12.59997215317999952, 115.9590670145843205, 152.9217693939943388 ) ) ; +#2421 = FACE_OUTER_BOUND ( 'NONE', #28104, .T. ) ; +#2422 = VECTOR ( 'NONE', #4496, 999.9999999999998863 ) ; +#2423 = ORIENTED_EDGE ( 'NONE', *, *, #1654, .F. ) ; +#2424 = CARTESIAN_POINT ( 'NONE', ( -38.15613654141999689, 119.1005567029999952, 87.44234925840000017 ) ) ; +#2425 = ADVANCED_FACE ( 'NONE', ( #27797 ), #40038, .F. ) ; +#2426 = CARTESIAN_POINT ( 'NONE', ( 16.24603267945985507, 152.0453547567774706, 181.0525560685096593 ) ) ; +#2427 = CARTESIAN_POINT ( 'NONE', ( -5.663464557155529988, 131.0206703453534374, 89.90489628355439322 ) ) ; +#2428 = ORIENTED_EDGE ( 'NONE', *, *, #20324, .F. ) ; +#2429 = CARTESIAN_POINT ( 'NONE', ( 35.86915118585585560, 191.5522503802022811, 106.8824361391712898 ) ) ; +#2430 = AXIS2_PLACEMENT_3D ( 'NONE', #36448, #5366, #27487 ) ; +#2431 = CARTESIAN_POINT ( 'NONE', ( -45.39773774286052088, 124.2994142384970218, 88.45363130071420699 ) ) ; +#2432 = CARTESIAN_POINT ( 'NONE', ( 17.20373620539847792, 122.0130630878173861, 174.6141869257109533 ) ) ; +#2433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #797, #21896, #18589, #31096 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2434 = FACE_OUTER_BOUND ( 'NONE', #35609, .T. ) ; +#2435 = DIRECTION ( 'NONE', ( 0.0006039748319383109534, 1.233022124494217175E-14, 0.9999998176071845934 ) ) ; +#2436 = ORIENTED_EDGE ( 'NONE', *, *, #19025, .F. ) ; +#2437 = CARTESIAN_POINT ( 'NONE', ( 38.33729829349999818, 118.8626431811999993, 87.57247875375999513 ) ) ; +#2438 = CARTESIAN_POINT ( 'NONE', ( -23.35081975911714380, 130.3436102262665486, 92.83812635286813020 ) ) ; +#2439 = DIRECTION ( 'NONE', ( 0.0005884948598593896978, -0.2255194595956526160, 0.9742384856992073461 ) ) ; +#2440 = CARTESIAN_POINT ( 'NONE', ( 20.00028792540915035, 151.9820690596619102, 94.72877128701482263 ) ) ; +#2441 = ORIENTED_EDGE ( 'NONE', *, *, #33295, .T. ) ; +#2442 = ORIENTED_EDGE ( 'NONE', *, *, #33075, .T. ) ; +#2443 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749903839, 130.6678814337496135, 90.32225895349807843 ) ) ; +#2444 = CARTESIAN_POINT ( 'NONE', ( -43.10638044614131559, 120.9782189030739232, 90.80560025573178962 ) ) ; +#2445 = CARTESIAN_POINT ( 'NONE', ( 25.83702252211450912, 212.0387306411581676, 73.04289916821271333 ) ) ; +#2446 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2447 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17403, #4121, #38476, #13745 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2448 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749098554, 132.4103119504792119, 92.77713868755240867 ) ) ; +#2449 = EDGE_CURVE ( 'NONE', #1363, #7877, #21277, .T. ) ; +#2450 = AXIS2_PLACEMENT_3D ( 'NONE', #4757, #29724, #17221 ) ; +#2451 = EDGE_CURVE ( 'NONE', #28767, #19429, #37186, .T. ) ; +#2452 = EDGE_CURVE ( 'NONE', #22589, #5068, #3222, .T. ) ; +#2453 = CARTESIAN_POINT ( 'NONE', ( -25.91665832970164374, 209.7105128082618251, 73.16760013480885050 ) ) ; +#2454 = AXIS2_PLACEMENT_3D ( 'NONE', #27916, #25242, #9487 ) ; +#2455 = CARTESIAN_POINT ( 'NONE', ( -0.02657825335728297364, 128.5632152146144449, 291.5585599878308471 ) ) ; +#2456 = PERSON_AND_ORGANIZATION_ROLE ( 'design_owner' ) ; +#2457 = CARTESIAN_POINT ( 'NONE', ( 38.80965466373000083, 119.1329998486999955, 90.12137990267000021 ) ) ; +#2458 = CARTESIAN_POINT ( 'NONE', ( 17.11663184279114347, 122.6447230097683843, 172.0965978585869607 ) ) ; +#2459 = DIRECTION ( 'NONE', ( -0.9999998268368044396, -0.0001323825928669451334, 0.0005734119025882206512 ) ) ; +#2460 = EDGE_CURVE ( 'NONE', #35062, #13439, #28453, .T. ) ; +#2461 = CARTESIAN_POINT ( 'NONE', ( 38.12525175933708965, 171.3045222593593166, 164.7303159086331448 ) ) ; +#2462 = CARTESIAN_POINT ( 'NONE', ( -20.60014793633816765, 116.2721715147326904, 87.28022626518796301 ) ) ; +#2463 = FACE_OUTER_BOUND ( 'NONE', #23516, .T. ) ; +#2464 = VERTEX_POINT ( 'NONE', #34292 ) ; +#2465 = ORIENTED_EDGE ( 'NONE', *, *, #18705, .T. ) ; +#2466 = EDGE_CURVE ( 'NONE', #31711, #7061, #6686, .T. ) ; +#2467 = CARTESIAN_POINT ( 'NONE', ( -1.063471189976053832, 188.6709375346488287, 103.2116839268398536 ) ) ; +#2468 = ORIENTED_EDGE ( 'NONE', *, *, #26367, .T. ) ; +#2469 = LINE ( 'NONE', #23941, #34625 ) ; +#2470 = LINE ( 'NONE', #30261, #31080 ) ; +#2471 = ORIENTED_EDGE ( 'NONE', *, *, #30996, .T. ) ; +#2472 = CARTESIAN_POINT ( 'NONE', ( -39.55746895486999648, 119.4471732075000006, 89.94349737900999742 ) ) ; +#2473 = ADVANCED_FACE ( 'NONE', ( #24733 ), #2834, .F. ) ; +#2474 = FACE_OUTER_BOUND ( 'NONE', #13977, .T. ) ; +#2475 = CARTESIAN_POINT ( 'NONE', ( -43.18873574177670349, 153.0051697192221241, 291.5846288494004739 ) ) ; +#2476 = EDGE_LOOP ( 'NONE', ( #6274, #22374, #13519, #13414 ) ) ; +#2477 = DIRECTION ( 'NONE', ( 0.9914447795421099663, -0.1270909273343945323, -0.02975139169821508847 ) ) ; +#2478 = CIRCLE ( 'NONE', #26645, 30.49999999998560085 ) ; +#2479 = CARTESIAN_POINT ( 'NONE', ( 16.56014902165552272, 121.8510385007027992, 177.5702860362286799 ) ) ; +#2480 = FACE_OUTER_BOUND ( 'NONE', #33139, .T. ) ; +#2481 = DIRECTION ( 'NONE', ( 0.0005884949961224158425, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2482 = AXIS2_PLACEMENT_3D ( 'NONE', #23464, #25949, #23264 ) ; +#2483 = CARTESIAN_POINT ( 'NONE', ( 15.75014751337000263, 145.1854452732999903, 93.41868622648999576 ) ) ; +#2484 = ORIENTED_EDGE ( 'NONE', *, *, #3814, .T. ) ; +#2485 = CARTESIAN_POINT ( 'NONE', ( -25.36704866655999879, 191.4398696147000010, 104.5177098329999978 ) ) ; +#2486 = CARTESIAN_POINT ( 'NONE', ( 1.253857910261999997, 188.7050348800999870, 103.2175213973000041 ) ) ; +#2487 = CARTESIAN_POINT ( 'NONE', ( 26.00268413466335460, 120.2421824539040358, 90.47622374426396163 ) ) ; +#2488 = ORIENTED_EDGE ( 'NONE', *, *, #24198, .F. ) ; +#2489 = EDGE_LOOP ( 'NONE', ( #36940, #30496, #27906, #8078, #30851, #22442, #39546, #38862 ) ) ; +#2490 = CARTESIAN_POINT ( 'NONE', ( -38.01211212650550664, 119.1971871873620472, 87.30118044812934386 ) ) ; +#2491 = ORIENTED_EDGE ( 'NONE', *, *, #23776, .F. ) ; +#2492 = EDGE_LOOP ( 'NONE', ( #1304, #25304, #38059, #9645 ) ) ; +#2493 = EDGE_LOOP ( 'NONE', ( #26634, #16558, #27972, #13628 ) ) ; +#2494 = EDGE_CURVE ( 'NONE', #31566, #8772, #26498, .T. ) ; +#2495 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2496 = EDGE_CURVE ( 'NONE', #2793, #4933, #6487, .T. ) ; +#2497 = CARTESIAN_POINT ( 'NONE', ( 23.36940079100686063, 177.7945392694463749, 100.6858723966742843 ) ) ; +#2498 = CARTESIAN_POINT ( 'NONE', ( 39.79988895049328335, 119.8651423291884726, 87.81508310122019623 ) ) ; +#2499 = CARTESIAN_POINT ( 'NONE', ( -37.67910728328570258, 190.9663396873137060, 106.3291846998849053 ) ) ; +#2500 = ORIENTED_EDGE ( 'NONE', *, *, #35353, .F. ) ; +#2501 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22035, #27584, #6073, #12604 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2502 = CARTESIAN_POINT ( 'NONE', ( 21.63968124537738547, 115.2790863461608097, 189.0193985308339393 ) ) ; +#2503 = VERTEX_POINT ( 'NONE', #31657 ) ; +#2504 = CARTESIAN_POINT ( 'NONE', ( 26.79907597897999949, 123.2871420175000026, 91.00767973732999394 ) ) ; +#2505 = VECTOR ( 'NONE', #7477, 1000.000000000000227 ) ; +#2506 = CARTESIAN_POINT ( 'NONE', ( 20.00150936005196201, 118.3414216785000121, 90.25570442875019239 ) ) ; +#2507 = VECTOR ( 'NONE', #4590, 1000.000000000000000 ) ; +#2509 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7071067167008887600, -0.7071068456722005013 ) ) ; +#2508 = CARTESIAN_POINT ( 'NONE', ( 15.53838427372360798, 112.1323247865566941, 152.4707203835889402 ) ) ; +#2510 = ORIENTED_EDGE ( 'NONE', *, *, #25823, .F. ) ; +#2511 = ORIENTED_EDGE ( 'NONE', *, *, #11299, .F. ) ; +#2512 = CARTESIAN_POINT ( 'NONE', ( -2.452854086982361626, 209.7096538831000032, 78.05998645676569936 ) ) ; +#2513 = ORIENTED_EDGE ( 'NONE', *, *, #4222, .F. ) ; +#2514 = DIRECTION ( 'NONE', ( -0.0005884949961241434102, 0.2249510543439057764, -0.9743698870671265722 ) ) ; +#2515 = EDGE_CURVE ( 'NONE', #5612, #14084, #37344, .T. ) ; +#2516 = DIRECTION ( 'NONE', ( -0.6087602338625655030, -0.7731011424623617234, -0.1781168189447182304 ) ) ; +#2517 = CARTESIAN_POINT ( 'NONE', ( 15.66823628282405423, 184.3661235549490129, 104.9445449394547438 ) ) ; +#2518 = CARTESIAN_POINT ( 'NONE', ( -12.64208105978997665, 134.9837024878036118, 90.91483575941917650 ) ) ; +#2519 = EDGE_LOOP ( 'NONE', ( #20999, #9202, #8933, #37777 ) ) ; +#2520 = EDGE_LOOP ( 'NONE', ( #11010, #319, #11078, #23029 ) ) ; +#2521 = DIRECTION ( 'NONE', ( 1.328421402153733269E-20, -0.9743043966640312359, -0.2252353050503803356 ) ) ; +#2522 = CARTESIAN_POINT ( 'NONE', ( 15.51352726335324483, 187.3921001862149467, 102.9064289159318690 ) ) ; +#2523 = ORIENTED_EDGE ( 'NONE', *, *, #11684, .T. ) ; +#2524 = AXIS2_PLACEMENT_3D ( 'NONE', #10267, #26208, #22735 ) ; +#2525 = CARTESIAN_POINT ( 'NONE', ( -4.037441717428633225, 144.1002716341167229, 93.43668138785120902 ) ) ; +#2526 = ADVANCED_FACE ( 'NONE', ( #25131 ), #12849, .F. ) ; +#2527 = CONICAL_SURFACE ( 'NONE', #3179, 2.502994210670941744, 0.7853981633984441491 ) ; +#2528 = CARTESIAN_POINT ( 'NONE', ( 1.799632749338529791, 188.6738461430155667, 106.2963457010693986 ) ) ; +#2529 = ORIENTED_EDGE ( 'NONE', *, *, #9279, .T. ) ; +#2530 = CARTESIAN_POINT ( 'NONE', ( -20.51970368596797556, 209.1729065476789913, 73.59374226241675387 ) ) ; +#2531 = EDGE_CURVE ( 'NONE', #26268, #10159, #37840, .T. ) ; +#2532 = LINE ( 'NONE', #33795, #6231 ) ; +#2533 = CARTESIAN_POINT ( 'NONE', ( 20.33484954814858270, 137.9142791705131970, 94.21752540843081647 ) ) ; +#2534 = CARTESIAN_POINT ( 'NONE', ( 18.99695336057541795, 148.4229678448664060, 183.7014091461406622 ) ) ; +#2535 = EDGE_LOOP ( 'NONE', ( #4795, #9710, #875, #18970, #20198 ) ) ; +#2536 = CYLINDRICAL_SURFACE ( 'NONE', #26308, 4.999999999999994671 ) ; +#2537 = EDGE_CURVE ( 'NONE', #26211, #23072, #10783, .T. ) ; +#2538 = EDGE_CURVE ( 'NONE', #21067, #7275, #10189, .T. ) ; +#2539 = CARTESIAN_POINT ( 'NONE', ( -0.04020359587071823532, 99.17590004611790278, 343.2031739270701678 ) ) ; +#2540 = CARTESIAN_POINT ( 'NONE', ( 6.034364035348885658, 135.2945551070078238, 91.39763805326617785 ) ) ; +#2541 = EDGE_CURVE ( 'NONE', #3107, #3241, #19867, .T. ) ; +#2542 = VERTEX_POINT ( 'NONE', #760 ) ; +#2543 = CARTESIAN_POINT ( 'NONE', ( -14.75947401827107974, 154.0969921037251424, 95.23793027177912052 ) ) ; +#2544 = VERTEX_POINT ( 'NONE', #3617 ) ; +#2546 = CARTESIAN_POINT ( 'NONE', ( 76.10748482111097246, 155.7951947758858182, 98.14087069360385840 ) ) ; +#2545 = CYLINDRICAL_SURFACE ( 'NONE', #31163, 3.000000000000002220 ) ; +#2547 = ORIENTED_EDGE ( 'NONE', *, *, #14868, .F. ) ; +#2548 = VECTOR ( 'NONE', #15680, 1000.000000000000000 ) ; +#2549 = ORIENTED_EDGE ( 'NONE', *, *, #39868, .T. ) ; +#2550 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36197, #2074, #13934, #27241 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2551 = ORIENTED_EDGE ( 'NONE', *, *, #1364, .F. ) ; +#2552 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2553 = VECTOR ( 'NONE', #9622, 1000.000000000000000 ) ; +#2554 = CARTESIAN_POINT ( 'NONE', ( -14.91027384103292874, 124.4773777159772550, 171.6934768334666899 ) ) ; +#2555 = DIRECTION ( 'NONE', ( 0.0006039748319385408043, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#2556 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 132.9726895863780385, 90.34121396988766151 ) ) ; +#2557 = AXIS2_PLACEMENT_3D ( 'NONE', #36887, #33398, #34007 ) ; +#2558 = CARTESIAN_POINT ( 'NONE', ( 31.79542158357200776, 220.4002260771000010, 75.53930090045915335 ) ) ; +#2559 = ORIENTED_EDGE ( 'NONE', *, *, #24055, .T. ) ; +#2560 = ORIENTED_EDGE ( 'NONE', *, *, #25261, .F. ) ; +#2561 = DIRECTION ( 'NONE', ( -0.0006039748319391170578, -1.156482106403593688E-14, -0.9999998176071845934 ) ) ; +#2562 = VECTOR ( 'NONE', #14208, 1000.000000000000227 ) ; +#2563 = ORIENTED_EDGE ( 'NONE', *, *, #9363, .F. ) ; +#2564 = ORIENTED_EDGE ( 'NONE', *, *, #24534, .F. ) ; +#2565 = CARTESIAN_POINT ( 'NONE', ( -75.98858757284095589, 155.6702750673094329, 98.71704506522667089 ) ) ; +#2566 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366368657916, 137.4659008082770697, 177.5714312369256049 ) ) ; +#2567 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596097999, 131.0247019790824083, 89.88805227292419886 ) ) ; +#2568 = CARTESIAN_POINT ( 'NONE', ( 2.461607553392946901, 209.5695820990317202, 73.55701783320675702 ) ) ; +#2569 = VERTEX_POINT ( 'NONE', #13449 ) ; +#2570 = ORIENTED_EDGE ( 'NONE', *, *, #24712, .F. ) ; +#2571 = ORIENTED_EDGE ( 'NONE', *, *, #26835, .F. ) ; +#2572 = DIRECTION ( 'NONE', ( 0.0005884949961230356809, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2573 = CARTESIAN_POINT ( 'NONE', ( -36.25900725070000874, 191.9988562334999926, 104.5625822764999953 ) ) ; +#2574 = EDGE_LOOP ( 'NONE', ( #6057, #6846, #15636, #2491 ) ) ; +#2575 = CARTESIAN_POINT ( 'NONE', ( -25.50130725202999926, 120.7286589635999974, 88.05403516466999747 ) ) ; +#2576 = ORIENTED_EDGE ( 'NONE', *, *, #11303, .F. ) ; +#2577 = ORIENTED_EDGE ( 'NONE', *, *, #29776, .T. ) ; +#2578 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282898364, 154.4034317162757475, 95.31352405033304365 ) ) ; +#2579 = CARTESIAN_POINT ( 'NONE', ( 37.28562273942550576, 118.1774615424172339, 122.8329667304428909 ) ) ; +#2580 = PLANE ( 'NONE', #16279 ) ; +#2581 = EDGE_LOOP ( 'NONE', ( #36892, #28216, #18170, #39993 ) ) ; +#2582 = EDGE_CURVE ( 'NONE', #34131, #2295, #10554, .T. ) ; +#2583 = CARTESIAN_POINT ( 'NONE', ( 3.797364302584283813, 174.7411840455865217, 102.8032958810170783 ) ) ; +#2584 = CARTESIAN_POINT ( 'NONE', ( -3.794011246975583340, 167.8782899004469868, 101.2272116182543868 ) ) ; +#2585 = DIRECTION ( 'NONE', ( 0.7933535325932957738, -0.5931614258681779939, -0.1369295263402617313 ) ) ; +#2586 = VECTOR ( 'NONE', #36195, 1000.000000000000114 ) ; +#2587 = EDGE_CURVE ( 'NONE', #12430, #36191, #13839, .T. ) ; +#2588 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927792771421, 0.0005734119022071876640 ) ) ; +#2589 = DIRECTION ( 'NONE', ( 0.5987319967475925875, 0.8009494341533932582, 0.000000000000000000 ) ) ; +#2590 = EDGE_CURVE ( 'NONE', #15550, #12347, #10615, .T. ) ; +#2591 = AXIS2_PLACEMENT_3D ( 'NONE', #17490, #29582, #1563 ) ; +#2592 = VERTEX_POINT ( 'NONE', #32063 ) ; +#2593 = PLANE ( 'NONE', #11922 ) ; +#2594 = VERTEX_POINT ( 'NONE', #25934 ) ; +#2595 = AXIS2_PLACEMENT_3D ( 'NONE', #25594, #10037, #28447 ) ; +#2596 = CARTESIAN_POINT ( 'NONE', ( -25.91449224140000140, 181.8727335915000367, 101.9137800610000113 ) ) ; +#2597 = ADVANCED_FACE ( 'NONE', ( #16884 ), #13355, .F. ) ; +#2598 = CARTESIAN_POINT ( 'NONE', ( -38.00841869184999666, 119.4135498740000116, 87.18468147088000819 ) ) ; +#2599 = AXIS2_PLACEMENT_3D ( 'NONE', #36218, #14360, #4738 ) ; +#2600 = CARTESIAN_POINT ( 'NONE', ( 36.30117620144000057, 114.1276906072999964, 89.58115698366999879 ) ) ; +#2601 = ADVANCED_FACE ( 'NONE', ( #4023 ), #32301, .F. ) ; +#2602 = ADVANCED_FACE ( 'NONE', ( #7489 ), #36199, .F. ) ; +#2603 = CARTESIAN_POINT ( 'NONE', ( -1.458415330484564842, 144.9404864492794047, 129.0359332385724258 ) ) ; +#2604 = CARTESIAN_POINT ( 'NONE', ( -25.75508418156459456, 122.1544537738279388, 90.43581502352311929 ) ) ; +#2605 = ORIENTED_EDGE ( 'NONE', *, *, #5620, .F. ) ; +#2606 = CARTESIAN_POINT ( 'NONE', ( -13.55543936426466267, 163.9606855452657044, 100.5933297005652349 ) ) ; +#2607 = ORIENTED_EDGE ( 'NONE', *, *, #31944, .T. ) ; +#2608 = FACE_OUTER_BOUND ( 'NONE', #36592, .T. ) ; +#2609 = FACE_OUTER_BOUND ( 'NONE', #35760, .T. ) ; +#2610 = FACE_OUTER_BOUND ( 'NONE', #2574, .T. ) ; +#2611 = LINE ( 'NONE', #17715, #9042 ) ; +#2612 = CARTESIAN_POINT ( 'NONE', ( -17.26247767858138005, 152.5342161776122225, 182.4800534808789791 ) ) ; +#2613 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2614 = ORIENTED_EDGE ( 'NONE', *, *, #33542, .F. ) ; +#2615 = DIRECTION ( 'NONE', ( -0.6087611434179127645, -0.7731004625452339019, -0.1781166614240815016 ) ) ; +#2616 = CARTESIAN_POINT ( 'NONE', ( 1.050070742191543838, 189.0588793901672773, 105.7534012852386951 ) ) ; +#2617 = CIRCLE ( 'NONE', #28103, 1.750000000000001998 ) ; +#2618 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; +#2619 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31747, #25013, #3705, #9059, #34379, #33982 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2620 = ORIENTED_EDGE ( 'NONE', *, *, #21659, .F. ) ; +#2621 = CARTESIAN_POINT ( 'NONE', ( 19.98110224327852080, 206.5438147855657007, 74.14602195566800447 ) ) ; +#2622 = VECTOR ( 'NONE', #2918, 1000.000000000000227 ) ; +#2623 = LINE ( 'NONE', #27978, #11984 ) ; +#2624 = VECTOR ( 'NONE', #35335, 1000.000000000000227 ) ; +#2625 = ORIENTED_EDGE ( 'NONE', *, *, #16537, .F. ) ; +#2626 = CARTESIAN_POINT ( 'NONE', ( -38.98627109030000071, 119.3757285326999948, 87.77087478292000355 ) ) ; +#2627 = CARTESIAN_POINT ( 'NONE', ( -4.036264727520263662, 143.6503695267791727, 95.38542116167025142 ) ) ; +#2628 = PLANE ( 'NONE', #69 ) ; +#2629 = VERTEX_POINT ( 'NONE', #23248 ) ; +#2630 = DIRECTION ( 'NONE', ( 0.6188015000093128881, -0.7855473910504855439, 0.000000000000000000 ) ) ; +#2631 = EDGE_CURVE ( 'NONE', #6854, #5478, #9449, .T. ) ; +#2632 = EDGE_CURVE ( 'NONE', #19017, #31008, #40106, .T. ) ; +#2633 = CARTESIAN_POINT ( 'NONE', ( 3.658380091855549132, 167.8528591461128485, 101.3558085340577861 ) ) ; +#2634 = EDGE_CURVE ( 'NONE', #5073, #26865, #18554, .T. ) ; +#2635 = DIRECTION ( 'NONE', ( -0.0006039748319346909108, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#2636 = CARTESIAN_POINT ( 'NONE', ( -20.00006126831510400, 120.3902141372887087, 87.45929000627990035 ) ) ; +#2637 = DIRECTION ( 'NONE', ( -0.0005884949961261437632, 0.2249510543439059151, -0.9743698870671263501 ) ) ; +#2638 = EDGE_LOOP ( 'NONE', ( #6449, #13575, #38237, #23383 ) ) ; +#2639 = LINE ( 'NONE', #37179, #426 ) ; +#2640 = ADVANCED_FACE ( 'NONE', ( #38377 ), #19371, .F. ) ; +#2641 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #30802, #21609 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2642 = CARTESIAN_POINT ( 'NONE', ( 14.74167426920670465, 136.8705781667366068, 91.75623271434285755 ) ) ; +#2643 = CARTESIAN_POINT ( 'NONE', ( 36.55775395379972537, 191.7245065411347866, 104.3510190822927512 ) ) ; +#2644 = EDGE_CURVE ( 'NONE', #12309, #3470, #22856, .T. ) ; +#2645 = CARTESIAN_POINT ( 'NONE', ( -46.08310388805222146, 124.8206055617895629, 91.40572349197309165 ) ) ; +#2646 = ORIENTED_EDGE ( 'NONE', *, *, #20612, .F. ) ; +#2647 = ORIENTED_EDGE ( 'NONE', *, *, #31666, .T. ) ; +#2648 = CARTESIAN_POINT ( 'NONE', ( 3.667815737293329548, 128.0237491601668012, 91.77307785500387638 ) ) ; +#2649 = CARTESIAN_POINT ( 'NONE', ( -42.71664881039649941, 121.2026473532693416, 91.16230517282474466 ) ) ; +#2650 = CARTESIAN_POINT ( 'NONE', ( -13.55573361191901327, 147.5088701836791643, 96.28197591222276230 ) ) ; +#2651 = ADVANCED_FACE ( 'NONE', ( #16296 ), #27833, .T. ) ; +#2652 = AXIS2_PLACEMENT_3D ( 'NONE', #10017, #3652, #34915 ) ; +#2653 = AXIS2_PLACEMENT_3D ( 'NONE', #10967, #11354, #23840 ) ; +#2654 = CARTESIAN_POINT ( 'NONE', ( 42.93322021095036689, 121.2550468398670631, 90.69983607254528124 ) ) ; +#2655 = CARTESIAN_POINT ( 'NONE', ( -35.89858226441000966, 191.4429044599000065, 103.7433184509000057 ) ) ; +#2656 = CARTESIAN_POINT ( 'NONE', ( 45.33167067307282849, 106.4616227746064965, 168.3623917205906935 ) ) ; +#2657 = AXIS2_PLACEMENT_3D ( 'NONE', #1373, #26342, #31679 ) ; +#2658 = AXIS2_PLACEMENT_3D ( 'NONE', #2650, #16491, #26132 ) ; +#2659 = CARTESIAN_POINT ( 'NONE', ( -25.87351351544322142, 209.7109041514216301, 73.21069294904006597 ) ) ; +#2660 = CARTESIAN_POINT ( 'NONE', ( 16.29163119313890462, 127.8751207047643135, 174.7510531964512381 ) ) ; +#2661 = ADVANCED_FACE ( 'NONE', ( #38569 ), #10194, .F. ) ; +#2662 = DATE_AND_TIME ( #30461, #21856 ) ; +#2663 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#2664 = CARTESIAN_POINT ( 'NONE', ( 15.59057381604194958, 127.7851801377129561, 174.7303348606990596 ) ) ; +#2665 = CARTESIAN_POINT ( 'NONE', ( 28.53094770716555217, 124.6122665164779164, 91.48361085109841895 ) ) ; +#2666 = CARTESIAN_POINT ( 'NONE', ( 37.31693588142861273, 172.3309151562380919, 164.9673944986862466 ) ) ; +#2667 = CARTESIAN_POINT ( 'NONE', ( 37.18465433961090127, 191.0605235969299827, 106.3282138741240175 ) ) ; +#2668 = CARTESIAN_POINT ( 'NONE', ( 36.28210829689000150, 191.1903982848999988, 106.7086603135000047 ) ) ; +#2669 = ORIENTED_EDGE ( 'NONE', *, *, #2631, .T. ) ; +#2670 = ORIENTED_EDGE ( 'NONE', *, *, #29219, .T. ) ; +#2671 = CARTESIAN_POINT ( 'NONE', ( -3.775665312923583983, 136.3156088712283633, 91.12613979520395446 ) ) ; +#2672 = ORIENTED_EDGE ( 'NONE', *, *, #22906, .F. ) ; +#2673 = CARTESIAN_POINT ( 'NONE', ( -23.36068474349395885, 177.2840630309062817, 101.0277236918410324 ) ) ; +#2674 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2675 = ORIENTED_EDGE ( 'NONE', *, *, #11593, .T. ) ; +#2676 = CARTESIAN_POINT ( 'NONE', ( -39.04616526641999741, 119.6286227024000084, 90.51519719377000683 ) ) ; +#2677 = CIRCLE ( 'NONE', #22262, 2.000000000000011546 ) ; +#2678 = AXIS2_PLACEMENT_3D ( 'NONE', #30918, #22117, #37244 ) ; +#2679 = CARTESIAN_POINT ( 'NONE', ( -15.60948748269644781, 129.0994725037932653, 89.46731047333636866 ) ) ; +#2680 = CARTESIAN_POINT ( 'NONE', ( -28.75108559008205233, 179.7798527233168500, 27.87065912392118605 ) ) ; +#2681 = CARTESIAN_POINT ( 'NONE', ( -1.458415328219436757, 152.0517121881307503, 130.6798743971081365 ) ) ; +#2682 = EDGE_CURVE ( 'NONE', #39309, #21279, #1260, .T. ) ; +#2683 = ORIENTED_EDGE ( 'NONE', *, *, #37605, .T. ) ; +#2684 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#2685 = AXIS2_PLACEMENT_3D ( 'NONE', #25798, #1232, #16366 ) ; +#2686 = EDGE_CURVE ( 'NONE', #39904, #12942, #33239, .T. ) ; +#2687 = AXIS2_PLACEMENT_3D ( 'NONE', #31604, #18907, #28737 ) ; +#2688 = EDGE_CURVE ( 'NONE', #16955, #38290, #965, .T. ) ; +#2689 = CARTESIAN_POINT ( 'NONE', ( 23.36439094505924885, 176.9364792392202048, 103.3159941272735836 ) ) ; +#2690 = EDGE_CURVE ( 'NONE', #19715, #326, #39495, .T. ) ; +#2691 = CARTESIAN_POINT ( 'NONE', ( -14.31745456527091065, 135.5135842727596867, 90.94734476969833281 ) ) ; +#2692 = CARTESIAN_POINT ( 'NONE', ( -16.00000031268763934, 184.9628657724767606, 102.3646292465979855 ) ) ; +#2693 = ORIENTED_EDGE ( 'NONE', *, *, #35963, .F. ) ; +#2694 = CARTESIAN_POINT ( 'NONE', ( 44.86784790978150994, 186.3346043671313623, 107.7755195579999850 ) ) ; +#2695 = CARTESIAN_POINT ( 'NONE', ( 2.506441910316879795, 190.4796823909260013, 104.1213521451730060 ) ) ; +#2696 = CARTESIAN_POINT ( 'NONE', ( -42.85608556665479796, 121.2471205135300920, 90.71943177383317902 ) ) ; +#2697 = ADVANCED_FACE ( 'NONE', ( #20574 ), #31667, .F. ) ; +#2698 = EDGE_LOOP ( 'NONE', ( #16415, #40389, #1348, #4785, #12096, #13170, #38230, #16916, #20711, #13465 ) ) ; +#2699 = ORIENTED_EDGE ( 'NONE', *, *, #30565, .F. ) ; +#2700 = CARTESIAN_POINT ( 'NONE', ( -38.22874400428858621, 119.4291492467365430, 87.31414389642802121 ) ) ; +#2701 = ORIENTED_EDGE ( 'NONE', *, *, #7573, .F. ) ; +#2702 = ADVANCED_FACE ( 'NONE', ( #29588 ), #8528, .F. ) ; +#2703 = CARTESIAN_POINT ( 'NONE', ( -37.98607222914999682, 191.2865337069999896, 104.9454608741999948 ) ) ; +#2704 = LINE ( 'NONE', #24588, #6475 ) ; +#2705 = CIRCLE ( 'NONE', #11839, 2.000000000035895731 ) ; +#2706 = DIRECTION ( 'NONE', ( 0.6974360921310663874, 0.000000000000000000, -0.7166469824069217065 ) ) ; +#2707 = VECTOR ( 'NONE', #32176, 1000.000000000000114 ) ; +#2708 = ORIENTED_EDGE ( 'NONE', *, *, #18123, .F. ) ; +#2709 = LINE ( 'NONE', #12105, #17887 ) ; +#2710 = CARTESIAN_POINT ( 'NONE', ( -25.83319905905518610, 118.8155673861722761, 90.11672205215975850 ) ) ; +#2711 = ORIENTED_EDGE ( 'NONE', *, *, #9789, .T. ) ; +#2712 = AXIS2_PLACEMENT_3D ( 'NONE', #17110, #16320, #35104 ) ; +#2713 = CARTESIAN_POINT ( 'NONE', ( -38.95638687694488311, 209.7096538831000032, 73.58203285567579144 ) ) ; +#2714 = AXIS2_PLACEMENT_3D ( 'NONE', #29465, #29269, #4709 ) ; +#2715 = CARTESIAN_POINT ( 'NONE', ( -39.71549914202294218, 121.2606343799488826, 123.5760462896040934 ) ) ; +#2717 = CYLINDRICAL_SURFACE ( 'NONE', #15516, 6.000000000000008882 ) ; +#2716 = CARTESIAN_POINT ( 'NONE', ( -23.36160747139575022, 175.2398358893866828, 100.6374888825866378 ) ) ; +#2718 = ORIENTED_EDGE ( 'NONE', *, *, #15045, .T. ) ; +#2719 = CARTESIAN_POINT ( 'NONE', ( 20.20324609528008963, 117.0251910644186495, 87.25558203764020959 ) ) ; +#2720 = ORIENTED_EDGE ( 'NONE', *, *, #537, .F. ) ; +#2721 = CARTESIAN_POINT ( 'NONE', ( 39.38871638061999647, 119.7579850174000029, 90.49501021186000571 ) ) ; +#2722 = DIRECTION ( 'NONE', ( 0.0005884949961273644664, -0.2249510543439051102, 0.9743698870671265722 ) ) ; +#2723 = DIRECTION ( 'NONE', ( 0.7072735235945706300, 0.6508952239913731175, 0.2758615054829884894 ) ) ; +#2724 = CARTESIAN_POINT ( 'NONE', ( 29.91522852905242402, 130.5857354469581537, 89.78294558542910409 ) ) ; +#2725 = LINE ( 'NONE', #30933, #19071 ) ; +#2726 = ORIENTED_EDGE ( 'NONE', *, *, #14656, .T. ) ; +#2727 = ORIENTED_EDGE ( 'NONE', *, *, #38334, .T. ) ; +#2728 = ADVANCED_FACE ( 'NONE', ( #33450 ), #27768, .T. ) ; +#2729 = CARTESIAN_POINT ( 'NONE', ( 30.07825772506129525, 177.1204444582162409, 103.6051399121813859 ) ) ; +#2730 = EDGE_CURVE ( 'NONE', #36211, #10675, #31477, .T. ) ; +#2731 = FACE_OUTER_BOUND ( 'NONE', #37378, .T. ) ; +#2732 = CARTESIAN_POINT ( 'NONE', ( 39.71627783778711773, 128.2995111889279656, 93.17753252016933629 ) ) ; +#2733 = ORIENTED_EDGE ( 'NONE', *, *, #30832, .F. ) ; +#2734 = CARTESIAN_POINT ( 'NONE', ( -35.79834011994000065, 191.7755580150999890, 106.7769966834000002 ) ) ; +#2735 = CONICAL_SURFACE ( 'NONE', #25589, 59.40509898898601904, 0.7853981633972927368 ) ; +#2736 = PLANE ( 'NONE', #31893 ) ; +#2737 = CARTESIAN_POINT ( 'NONE', ( 31.91158940776717046, 137.5571349200599798, 93.95697525044668907 ) ) ; +#2738 = CARTESIAN_POINT ( 'NONE', ( -20.51893387759604082, 207.0373196925199011, 74.44320791140408744 ) ) ; +#2739 = FACE_BOUND ( 'NONE', #7188, .T. ) ; +#2740 = CARTESIAN_POINT ( 'NONE', ( -14.22274084689574636, 128.8778062397453539, 177.5848030100378026 ) ) ; +#2741 = CARTESIAN_POINT ( 'NONE', ( 3.534327104360340588, 144.2236672556986434, 92.94748474794259607 ) ) ; +#2742 = EDGE_LOOP ( 'NONE', ( #6288, #35655, #1003, #25189, #38738, #19601, #16761, #33005, #4527, #15563, #23152, #9113, #3922, #11528, #9787, #39752 ) ) ; +#2743 = CARTESIAN_POINT ( 'NONE', ( -82.80843920860921514, 105.1411378422745315, 24.32376295616780482 ) ) ; +#2744 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971581223 ) ) ; +#2745 = EDGE_CURVE ( 'NONE', #25509, #26218, #12006, .T. ) ; +#2746 = VERTEX_POINT ( 'NONE', #26528 ) ; +#2747 = CARTESIAN_POINT ( 'NONE', ( 16.15375828964846860, 121.3852290249194823, 177.4225633343677089 ) ) ; +#2748 = VERTEX_POINT ( 'NONE', #11799 ) ; +#2749 = VECTOR ( 'NONE', #7330, 999.9999999999998863 ) ; +#2750 = CARTESIAN_POINT ( 'NONE', ( -16.17310216730872696, 121.3958435379269361, 177.4085436696588545 ) ) ; +#2751 = ORIENTED_EDGE ( 'NONE', *, *, #3245, .T. ) ; +#2752 = CIRCLE ( 'NONE', #7282, 22.50000000000899902 ) ; +#2753 = ORIENTED_EDGE ( 'NONE', *, *, #10704, .F. ) ; +#2754 = AXIS2_PLACEMENT_3D ( 'NONE', #35598, #17003, #13965 ) ; +#2755 = ORIENTED_EDGE ( 'NONE', *, *, #12494, .T. ) ; +#2756 = CARTESIAN_POINT ( 'NONE', ( 2.666556751974999973, 208.9737835306000022, 75.79860644781000190 ) ) ; +#2757 = CARTESIAN_POINT ( 'NONE', ( 36.06505478217123795, 192.7057421143160525, 106.3400883098223915 ) ) ; +#2758 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452351231, 0.1781166614240801693 ) ) ; +#2759 = ORIENTED_EDGE ( 'NONE', *, *, #4118, .T. ) ; +#2760 = ORIENTED_EDGE ( 'NONE', *, *, #32084, .F. ) ; +#2761 = EDGE_LOOP ( 'NONE', ( #7505, #1166, #24850, #31777 ) ) ; +#2762 = ORIENTED_EDGE ( 'NONE', *, *, #30260, .F. ) ; +#2763 = FACE_OUTER_BOUND ( 'NONE', #20064, .T. ) ; +#2764 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; +#2765 = FACE_BOUND ( 'NONE', #10228, .T. ) ; +#2766 = ORIENTED_EDGE ( 'NONE', *, *, #11303, .T. ) ; +#2767 = ORIENTED_EDGE ( 'NONE', *, *, #13162, .T. ) ; +#2768 = LINE ( 'NONE', #15825, #2386 ) ; +#2769 = EDGE_CURVE ( 'NONE', #12555, #16053, #2301, .T. ) ; +#2770 = CARTESIAN_POINT ( 'NONE', ( -23.36150835702999728, 130.4188133232366340, 90.28973853306328579 ) ) ; +#2771 = EDGE_CURVE ( 'NONE', #22073, #29530, #19292, .T. ) ; +#2772 = ORIENTED_EDGE ( 'NONE', *, *, #38385, .F. ) ; +#2773 = CARTESIAN_POINT ( 'NONE', ( 32.37225758321823577, 137.6347993665977185, 94.48777941942033465 ) ) ; +#2774 = ORIENTED_EDGE ( 'NONE', *, *, #35353, .T. ) ; +#2775 = CARTESIAN_POINT ( 'NONE', ( -27.39351927441814638, 155.9581902257390880, 179.7869227509170003 ) ) ; +#2776 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457973672226, -32.89481530046830926, 142.2936922234670476 ) ) ; +#2777 = ORIENTED_EDGE ( 'NONE', *, *, #27707, .T. ) ; +#2778 = AXIS2_PLACEMENT_3D ( 'NONE', #27769, #12219, #18517 ) ; +#2779 = CARTESIAN_POINT ( 'NONE', ( 20.50124359822353881, 192.8415971392297195, 106.3310570022938322 ) ) ; +#2780 = CARTESIAN_POINT ( 'NONE', ( 39.23222213371558098, 119.5446253043629952, 90.30966899337110476 ) ) ; +#2781 = VECTOR ( 'NONE', #37657, 999.9999999999998863 ) ; +#2782 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#2783 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14652, #2181, #7689, #38967 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2784 = PLANE ( 'NONE', #36521 ) ; +#2785 = ORIENTED_EDGE ( 'NONE', *, *, #29901, .T. ) ; +#2786 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319378513601 ) ) ; +#2787 = CARTESIAN_POINT ( 'NONE', ( 3.166361538018682253, 127.9931434315633680, 89.20057147989687962 ) ) ; +#2788 = CARTESIAN_POINT ( 'NONE', ( -38.02586384959000299, 119.0401732150000100, 87.39466375838000545 ) ) ; +#2789 = CARTESIAN_POINT ( 'NONE', ( 35.67189333922000571, 113.0182598455999994, 90.12293602590000319 ) ) ; +#2790 = CARTESIAN_POINT ( 'NONE', ( 15.50029466864684835, 174.4049028184354881, 100.4212577462347866 ) ) ; +#2791 = ORIENTED_EDGE ( 'NONE', *, *, #30996, .F. ) ; +#2792 = CARTESIAN_POINT ( 'NONE', ( -13.73941655677348628, 149.5987884763016496, 180.3728828259357897 ) ) ; +#2793 = VERTEX_POINT ( 'NONE', #26944 ) ; +#2794 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 7.822507694019388974E-18, 0.0006039748319385908944 ) ) ; +#2795 = CARTESIAN_POINT ( 'NONE', ( -42.87043966560433716, 121.9075745850112753, 87.82339463871453233 ) ) ; +#2796 = CARTESIAN_POINT ( 'NONE', ( 15.66686156597643631, 151.8948118906095601, 95.05324321876020122 ) ) ; +#2797 = AXIS2_PLACEMENT_3D ( 'NONE', #17005, #10910, #35808 ) ; +#2798 = VERTEX_POINT ( 'NONE', #8735 ) ; +#2799 = DIRECTION ( 'NONE', ( 0.7865509479255969882, 0.6175253892086907115, 0.000000000000000000 ) ) ; +#2800 = ADVANCED_FACE ( 'NONE', ( #38980 ), #12086, .F. ) ; +#2801 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2802 = CARTESIAN_POINT ( 'NONE', ( 0.5640095659521695559, 188.6937662663199546, 105.9805870164321959 ) ) ; +#2803 = AXIS2_PLACEMENT_3D ( 'NONE', #26495, #11151, #39553 ) ; +#2804 = CARTESIAN_POINT ( 'NONE', ( 45.38353882083961821, 130.5441024140029924, 92.50080282210461746 ) ) ; +#2805 = VERTEX_POINT ( 'NONE', #23452 ) ; +#2806 = FACE_OUTER_BOUND ( 'NONE', #3480, .T. ) ; +#2807 = EDGE_CURVE ( 'NONE', #11663, #18757, #35522, .T. ) ; +#2808 = AXIS2_PLACEMENT_3D ( 'NONE', #10678, #29685, #29076 ) ; +#2809 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988446461073, 161.7142231051529677, 96.98759364904307745 ) ) ; +#2810 = ORIENTED_EDGE ( 'NONE', *, *, #6040, .F. ) ; +#2811 = CARTESIAN_POINT ( 'NONE', ( 19.98193060325066384, 205.2974737221514658, 75.64420744299060573 ) ) ; +#2812 = EDGE_CURVE ( 'NONE', #34518, #38661, #11378, .T. ) ; +#2813 = ADVANCED_FACE ( 'NONE', ( #27148 ), #4826, .T. ) ; +#2814 = ORIENTED_EDGE ( 'NONE', *, *, #22234, .T. ) ; +#2815 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#2816 = EDGE_CURVE ( 'NONE', #5155, #6206, #11486, .T. ) ; +#2817 = ADVANCED_FACE ( 'NONE', ( #5033 ), #33849, .F. ) ; +#2818 = DIRECTION ( 'NONE', ( -0.0005884949961248158324, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#2819 = ORIENTED_EDGE ( 'NONE', *, *, #34467, .F. ) ; +#2820 = DIRECTION ( 'NONE', ( 0.6088160902985568779, -0.7729595817128234181, -0.1785397805306046526 ) ) ; +#2821 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#2822 = CARTESIAN_POINT ( 'NONE', ( -15.99823486132552119, 118.9409032897876841, 90.20116722531848552 ) ) ; +#2823 = LINE ( 'NONE', #40027, #28101 ) ; +#2824 = LINE ( 'NONE', #15101, #1475 ) ; +#2825 = ORIENTED_EDGE ( 'NONE', *, *, #10668, .F. ) ; +#2826 = CARTESIAN_POINT ( 'NONE', ( -20.34738573694473729, 105.2139170220266777, 87.78007369431503548 ) ) ; +#2827 = DIRECTION ( 'NONE', ( 0.2974094561516589241, -0.7922998565502274992, 0.5327368512709285131 ) ) ; +#2828 = AXIS2_PLACEMENT_3D ( 'NONE', #29800, #26735, #23660 ) ; +#2829 = CARTESIAN_POINT ( 'NONE', ( 3.667815737396241893, 185.3461555469997109, 105.0070005409011742 ) ) ; +#2830 = CARTESIAN_POINT ( 'NONE', ( -46.08406567220261252, 125.3099125453316702, 91.70648740491583339 ) ) ; +#2831 = ORIENTED_EDGE ( 'NONE', *, *, #29624, .F. ) ; +#2832 = VECTOR ( 'NONE', #21327, 999.9999999999998863 ) ; +#2833 = CARTESIAN_POINT ( 'NONE', ( -43.57149696744355083, 121.9974121635120383, 87.84455870325962223 ) ) ; +#2834 = PLANE ( 'NONE', #18617 ) ; +#2835 = CARTESIAN_POINT ( 'NONE', ( 25.40408268398181235, 212.9186129770236846, 73.04316065302639061 ) ) ; +#2836 = DIRECTION ( 'NONE', ( 0.0005884949961259294164, -0.2255194585872565272, 0.9742384859325513569 ) ) ; +#2837 = CARTESIAN_POINT ( 'NONE', ( 14.17036433007075757, 182.7613733346053380, 102.3513045738081502 ) ) ; +#2838 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452351231, -0.1781166614240801693 ) ) ; +#2839 = CARTESIAN_POINT ( 'NONE', ( 15.10714331102995800, 183.1006619385863701, 101.9159176678921312 ) ) ; +#2840 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1093, #7421, #13578, #26060 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2841 = SECURITY_CLASSIFICATION_LEVEL ( 'unclassified' ) ; +#2842 = DIRECTION ( 'NONE', ( -0.0004161288024524960371, -0.5299192578740949955, -0.8480479980348919478 ) ) ; +#2843 = FACE_OUTER_BOUND ( 'NONE', #27795, .T. ) ; +#2844 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001722, 130.3419545077132682, 92.84535593379679597 ) ) ; +#2845 = EDGE_CURVE ( 'NONE', #35508, #32912, #30605, .T. ) ; +#2846 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#2847 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8519, #2383, #24061, #26933 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2849 = VERTEX_POINT ( 'NONE', #39990 ) ; +#2848 = CARTESIAN_POINT ( 'NONE', ( 36.82578048503000190, 191.4974673927000026, 106.2209708588000012 ) ) ; +#2850 = EDGE_LOOP ( 'NONE', ( #12807, #15761 ) ) ; +#2851 = ORIENTED_EDGE ( 'NONE', *, *, #16040, .T. ) ; +#2852 = DIRECTION ( 'NONE', ( 0.7933533411653069800, -0.5930537057989941907, -0.1373964268091564245 ) ) ; +#2853 = EDGE_CURVE ( 'NONE', #16970, #17201, #27954, .T. ) ; +#2854 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24266, #8722, #8925, #37321, #39764, #27551, #24672, #34230, #33638, #9313, #36511, #27337, #31187, #21180, #36919, #18085 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.0004796803808468277225, 0.0009593607616936554450, 0.001439041142540483167, 0.001918721523387310890, 0.002398401904234139046, 0.002878082285080966335, 0.003837443046774705480 ), + .UNSPECIFIED. ) ; +#2855 = PLANE ( 'NONE', #2031 ) ; +#2856 = EDGE_CURVE ( 'NONE', #27307, #25353, #298, .T. ) ; +#2857 = DIRECTION ( 'NONE', ( -0.6087614810001780175, 0.7729390313185915407, 0.1788147452386051883 ) ) ; +#2858 = EDGE_LOOP ( 'NONE', ( #15921, #1293, #9765, #36742 ) ) ; +#2859 = FACE_OUTER_BOUND ( 'NONE', #35206, .T. ) ; +#2860 = ADVANCED_FACE ( 'NONE', ( #31201 ), #5852, .T. ) ; +#2861 = CIRCLE ( 'NONE', #13313, 2.000000000000011546 ) ; +#2862 = CARTESIAN_POINT ( 'NONE', ( -15.99993873281328050, 165.3377715421495111, 97.83388156752448594 ) ) ; +#2863 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#2864 = ORIENTED_EDGE ( 'NONE', *, *, #4865, .F. ) ; +#2865 = LINE ( 'NONE', #11467, #13995 ) ; +#2866 = CARTESIAN_POINT ( 'NONE', ( 36.05382442436784629, 113.8881156701999942, 87.74600877634995300 ) ) ; +#2867 = CARTESIAN_POINT ( 'NONE', ( 36.56518236884102890, 116.6077097462014933, 90.24570038530379179 ) ) ; +#2868 = CARTESIAN_POINT ( 'NONE', ( -4.704247605369164198, 188.1541984058357286, 103.0945842148524605 ) ) ; +#2869 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2870 = ORIENTED_EDGE ( 'NONE', *, *, #6162, .T. ) ; +#2871 = ORIENTED_EDGE ( 'NONE', *, *, #7035, .T. ) ; +#2872 = DIRECTION ( 'NONE', ( 1.040834085586078261E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#2873 = CARTESIAN_POINT ( 'NONE', ( 1.870897341094000188, 189.3091107925999950, 103.6431386051000061 ) ) ; +#2874 = CARTESIAN_POINT ( 'NONE', ( 20.25161797161999999, 167.0117879878999929, 101.0207373691000043 ) ) ; +#2875 = ORIENTED_EDGE ( 'NONE', *, *, #6847, .F. ) ; +#2876 = CARTESIAN_POINT ( 'NONE', ( -15.56603823807074782, 147.4087826306812019, 179.2784924189769242 ) ) ; +#2877 = ORIENTED_EDGE ( 'NONE', *, *, #16160, .T. ) ; +#2878 = VECTOR ( 'NONE', #8767, 1000.000000000000227 ) ; +#2879 = AXIS2_PLACEMENT_3D ( 'NONE', #33926, #27231, #18181 ) ; +#2880 = CARTESIAN_POINT ( 'NONE', ( 25.50041447495308233, 118.1134306400200416, 89.75249416949174019 ) ) ; +#2881 = CARTESIAN_POINT ( 'NONE', ( 22.64184747305000300, 153.5472371799000086, 97.91075667399999816 ) ) ; +#2882 = FACE_OUTER_BOUND ( 'NONE', #14817, .T. ) ; +#2883 = AXIS2_PLACEMENT_3D ( 'NONE', #30024, #2022, #14087 ) ; +#2884 = FACE_OUTER_BOUND ( 'NONE', #10490, .T. ) ; +#2885 = CARTESIAN_POINT ( 'NONE', ( -12.63737457481493465, 134.4755188138004769, 93.58620110311106544 ) ) ; +#2886 = DIRECTION ( 'NONE', ( -0.0005884949961244347353, 0.2249510543439056098, -0.9743698870671265722 ) ) ; +#2887 = EDGE_LOOP ( 'NONE', ( #2814, #7899, #26105, #7331 ) ) ; +#2888 = EDGE_CURVE ( 'NONE', #1525, #12519, #18497, .T. ) ; +#2889 = ADVANCED_FACE ( 'NONE', ( #3170 ), #6825, .F. ) ; +#2890 = CARTESIAN_POINT ( 'NONE', ( -42.69302072565936612, 103.2982249598779276, 168.6358421031195860 ) ) ; +#2891 = PLANE ( 'NONE', #33993 ) ; +#2892 = ADVANCED_FACE ( 'NONE', ( #9129 ), #36227, .T. ) ; +#2893 = EDGE_CURVE ( 'NONE', #30526, #21678, #15462, .T. ) ; +#2895 = CARTESIAN_POINT ( 'NONE', ( 16.22188721871033934, 122.1949268581505521, 174.0451402755014101 ) ) ; +#2894 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709481474, 82.27946979429644614, 322.5205145037751890 ) ) ; +#2896 = CARTESIAN_POINT ( 'NONE', ( 3.993984635816554718, 143.6429547678539507, 95.42167272605998107 ) ) ; +#2897 = ORIENTED_EDGE ( 'NONE', *, *, #18106, .T. ) ; +#2898 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319383136639 ) ) ; +#2899 = ORIENTED_EDGE ( 'NONE', *, *, #20092, .T. ) ; +#2900 = CARTESIAN_POINT ( 'NONE', ( 27.41760324789147418, 125.0582898930202589, 89.02149762882548600 ) ) ; +#2901 = EDGE_CURVE ( 'NONE', #12880, #5671, #30374, .T. ) ; +#2902 = CARTESIAN_POINT ( 'NONE', ( 29.62326790002893162, 185.7454482597306651, 103.0308995128836216 ) ) ; +#2903 = CARTESIAN_POINT ( 'NONE', ( -25.49213558285381254, 194.2771767961476996, 102.9136721320308538 ) ) ; +#2904 = AXIS2_PLACEMENT_3D ( 'NONE', #21038, #17538, #17737 ) ; +#2905 = CARTESIAN_POINT ( 'NONE', ( -45.15244941250207944, 106.4211879749299925, 169.3571905553632746 ) ) ; +#2906 = ORIENTED_EDGE ( 'NONE', *, *, #3889, .F. ) ; +#2907 = ORIENTED_EDGE ( 'NONE', *, *, #35218, .F. ) ; +#2908 = FACE_OUTER_BOUND ( 'NONE', #18219, .T. ) ; +#2909 = AXIS2_PLACEMENT_3D ( 'NONE', #12257, #9194, #9587 ) ; +#2910 = LINE ( 'NONE', #37068, #4658 ) ; +#2911 = ADVANCED_FACE ( 'NONE', ( #6243 ), #18698, .F. ) ; +#2912 = ORIENTED_EDGE ( 'NONE', *, *, #20668, .T. ) ; +#2913 = CARTESIAN_POINT ( 'NONE', ( -2.437379602309801996, 196.1181861109790532, 103.6812116298660129 ) ) ; +#2914 = CARTESIAN_POINT ( 'NONE', ( 55.76220932283968068, 8.811273727124799393, 151.9488229758013347 ) ) ; +#2915 = CARTESIAN_POINT ( 'NONE', ( 2.328920004101604491, 189.0592395469226972, 106.3913415630415926 ) ) ; +#2916 = CARTESIAN_POINT ( 'NONE', ( -28.45663166759245399, 131.0177812377234545, 89.91795229967709702 ) ) ; +#2917 = CARTESIAN_POINT ( 'NONE', ( 30.07478355117409308, 177.7951688118731681, 100.6820556990014950 ) ) ; +#2918 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#2919 = CARTESIAN_POINT ( 'NONE', ( 4.067263459342049359, 146.7371158628018293, 93.52739776953615092 ) ) ; +#2920 = ORIENTED_EDGE ( 'NONE', *, *, #21000, .F. ) ; +#2921 = CARTESIAN_POINT ( 'NONE', ( 44.88156389711864591, 173.0388276432278190, 165.3842276987274147 ) ) ; +#2922 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825994489843006, 0.0005734119006650908101 ) ) ; +#2923 = CARTESIAN_POINT ( 'NONE', ( -20.33420132830697469, 127.1423375402870306, 91.75263487369595339 ) ) ; +#2924 = AXIS2_PLACEMENT_3D ( 'NONE', #16837, #39128, #11322 ) ; +#2925 = CIRCLE ( 'NONE', #32303, 4.499999279730864998 ) ; +#2926 = ORIENTED_EDGE ( 'NONE', *, *, #36637, .F. ) ; +#2927 = CARTESIAN_POINT ( 'NONE', ( 41.34016251261648023, 109.2214168434603039, 170.0257790416202397 ) ) ; +#2928 = EDGE_LOOP ( 'NONE', ( #5157, #11625, #34525, #5805, #17815 ) ) ; +#2929 = EDGE_CURVE ( 'NONE', #19656, #5211, #32411, .T. ) ; +#2930 = VECTOR ( 'NONE', #2406, 1000.000000000000227 ) ; +#2931 = EDGE_CURVE ( 'NONE', #12603, #2592, #29942, .T. ) ; +#2933 = CARTESIAN_POINT ( 'NONE', ( -3.169881662145332513, 128.5839160399947332, 89.34077473205128683 ) ) ; +#2932 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2934 = ORIENTED_EDGE ( 'NONE', *, *, #635, .F. ) ; +#2935 = ORIENTED_EDGE ( 'NONE', *, *, #21894, .T. ) ; +#2936 = ORIENTED_EDGE ( 'NONE', *, *, #34942, .T. ) ; +#2937 = CARTESIAN_POINT ( 'NONE', ( -13.49852954174901143, 127.1816645162778769, 91.58903530335827270 ) ) ; +#2938 = CARTESIAN_POINT ( 'NONE', ( -76.10954455358901782, 156.3528031849876072, 95.79577929590617202 ) ) ; +#2939 = EDGE_LOOP ( 'NONE', ( #1582, #33183, #27530, #14563 ) ) ; +#2940 = VERTEX_POINT ( 'NONE', #13593 ) ; +#2941 = ORIENTED_EDGE ( 'NONE', *, *, #27801, .F. ) ; +#2942 = CARTESIAN_POINT ( 'NONE', ( -19.33539756116881847, 125.3880314484919722, 178.3186149148302775 ) ) ; +#2943 = PLANE ( 'NONE', #22624 ) ; +#2944 = CARTESIAN_POINT ( 'NONE', ( 22.98769521848599595, 181.6927287775007755, 101.5861108980980987 ) ) ; +#2945 = CARTESIAN_POINT ( 'NONE', ( 21.72804141255551968, 135.8412665901933281, 91.00123227078390187 ) ) ; +#2946 = ORIENTED_EDGE ( 'NONE', *, *, #36645, .F. ) ; +#2947 = ORIENTED_EDGE ( 'NONE', *, *, #40253, .T. ) ; +#2948 = ORIENTED_EDGE ( 'NONE', *, *, #39983, .F. ) ; +#2949 = FACE_OUTER_BOUND ( 'NONE', #39766, .T. ) ; +#2950 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; +#2951 = CARTESIAN_POINT ( 'NONE', ( -28.02783910825000291, 125.2760234380999833, 88.93426760747999538 ) ) ; +#2952 = VECTOR ( 'NONE', #34198, 1000.000000000000000 ) ; +#2953 = ORIENTED_EDGE ( 'NONE', *, *, #15818, .T. ) ; +#2954 = EDGE_CURVE ( 'NONE', #23911, #12970, #34831, .T. ) ; +#2955 = EDGE_LOOP ( 'NONE', ( #25879, #17638, #17452, #30852 ) ) ; +#2956 = DIRECTION ( 'NONE', ( -0.0005734119072319342333, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#2957 = CARTESIAN_POINT ( 'NONE', ( -40.99137513204986050, 188.9331334093535872, 107.3249050511072369 ) ) ; +#2958 = ORIENTED_EDGE ( 'NONE', *, *, #38990, .T. ) ; +#2959 = AXIS2_PLACEMENT_3D ( 'NONE', #36257, #19892, #33177 ) ; +#2960 = CYLINDRICAL_SURFACE ( 'NONE', #38766, 6.000000000048013149 ) ; +#2961 = VECTOR ( 'NONE', #17478, 1000.000000000000227 ) ; +#2962 = AXIS2_PLACEMENT_3D ( 'NONE', #21691, #2, #28616 ) ; +#2963 = CARTESIAN_POINT ( 'NONE', ( 3.993858315201923137, 174.7847376312480776, 102.6114509115379718 ) ) ; +#2964 = CARTESIAN_POINT ( 'NONE', ( -3.820567177493512823, 167.8841678059111757, 101.2013462384420990 ) ) ; +#2965 = FACE_OUTER_BOUND ( 'NONE', #5281, .T. ) ; +#2966 = CARTESIAN_POINT ( 'NONE', ( -3.537744320960331645, 175.3497732290038300, 100.1377481765469355 ) ) ; +#2967 = VERTEX_POINT ( 'NONE', #1308 ) ; +#2968 = CARTESIAN_POINT ( 'NONE', ( -20.51863885680050359, 209.7097602209678939, 75.57089512796630970 ) ) ; +#2969 = ORIENTED_EDGE ( 'NONE', *, *, #25163, .T. ) ; +#2970 = CARTESIAN_POINT ( 'NONE', ( 29.98785144339129616, 77.14301703112315067, 291.5404320243928282 ) ) ; +#2971 = CARTESIAN_POINT ( 'NONE', ( -37.67452696363999820, 118.6320779777999945, 87.39106427871999472 ) ) ; +#2972 = DIRECTION ( 'NONE', ( 0.7933533411653070910, -0.5930537057989941907, -0.1373964268091563690 ) ) ; +#2973 = CARTESIAN_POINT ( 'NONE', ( -28.79107131398339448, 181.6858502269169264, 101.6157959367960189 ) ) ; +#2974 = EDGE_LOOP ( 'NONE', ( #21035, #24661, #17242, #28641 ) ) ; +#2975 = DIRECTION ( 'NONE', ( 0.0004161288024490636698, -0.8480480897979184585, 0.5299191110225421886 ) ) ; +#2976 = ORIENTED_EDGE ( 'NONE', *, *, #37448, .F. ) ; +#2977 = DIRECTION ( 'NONE', ( 0.0005884949961242894522, -0.2249510543439076082, 0.9743698870671259060 ) ) ; +#2978 = VECTOR ( 'NONE', #14074, 1000.000000000000114 ) ; +#2979 = EDGE_CURVE ( 'NONE', #24908, #8891, #6832, .T. ) ; +#2980 = EDGE_CURVE ( 'NONE', #18813, #3536, #13791, .T. ) ; +#2981 = VECTOR ( 'NONE', #31122, 1000.000000000000227 ) ; +#2982 = VECTOR ( 'NONE', #23974, 1000.000000000000114 ) ; +#2983 = CARTESIAN_POINT ( 'NONE', ( -38.37912446231000274, 118.5515219785000056, 89.85344207503999314 ) ) ; +#2984 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#2985 = VECTOR ( 'NONE', #19754, 1000.000000000000114 ) ; +#2986 = ORIENTED_EDGE ( 'NONE', *, *, #36163, .F. ) ; +#2988 = AXIS2_PLACEMENT_3D ( 'NONE', #4084, #23519, #16556 ) ; +#2987 = CARTESIAN_POINT ( 'NONE', ( -25.49999614779992640, 119.8278461530000101, 89.89852083536001714 ) ) ; +#2989 = CARTESIAN_POINT ( 'NONE', ( -23.36160747139494021, 184.0091663913295577, 102.6620487233715551 ) ) ; +#2990 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11577, #10970, #14648, #13277 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#2991 = AXIS2_PLACEMENT_3D ( 'NONE', #20767, #26713, #38748 ) ; +#2992 = CARTESIAN_POINT ( 'NONE', ( 19.98210856654580780, 205.1070970766282358, 76.09272704596726555 ) ) ; +#2993 = CARTESIAN_POINT ( 'NONE', ( 17.27264158547648165, 121.9609240029174941, 174.6061468887760668 ) ) ; +#2994 = CARTESIAN_POINT ( 'NONE', ( -35.44460436179470264, 113.0640021328997875, 90.28919249207498865 ) ) ; +#2995 = VERTEX_POINT ( 'NONE', #19707 ) ; +#2996 = EDGE_LOOP ( 'NONE', ( #34523, #5630, #33469, #11148, #36155 ) ) ; +#2997 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749905615, 132.8602140593031891, 90.82839891348385208 ) ) ; +#2998 = CARTESIAN_POINT ( 'NONE', ( 26.00067918362605468, 118.8155664802563791, 90.25207353690788636 ) ) ; +#2999 = EDGE_LOOP ( 'NONE', ( #5197, #35022, #14101, #9515, #6734, #2069 ) ) ; +#3000 = CARTESIAN_POINT ( 'NONE', ( -23.36207384156027089, 135.2596320619993264, 91.36483358189200032 ) ) ; +#3001 = ORIENTED_EDGE ( 'NONE', *, *, #8106, .T. ) ; +#3002 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971574284 ) ) ; +#3003 = ADVANCED_FACE ( 'NONE', ( #26077 ), #29336, .T. ) ; +#3004 = CARTESIAN_POINT ( 'NONE', ( -21.44517133412774967, 181.8810903885702999, 104.7353468333731428 ) ) ; +#3005 = CARTESIAN_POINT ( 'NONE', ( -42.87041437821633139, 121.8978841230586170, 87.86525719409469559 ) ) ; +#3006 = ORIENTED_EDGE ( 'NONE', *, *, #30138, .T. ) ; +#3007 = CARTESIAN_POINT ( 'NONE', ( -39.12307687603004780, 119.5446354990494342, 90.35700216072328317 ) ) ; +#3008 = CARTESIAN_POINT ( 'NONE', ( 3.867917397069210228, 167.8992108979956015, 101.1512074224550588 ) ) ; +#3009 = CARTESIAN_POINT ( 'NONE', ( 16.92920261701720364, 122.1329027301315477, 174.6418107832293742 ) ) ; +#3010 = AXIS2_PLACEMENT_3D ( 'NONE', #22825, #3786, #35053 ) ; +#3011 = DIRECTION ( 'NONE', ( 0.0005884949961217976304, -0.2249510543439088295, 0.9743698870671256840 ) ) ; +#3012 = CARTESIAN_POINT ( 'NONE', ( -5.670816646075872214, 124.6073922305314881, 88.75515748818936856 ) ) ; +#3013 = VECTOR ( 'NONE', #8225, 1000.000000000000000 ) ; +#3014 = ORIENTED_EDGE ( 'NONE', *, *, #30797, .F. ) ; +#3015 = CARTESIAN_POINT ( 'NONE', ( 15.50147167040193885, 126.2420947773999984, 91.35460322364998831 ) ) ; +#3016 = CARTESIAN_POINT ( 'NONE', ( 21.15458122718195000, 129.0140306984282859, 89.76749365585642693 ) ) ; +#3017 = FACE_OUTER_BOUND ( 'NONE', #18420, .T. ) ; +#3018 = CIRCLE ( 'NONE', #8253, 4.500000000138546952 ) ; +#3019 = EDGE_CURVE ( 'NONE', #27631, #39445, #23657, .T. ) ; +#3020 = CARTESIAN_POINT ( 'NONE', ( -46.09662356910047265, 125.3295157413326422, 91.69427356735783974 ) ) ; +#3021 = ORIENTED_EDGE ( 'NONE', *, *, #7401, .T. ) ; +#3022 = PLANE ( 'NONE', #15352 ) ; +#3023 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#3024 = CARTESIAN_POINT ( 'NONE', ( 25.99015001018950244, 211.2814243414217401, 73.04280668304699020 ) ) ; +#3025 = ADVANCED_FACE ( 'NONE', ( #3567 ), #3556, .F. ) ; +#3026 = CARTESIAN_POINT ( 'NONE', ( -35.90297270143999953, 191.4412966076000089, 103.7424780479999953 ) ) ; +#3027 = ORIENTED_EDGE ( 'NONE', *, *, #22435, .F. ) ; +#3028 = CARTESIAN_POINT ( 'NONE', ( -25.88079993598000073, 189.6069161131000271, 106.1795723502000044 ) ) ; +#3029 = EDGE_CURVE ( 'NONE', #9503, #25148, #16048, .T. ) ; +#3030 = EDGE_CURVE ( 'NONE', #26246, #33584, #23151, .T. ) ; +#3031 = EDGE_CURVE ( 'NONE', #6620, #4954, #8820, .T. ) ; +#3032 = ADVANCED_FACE ( 'NONE', ( #12999 ), #29142, .F. ) ; +#3033 = FACE_OUTER_BOUND ( 'NONE', #7012, .T. ) ; +#3034 = COORDINATED_UNIVERSAL_TIME_OFFSET ( 8, 0, .AHEAD. ) ; +#3035 = CARTESIAN_POINT ( 'NONE', ( 4.469208178247156660, 181.9837231390557122, 101.6644769543693343 ) ) ; +#3036 = CARTESIAN_POINT ( 'NONE', ( 20.45340480371016767, 105.2139170030256281, 87.75543103923976673 ) ) ; +#3037 = FACE_OUTER_BOUND ( 'NONE', #5511, .T. ) ; +#3038 = CARTESIAN_POINT ( 'NONE', ( -13.50718409113456886, 124.3648481134796242, 88.37302201493642428 ) ) ; +#3039 = CONICAL_SURFACE ( 'NONE', #25921, 5.999999999877434931, 0.7853981633861987222 ) ; +#3040 = CARTESIAN_POINT ( 'NONE', ( 38.09222635126999990, 190.2036213682000039, 106.7598474027000037 ) ) ; +#3041 = CARTESIAN_POINT ( 'NONE', ( 37.96379117489740906, 191.4230855713359745, 104.2930860270950006 ) ) ; +#3042 = CARTESIAN_POINT ( 'NONE', ( 36.36134859205999703, 190.7141038027000093, 106.8889422767999946 ) ) ; +#3043 = VECTOR ( 'NONE', #23257, 1000.000000000000227 ) ; +#3044 = ORIENTED_EDGE ( 'NONE', *, *, #21570, .F. ) ; +#3045 = EDGE_LOOP ( 'NONE', ( #15326, #10594, #7691, #23629 ) ) ; +#3046 = LINE ( 'NONE', #15526, #16008 ) ; +#3047 = CARTESIAN_POINT ( 'NONE', ( 20.16621962310517091, 126.7988427542629211, 91.82459364418598113 ) ) ; +#3048 = AXIS2_PLACEMENT_3D ( 'NONE', #11110, #20915, #33163 ) ; +#3049 = CARTESIAN_POINT ( 'NONE', ( 39.04493984371199389, 209.7096538830999748, 73.03492191709887038 ) ) ; +#3050 = CARTESIAN_POINT ( 'NONE', ( -28.47589466077455356, 181.0102030230047774, 104.5385275604374868 ) ) ; +#3051 = ORIENTED_EDGE ( 'NONE', *, *, #19811, .F. ) ; +#3052 = CARTESIAN_POINT ( 'NONE', ( 36.18220281975000319, 191.5955271818000085, 103.9696148665999971 ) ) ; +#3053 = CARTESIAN_POINT ( 'NONE', ( 25.99874167938696345, 118.1131156663084738, 87.25205387058410622 ) ) ; +#3054 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; +#3055 = CARTESIAN_POINT ( 'NONE', ( 25.75064116263000003, 119.9649558487000007, 90.15579708161000383 ) ) ; +#3056 = ORIENTED_EDGE ( 'NONE', *, *, #3209, .F. ) ; +#3057 = CARTESIAN_POINT ( 'NONE', ( 35.04675249777811530, 220.4002260771000294, 76.03733726949710103 ) ) ; +#3058 = CARTESIAN_POINT ( 'NONE', ( 23.36437870454795984, 176.9522535532045424, 103.3412383233359435 ) ) ; +#3059 = CARTESIAN_POINT ( 'NONE', ( -14.03369136115023075, 135.3010097591426302, 90.89809668144418708 ) ) ; +#3060 = FACE_OUTER_BOUND ( 'NONE', #12196, .T. ) ; +#3061 = EDGE_LOOP ( 'NONE', ( #11402, #19829, #12800, #27926 ) ) ; +#3062 = EDGE_LOOP ( 'NONE', ( #15157, #14035, #37232, #35570 ) ) ; +#3063 = CARTESIAN_POINT ( 'NONE', ( 15.95615386316613282, 121.8819051936993816, 174.5510063636885150 ) ) ; +#3064 = CARTESIAN_POINT ( 'NONE', ( 1.635480799156000087, 189.1538750077000088, 103.6018120742999997 ) ) ; +#3065 = CARTESIAN_POINT ( 'NONE', ( -22.78405533929291948, 158.5507182435040079, 96.61310224121642420 ) ) ; +#3066 = EDGE_CURVE ( 'NONE', #16493, #6692, #14812, .T. ) ; +#3067 = CONICAL_SURFACE ( 'NONE', #29204, 2.999999999919114035, 0.7853981633692810327 ) ; +#3068 = EDGE_LOOP ( 'NONE', ( #7435, #9216, #38555, #4790, #34771 ) ) ; +#3069 = ORIENTED_EDGE ( 'NONE', *, *, #38556, .F. ) ; +#3070 = FACE_OUTER_BOUND ( 'NONE', #38897, .T. ) ; +#3071 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38379, #26332, #10787, #13453 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3072 = AXIS2_PLACEMENT_3D ( 'NONE', #2061, #11456, #23942 ) ; +#3073 = VERTEX_POINT ( 'NONE', #35631 ) ; +#3074 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #36647, #29910, #33364, #8649 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.570796326794906994, 1.749868521873144678 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973295471489362907, 0.9973295471489362907, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#3075 = AXIS2_PLACEMENT_3D ( 'NONE', #26138, #10593, #13846 ) ; +#3076 = ADVANCED_FACE ( 'NONE', ( #14207 ), #14607, .F. ) ; +#3077 = CARTESIAN_POINT ( 'NONE', ( -17.26187873221201130, 121.2921859730249849, 177.4392858027187003 ) ) ; +#3079 = EDGE_CURVE ( 'NONE', #18693, #38501, #38192, .T. ) ; +#3078 = CARTESIAN_POINT ( 'NONE', ( -3.786117645261999787, 140.1650965393000092, 94.83720733612000231 ) ) ; +#3080 = CARTESIAN_POINT ( 'NONE', ( -35.45366962802970789, 209.7096538831000032, 78.07991812242468654 ) ) ; +#3081 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4681, #33290, #11232, #33093 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.002027470929952764501 ), + .UNSPECIFIED. ) ; +#3082 = EDGE_CURVE ( 'NONE', #15187, #7826, #4223, .T. ) ; +#3083 = CARTESIAN_POINT ( 'NONE', ( -25.02112439774744246, 181.4181497952224333, 104.6306287658777165 ) ) ; +#3084 = EDGE_CURVE ( 'NONE', #34551, #7887, #4775, .T. ) ; +#3085 = DIRECTION ( 'NONE', ( -0.0006039748319384231684, -2.335630580398557718E-15, -0.9999998176071847045 ) ) ; +#3086 = EDGE_CURVE ( 'NONE', #36516, #15062, #5390, .T. ) ; +#3087 = PLANE ( 'NONE', #35585 ) ; +#3088 = CARTESIAN_POINT ( 'NONE', ( -0.9305748042227944827, 189.0423004457716161, 105.7504655986643911 ) ) ; +#3089 = VERTEX_POINT ( 'NONE', #5176 ) ; +#3090 = CARTESIAN_POINT ( 'NONE', ( -7.998197201794713607, 181.6877316537963907, 101.6036458862231058 ) ) ; +#3091 = CARTESIAN_POINT ( 'NONE', ( -39.71708503720267203, 121.0975557797884932, 124.2941153462564756 ) ) ; +#3092 = LINE ( 'NONE', #31510, #21621 ) ; +#3094 = CARTESIAN_POINT ( 'NONE', ( 16.22047286113847164, 122.4940578689917601, 172.7457956654259590 ) ) ; +#3093 = FACE_OUTER_BOUND ( 'NONE', #38541, .T. ) ; +#3095 = EDGE_LOOP ( 'NONE', ( #33717, #38442, #21115, #9200, #16559 ) ) ; +#3096 = AXIS2_PLACEMENT_3D ( 'NONE', #39306, #14797, #7828 ) ; +#3097 = CARTESIAN_POINT ( 'NONE', ( 21.73150615163542554, 115.3932069353914471, 87.25465900686118914 ) ) ; +#3098 = CARTESIAN_POINT ( 'NONE', ( 46.55403492231632612, 110.7336015912822376, 151.9816296823271955 ) ) ; +#3099 = ORIENTED_EDGE ( 'NONE', *, *, #8822, .F. ) ; +#3100 = CARTESIAN_POINT ( 'NONE', ( -27.65129847970650800, 123.9714961408685951, 91.36960946739799283 ) ) ; +#3101 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319386436951 ) ) ; +#3102 = CARTESIAN_POINT ( 'NONE', ( 29.46758137170211356, 130.8205874185748598, 89.83743581285379776 ) ) ; +#3103 = DIRECTION ( 'NONE', ( 1.734723476008841552E-15, 0.9743700557921586292, 0.2249510932971562072 ) ) ; +#3104 = CARTESIAN_POINT ( 'NONE', ( -12.64130811310021762, 134.9973451780017228, 90.93666802679005912 ) ) ; +#3105 = ORIENTED_EDGE ( 'NONE', *, *, #31685, .F. ) ; +#3106 = DIRECTION ( 'NONE', ( -0.0005734119072321099825, 0.000000000000000000, -0.9999998355993788834 ) ) ; +#3107 = VERTEX_POINT ( 'NONE', #27091 ) ; +#3108 = CARTESIAN_POINT ( 'NONE', ( 5.664720472934660300, 124.5090647592738975, 88.58889915586530606 ) ) ; +#3109 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#3110 = CARTESIAN_POINT ( 'NONE', ( -38.72339233899131727, 70.77327613454784228, 322.7414739270242308 ) ) ; +#3111 = ORIENTED_EDGE ( 'NONE', *, *, #11119, .T. ) ; +#3112 = ORIENTED_EDGE ( 'NONE', *, *, #4816, .F. ) ; +#3113 = CARTESIAN_POINT ( 'NONE', ( -35.64769185326999690, 191.6906041802000118, 106.9440936951999959 ) ) ; +#3114 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971522381 ) ) ; +#3115 = EDGE_CURVE ( 'NONE', #13026, #14171, #20317, .T. ) ; +#3116 = CARTESIAN_POINT ( 'NONE', ( 2.428755093643999885, 191.0297069190999935, 106.1808341487000007 ) ) ; +#3117 = ADVANCED_FACE ( 'NONE', ( #39320 ), #26883, .T. ) ; +#3118 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29702, #20275, #14569, #39486, #16992, #29494, #23366, #9033, #31114, #34352, #24393, #27474 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999996406208, 0.3749999999994609312, 0.4374999999993957056, 0.4687499999993570143, 0.4843749999993131050, 0.4999999999992691402, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3119 = ADVANCED_FACE ( 'NONE', ( #32593 ), #36466, .F. ) ; +#3120 = VERTEX_POINT ( 'NONE', #10940 ) ; +#3121 = CARTESIAN_POINT ( 'NONE', ( 2.563235677694000181, 190.8834820154999932, 106.2802016037999948 ) ) ; +#3122 = VERTEX_POINT ( 'NONE', #17235 ) ; +#3123 = CARTESIAN_POINT ( 'NONE', ( -37.26517045375702963, 190.4055305187127374, 106.7129241467131493 ) ) ; +#3124 = CARTESIAN_POINT ( 'NONE', ( 36.34648484248651812, 191.3863812484165692, 103.8159989434559236 ) ) ; +#3125 = CARTESIAN_POINT ( 'NONE', ( -25.62251701078999844, 120.0771796793000163, 90.08090160909999611 ) ) ; +#3126 = ADVANCED_FACE ( 'NONE', ( #4980 ), #39526, .T. ) ; +#3127 = AXIS2_PLACEMENT_3D ( 'NONE', #2226, #8360, #20613 ) ; +#3128 = ORIENTED_EDGE ( 'NONE', *, *, #15640, .F. ) ; +#3129 = CARTESIAN_POINT ( 'NONE', ( 23.44927699246683162, 122.1667780762339959, 174.9970789168699525 ) ) ; +#3130 = DIRECTION ( 'NONE', ( -0.7933310414247657372, -0.5931044597393388962, -0.1373060761554398823 ) ) ; +#3131 = EDGE_CURVE ( 'NONE', #13855, #15604, #24616, .T. ) ; +#3132 = ORIENTED_EDGE ( 'NONE', *, *, #6864, .F. ) ; +#3133 = FACE_OUTER_BOUND ( 'NONE', #29079, .T. ) ; +#3134 = EDGE_LOOP ( 'NONE', ( #34278, #8195, #30284 ) ) ; +#3136 = DIRECTION ( 'NONE', ( -9.842052273231448302E-18, 0.9743043966640313469, 0.2252353050503801690 ) ) ; +#3135 = CARTESIAN_POINT ( 'NONE', ( 36.17584157855313265, 192.0444006922266453, 104.3821376135421417 ) ) ; +#3137 = VERTEX_POINT ( 'NONE', #29535 ) ; +#3138 = EDGE_CURVE ( 'NONE', #34249, #19429, #26475, .T. ) ; +#3139 = ORIENTED_EDGE ( 'NONE', *, *, #6715, .T. ) ; +#3140 = CARTESIAN_POINT ( 'NONE', ( 2.869617488373000125, 209.5348629560000120, 75.94025826473999530 ) ) ; +#3141 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#3142 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#3143 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #32691, #7133, #23094 ), + ( #29629, #4672, #19603 ), + ( #29430, #35516, #32101 ), + ( #1608, #29019, #4055 ) ), + .UNSPECIFIED., .F., .F., .T. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), + ( 3, 3 ), + ( 0.4676625337841107677, 0.4676714590453207032 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.7512080252030892691, 1.000000000000000000), + ( 1.000000000000000000, 0.7512041196470712334, 1.000000000000000000), + ( 1.000000000000000000, 0.7512002140471668588, 1.000000000000000000), + ( 1.000000000000000000, 0.7511963084032677873, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#3144 = ORIENTED_EDGE ( 'NONE', *, *, #11721, .T. ) ; +#3145 = VERTEX_POINT ( 'NONE', #23402 ) ; +#3146 = CARTESIAN_POINT ( 'NONE', ( -10.07691662939999944, 159.1892556871999886, 28.07991271570000080 ) ) ; +#3147 = CARTESIAN_POINT ( 'NONE', ( 23.35635955975471134, 181.6919812636757285, 101.5857449861623110 ) ) ; +#3148 = CARTESIAN_POINT ( 'NONE', ( 2.939913603357601879, 209.7148157245962636, 73.05672935661613110 ) ) ; +#3149 = ORIENTED_EDGE ( 'NONE', *, *, #26909, .F. ) ; +#3150 = AXIS2_PLACEMENT_3D ( 'NONE', #4105, #19246, #16577 ) ; +#3151 = ORIENTED_EDGE ( 'NONE', *, *, #12026, .T. ) ; +#3152 = CARTESIAN_POINT ( 'NONE', ( -38.46311518618121994, 218.5902260770998282, 61.08173265144981201 ) ) ; +#3153 = CARTESIAN_POINT ( 'NONE', ( -3.168077782478838866, 185.2310913118877238, 105.4977280106237032 ) ) ; +#3154 = CARTESIAN_POINT ( 'NONE', ( -25.69440169518000161, 121.2625582629000007, 88.00628069721000202 ) ) ; +#3155 = ORIENTED_EDGE ( 'NONE', *, *, #13476, .F. ) ; +#3156 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178582675974E-05, -0.0002331579774919535406 ) ) ; +#3157 = CARTESIAN_POINT ( 'NONE', ( 36.06517739910999865, 192.1776130000999956, 106.5431043960000039 ) ) ; +#3158 = ORIENTED_EDGE ( 'NONE', *, *, #16427, .F. ) ; +#3159 = EDGE_CURVE ( 'NONE', #38835, #6430, #22649, .T. ) ; +#3160 = ADVANCED_FACE ( 'NONE', ( #35839 ), #29937, .T. ) ; +#3161 = ADVANCED_FACE ( 'NONE', ( #33801 ), #32978, .T. ) ; +#3162 = CARTESIAN_POINT ( 'NONE', ( 20.50133968371435600, 192.3938364616093395, 106.3952512657694740 ) ) ; +#3163 = CARTESIAN_POINT ( 'NONE', ( -45.39778118714025368, 124.3162297631632498, 88.38100305590371875 ) ) ; +#3164 = FACE_OUTER_BOUND ( 'NONE', #20719, .T. ) ; +#3165 = CARTESIAN_POINT ( 'NONE', ( 1.447658033344549455, 144.9407251398178005, 129.0349007176305065 ) ) ; +#3166 = ADVANCED_FACE ( 'NONE', ( #37082 ), #15007, .T. ) ; +#3167 = ORIENTED_EDGE ( 'NONE', *, *, #32934, .F. ) ; +#3168 = CARTESIAN_POINT ( 'NONE', ( 24.51658391451750063, 115.4942485871420530, 90.25297743685760565 ) ) ; +#3169 = DIRECTION ( 'NONE', ( 0.0005884949961226875435, -0.2249510543439053323, 0.9743698870671265722 ) ) ; +#3170 = FACE_OUTER_BOUND ( 'NONE', #32233, .T. ) ; +#3171 = CARTESIAN_POINT ( 'NONE', ( 36.04803287507999698, 114.1790057977000004, 89.85008343190000346 ) ) ; +#3172 = EDGE_CURVE ( 'NONE', #15935, #23183, #13866, .T. ) ; +#3173 = VECTOR ( 'NONE', #7574, 999.9999999999998863 ) ; +#3174 = CARTESIAN_POINT ( 'NONE', ( 5.957091369052168517, 163.5651307542015900, 97.41131042763848313 ) ) ; +#3175 = VERTEX_POINT ( 'NONE', #21355 ) ; +#3176 = LINE ( 'NONE', #18911, #10887 ) ; +#3177 = ORIENTED_EDGE ( 'NONE', *, *, #16231, .F. ) ; +#3178 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981262413, 143.0051697192221241, 291.5876487235602212 ) ) ; +#3179 = AXIS2_PLACEMENT_3D ( 'NONE', #10428, #3862, #32296 ) ; +#3180 = VECTOR ( 'NONE', #23202, 1000.000000000000114 ) ; +#3181 = AXIS2_PLACEMENT_3D ( 'NONE', #15744, #31715, #31499 ) ; +#3182 = FACE_OUTER_BOUND ( 'NONE', #34564, .T. ) ; +#3183 = ADVANCED_FACE ( 'NONE', ( #24635 ), #30756, .F. ) ; +#3184 = DIRECTION ( 'NONE', ( -0.0006039748319369852994, -1.041357760393576070E-14, -0.9999998176071845934 ) ) ; +#3185 = ORIENTED_EDGE ( 'NONE', *, *, #3482, .T. ) ; +#3186 = DIRECTION ( 'NONE', ( -0.6185863125140933505, -0.7857168535612663041, 0.000000000000000000 ) ) ; +#3187 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#3188 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2068, #20871, #15152, #36612, #20664, #39455 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 2.860979249076398407E-17, 0.0006096144684851653424, 0.001219228936970302062 ), + .UNSPECIFIED. ) ; +#3189 = CARTESIAN_POINT ( 'NONE', ( -26.69810905257040901, 110.6131156702000027, 87.28390928083501876 ) ) ; +#3190 = FACE_OUTER_BOUND ( 'NONE', #1109, .T. ) ; +#3191 = FACE_OUTER_BOUND ( 'NONE', #39757, .T. ) ; +#3192 = ORIENTED_EDGE ( 'NONE', *, *, #10341, .F. ) ; +#3193 = VERTEX_POINT ( 'NONE', #31353 ) ; +#3194 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; +#3195 = FACE_OUTER_BOUND ( 'NONE', #15204, .T. ) ; +#3196 = ORIENTED_EDGE ( 'NONE', *, *, #11647, .T. ) ; +#3197 = CARTESIAN_POINT ( 'NONE', ( -23.36258049448036545, 135.1102247128141869, 91.12573217262112735 ) ) ; +#3198 = EDGE_LOOP ( 'NONE', ( #36355, #8871, #6552, #27673 ) ) ; +#3199 = CARTESIAN_POINT ( 'NONE', ( 31.30352330330278576, 110.6131156702000027, 87.24887774834422771 ) ) ; +#3200 = CARTESIAN_POINT ( 'NONE', ( -3.544777117989765358, 143.5348730270079045, 95.86257910123372028 ) ) ; +#3201 = CARTESIAN_POINT ( 'NONE', ( -30.07082631362985836, 134.8398731441967868, 93.36708164982407254 ) ) ; +#3202 = ORIENTED_EDGE ( 'NONE', *, *, #23674, .F. ) ; +#3203 = CARTESIAN_POINT ( 'NONE', ( 28.50030073765000438, 125.2690929875000023, 88.55614377201999332 ) ) ; +#3204 = VECTOR ( 'NONE', #31398, 1000.000000000000114 ) ; +#3205 = CARTESIAN_POINT ( 'NONE', ( 3.951797994296321281, 167.9176274429178477, 101.0692708321294617 ) ) ; +#3206 = VECTOR ( 'NONE', #33150, 1000.000000000000114 ) ; +#3207 = DIRECTION ( 'NONE', ( 0.6087611427424952648, 0.7731004630501230324, 0.1781166615410720855 ) ) ; +#3208 = ADVANCED_FACE ( 'NONE', ( #18853 ), #21559, .T. ) ; +#3209 = EDGE_CURVE ( 'NONE', #15600, #39537, #327, .T. ) ; +#3210 = CARTESIAN_POINT ( 'NONE', ( -23.47088702255031833, 115.1393135932683549, 90.28196066683830168 ) ) ; +#3211 = VECTOR ( 'NONE', #40335, 1000.000000000000114 ) ; +#3212 = CARTESIAN_POINT ( 'NONE', ( 20.48136443024816344, 209.7093559074854454, 75.54613107284740181 ) ) ; +#3213 = ORIENTED_EDGE ( 'NONE', *, *, #29997, .T. ) ; +#3214 = CARTESIAN_POINT ( 'NONE', ( -28.46687737262882578, 130.4181374544887717, 90.29266601121980784 ) ) ; +#3215 = CARTESIAN_POINT ( 'NONE', ( -38.01211212650550664, 119.1971871873620472, 87.30118044812934386 ) ) ; +#3216 = CARTESIAN_POINT ( 'NONE', ( 36.75389250537243413, 191.6320475598886617, 104.3442590335249491 ) ) ; +#3217 = CARTESIAN_POINT ( 'NONE', ( 20.50029382560668267, 151.8610500380989947, 95.21357841101577435 ) ) ; +#3218 = ORIENTED_EDGE ( 'NONE', *, *, #21345, .T. ) ; +#3219 = EDGE_CURVE ( 'NONE', #9009, #17381, #3328, .T. ) ; +#3220 = VERTEX_POINT ( 'NONE', #37481 ) ; +#3221 = CARTESIAN_POINT ( 'NONE', ( 38.51916230496642157, 119.0542509004514216, 90.25158710978716670 ) ) ; +#3222 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31244, #22260, #21851, #21462 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3223 = CARTESIAN_POINT ( 'NONE', ( 45.67081843470916880, 116.8212980865162507, 122.5178260610734355 ) ) ; +#3224 = DIRECTION ( 'NONE', ( 0.0006039748319386906410, -0.000000000000000000, 0.9999998176071845934 ) ) ; +#3225 = CARTESIAN_POINT ( 'NONE', ( -12.63810009328765815, 177.7933493439334995, 100.7042247836448752 ) ) ; +#3226 = CARTESIAN_POINT ( 'NONE', ( -25.50227423591953979, 190.9796784765214852, 106.3235097443510284 ) ) ; +#3227 = ORIENTED_EDGE ( 'NONE', *, *, #35102, .T. ) ; +#3228 = CARTESIAN_POINT ( 'NONE', ( -12.64562993050861550, 181.6872450680611450, 101.6064063805796280 ) ) ; +#3229 = AXIS2_PLACEMENT_3D ( 'NONE', #30492, #17990, #23743 ) ; +#3230 = EDGE_CURVE ( 'NONE', #33101, #31797, #14800, .T. ) ; +#3231 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#3232 = ORIENTED_EDGE ( 'NONE', *, *, #15673, .T. ) ; +#3233 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971562627 ) ) ; +#3234 = LINE ( 'NONE', #2844, #13337 ) ; +#3235 = AXIS2_PLACEMENT_3D ( 'NONE', #11050, #8797, #20429 ) ; +#3236 = CARTESIAN_POINT ( 'NONE', ( 15.94114414956070114, 127.7634661670421821, 175.0287683583358671 ) ) ; +#3237 = CARTESIAN_POINT ( 'NONE', ( 37.18464630843030250, 191.0632717833100003, 106.3149164087080010 ) ) ; +#3238 = CIRCLE ( 'NONE', #26753, 47.99999999997671551 ) ; +#3239 = AXIS2_PLACEMENT_3D ( 'NONE', #33349, #5346, #17800 ) ; +#3240 = CARTESIAN_POINT ( 'NONE', ( 36.82629873762999750, 191.4958914448999963, 106.2217378751000041 ) ) ; +#3241 = VERTEX_POINT ( 'NONE', #6395 ) ; +#3242 = VERTEX_POINT ( 'NONE', #9282 ) ; +#3243 = CARTESIAN_POINT ( 'NONE', ( 12.68911377202444690, 149.1576569327452830, 181.5431584767406719 ) ) ; +#3244 = CARTESIAN_POINT ( 'NONE', ( 18.27501454530099778, 148.8043935767992991, 179.5886459556068075 ) ) ; +#3245 = EDGE_CURVE ( 'NONE', #6212, #13097, #23870, .T. ) ; +#3246 = ORIENTED_EDGE ( 'NONE', *, *, #18524, .F. ) ; +#3247 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098504, 132.2930706491191302, 93.28496646305455897 ) ) ; +#3248 = VERTEX_POINT ( 'NONE', #39727 ) ; +#3249 = CARTESIAN_POINT ( 'NONE', ( 37.68422603034999696, 118.9267550994999993, 87.11617958790999694 ) ) ; +#3250 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#3251 = CARTESIAN_POINT ( 'NONE', ( -23.36055974376046152, 134.8407614661141167, 93.36323390133236444 ) ) ; +#3252 = ORIENTED_EDGE ( 'NONE', *, *, #25857, .F. ) ; +#3253 = DIRECTION ( 'NONE', ( -0.0006039748319369852994, -1.041357760393576070E-14, -0.9999998176071845934 ) ) ; +#3254 = PLANE ( 'NONE', #37712 ) ; +#3255 = EDGE_CURVE ( 'NONE', #5536, #3701, #11740, .T. ) ; +#3256 = EDGE_CURVE ( 'NONE', #14356, #26486, #29734, .T. ) ; +#3257 = CARTESIAN_POINT ( 'NONE', ( -20.00022154816416986, 118.3566885621645355, 87.28023708086698207 ) ) ; +#3258 = CARTESIAN_POINT ( 'NONE', ( -20.61947746437169471, 212.9340256350066625, 76.07098123360772490 ) ) ; +#3259 = EDGE_CURVE ( 'NONE', #5536, #723, #16660, .T. ) ; +#3260 = ORIENTED_EDGE ( 'NONE', *, *, #38392, .F. ) ; +#3261 = CIRCLE ( 'NONE', #4566, 2.000000000410405487 ) ; +#3262 = CARTESIAN_POINT ( 'NONE', ( 12.64014591831122658, 176.7741019297823470, 103.0645574512443829 ) ) ; +#3263 = VECTOR ( 'NONE', #13370, 1000.000000000000227 ) ; +#3264 = CARTESIAN_POINT ( 'NONE', ( 2.407405297639999997, 189.3998359004000349, 103.3772235684999998 ) ) ; +#3265 = CARTESIAN_POINT ( 'NONE', ( -22.49965381657531438, 154.2035805907503061, 95.43826538557833317 ) ) ; +#3266 = AXIS2_PLACEMENT_3D ( 'NONE', #8338, #17912, #17303 ) ; +#3267 = ORIENTED_EDGE ( 'NONE', *, *, #5427, .T. ) ; +#3268 = ORIENTED_EDGE ( 'NONE', *, *, #2954, .F. ) ; +#3269 = DIRECTION ( 'NONE', ( -0.7855779781279679241, -0.6187626687837380901, 0.000000000000000000 ) ) ; +#3270 = ORIENTED_EDGE ( 'NONE', *, *, #390, .T. ) ; +#3271 = CARTESIAN_POINT ( 'NONE', ( -17.02532382067440864, 121.5076908700915084, 177.5319285829079661 ) ) ; +#3272 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971551802 ) ) ; +#3273 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#3274 = CARTESIAN_POINT ( 'NONE', ( -17.26247767858138005, 152.5342161776122225, 182.4800534808789791 ) ) ; +#3275 = LINE ( 'NONE', #16159, #11544 ) ; +#3276 = CARTESIAN_POINT ( 'NONE', ( -12.64347415174542810, 134.2426399615423236, 93.73178815038983203 ) ) ; +#3277 = CARTESIAN_POINT ( 'NONE', ( -1.245306343188852249, 189.1709453704749819, 105.7877068131130471 ) ) ; +#3278 = ORIENTED_EDGE ( 'NONE', *, *, #2812, .F. ) ; +#3279 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; +#3280 = DIRECTION ( 'NONE', ( -0.5987319960703999522, -0.8009494346596135461, 0.000000000000000000 ) ) ; +#3281 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178630073228E-05, 0.0002331579774917273760 ) ) ; +#3282 = CARTESIAN_POINT ( 'NONE', ( -2.789070135026212149, 208.9474333102131709, 73.28733511393602384 ) ) ; +#3283 = VERTEX_POINT ( 'NONE', #24835 ) ; +#3284 = ORIENTED_EDGE ( 'NONE', *, *, #18399, .F. ) ; +#3285 = AXIS2_PLACEMENT_3D ( 'NONE', #31853, #7279, #25318 ) ; +#3286 = CIRCLE ( 'NONE', #10495, 2.000000000000005773 ) ; +#3287 = VERTEX_POINT ( 'NONE', #6195 ) ; +#3288 = EDGE_CURVE ( 'NONE', #29278, #35994, #13364, .T. ) ; +#3289 = AXIS2_PLACEMENT_3D ( 'NONE', #15025, #630, #21159 ) ; +#3290 = CIRCLE ( 'NONE', #5933, 51.40509898897001761 ) ; +#3291 = CARTESIAN_POINT ( 'NONE', ( -14.16859889492986468, 129.2741495211867004, 92.07252832466726034 ) ) ; +#3292 = ORIENTED_EDGE ( 'NONE', *, *, #11636, .F. ) ; +#3293 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25974, #10427, #22897, #32295 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3294 = ORIENTED_EDGE ( 'NONE', *, *, #7500, .F. ) ; +#3295 = CARTESIAN_POINT ( 'NONE', ( 8.048542121204103950, 160.5989240000510279, 99.80415721606205182 ) ) ; +#3296 = DIRECTION ( 'NONE', ( -0.9999998176071852596, 0.000000000000000000, 0.0006039748306867266138 ) ) ; +#3297 = ADVANCED_FACE ( 'NONE', ( #18048 ), #30549, .F. ) ; +#3298 = CARTESIAN_POINT ( 'NONE', ( -40.80719639505100105, 126.7988830470261092, 92.03030911972437877 ) ) ; +#3299 = DIRECTION ( 'NONE', ( -0.0006039748319384873531, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#3300 = CARTESIAN_POINT ( 'NONE', ( -12.63793204807002901, 135.2920832194301397, 91.40834497133602099 ) ) ; +#3301 = ORIENTED_EDGE ( 'NONE', *, *, #35203, .T. ) ; +#3302 = CARTESIAN_POINT ( 'NONE', ( 15.95571139697598717, 122.2635198402779366, 172.8964588220518124 ) ) ; +#3303 = ORIENTED_EDGE ( 'NONE', *, *, #14263, .F. ) ; +#3304 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#3305 = EDGE_CURVE ( 'NONE', #5125, #1066, #27079, .T. ) ; +#3306 = EDGE_CURVE ( 'NONE', #15935, #35968, #1709, .T. ) ; +#3307 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25192, #425, #6157, #15565 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 6.279468620546222013, 9.421061274136015129 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.3333333333333333703, 0.3333333333333333703, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#3308 = CARTESIAN_POINT ( 'NONE', ( -45.39778154263243692, 124.3161987079337507, 88.38112278943124522 ) ) ; +#3309 = EDGE_CURVE ( 'NONE', #29516, #13086, #34346, .T. ) ; +#3310 = EDGE_LOOP ( 'NONE', ( #31426, #2711 ) ) ; +#3311 = LINE ( 'NONE', #22350, #7569 ) ; +#3312 = ADVANCED_FACE ( 'NONE', ( #16000 ), #8189, .T. ) ; +#3313 = CARTESIAN_POINT ( 'NONE', ( 1.765720771383857191, 188.9184207026980005, 103.2671111675515476 ) ) ; +#3314 = CARTESIAN_POINT ( 'NONE', ( 16.24603267945985507, 152.0453547567774706, 181.0525560685096593 ) ) ; +#3315 = ORIENTED_EDGE ( 'NONE', *, *, #2634, .F. ) ; +#3316 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950931402, 137.3532831589782575, 178.0585834213011083 ) ) ; +#3317 = CARTESIAN_POINT ( 'NONE', ( 45.50974939072701630, 131.1361171346210313, 90.41374468093005135 ) ) ; +#3318 = ORIENTED_EDGE ( 'NONE', *, *, #27942, .F. ) ; +#3319 = AXIS2_PLACEMENT_3D ( 'NONE', #270, #10504, #35397 ) ; +#3320 = VECTOR ( 'NONE', #13579, 1000.000000000000227 ) ; +#3321 = CARTESIAN_POINT ( 'NONE', ( -17.26178222639411430, 121.7713432978476220, 175.3684242141576703 ) ) ; +#3322 = CARTESIAN_POINT ( 'NONE', ( 36.11364262193256280, 191.5260145455536929, 103.8483746271915322 ) ) ; +#3323 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048985379, 177.1117171981417471, 103.6430084149241679 ) ) ; +#3324 = VECTOR ( 'NONE', #140, 1000.000000000000000 ) ; +#3325 = ORIENTED_EDGE ( 'NONE', *, *, #35536, .T. ) ; +#3326 = AXIS2_PLACEMENT_3D ( 'NONE', #7074, #22838, #19941 ) ; +#3327 = CARTESIAN_POINT ( 'NONE', ( 0.7299322866671852372, 188.3861608050018219, 106.2237677405733081 ) ) ; +#3328 = LINE ( 'NONE', #15213, #6862 ) ; +#3329 = CARTESIAN_POINT ( 'NONE', ( -75.98888182033904570, 155.7827505944902953, 98.22986012165449665 ) ) ; +#3330 = ORIENTED_EDGE ( 'NONE', *, *, #29917, .F. ) ; +#3331 = FACE_OUTER_BOUND ( 'NONE', #28822, .T. ) ; +#3332 = CARTESIAN_POINT ( 'NONE', ( -25.50006458888940131, 118.8155663869242886, 89.78318340809063614 ) ) ; +#3334 = CARTESIAN_POINT ( 'NONE', ( 35.65490496190012237, 191.9590344014766572, 103.8998585555165590 ) ) ; +#3333 = DIRECTION ( 'NONE', ( 0.0005884949961249847511, -0.2249510543439063592, 0.9743698870671262391 ) ) ; +#3335 = EDGE_LOOP ( 'NONE', ( #4901, #11154 ) ) ; +#3336 = ORIENTED_EDGE ( 'NONE', *, *, #10892, .T. ) ; +#3337 = CARTESIAN_POINT ( 'NONE', ( -20.18507781052162287, 209.7097153168429600, 75.90405272105060419 ) ) ; +#3338 = EDGE_CURVE ( 'NONE', #10716, #14788, #10493, .T. ) ; +#3339 = CARTESIAN_POINT ( 'NONE', ( 26.71540924722000199, 177.4950356244999909, 100.8713215240999972 ) ) ; +#3340 = ORIENTED_EDGE ( 'NONE', *, *, #28037, .T. ) ; +#3341 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #477, #24853, #9905, #37302 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3342 = AXIS2_PLACEMENT_3D ( 'NONE', #39209, #23896, #23479 ) ; +#3343 = ORIENTED_EDGE ( 'NONE', *, *, #25724, .F. ) ; +#3345 = AXIS2_PLACEMENT_3D ( 'NONE', #36874, #5993, #5383 ) ; +#3344 = CARTESIAN_POINT ( 'NONE', ( -35.52033196490545208, 114.0817143859714662, 87.28923768247270232 ) ) ; +#3346 = EDGE_CURVE ( 'NONE', #29413, #33023, #36916, .T. ) ; +#3347 = VECTOR ( 'NONE', #6489, 1000.000000000000227 ) ; +#3348 = CARTESIAN_POINT ( 'NONE', ( 13.50310338664140986, 187.4678188521250775, 105.7260407433838338 ) ) ; +#3349 = CARTESIAN_POINT ( 'NONE', ( 23.03875873965262855, 135.0043594556615290, 90.80721871908795606 ) ) ; +#3350 = EDGE_CURVE ( 'NONE', #34342, #35508, #37760, .T. ) ; +#3351 = ORIENTED_EDGE ( 'NONE', *, *, #17326, .T. ) ; +#3352 = EDGE_LOOP ( 'NONE', ( #33209, #6934, #12947, #39276, #30298 ) ) ; +#3353 = FACE_OUTER_BOUND ( 'NONE', #13596, .T. ) ; +#3354 = FACE_OUTER_BOUND ( 'NONE', #8982, .T. ) ; +#3355 = CARTESIAN_POINT ( 'NONE', ( -25.83361275620000086, 122.1073251810999949, 88.20139195350000705 ) ) ; +#3356 = EDGE_CURVE ( 'NONE', #133, #16029, #37681, .T. ) ; +#3357 = ORIENTED_EDGE ( 'NONE', *, *, #15898, .F. ) ; +#3358 = CARTESIAN_POINT ( 'NONE', ( 0.04503145192460000085, 226.4002260771000010, 74.55847715811999876 ) ) ; +#3359 = DIRECTION ( 'NONE', ( 0.7856637149787866203, -0.6186538021912836305, 0.000000000000000000 ) ) ; +#3360 = CARTESIAN_POINT ( 'NONE', ( 17.07624313959705020, 121.4538017505177123, 177.4665436634097091 ) ) ; +#3361 = ORIENTED_EDGE ( 'NONE', *, *, #24391, .T. ) ; +#3362 = CARTESIAN_POINT ( 'NONE', ( -45.30371984282656683, 124.3227729409930618, 91.46136974178453727 ) ) ; +#3363 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#3364 = CARTESIAN_POINT ( 'NONE', ( -1.362136793684999958, 189.3876565648999986, 105.6752102165999929 ) ) ; +#3365 = LINE ( 'NONE', #35625, #9767 ) ; +#3366 = ORIENTED_EDGE ( 'NONE', *, *, #36327, .T. ) ; +#3367 = CARTESIAN_POINT ( 'NONE', ( -43.13843726988963567, 112.6550928102931834, 129.5909698073101595 ) ) ; +#3368 = ORIENTED_EDGE ( 'NONE', *, *, #27064, .F. ) ; +#3369 = CARTESIAN_POINT ( 'NONE', ( 36.05539628079529990, 119.7153706280430470, 90.34852804255076819 ) ) ; +#3370 = CARTESIAN_POINT ( 'NONE', ( -13.51345484135845965, 174.8561185417166826, 26.73029491429123894 ) ) ; +#3371 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#3372 = AXIS2_PLACEMENT_3D ( 'NONE', #20570, #4423, #35475 ) ; +#3373 = AXIS2_PLACEMENT_3D ( 'NONE', #1829, #1416, #35947 ) ; +#3374 = ORIENTED_EDGE ( 'NONE', *, *, #30051, .F. ) ; +#3375 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#3376 = ORIENTED_EDGE ( 'NONE', *, *, #19466, .T. ) ; +#3377 = CARTESIAN_POINT ( 'NONE', ( -25.65167874464251696, 209.7116445767937876, 73.43226018034312119 ) ) ; +#3378 = CARTESIAN_POINT ( 'NONE', ( -25.58080687204398629, 190.4782248801624007, 104.1568888495789480 ) ) ; +#3379 = VERTEX_POINT ( 'NONE', #16592 ) ; +#3380 = DIRECTION ( 'NONE', ( -0.0004161288024629044321, -0.5299192578506427553, -0.8480479980495465586 ) ) ; +#3381 = ADVANCED_FACE ( 'NONE', ( #10084 ), #5555, .F. ) ; +#3382 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#3383 = CARTESIAN_POINT ( 'NONE', ( -28.46737701140906651, 128.5818728498977634, 89.35557899873234078 ) ) ; +#3384 = ADVANCED_FACE ( 'NONE', ( #258 ), #12741, .T. ) ; +#3385 = CYLINDRICAL_SURFACE ( 'NONE', #35091, 6.000000000000008882 ) ; +#3386 = EDGE_CURVE ( 'NONE', #32614, #26491, #18615, .T. ) ; +#3387 = CARTESIAN_POINT ( 'NONE', ( -0.4543644846840136919, 210.9999999999990621, 75.55877896310728659 ) ) ; +#3388 = ORIENTED_EDGE ( 'NONE', *, *, #1455, .F. ) ; +#3389 = ORIENTED_EDGE ( 'NONE', *, *, #10181, .F. ) ; +#3390 = CARTESIAN_POINT ( 'NONE', ( 5.668045263090168540, 187.9945100871488251, 103.3510643583489639 ) ) ; +#3391 = CARTESIAN_POINT ( 'NONE', ( -35.98817295377529746, 191.5260130662397273, 103.8919236801626340 ) ) ; +#3392 = DIRECTION ( 'NONE', ( 0.0005884949961255732560, -0.2249510543439049715, 0.9743698870671266832 ) ) ; +#3393 = PLANE ( 'NONE', #11160 ) ; +#3394 = EDGE_CURVE ( 'NONE', #1633, #31589, #30972, .T. ) ; +#3395 = ORIENTED_EDGE ( 'NONE', *, *, #27581, .T. ) ; +#3396 = CARTESIAN_POINT ( 'NONE', ( 19.98046760410895573, 208.7354111918591570, 73.11857707450180044 ) ) ; +#3397 = CONICAL_SURFACE ( 'NONE', #17750, 5.249999999894133573, 0.7853981634251984145 ) ; +#3398 = ORIENTED_EDGE ( 'NONE', *, *, #22668, .F. ) ; +#3399 = LINE ( 'NONE', #340, #35260 ) ; +#3400 = VECTOR ( 'NONE', #18495, 1000.000000000000227 ) ; +#3401 = EDGE_CURVE ( 'NONE', #13672, #18171, #28491, .T. ) ; +#3402 = VECTOR ( 'NONE', #32018, 1000.000000000000227 ) ; +#3403 = LINE ( 'NONE', #15876, #40416 ) ; +#3404 = CARTESIAN_POINT ( 'NONE', ( 39.32399170537505029, 121.5657277381213817, 123.6169974531826341 ) ) ; +#3405 = ORIENTED_EDGE ( 'NONE', *, *, #18255, .T. ) ; +#3406 = CARTESIAN_POINT ( 'NONE', ( -20.34617778358973439, 105.2139170254723695, 89.78007332956207165 ) ) ; +#3407 = CARTESIAN_POINT ( 'NONE', ( -15.74985326587000145, 185.3779283803999931, 102.7168790019000113 ) ) ; +#3408 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#3409 = CARTESIAN_POINT ( 'NONE', ( 18.59950176168990055, 126.0162487695453706, 174.9291204768238117 ) ) ; +#3410 = CARTESIAN_POINT ( 'NONE', ( 4.468727364937352675, 124.6616761605458379, 88.43063753346716283 ) ) ; +#3411 = ORIENTED_EDGE ( 'NONE', *, *, #17615, .T. ) ; +#3412 = DIRECTION ( 'NONE', ( -0.6087611434211035455, 0.7728348337987402950, 0.1792656964617155846 ) ) ; +#3413 = PLANE ( 'NONE', #334 ) ; +#3414 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265228896, -0.1368326740407719011 ) ) ; +#3415 = FACE_OUTER_BOUND ( 'NONE', #4974, .T. ) ; +#3416 = ORIENTED_EDGE ( 'NONE', *, *, #24803, .F. ) ; +#3417 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971576782 ) ) ; +#3418 = DIRECTION ( 'NONE', ( 0.7933533411653060918, -0.5930537057989936356, -0.1373964268091645846 ) ) ; +#3419 = CARTESIAN_POINT ( 'NONE', ( -3.772473109594537188, 168.4423924140773465, 98.78424517642510239 ) ) ; +#3420 = VECTOR ( 'NONE', #35388, 1000.000000000000227 ) ; +#3421 = CARTESIAN_POINT ( 'NONE', ( -26.29277745650999876, 188.3533238026000163, 105.7193558339999981 ) ) ; +#3422 = VERTEX_POINT ( 'NONE', #7195 ) ; +#3423 = CARTESIAN_POINT ( 'NONE', ( 38.33010151215698613, 191.0388342792613798, 103.7345633339579365 ) ) ; +#3424 = CIRCLE ( 'NONE', #175, 2.749999999950412999 ) ; +#3425 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#3426 = CARTESIAN_POINT ( 'NONE', ( 20.50147137495634198, 190.9646546281344683, 106.2940065278771016 ) ) ; +#3427 = CARTESIAN_POINT ( 'NONE', ( 36.04689830208332069, 205.5673820496000133, 76.27844315544000153 ) ) ; +#3428 = CARTESIAN_POINT ( 'NONE', ( -25.02200714046000130, 181.7555764690000046, 103.1690735356000062 ) ) ; +#3429 = CARTESIAN_POINT ( 'NONE', ( 20.02762529703683825, 127.4325933158175985, 89.08929274300049883 ) ) ; +#3430 = CARTESIAN_POINT ( 'NONE', ( 36.67680774640550112, 191.6480351179000081, 104.3376580875839892 ) ) ; +#3431 = EDGE_CURVE ( 'NONE', #17689, #3422, #28885, .T. ) ; +#3432 = EDGE_CURVE ( 'NONE', #31885, #19846, #10292, .T. ) ; +#3433 = CARTESIAN_POINT ( 'NONE', ( 36.71549788546000315, 191.5837423664000028, 106.2320285050000024 ) ) ; +#3434 = EDGE_LOOP ( 'NONE', ( #25076, #16431, #18280 ) ) ; +#3435 = VERTEX_POINT ( 'NONE', #862 ) ; +#3436 = DIRECTION ( 'NONE', ( 0.0006039748319385504537, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#3437 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971557353 ) ) ; +#3438 = CC_DESIGN_PERSON_AND_ORGANIZATION_ASSIGNMENT ( #33706, #9191, ( #14451 ) ) ; +#3439 = DIRECTION ( 'NONE', ( 0.0005884941600622460708, -0.2249510532593050338, 0.9743698873180313136 ) ) ; +#3440 = ORIENTED_EDGE ( 'NONE', *, *, #29824, .F. ) ; +#3441 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927782437076, 0.0005734119022074447283 ) ) ; +#3442 = EDGE_LOOP ( 'NONE', ( #22171, #12261, #35414, #10284, #35925 ) ) ; +#3443 = CARTESIAN_POINT ( 'NONE', ( 12.63603855934096920, 128.0249363968860337, 91.76793536831303300 ) ) ; +#3444 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749386209, 132.8602140592488468, 90.82839891337145843 ) ) ; +#3445 = AXIS2_PLACEMENT_3D ( 'NONE', #28692, #6203, #9288 ) ; +#3446 = ORIENTED_EDGE ( 'NONE', *, *, #1794, .T. ) ; +#3447 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319376807067 ) ) ; +#3448 = PLANE ( 'NONE', #21137 ) ; +#3449 = CARTESIAN_POINT ( 'NONE', ( -28.46728868142984226, 182.0597503807817645, 102.2150741964074143 ) ) ; +#3450 = AXIS2_PLACEMENT_3D ( 'NONE', #1748, #20539, #33009 ) ; +#3451 = CARTESIAN_POINT ( 'NONE', ( 36.82553848920489514, 117.0567498273620402, 90.24554313673101547 ) ) ; +#3452 = DIRECTION ( 'NONE', ( -0.0003200578985643136158, 0.8480480961564359488, -0.5299191675797225720 ) ) ; +#3453 = ORIENTED_EDGE ( 'NONE', *, *, #1043, .T. ) ; +#3454 = EDGE_CURVE ( 'NONE', #25759, #27090, #19666, .T. ) ; +#3455 = DIRECTION ( 'NONE', ( 0.0001408404075805813865, -0.2249510913125021550, 0.9743700460714572742 ) ) ; +#3456 = AXIS2_PLACEMENT_3D ( 'NONE', #31218, #735, #13221 ) ; +#3457 = CARTESIAN_POINT ( 'NONE', ( 2.749831409735000065, 189.8396373187000279, 103.4785235852000085 ) ) ; +#3458 = CARTESIAN_POINT ( 'NONE', ( -22.78437402937589695, 158.4258150520903143, 96.41321554517463710 ) ) ; +#3459 = VERTEX_POINT ( 'NONE', #32163 ) ; +#3460 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#3461 = EDGE_LOOP ( 'NONE', ( #38467, #14315, #24519, #21418 ) ) ; +#3462 = LINE ( 'NONE', #34151, #35147 ) ; +#3463 = CARTESIAN_POINT ( 'NONE', ( -14.55306305638819886, 182.5568561273574630, 101.8082842025129366 ) ) ; +#3464 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#3465 = CARTESIAN_POINT ( 'NONE', ( -39.68697719330018714, 104.2905048274892437, 197.1740080326739530 ) ) ; +#3466 = CYLINDRICAL_SURFACE ( 'NONE', #32773, 2.000000000000011546 ) ; +#3467 = CARTESIAN_POINT ( 'NONE', ( -2.541354399913000162, 209.3993418770999995, 73.44252218553999967 ) ) ; +#3468 = CARTESIAN_POINT ( 'NONE', ( -42.70458103469926670, 67.79617006382294164, 322.0565592465368354 ) ) ; +#3469 = CIRCLE ( 'NONE', #26384, 2.000000000000011546 ) ; +#3470 = VERTEX_POINT ( 'NONE', #1063 ) ; +#3471 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363195980786E-14, -0.9999998176071845934 ) ) ; +#3472 = DIRECTION ( 'NONE', ( -0.0006039748319386984473, 0.000000000000000000, -0.9999998176071845934 ) ) ; +#3473 = FACE_OUTER_BOUND ( 'NONE', #6644, .T. ) ; +#3474 = EDGE_CURVE ( 'NONE', #7294, #21726, #36321, .T. ) ; +#3475 = EDGE_CURVE ( 'NONE', #5782, #21943, #9510, .T. ) ; +#3476 = CARTESIAN_POINT ( 'NONE', ( 12.64524319930002783, 177.7928828500099598, 100.6920447773197225 ) ) ; +#3477 = EDGE_LOOP ( 'NONE', ( #35651, #6362, #34196, #28564 ) ) ; +#3478 = ORIENTED_EDGE ( 'NONE', *, *, #31818, .T. ) ; +#3479 = VECTOR ( 'NONE', #30984, 1000.000000000000114 ) ; +#3480 = EDGE_LOOP ( 'NONE', ( #39399, #29383, #13365, #5446 ) ) ; +#3481 = CARTESIAN_POINT ( 'NONE', ( 25.70209235779490342, 191.4202673505085954, 104.1723544197036802 ) ) ; +#3482 = EDGE_CURVE ( 'NONE', #36851, #19053, #26465, .T. ) ; +#3483 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971581778 ) ) ; +#3484 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31280, #34331, #34132, #31483 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0002855128694785529853, 0.0003233533305980134482 ), + .UNSPECIFIED. ) ; +#3485 = VERTEX_POINT ( 'NONE', #10690 ) ; +#3486 = ORIENTED_EDGE ( 'NONE', *, *, #19723, .T. ) ; +#3487 = DIRECTION ( 'NONE', ( 2.151057110228587533E-14, 0.9743700557921592953, 0.2249510932971532096 ) ) ; +#3488 = CARTESIAN_POINT ( 'NONE', ( 38.46700359482129272, 118.8212168396402717, 87.67371270529410765 ) ) ; +#3489 = CARTESIAN_POINT ( 'NONE', ( -35.45414161172500656, 207.8686442644066403, 77.29845580048690579 ) ) ; +#3490 = CARTESIAN_POINT ( 'NONE', ( -24.42625686036400268, 103.6131156702357998, 89.78253759510907628 ) ) ; +#3491 = ORIENTED_EDGE ( 'NONE', *, *, #16417, .F. ) ; +#3492 = FACE_OUTER_BOUND ( 'NONE', #35380, .T. ) ; +#3493 = ORIENTED_EDGE ( 'NONE', *, *, #28787, .T. ) ; +#3494 = ORIENTED_EDGE ( 'NONE', *, *, #13841, .F. ) ; +#3495 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#3496 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971558463 ) ) ; +#3497 = ORIENTED_EDGE ( 'NONE', *, *, #21888, .F. ) ; +#3498 = EDGE_CURVE ( 'NONE', #19007, #26517, #31702, .T. ) ; +#3499 = CARTESIAN_POINT ( 'NONE', ( -2.943640821425400400, 190.8913430625419778, 103.7204105821340221 ) ) ; +#3500 = CARTESIAN_POINT ( 'NONE', ( 0.9003320879892923179, 188.6348484842668256, 103.2021660235679832 ) ) ; +#3501 = AXIS2_PLACEMENT_3D ( 'NONE', #34969, #19658, #19456 ) ; +#3502 = AXIS2_PLACEMENT_3D ( 'NONE', #34402, #18858, #19065 ) ; +#3503 = CARTESIAN_POINT ( 'NONE', ( -26.01026747887119583, 207.8020231323739608, 73.42646037265581072 ) ) ; +#3504 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#3505 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19755, #19372, #16695, #29195 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999992928434677797 ), + .UNSPECIFIED. ) ; +#3506 = AXIS2_PLACEMENT_3D ( 'NONE', #33765, #3279, #5763 ) ; +#3507 = ORIENTED_EDGE ( 'NONE', *, *, #10100, .F. ) ; +#3508 = CARTESIAN_POINT ( 'NONE', ( -22.62212617741983678, 214.0904530554988696, 73.07216727974267201 ) ) ; +#3509 = CARTESIAN_POINT ( 'NONE', ( -31.73518137046647780, 115.2741031936126177, 176.5389297272637634 ) ) ; +#3510 = VERTEX_POINT ( 'NONE', #27048 ) ; +#3511 = CYLINDRICAL_SURFACE ( 'NONE', #1685, 1.750000000000001998 ) ; +#3512 = PLANE ( 'NONE', #39836 ) ; +#3513 = CARTESIAN_POINT ( 'NONE', ( -25.36035329269000016, 120.6009619010000051, 89.93798750253999685 ) ) ; +#3514 = EDGE_CURVE ( 'NONE', #38213, #15039, #11932, .T. ) ; +#3515 = ORIENTED_EDGE ( 'NONE', *, *, #15151, .T. ) ; +#3516 = CARTESIAN_POINT ( 'NONE', ( -45.39778154263243692, 124.3161987079337507, 88.38112278943124522 ) ) ; +#3517 = CARTESIAN_POINT ( 'NONE', ( 37.55190133016288456, 77.26223394093688057, 291.2877482218110572 ) ) ; +#3518 = EDGE_CURVE ( 'NONE', #31222, #5278, #38875, .T. ) ; +#3519 = EDGE_LOOP ( 'NONE', ( #29552, #37330, #19170, #21640 ) ) ; +#3520 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749899931, 179.6299767373261602, 101.6260513916142116 ) ) ; +#3521 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#3522 = ADVANCED_FACE ( 'NONE', ( #20471 ), #6251, .T. ) ; +#3523 = EDGE_CURVE ( 'NONE', #35577, #21316, #11282, .T. ) ; +#3525 = CARTESIAN_POINT ( 'NONE', ( 35.56356469037133650, 192.3002554099812471, 103.8734939767707885 ) ) ; +#3524 = LINE ( 'NONE', #676, #21105 ) ; +#3526 = EDGE_CURVE ( 'NONE', #21067, #12970, #23249, .T. ) ; +#3527 = ORIENTED_EDGE ( 'NONE', *, *, #1989, .F. ) ; +#3528 = DIRECTION ( 'NONE', ( -0.0005884949961239638663, 0.2249510543439075250, -0.9743698870671260170 ) ) ; +#3529 = ADVANCED_FACE ( 'NONE', ( #8223 ), #39282, .T. ) ; +#3530 = VECTOR ( 'NONE', #27606, 1000.000000000000000 ) ; +#3531 = VECTOR ( 'NONE', #39789, 1000.000000000000114 ) ; +#3532 = EDGE_LOOP ( 'NONE', ( #23425, #4247, #36062, #1091, #564 ) ) ; +#3533 = CARTESIAN_POINT ( 'NONE', ( 38.54411846755796489, 218.5902260770999987, 73.03522440068014987 ) ) ; +#3534 = FACE_OUTER_BOUND ( 'NONE', #874, .T. ) ; +#3535 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971556243 ) ) ; +#3536 = VERTEX_POINT ( 'NONE', #39480 ) ; +#3537 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #18779, #25361, #9417, #34914 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.712388980384695003, 4.891461175462934463 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973295471489361796, 0.9973295471489361796, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#3538 = ORIENTED_EDGE ( 'NONE', *, *, #21888, .T. ) ; +#3539 = CARTESIAN_POINT ( 'NONE', ( -13.46991461394048706, 153.3545038370762654, 97.63149519329859061 ) ) ; +#3540 = CARTESIAN_POINT ( 'NONE', ( 21.96933826409811630, 182.0731317569477312, 101.6745489239626465 ) ) ; +#3541 = LINE ( 'NONE', #28909, #16933 ) ; +#3542 = ORIENTED_EDGE ( 'NONE', *, *, #31617, .F. ) ; +#3543 = ORIENTED_EDGE ( 'NONE', *, *, #14309, .F. ) ; +#3544 = ORIENTED_EDGE ( 'NONE', *, *, #10577, .T. ) ; +#3545 = LINE ( 'NONE', #16228, #21335 ) ; +#3546 = CARTESIAN_POINT ( 'NONE', ( 21.83140103668416998, 176.0486778938952739, 102.8495379525328985 ) ) ; +#3547 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971556798 ) ) ; +#3548 = ORIENTED_EDGE ( 'NONE', *, *, #30561, .F. ) ; +#3549 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #24071, #26328, #39182, #26945 ), + ( #38764, #39583, #11187, #4428 ), + ( #35687, #20784, #17702, #35898 ), + ( #5233, #7903, #14459, #20368 ), + ( #20575, #23250, #29799, #14257 ), + ( #23659, #36105, #33044, #5034 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 4 ), + ( 4, 4 ), + ( -0.4541100403105999828, 0.000000000000000000, 1.000000000000000000, 1.454054756616000033 ), + ( -2.029131470331999940E-05, 1.000000271963999987 ), + .UNSPECIFIED. ) ; +#3550 = CARTESIAN_POINT ( 'NONE', ( -21.02099060171535427, 212.6267540641154028, 73.57122262233082211 ) ) ; +#3551 = EDGE_LOOP ( 'NONE', ( #22885, #21728, #1632, #13966 ) ) ; +#3552 = CARTESIAN_POINT ( 'NONE', ( -36.97421542778027259, 116.5047944643511357, 89.73514664299061394 ) ) ; +#3553 = CARTESIAN_POINT ( 'NONE', ( 37.33114329194350489, 166.9001604414680173, 188.4905732344037119 ) ) ; +#3554 = EDGE_LOOP ( 'NONE', ( #7656, #17473, #16858, #18750 ) ) ; +#3555 = PLANE ( 'NONE', #21647 ) ; +#3556 = CONICAL_SURFACE ( 'NONE', #26441, 51.90509899272666416, 0.7853981633973107224 ) ; +#3557 = CARTESIAN_POINT ( 'NONE', ( -0.9776028703166999012, 188.8974623888000224, 105.8690628777000029 ) ) ; +#3558 = VECTOR ( 'NONE', #22209, 1000.000000000000114 ) ; +#3559 = AXIS2_PLACEMENT_3D ( 'NONE', #38015, #16526, #38805 ) ; +#3560 = CARTESIAN_POINT ( 'NONE', ( -44.92025114620013682, 180.7728939925537759, 104.3226271335811361 ) ) ; +#3561 = EDGE_CURVE ( 'NONE', #36902, #15091, #17196, .T. ) ; +#3562 = ORIENTED_EDGE ( 'NONE', *, *, #4113, .T. ) ; +#3563 = CARTESIAN_POINT ( 'NONE', ( -28.70758036415549697, 148.4279572010033519, 96.50331524374598757 ) ) ; +#3564 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13213, #26093, #25701, #34452 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3565 = CIRCLE ( 'NONE', #24508, 1.999999999999996891 ) ; +#3566 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; +#3567 = FACE_OUTER_BOUND ( 'NONE', #9650, .T. ) ; +#3568 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; +#3569 = ADVANCED_FACE ( 'NONE', ( #20890 ), #18885, .F. ) ; +#3570 = DIRECTION ( 'NONE', ( 0.7933535325932957738, -0.5931614258681779939, -0.1369295263402617313 ) ) ; +#3571 = ORIENTED_EDGE ( 'NONE', *, *, #3678, .T. ) ; +#3572 = EDGE_CURVE ( 'NONE', #25978, #25353, #36234, .T. ) ; +#3573 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775999513 ) ) ; +#3574 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825925439549636, 0.0005734119022586144088 ) ) ; +#3575 = EDGE_CURVE ( 'NONE', #29855, #16955, #24558, .T. ) ; +#3576 = VERTEX_POINT ( 'NONE', #1571 ) ; +#3577 = EDGE_LOOP ( 'NONE', ( #27279, #19247, #7667, #35253, #12995 ) ) ; +#3578 = CARTESIAN_POINT ( 'NONE', ( 1.752038607275829607, 145.3272753739126983, 129.1239590489928162 ) ) ; +#3579 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; +#3580 = CARTESIAN_POINT ( 'NONE', ( -38.93740081958814159, 190.3639749098083200, 106.7043400420495374 ) ) ; +#3581 = ORIENTED_EDGE ( 'NONE', *, *, #26633, .T. ) ; +#3582 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; +#3583 = ORIENTED_EDGE ( 'NONE', *, *, #27396, .F. ) ; +#3584 = ORIENTED_EDGE ( 'NONE', *, *, #11907, .F. ) ; +#3585 = CARTESIAN_POINT ( 'NONE', ( -6.033304800909325749, 177.7287101295752905, 100.7413749438379682 ) ) ; +#3586 = AXIS2_PLACEMENT_3D ( 'NONE', #34563, #6176, #19036 ) ; +#3587 = CARTESIAN_POINT ( 'NONE', ( -20.49853057565002601, 184.3993303303604705, 104.8029991440840973 ) ) ; +#3588 = AXIS2_PLACEMENT_3D ( 'NONE', #6886, #22655, #10381 ) ; +#3589 = CARTESIAN_POINT ( 'NONE', ( -21.82963555936113309, 135.9868450106493185, 91.57429495730107760 ) ) ; +#3590 = AXIS2_PLACEMENT_3D ( 'NONE', #21844, #24726, #34091 ) ; +#3591 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8849, #20697, #5142, #27478 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.003686124987248532749, 0.004393344453691859670 ), + .UNSPECIFIED. ) ; +#3592 = ORIENTED_EDGE ( 'NONE', *, *, #13764, .F. ) ; +#3593 = CARTESIAN_POINT ( 'NONE', ( -19.99823416869593373, 118.9403737594142854, 90.20346087292679726 ) ) ; +#3594 = AXIS2_PLACEMENT_3D ( 'NONE', #25149, #5724, #2852 ) ; +#3595 = CARTESIAN_POINT ( 'NONE', ( 27.71217996750916512, 149.2638841111731267, 291.5418064729402658 ) ) ; +#3596 = ORIENTED_EDGE ( 'NONE', *, *, #4858, .T. ) ; +#3597 = CARTESIAN_POINT ( 'NONE', ( 35.56237296995020358, 191.9759150222000130, 101.8999685582251260 ) ) ; +#3598 = CARTESIAN_POINT ( 'NONE', ( -23.36581923842090092, 181.0107737450888976, 104.5356085457618889 ) ) ; +#3599 = CARTESIAN_POINT ( 'NONE', ( 31.30533522768502763, 110.6131156702000027, 90.24887720109859401 ) ) ; +#3600 = ORIENTED_EDGE ( 'NONE', *, *, #19388, .T. ) ; +#3601 = CARTESIAN_POINT ( 'NONE', ( 27.83433066462000127, 125.1256074409000121, 88.86582280017999835 ) ) ; +#3602 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15490, #34866, #6876, #19346 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.9970396573944148022, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3603 = FACE_OUTER_BOUND ( 'NONE', #15855, .T. ) ; +#3604 = CARTESIAN_POINT ( 'NONE', ( 4.034499241564549976, 175.2435454650956217, 100.6217987443190509 ) ) ; +#3605 = CARTESIAN_POINT ( 'NONE', ( 5.668109638569079678, 185.2338525438773900, 105.4930173663374262 ) ) ; +#3606 = EDGE_LOOP ( 'NONE', ( #20977, #38043, #37815, #23828, #6626 ) ) ; +#3607 = CARTESIAN_POINT ( 'NONE', ( 16.55926621263987641, 122.5128711786446445, 174.6304772722791654 ) ) ; +#3608 = CARTESIAN_POINT ( 'NONE', ( 0.6894063899216041902, 189.0039686778983139, 103.6859152462737796 ) ) ; +#3609 = CARTESIAN_POINT ( 'NONE', ( 36.47897566921480461, 191.7700612336033430, 104.3554365893951825 ) ) ; +#3610 = ADVANCED_FACE ( 'NONE', ( #1362 ), #4025, .T. ) ; +#3611 = EDGE_CURVE ( 'NONE', #8754, #1723, #18696, .T. ) ; +#3612 = CARTESIAN_POINT ( 'NONE', ( 25.99876818124551292, 118.1164810761916470, 87.25208046938912787 ) ) ; +#3613 = EDGE_CURVE ( 'NONE', #33506, #24100, #27188, .T. ) ; +#3614 = DIRECTION ( 'NONE', ( -0.1305262051639064225, -0.9660383184132061984, -0.2230086929312280475 ) ) ; +#3615 = EDGE_CURVE ( 'NONE', #6960, #14645, #26048, .T. ) ; +#3616 = CONICAL_SURFACE ( 'NONE', #5582, 2.500000074000459094, 0.7853981633357993708 ) ; +#3617 = CARTESIAN_POINT ( 'NONE', ( 20.50147081616042755, 137.9496117178372003, 94.05447709939286938 ) ) ; +#3618 = AXIS2_PLACEMENT_3D ( 'NONE', #30399, #33654, #11190 ) ; +#3619 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; +#3620 = CARTESIAN_POINT ( 'NONE', ( -33.45586840016203922, 218.5902260770999987, 73.07871058858016511 ) ) ; +#3621 = CARTESIAN_POINT ( 'NONE', ( -44.46121984373956337, 189.2577286604973210, 103.8865186576782804 ) ) ; +#3622 = VECTOR ( 'NONE', #30854, 1000.000000000000227 ) ; +#3623 = CARTESIAN_POINT ( 'NONE', ( -25.50501342766671442, 190.9440501067191747, 106.3152859405670085 ) ) ; +#3624 = VERTEX_POINT ( 'NONE', #19961 ) ; +#3625 = CIRCLE ( 'NONE', #35589, 7.499999999921035609 ) ; +#3626 = EDGE_CURVE ( 'NONE', #15694, #22830, #23455, .T. ) ; +#3627 = CONICAL_SURFACE ( 'NONE', #31092, 2.503009339059525828, 0.7854392546297950251 ) ; +#3628 = PLANE ( 'NONE', #5683 ) ; +#3629 = EDGE_CURVE ( 'NONE', #5465, #34776, #13843, .T. ) ; +#3630 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552357 ) ) ; +#3631 = DIRECTION ( 'NONE', ( -5.782411586657655244E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; +#3632 = CARTESIAN_POINT ( 'NONE', ( 0.04412548967667000166, 9.379164112032999336E-13, 73.05847743171000275 ) ) ; +#3633 = CARTESIAN_POINT ( 'NONE', ( 20.41791641949827607, 127.3413591030548275, 89.46831587257177887 ) ) ; +#3634 = FACE_OUTER_BOUND ( 'NONE', #28847, .T. ) ; +#3635 = CARTESIAN_POINT ( 'NONE', ( -39.03036842895058811, 175.8132598316807105, 136.1868359458795510 ) ) ; +#3636 = ORIENTED_EDGE ( 'NONE', *, *, #23575, .F. ) ; +#3637 = EDGE_CURVE ( 'NONE', #39104, #33123, #17092, .T. ) ; +#3638 = CARTESIAN_POINT ( 'NONE', ( 14.93318671017543231, 151.7188427972803311, 177.9798661502222217 ) ) ; +#3639 = CARTESIAN_POINT ( 'NONE', ( -20.49970645903284705, 184.8492302318938698, 102.8542671896393301 ) ) ; +#3640 = LINE ( 'NONE', #8910, #27225 ) ; +#3641 = ORIENTED_EDGE ( 'NONE', *, *, #769, .F. ) ; +#3642 = LINE ( 'NONE', #30880, #22679 ) ; +#3643 = AXIS2_PLACEMENT_3D ( 'NONE', #28953, #4392, #6652 ) ; +#3644 = VERTEX_POINT ( 'NONE', #10590 ) ; +#3645 = CIRCLE ( 'NONE', #14125, 2.000000000000011546 ) ; +#3646 = LINE ( 'NONE', #28813, #10408 ) ; +#3647 = CARTESIAN_POINT ( 'NONE', ( -22.78246931443002055, 153.3538690588717941, 97.63697319274456277 ) ) ; +#3648 = CARTESIAN_POINT ( 'NONE', ( -3.669581230397975791, 128.4724600144964484, 89.82849395191713882 ) ) ; +#3649 = PLANE ( 'NONE', #28432 ) ; +#3650 = CARTESIAN_POINT ( 'NONE', ( -15.66510111023692176, 126.2008059057987452, 91.53494892955571061 ) ) ; +#3651 = CIRCLE ( 'NONE', #1716, 2.749999999886777236 ) ; +#3652 = DIRECTION ( 'NONE', ( -0.0006039748319383847876, -4.625770492314939281E-15, -0.9999998176071847045 ) ) ; +#3653 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3966, #4159, #12994, #25474 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3654 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191947214049181, 0.8480481395922153665 ) ) ; +#3655 = VERTEX_POINT ( 'NONE', #7906 ) ; +#3656 = CARTESIAN_POINT ( 'NONE', ( -14.55129769576823939, 181.8820030174664737, 104.7313938035605787 ) ) ; +#3657 = CARTESIAN_POINT ( 'NONE', ( 30.07309061344315992, 177.7341748906488021, 100.7202431291636628 ) ) ; +#3658 = PLANE ( 'NONE', #28643 ) ; +#3659 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #5717, #33309 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 6.391201751766900243E-06, 0.9999992928678075321 ), + .UNSPECIFIED. ) ; +#3660 = EDGE_CURVE ( 'NONE', #8079, #7563, #4431, .T. ) ; +#3661 = CARTESIAN_POINT ( 'NONE', ( -37.93405609845000015, 190.9294051681999917, 103.6063423062000197 ) ) ; +#3662 = ORIENTED_EDGE ( 'NONE', *, *, #34489, .T. ) ; +#3663 = EDGE_CURVE ( 'NONE', #11449, #31116, #12143, .T. ) ; +#3664 = EDGE_LOOP ( 'NONE', ( #9024, #478, #16128, #30068 ) ) ; +#3665 = CYLINDRICAL_SURFACE ( 'NONE', #17893, 8.999999999999996447 ) ; +#3666 = EDGE_CURVE ( 'NONE', #3536, #26219, #22138, .T. ) ; +#3667 = ORIENTED_EDGE ( 'NONE', *, *, #28798, .T. ) ; +#3668 = CARTESIAN_POINT ( 'NONE', ( 15.00009867560111232, 176.2215782928612668, 100.4988710758687205 ) ) ; +#3669 = DIRECTION ( 'NONE', ( 0.7691761624280191167, 0.6302414090841090832, -0.1056588729268960053 ) ) ; +#3670 = CARTESIAN_POINT ( 'NONE', ( 20.00136918061618374, 193.8834552009329855, 106.5568097150586482 ) ) ; +#3671 = ADVANCED_FACE ( 'NONE', ( #38767 ), #28986, .T. ) ; +#3672 = VECTOR ( 'NONE', #33304, 1000.000000000000227 ) ; +#3673 = CARTESIAN_POINT ( 'NONE', ( 25.42668613043140269, 211.7447100920389573, 75.54331620179917195 ) ) ; +#3674 = VECTOR ( 'NONE', #11058, 1000.000000000000114 ) ; +#3675 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425360569, 126.1257801542146666, 91.85841711592105696 ) ) ; +#3676 = VECTOR ( 'NONE', #15750, 1000.000000000000114 ) ; +#3677 = CARTESIAN_POINT ( 'NONE', ( 15.50068700633101670, 185.6474399458666937, 103.7010050552331677 ) ) ; +#3678 = EDGE_CURVE ( 'NONE', #13325, #12780, #3071, .T. ) ; +#3679 = CARTESIAN_POINT ( 'NONE', ( 20.48220618717283870, 205.6521300892295301, 76.08837086243011072 ) ) ; +#3680 = CARTESIAN_POINT ( 'NONE', ( 38.65781128404000100, 118.3725735404999995, 89.51293966676000480 ) ) ; +#3681 = ORIENTED_EDGE ( 'NONE', *, *, #25511, .T. ) ; +#3682 = CONICAL_SURFACE ( 'NONE', #4993, 2.249999999984611421, 0.7853981634347277918 ) ; +#3683 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825971794438422, 0.0005734119011913576657 ) ) ; +#3684 = CARTESIAN_POINT ( 'NONE', ( -28.55676206495941827, 225.5077044902725163, 73.57575174230528603 ) ) ; +#3685 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971592325 ) ) ; +#3686 = VECTOR ( 'NONE', #29579, 1000.000000000000114 ) ; +#3687 = CARTESIAN_POINT ( 'NONE', ( 3.061557431010443864, 191.9759150222000130, 101.9195982363917778 ) ) ; +#3688 = ORIENTED_EDGE ( 'NONE', *, *, #4920, .F. ) ; +#3689 = VERTEX_POINT ( 'NONE', #4220 ) ; +#3690 = EDGE_CURVE ( 'NONE', #16546, #5612, #25938, .T. ) ; +#3691 = ORIENTED_EDGE ( 'NONE', *, *, #23773, .T. ) ; +#3692 = CARTESIAN_POINT ( 'NONE', ( 5.669154559842989549, 131.0223146068671269, 89.89838186586590041 ) ) ; +#3693 = CARTESIAN_POINT ( 'NONE', ( 37.23701003965144452, 182.4168621411915581, 119.7221224191138020 ) ) ; +#3694 = ORIENTED_EDGE ( 'NONE', *, *, #36312, .T. ) ; +#3695 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#3696 = CARTESIAN_POINT ( 'NONE', ( 19.71401682987599457, 154.2187378489598188, 161.0543666918586609 ) ) ; +#3697 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#3698 = CARTESIAN_POINT ( 'NONE', ( -44.76461391232829357, 172.9647176225852832, 165.3418576905968678 ) ) ; +#3699 = DIRECTION ( 'NONE', ( -0.0005884949961153481453, 0.2249510543439053600, -0.9743698870671265722 ) ) ; +#3700 = CYLINDRICAL_SURFACE ( 'NONE', #28186, 9.999999999999998224 ) ; +#3701 = VERTEX_POINT ( 'NONE', #16299 ) ; +#3702 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825911326306185, 0.0005734119025866840115 ) ) ; +#3703 = CONICAL_SURFACE ( 'NONE', #4339, 5.000000000100857989, 0.7853981633860493972 ) ; +#3704 = ORIENTED_EDGE ( 'NONE', *, *, #27852, .T. ) ; +#3705 = CARTESIAN_POINT ( 'NONE', ( -20.01780204100229099, 208.2807494580173113, 76.61795221373991183 ) ) ; +#3706 = CARTESIAN_POINT ( 'NONE', ( 19.98246575633744726, 209.3198221927136160, 76.04644364893974284 ) ) ; +#3707 = CIRCLE ( 'NONE', #18639, 4.500000000083482554 ) ; +#3708 = CARTESIAN_POINT ( 'NONE', ( -20.89282324149344561, 183.0959377177359215, 101.9365769416837253 ) ) ; +#3709 = AXIS2_PLACEMENT_3D ( 'NONE', #14405, #36473, #8893 ) ; +#3710 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; +#3711 = ORIENTED_EDGE ( 'NONE', *, *, #29941, .F. ) ; +#3712 = CARTESIAN_POINT ( 'NONE', ( -2.938634685006000336, 190.8906618492000007, 103.7252800252999947 ) ) ; +#3713 = CARTESIAN_POINT ( 'NONE', ( 1.148973024146567434, 188.6822756551911198, 103.2129652778315858 ) ) ; +#3714 = CARTESIAN_POINT ( 'NONE', ( 19.99378154282333497, 200.3418858662740263, 94.99690145743463177 ) ) ; +#3715 = CIRCLE ( 'NONE', #3048, 2.000000000000007994 ) ; +#3716 = EDGE_CURVE ( 'NONE', #14645, #38065, #19957, .T. ) ; +#3717 = ORIENTED_EDGE ( 'NONE', *, *, #14784, .F. ) ; +#3718 = CARTESIAN_POINT ( 'NONE', ( -25.75142470483000068, 118.8155666110999960, 87.53333755287000884 ) ) ; +#3719 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#3720 = EDGE_CURVE ( 'NONE', #16466, #1023, #26994, .T. ) ; +#3721 = ORIENTED_EDGE ( 'NONE', *, *, #26259, .F. ) ; +#3722 = CYLINDRICAL_SURFACE ( 'NONE', #365, 9.999999999999998224 ) ; +#3723 = CARTESIAN_POINT ( 'NONE', ( 19.71670726246199123, 125.1288345936551423, 175.0446023669997260 ) ) ; +#3724 = CARTESIAN_POINT ( 'NONE', ( 17.02367223262315576, 152.0219492114602247, 183.9187395736230712 ) ) ; +#3725 = ORIENTED_EDGE ( 'NONE', *, *, #16999, .F. ) ; +#3726 = EDGE_CURVE ( 'NONE', #3624, #26044, #22861, .T. ) ; +#3727 = LINE ( 'NONE', #18852, #35964 ) ; +#3728 = CARTESIAN_POINT ( 'NONE', ( -39.77033354370986729, 107.3143903442909277, 174.6968655561054220 ) ) ; +#3729 = DIRECTION ( 'NONE', ( -0.5605393316030450324, 0.2603260636278126872, 0.7861462957503898563 ) ) ; +#3730 = ORIENTED_EDGE ( 'NONE', *, *, #30926, .T. ) ; +#3731 = CARTESIAN_POINT ( 'NONE', ( 26.00403119534400176, 120.1365576043379804, 90.45255660088920990 ) ) ; +#3732 = AXIS2_PLACEMENT_3D ( 'NONE', #33785, #28080, #51 ) ; +#3733 = DIRECTION ( 'NONE', ( 0.0005884949961250770167, -0.2249510543439080523, 0.9743698870671260170 ) ) ; +#3734 = LINE ( 'NONE', #6401, #30289 ) ; +#3735 = CIRCLE ( 'NONE', #1113, 2.000000001211691636 ) ; +#3737 = CARTESIAN_POINT ( 'NONE', ( -13.49615031087043704, 188.2556029912739461, 103.1973190696492253 ) ) ; +#3736 = CARTESIAN_POINT ( 'NONE', ( -36.18239550624663536, 191.7212396232838216, 104.2340660787839823 ) ) ; +#3738 = DIRECTION ( 'NONE', ( -0.1305262860326017182, 0.9659761103945228022, 0.2232779496537980746 ) ) ; +#3739 = ORIENTED_EDGE ( 'NONE', *, *, #6576, .T. ) ; +#3740 = CARTESIAN_POINT ( 'NONE', ( 20.50029381463220091, 127.3219018078964382, 89.54826868587551303 ) ) ; +#3741 = DIRECTION ( 'NONE', ( 0.6982900371914135818, 0.000000000000000000, 0.7158149369489396063 ) ) ; +#3742 = ORIENTED_EDGE ( 'NONE', *, *, #16645, .F. ) ; +#3743 = EDGE_LOOP ( 'NONE', ( #17821, #9746 ) ) ; +#3744 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#3745 = CARTESIAN_POINT ( 'NONE', ( -5.675513023005390956, 123.6907347205156924, 91.29157260444318922 ) ) ; +#3746 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540969802, 184.8500661882999054, 102.8514373824003343 ) ) ; +#3747 = CARTESIAN_POINT ( 'NONE', ( 5.669458964429918701, 187.5045916731542377, 105.7910410896365647 ) ) ; +#3748 = DIRECTION ( 'NONE', ( 0.5613714522130487383, -0.5784550691277038359, 0.5918207715522294521 ) ) ; +#3749 = EDGE_LOOP ( 'NONE', ( #11621, #22632, #1516, #23077 ) ) ; +#3750 = EDGE_CURVE ( 'NONE', #33855, #23012, #35613, .T. ) ; +#3751 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10143, #10345, #36840, #24591 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3752 = ORIENTED_EDGE ( 'NONE', *, *, #24619, .T. ) ; +#3753 = CARTESIAN_POINT ( 'NONE', ( -6.034863718937535815, 176.8968501839344469, 103.2756606735491403 ) ) ; +#3754 = PLANE ( 'NONE', #1108 ) ; +#3755 = DIRECTION ( 'NONE', ( 0.7075388796814503500, 9.784181737230435625E-15, 0.7066744184835885845 ) ) ; +#3756 = EDGE_CURVE ( 'NONE', #26044, #33081, #23567, .T. ) ; +#3757 = ORIENTED_EDGE ( 'NONE', *, *, #31446, .T. ) ; +#3758 = CARTESIAN_POINT ( 'NONE', ( 39.85586901997003650, 129.5283103249424244, 336.2586849593528768 ) ) ; +#3759 = EDGE_LOOP ( 'NONE', ( #2358, #17191, #20310, #3270 ) ) ; +#3760 = EDGE_CURVE ( 'NONE', #30155, #37805, #30200, .T. ) ; +#3761 = CARTESIAN_POINT ( 'NONE', ( -6.037735614373251458, 137.3541716869147820, 91.36728157005168782 ) ) ; +#3762 = EDGE_CURVE ( 'NONE', #19715, #23911, #28933, .T. ) ; +#3763 = ORIENTED_EDGE ( 'NONE', *, *, #2107, .F. ) ; +#3764 = CARTESIAN_POINT ( 'NONE', ( 36.03687122555673739, 218.5902260770998282, 61.03673652646995862 ) ) ; +#3765 = AXIS2_PLACEMENT_3D ( 'NONE', #19383, #24995, #35098 ) ; +#3766 = ADVANCED_FACE ( 'NONE', ( #14669 ), #1780, .F. ) ; +#3767 = CARTESIAN_POINT ( 'NONE', ( -1.616825569521000094, 188.8197794939999881, 106.1757460699000006 ) ) ; +#3768 = CARTESIAN_POINT ( 'NONE', ( 29.19927575787174234, 149.0747586894985659, 94.05190613317014936 ) ) ; +#3769 = EDGE_LOOP ( 'NONE', ( #18900, #26761, #37495, #24450 ) ) ; +#3770 = CARTESIAN_POINT ( 'NONE', ( 2.621864883072559937, 209.6150426461021254, 73.39025409901792329 ) ) ; +#3771 = ORIENTED_EDGE ( 'NONE', *, *, #36251, .F. ) ; +#3772 = CARTESIAN_POINT ( 'NONE', ( -45.25054442514785791, 110.5556416651509437, 150.9936149799888483 ) ) ; +#3773 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39426, #33294, #21048, #5289 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3774 = CARTESIAN_POINT ( 'NONE', ( -39.29583505786987274, 162.0679957853012354, 197.6227201487129150 ) ) ; +#3775 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; +#3776 = CARTESIAN_POINT ( 'NONE', ( 16.17545524454269312, 122.0361947523238229, 178.1139273532624259 ) ) ; +#3777 = ORIENTED_EDGE ( 'NONE', *, *, #27962, .F. ) ; +#3778 = CARTESIAN_POINT ( 'NONE', ( 19.98635445618997863, 211.0854288155255460, 76.04696776081749476 ) ) ; +#3779 = CARTESIAN_POINT ( 'NONE', ( -15.49970618472456074, 126.6879451655382809, 89.42365126055415203 ) ) ; +#3780 = DIRECTION ( 'NONE', ( -0.6771712326825307660, 0.7358254695423512848, 0.000000000000000000 ) ) ; +#3781 = ORIENTED_EDGE ( 'NONE', *, *, #29821, .F. ) ; +#3782 = ORIENTED_EDGE ( 'NONE', *, *, #35277, .F. ) ; +#3783 = CARTESIAN_POINT ( 'NONE', ( 8.420554314666548024, 160.7376577964533055, 96.75704887148856415 ) ) ; +#3784 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#3785 = CARTESIAN_POINT ( 'NONE', ( -40.45668859049753507, 217.7719116710999856, 73.08293890847663477 ) ) ; +#3786 = DIRECTION ( 'NONE', ( 0.0005884949961249387809, -0.2249510543439043608, 0.9743698870671267942 ) ) ; +#3787 = AXIS2_PLACEMENT_3D ( 'NONE', #8953, #14880, #8545 ) ; +#3788 = VERTEX_POINT ( 'NONE', #5445 ) ; +#3789 = ORIENTED_EDGE ( 'NONE', *, *, #26033, .F. ) ; +#3790 = CYLINDRICAL_SURFACE ( 'NONE', #3456, 5.000000000000007994 ) ; +#3791 = CARTESIAN_POINT ( 'NONE', ( -20.00000737806465523, 151.9608748777371545, 94.74793644920653435 ) ) ; +#3792 = CARTESIAN_POINT ( 'NONE', ( 40.54675149461998984, 206.4002260771000010, 76.03401540768531675 ) ) ; +#3793 = ADVANCED_FACE ( 'NONE', ( #8943 ), #26492, .T. ) ; +#3794 = ORIENTED_EDGE ( 'NONE', *, *, #4773, .F. ) ; +#3795 = CARTESIAN_POINT ( 'NONE', ( 3.784352160272999921, 171.8704258944000003, 99.58662759693000055 ) ) ; +#3796 = CARTESIAN_POINT ( 'NONE', ( 22.11658944985360264, 129.6856566903868213, 90.09300832417258675 ) ) ; +#3797 = CARTESIAN_POINT ( 'NONE', ( 36.33870953241000024, 191.7478208022000103, 104.2407745632000058 ) ) ; +#3798 = ORIENTED_EDGE ( 'NONE', *, *, #32167, .F. ) ; +#3799 = CARTESIAN_POINT ( 'NONE', ( 2.988438011343841794, 209.5693627156126126, 76.06144145553551539 ) ) ; +#3800 = ADVANCED_FACE ( 'NONE', ( #39183 ), #29761, .T. ) ; +#3801 = LINE ( 'NONE', #31846, #16034 ) ; +#3802 = CARTESIAN_POINT ( 'NONE', ( 17.73018223044451247, 121.4662574373030992, 177.9825536785120619 ) ) ; +#3803 = LINE ( 'NONE', #3404, #18351 ) ; +#3804 = EDGE_LOOP ( 'NONE', ( #14995, #32810, #9348, #32966 ) ) ; +#3805 = CARTESIAN_POINT ( 'NONE', ( 28.51215300032000144, 125.2759241664000172, 88.55825304898000638 ) ) ; +#3806 = CARTESIAN_POINT ( 'NONE', ( -23.36147737338999519, 177.1885760182403260, 101.0873909946558769 ) ) ; +#3807 = DIRECTION ( 'NONE', ( 0.6337575784460532935, -0.7735316317038959388, -0.0003827736967368305454 ) ) ; +#3808 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282901917, 148.0700263536807597, 93.85134194385574347 ) ) ; +#3809 = ADVANCED_FACE ( 'NONE', ( #23661 ), #33006, .T. ) ; +#3810 = CARTESIAN_POINT ( 'NONE', ( 21.84813133371958216, 158.3688974985749951, 96.20206744650923270 ) ) ; +#3811 = EDGE_CURVE ( 'NONE', #26636, #32491, #14305, .T. ) ; +#3812 = EDGE_LOOP ( 'NONE', ( #26900, #4720 ) ) ; +#3813 = CARTESIAN_POINT ( 'NONE', ( 23.36189995341599968, 184.1285021912421769, 102.1451486796015615 ) ) ; +#3814 = EDGE_CURVE ( 'NONE', #7673, #853, #36110, .T. ) ; +#3815 = CARTESIAN_POINT ( 'NONE', ( 1.068853090858757904, 189.0651350939791371, 103.7028959401992552 ) ) ; +#3816 = DIRECTION ( 'NONE', ( 0.7947983679126050527, -0.5912140607310475415, -0.1369725839625022812 ) ) ; +#3817 = VECTOR ( 'NONE', #18786, 1000.000000000000000 ) ; +#3818 = DIRECTION ( 'NONE', ( -0.0006039748319386124701, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#3819 = ORIENTED_EDGE ( 'NONE', *, *, #33484, .F. ) ; +#3820 = DIRECTION ( 'NONE', ( 0.7947985590179719173, -0.5913221741348984040, -0.1365039814779489546 ) ) ; +#3821 = CARTESIAN_POINT ( 'NONE', ( 13.81047920904208226, 125.0581942443353114, 174.4028524411866954 ) ) ; +#3822 = DIRECTION ( 'NONE', ( -0.0006039748319390056018, -1.156901198131326670E-14, -0.9999998176071845934 ) ) ; +#3823 = DIRECTION ( 'NONE', ( -0.0002393071182785538799, -0.2252352986010040803, 0.9743043687658492491 ) ) ; +#3824 = VERTEX_POINT ( 'NONE', #12001 ) ; +#3825 = CYLINDRICAL_SURFACE ( 'NONE', #15781, 1.999999999999989342 ) ; +#3826 = CARTESIAN_POINT ( 'NONE', ( -19.44510706094013486, 147.9316356728690209, 182.5581845579670528 ) ) ; +#3827 = CARTESIAN_POINT ( 'NONE', ( 19.98776270734149207, 201.3437068452617780, 84.95876186640749950 ) ) ; +#3828 = EDGE_LOOP ( 'NONE', ( #883, #31385, #19674, #21236 ) ) ; +#3829 = CARTESIAN_POINT ( 'NONE', ( 30.05503346839208945, 109.6131156702000027, 89.74963226103227498 ) ) ; +#3830 = CARTESIAN_POINT ( 'NONE', ( 3.534343284623258974, 175.3621990150981276, 100.1363906404241675 ) ) ; +#3831 = CARTESIAN_POINT ( 'NONE', ( -0.4540624946311256349, 209.0000000000000000, 76.05877887192488629 ) ) ; +#3832 = CARTESIAN_POINT ( 'NONE', ( 36.06384775776000140, 192.3136458038000001, 104.3415608640000158 ) ) ; +#3833 = CARTESIAN_POINT ( 'NONE', ( -15.94449010895081642, 152.1461032928982036, 184.5535245782780294 ) ) ; +#3834 = CARTESIAN_POINT ( 'NONE', ( 47.95547122009493535, 140.0147268217544934, 290.8391817639516148 ) ) ; +#3835 = VERTEX_POINT ( 'NONE', #39585 ) ; +#3837 = AXIS2_PLACEMENT_3D ( 'NONE', #341, #744, #25313 ) ; +#3836 = CARTESIAN_POINT ( 'NONE', ( -2.371531496848751086, 209.5696226675259197, 75.55993729815415350 ) ) ; +#3838 = CARTESIAN_POINT ( 'NONE', ( 20.49930103516235746, 196.1188360154283430, 103.6658478038365558 ) ) ; +#3839 = EDGE_CURVE ( 'NONE', #23778, #10555, #24283, .T. ) ; +#3840 = EDGE_CURVE ( 'NONE', #31651, #7316, #12864, .T. ) ; +#3841 = AXIS2_PLACEMENT_3D ( 'NONE', #11370, #2187, #35892 ) ; +#3842 = CARTESIAN_POINT ( 'NONE', ( 25.02112415049811389, 129.9425189236814049, 92.71631678198431814 ) ) ; +#3843 = ORIENTED_EDGE ( 'NONE', *, *, #6618, .T. ) ; +#3844 = CARTESIAN_POINT ( 'NONE', ( -32.35856811579363068, 153.0051697192221241, 291.5780876995356721 ) ) ; +#3845 = AXIS2_PLACEMENT_3D ( 'NONE', #29654, #11244, #23718 ) ; +#3846 = EDGE_CURVE ( 'NONE', #20460, #34687, #12204, .T. ) ; +#3847 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18737, #31445, #34681, #12619, #28774, #24928 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.003332437842000458231, 0.5016662189210002731, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3848 = AXIS2_PLACEMENT_3D ( 'NONE', #5903, #27610, #30857 ) ; +#3849 = EDGE_LOOP ( 'NONE', ( #29863, #11717, #5786 ) ) ; +#3850 = ADVANCED_FACE ( 'NONE', ( #9533 ), #417, .T. ) ; +#3851 = CARTESIAN_POINT ( 'NONE', ( -3.470874896381920482, 129.7916855490838657, 89.61978905829030850 ) ) ; +#3852 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; +#3853 = EDGE_CURVE ( 'NONE', #11101, #11920, #24690, .T. ) ; +#3854 = DIRECTION ( 'NONE', ( -0.0006039748319382906789, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#3855 = CARTESIAN_POINT ( 'NONE', ( -43.95866919468323886, 185.6592565981171390, 107.3047072462908460 ) ) ; +#3856 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559019 ) ) ; +#3857 = CARTESIAN_POINT ( 'NONE', ( -63.18208837076905127, 87.27946979429619034, 302.5967063397189349 ) ) ; +#3858 = EDGE_CURVE ( 'NONE', #8264, #11241, #13789, .T. ) ; +#3859 = ORIENTED_EDGE ( 'NONE', *, *, #8633, .T. ) ; +#3860 = CARTESIAN_POINT ( 'NONE', ( 12.64700864260225366, 177.1180462903230364, 103.6150826217330803 ) ) ; +#3861 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; +#3862 = DIRECTION ( 'NONE', ( 0.0005884949961181263050, -0.2249510543439084131, 0.9743698870671259060 ) ) ; +#3863 = CARTESIAN_POINT ( 'NONE', ( -37.97368744632999693, 191.1281716224000036, 103.9225511041999965 ) ) ; +#3864 = ORIENTED_EDGE ( 'NONE', *, *, #19650, .F. ) ; +#3865 = ORIENTED_EDGE ( 'NONE', *, *, #34085, .T. ) ; +#3866 = DIRECTION ( 'NONE', ( 0.0005884949961230984562, -0.2249510543439063037, 0.9743698870671264611 ) ) ; +#3867 = ORIENTED_EDGE ( 'NONE', *, *, #29488, .F. ) ; +#3868 = VECTOR ( 'NONE', #34042, 1000.000000000000114 ) ; +#3869 = LINE ( 'NONE', #28831, #24108 ) ; +#3870 = AXIS2_PLACEMENT_3D ( 'NONE', #12335, #37275, #34195 ) ; +#3871 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 77.27946979429611929, 297.5967072516833127 ) ) ; +#3872 = CONICAL_SURFACE ( 'NONE', #24815, 22.50000000000898837, 0.7853981633973132759 ) ; +#3873 = CIRCLE ( 'NONE', #610, 2.000000000000011546 ) ; +#3874 = FACE_OUTER_BOUND ( 'NONE', #16149, .T. ) ; +#3875 = CARTESIAN_POINT ( 'NONE', ( 41.20534109643615039, 166.2329448439782027, 182.1790434216227084 ) ) ; +#3876 = DIRECTION ( 'NONE', ( -0.0006039748319391913256, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#3877 = CARTESIAN_POINT ( 'NONE', ( 20.48167154976358262, 206.1645954224638047, 75.27430365288482506 ) ) ; +#3878 = CARTESIAN_POINT ( 'NONE', ( 38.33548734387000678, 118.7516758551000038, 90.10263491839000949 ) ) ; +#3879 = ORIENTED_EDGE ( 'NONE', *, *, #35483, .F. ) ; +#3880 = CARTESIAN_POINT ( 'NONE', ( -29.20280672794129373, 149.0670272684989186, 94.08539458806572497 ) ) ; +#3881 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5317, #17576, #38848, #26611 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3882 = CARTESIAN_POINT ( 'NONE', ( 20.79310939989340667, 105.5805168952036865, 87.25522577498226440 ) ) ; +#3883 = LINE ( 'NONE', #16358, #25557 ) ; +#3884 = CARTESIAN_POINT ( 'NONE', ( -20.50092100153493746, 194.2771564787859120, 102.9104786413515740 ) ) ; +#3885 = EDGE_LOOP ( 'NONE', ( #38415, #28250, #26385, #11969 ) ) ; +#3886 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #37655, #9654, #13126, #31937 ), + ( #35159, #31740, #10054, #13719 ), + ( #38446, #38641, #16176, #1033 ), + ( #38052, #835, #10465, #9862 ), + ( #19638, #35553, #22933, #29463 ), + ( #28857, #7169, #19229, #13318 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 4 ), + ( 4, 4 ), + ( 5.706021859055999814E-12, 0.3333331262859999811, 0.6666662542622999732, 0.9999999999862000388 ), + ( 0.1697962087406000020, 0.8302040021366999811 ), + .UNSPECIFIED. ) ; +#3887 = ORIENTED_EDGE ( 'NONE', *, *, #6261, .F. ) ; +#3888 = LINE ( 'NONE', #29661, #37922 ) ; +#3889 = EDGE_CURVE ( 'NONE', #2544, #16362, #13003, .T. ) ; +#3890 = EDGE_CURVE ( 'NONE', #27747, #13602, #6441, .T. ) ; +#3891 = CARTESIAN_POINT ( 'NONE', ( -48.18886129041272426, 139.8560090933335687, 291.3782681826108387 ) ) ; +#3892 = EDGE_CURVE ( 'NONE', #29469, #4808, #21417, .T. ) ; +#3893 = ADVANCED_FACE ( 'NONE', ( #30811 ), #22013, .F. ) ; +#3894 = ORIENTED_EDGE ( 'NONE', *, *, #18392, .F. ) ; +#3895 = LINE ( 'NONE', #25805, #34815 ) ; +#3896 = AXIS2_PLACEMENT_3D ( 'NONE', #36657, #40312, #2317 ) ; +#3897 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825975761958095, 0.0005734119010998334383 ) ) ; +#3898 = CARTESIAN_POINT ( 'NONE', ( -38.12770169932999664, 119.0718537988000065, 87.43999389818000623 ) ) ; +#3899 = DIRECTION ( 'NONE', ( 0.6087614883550946931, -0.7730004026499608383, -0.1785492307423600933 ) ) ; +#3900 = EDGE_LOOP ( 'NONE', ( #8599, #34901, #20291, #34315 ) ) ; +#3901 = EDGE_CURVE ( 'NONE', #36231, #20521, #18504, .T. ) ; +#3902 = CARTESIAN_POINT ( 'NONE', ( 17.27218345960016421, 121.9621389981125361, 174.6024314160012523 ) ) ; +#3903 = CIRCLE ( 'NONE', #39163, 2.000000000000011546 ) ; +#3904 = AXIS2_PLACEMENT_3D ( 'NONE', #5901, #37187, #12633 ) ; +#3905 = ORIENTED_EDGE ( 'NONE', *, *, #27391, .T. ) ; +#3906 = CARTESIAN_POINT ( 'NONE', ( 5.665047306215249989, 124.5420718655650489, 88.64172132599090048 ) ) ; +#3907 = CARTESIAN_POINT ( 'NONE', ( -39.69814225588821444, 114.9854446628631450, 150.7514082625260130 ) ) ; +#3908 = DIRECTION ( 'NONE', ( -1.387778780769265269E-15, 0.9743700557921585181, 0.2249510932971561517 ) ) ; +#3909 = ADVANCED_FACE ( 'NONE', ( #22216 ), #25089, .F. ) ; +#3910 = ORIENTED_EDGE ( 'NONE', *, *, #12056, .T. ) ; +#3911 = CARTESIAN_POINT ( 'NONE', ( -15.10714335758950888, 136.3268993782255620, 91.13559034338766196 ) ) ; +#3912 = CARTESIAN_POINT ( 'NONE', ( -16.27370299762399597, 147.0379182250262318, 180.4996822280638185 ) ) ; +#3913 = CARTESIAN_POINT ( 'NONE', ( -26.00831778363330571, 205.1071295951813340, 76.12055741644476825 ) ) ; +#3914 = FACE_OUTER_BOUND ( 'NONE', #24441, .T. ) ; +#3915 = VERTEX_POINT ( 'NONE', #21615 ) ; +#3916 = CARTESIAN_POINT ( 'NONE', ( -20.09540649625984798, 211.8672601595316110, 73.07064120436956500 ) ) ; +#3917 = DIRECTION ( 'NONE', ( -0.0004270258721590739501, -0.7071067811865945352, -0.7071066522447926328 ) ) ; +#3918 = EDGE_LOOP ( 'NONE', ( #37314, #5199, #29544, #11091 ) ) ; +#3919 = CARTESIAN_POINT ( 'NONE', ( -9.153839583927000589, 130.7205244689999972, 90.09423690069999680 ) ) ; +#3920 = CARTESIAN_POINT ( 'NONE', ( 21.44693881909371669, 176.9241929811547038, 100.4861407201621120 ) ) ; +#3921 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250618410, 179.6252109630661380, 101.6466942236366151 ) ) ; +#3922 = ORIENTED_EDGE ( 'NONE', *, *, #31476, .F. ) ; +#3923 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.261220487827980362E-14, 0.9999998176071844824 ) ) ; +#3924 = DIRECTION ( 'NONE', ( 0.0005884951729871207987, -0.2249510544218079611, 0.9743698870490344888 ) ) ; +#3925 = AXIS2_PLACEMENT_3D ( 'NONE', #38753, #29979, #32638 ) ; +#3926 = AXIS2_PLACEMENT_3D ( 'NONE', #40367, #12773, #25262 ) ; +#3927 = ORIENTED_EDGE ( 'NONE', *, *, #22353, .F. ) ; +#3928 = VECTOR ( 'NONE', #10951, 1000.000000000000114 ) ; +#3929 = CARTESIAN_POINT ( 'NONE', ( 25.83405454150999958, 120.1395495440000047, 90.28159412456000155 ) ) ; +#3930 = CIRCLE ( 'NONE', #25534, 10.00000000000000533 ) ; +#3931 = CARTESIAN_POINT ( 'NONE', ( 16.30346404997956000, 121.9765769214875490, 177.9351893625809282 ) ) ; +#3932 = CARTESIAN_POINT ( 'NONE', ( 3.666638747408697441, 128.4736512688499488, 89.82433808099703754 ) ) ; +#3933 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9402, #40457, #31269, #25150 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#3935 = CARTESIAN_POINT ( 'NONE', ( -13.49953887075311698, 187.7424330182009840, 103.5179849509054435 ) ) ; +#3934 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 77.27946979429611929, 297.5967072516830854 ) ) ; +#3936 = CARTESIAN_POINT ( 'NONE', ( -82.81915783535940534, 72.22391443751210716, 166.5742336941280257 ) ) ; +#3937 = ORIENTED_EDGE ( 'NONE', *, *, #33871, .T. ) ; +#3938 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989120913, 109.3655459317195522, 175.1905691378508436 ) ) ; +#3939 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825897900247689, 0.0005734119028982040270 ) ) ; +#3940 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -3.370379598151327408E-34, 0.0006039748319386880390 ) ) ; +#3941 = VERTEX_POINT ( 'NONE', #31609 ) ; +#3942 = EDGE_CURVE ( 'NONE', #25599, #30846, #34061, .T. ) ; +#3943 = VERTEX_POINT ( 'NONE', #40388 ) ; +#3944 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#3945 = CARTESIAN_POINT ( 'NONE', ( 44.64491191134371917, 188.7542347311224376, 105.7690686227471559 ) ) ; +#3946 = CARTESIAN_POINT ( 'NONE', ( 31.30352330330278576, 110.6131156702000027, 87.24887774834422771 ) ) ; +#3947 = LINE ( 'NONE', #32377, #3263 ) ; +#3948 = ORIENTED_EDGE ( 'NONE', *, *, #2037, .F. ) ; +#3949 = ORIENTED_EDGE ( 'NONE', *, *, #13693, .F. ) ; +#3950 = CARTESIAN_POINT ( 'NONE', ( 14.42353522632744678, 129.4117444856125871, 92.42912713004928094 ) ) ; +#3951 = CARTESIAN_POINT ( 'NONE', ( -12.63408200835842976, 177.6899303382640483, 100.7688461857968036 ) ) ; +#3952 = FACE_OUTER_BOUND ( 'NONE', #3310, .T. ) ; +#3953 = CARTESIAN_POINT ( 'NONE', ( 30.02141569587843151, 185.4797026447788255, 105.5350675575252524 ) ) ; +#3954 = EDGE_LOOP ( 'NONE', ( #32030, #30628, #38265, #9406 ) ) ; +#3955 = CARTESIAN_POINT ( 'NONE', ( -22.36573918166319430, 213.5251468429292458, 73.57207195213049999 ) ) ; +#3956 = CIRCLE ( 'NONE', #9854, 1.750000000000001998 ) ; +#3957 = ORIENTED_EDGE ( 'NONE', *, *, #5237, .T. ) ; +#3958 = CIRCLE ( 'NONE', #28788, 6.500000000066489925 ) ; +#3959 = CONICAL_SURFACE ( 'NONE', #2032, 6.000000367495921694, 0.7853981634064428619 ) ; +#3960 = ORIENTED_EDGE ( 'NONE', *, *, #22306, .T. ) ; +#3961 = PLANE ( 'NONE', #19602 ) ; +#3962 = ORIENTED_EDGE ( 'NONE', *, *, #22403, .T. ) ; +#3963 = CARTESIAN_POINT ( 'NONE', ( -37.27993193924111637, 164.6275578583710342, 198.2149168068204688 ) ) ; +#3964 = EDGE_CURVE ( 'NONE', #32767, #2748, #31408, .T. ) ; +#3965 = CARTESIAN_POINT ( 'NONE', ( -1.489481181603000026, 189.1037180294000279, 105.9254781432999977 ) ) ; +#3966 = CARTESIAN_POINT ( 'NONE', ( -2.435581690730916016, 190.9709058671855360, 106.3075837308457352 ) ) ; +#3967 = ORIENTED_EDGE ( 'NONE', *, *, #23483, .T. ) ; +#3968 = CARTESIAN_POINT ( 'NONE', ( 22.78253045494810891, 153.6097073741841541, 98.01061943718465841 ) ) ; +#3969 = CARTESIAN_POINT ( 'NONE', ( -25.18576680417500668, 116.8541585394636684, 87.78282270138144838 ) ) ; +#3970 = CARTESIAN_POINT ( 'NONE', ( 22.79043357853658591, 214.0899764684317574, 73.04473923159348203 ) ) ; +#3971 = CARTESIAN_POINT ( 'NONE', ( 13.50023901242825275, 124.1961254174222802, 90.96643860594015507 ) ) ; +#3972 = CARTESIAN_POINT ( 'NONE', ( -37.83775869339704201, 191.4135373797588215, 104.3802259940997033 ) ) ; +#3973 = VERTEX_POINT ( 'NONE', #2792 ) ; +#3974 = CARTESIAN_POINT ( 'NONE', ( 24.25953830040776893, 115.9286994022373420, 89.75330581144697817 ) ) ; +#3975 = AXIS2_PLACEMENT_3D ( 'NONE', #21077, #5929, #40263 ) ; +#3976 = CARTESIAN_POINT ( 'NONE', ( -37.97865408599000148, 118.8664476399000023, 90.44763526090001449 ) ) ; +#3977 = VECTOR ( 'NONE', #33589, 1000.000000000000114 ) ; +#3978 = VERTEX_POINT ( 'NONE', #27755 ) ; +#3979 = AXIS2_PLACEMENT_3D ( 'NONE', #25936, #10392, #7491 ) ; +#3980 = ORIENTED_EDGE ( 'NONE', *, *, #12311, .T. ) ; +#3981 = LINE ( 'NONE', #28551, #33606 ) ; +#3982 = CARTESIAN_POINT ( 'NONE', ( -26.79701054014554984, 123.5536321148342864, 88.19370908452887647 ) ) ; +#3983 = CARTESIAN_POINT ( 'NONE', ( -31.50112765883515564, 162.4459499757934964, 187.8003480921526318 ) ) ; +#3984 = CARTESIAN_POINT ( 'NONE', ( -13.50199777270016810, 123.7767173896095159, 91.24176358735705605 ) ) ; +#3985 = EDGE_CURVE ( 'NONE', #15161, #8051, #17686, .T. ) ; +#3986 = ORIENTED_EDGE ( 'NONE', *, *, #28562, .T. ) ; +#3987 = ADVANCED_FACE ( 'NONE', ( #31205 ), #9335, .T. ) ; +#3988 = ORIENTED_EDGE ( 'NONE', *, *, #631, .F. ) ; +#3989 = CARTESIAN_POINT ( 'NONE', ( -19.99799082025366204, 173.8313734241264967, 102.8761342917995734 ) ) ; +#3990 = VERTEX_POINT ( 'NONE', #120 ) ; +#3991 = ORIENTED_EDGE ( 'NONE', *, *, #1828, .F. ) ; +#3992 = ORIENTED_EDGE ( 'NONE', *, *, #32263, .T. ) ; +#3993 = CARTESIAN_POINT ( 'NONE', ( 5.696732336563999688, 172.5096616001999905, 152.4718672074000381 ) ) ; +#3994 = CARTESIAN_POINT ( 'NONE', ( -14.82260162707301809, 143.3364409748008086, 28.42526875798066399 ) ) ; +#3995 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 82.27946979429634666, 315.0857197240630967 ) ) ; +#3996 = ORIENTED_EDGE ( 'NONE', *, *, #31157, .F. ) ; +#3997 = EDGE_CURVE ( 'NONE', #3655, #13769, #3176, .T. ) ; +#3998 = ORIENTED_EDGE ( 'NONE', *, *, #7686, .F. ) ; +#3999 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263834, 86.95598109309847246, 291.5876487235610739 ) ) ; +#4000 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #4786, #13802 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4001 = CARTESIAN_POINT ( 'NONE', ( 20.48253891412411321, 207.4083879957671002, 77.06951181954761410 ) ) ; +#4002 = LINE ( 'NONE', #16671, #11745 ) ; +#4003 = CARTESIAN_POINT ( 'NONE', ( 43.13736350275988940, 121.9393806477530404, 87.86294449587100530 ) ) ; +#4004 = CARTESIAN_POINT ( 'NONE', ( 20.00007342045880065, 191.7526597988445189, 103.9104467472352979 ) ) ; +#4005 = DIRECTION ( 'NONE', ( -0.7933533411653073131, 0.5930537057989938576, 0.1373964268091566188 ) ) ; +#4006 = CARTESIAN_POINT ( 'NONE', ( -15.10713178427481651, 176.3794795624077096, 100.3824614381103828 ) ) ; +#4007 = ORIENTED_EDGE ( 'NONE', *, *, #14262, .T. ) ; +#4008 = DIRECTION ( 'NONE', ( 3.469446951931442070E-15, 0.9743700557921584071, 0.2249510932971566513 ) ) ; +#4009 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; +#4010 = CARTESIAN_POINT ( 'NONE', ( 22.50029346544275199, 184.8550509193516973, 102.8296322281952513 ) ) ; +#4011 = AXIS2_PLACEMENT_3D ( 'NONE', #22246, #28768, #4008 ) ; +#4012 = CARTESIAN_POINT ( 'NONE', ( -32.61688159666169184, 141.9329143176964863, 280.9718830317659695 ) ) ; +#4013 = CARTESIAN_POINT ( 'NONE', ( 5.035334123826465280, 124.4259184218055623, 88.37586634456850732 ) ) ; +#4014 = ORIENTED_EDGE ( 'NONE', *, *, #18481, .T. ) ; +#4015 = AXIS2_PLACEMENT_3D ( 'NONE', #12845, #33235, #32645 ) ; +#4016 = CARTESIAN_POINT ( 'NONE', ( -21.68500723473647795, 135.5097507517283759, 90.95090954866776656 ) ) ; +#4017 = ADVANCED_FACE ( 'NONE', ( #15847 ), #15655, .F. ) ; +#4018 = CIRCLE ( 'NONE', #7284, 2.499999999946084017 ) ; +#4019 = CARTESIAN_POINT ( 'NONE', ( 0.6665120506454667026, 189.0026601577200154, 103.6872697040404745 ) ) ; +#4020 = CARTESIAN_POINT ( 'NONE', ( -2.934188061559037219, 190.6895742892954217, 106.7577657789754966 ) ) ; +#4021 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049039381, 157.6243160761316346, 99.14398654755730433 ) ) ; +#4022 = CARTESIAN_POINT ( 'NONE', ( -26.12766474369999870, 191.8600560154999926, 103.7976276137000013 ) ) ; +#4023 = FACE_OUTER_BOUND ( 'NONE', #11056, .T. ) ; +#4024 = LINE ( 'NONE', #28984, #20910 ) ; +#4025 = PLANE ( 'NONE', #4287 ) ; +#4026 = ORIENTED_EDGE ( 'NONE', *, *, #489, .F. ) ; +#4027 = EDGE_CURVE ( 'NONE', #19373, #23019, #10220, .T. ) ; +#4028 = FACE_OUTER_BOUND ( 'NONE', #8833, .T. ) ; +#4029 = EDGE_CURVE ( 'NONE', #7166, #26491, #20150, .T. ) ; +#4030 = CARTESIAN_POINT ( 'NONE', ( -75.99005881032610432, 156.2326527032377328, 96.28112034756948390 ) ) ; +#4031 = LINE ( 'NONE', #31873, #2224 ) ; +#4032 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098148, 129.6135529956771677, 92.66635095651142251 ) ) ; +#4033 = CARTESIAN_POINT ( 'NONE', ( -35.98817295377529746, 191.5260130662397273, 103.8919236801626340 ) ) ; +#4034 = CARTESIAN_POINT ( 'NONE', ( -41.44764783254269958, 120.6681368631575850, 88.04954071273041905 ) ) ; +#4035 = CARTESIAN_POINT ( 'NONE', ( -6.037582702821003622, 135.2929569892681343, 91.40456025087448211 ) ) ; +#4036 = ADVANCED_FACE ( 'NONE', ( #10141 ), #22813, .T. ) ; +#4037 = CARTESIAN_POINT ( 'NONE', ( 35.72259725408999742, 192.2500497483999879, 106.7785130986000155 ) ) ; +#4038 = ORIENTED_EDGE ( 'NONE', *, *, #15850, .F. ) ; +#4039 = EDGE_CURVE ( 'NONE', #1663, #19888, #38274, .T. ) ; +#4040 = ORIENTED_EDGE ( 'NONE', *, *, #8017, .F. ) ; +#4041 = CIRCLE ( 'NONE', #33440, 2.499999889092850758 ) ; +#4042 = CARTESIAN_POINT ( 'NONE', ( -2.690201782050851698, 209.6661438676858040, 75.89346438378312598 ) ) ; +#4043 = EDGE_CURVE ( 'NONE', #21267, #35219, #23069, .T. ) ; +#4044 = CARTESIAN_POINT ( 'NONE', ( 5.675840488321574284, 188.3446150673902650, 103.1322824216947396 ) ) ; +#4045 = CARTESIAN_POINT ( 'NONE', ( 20.48811801917814179, 203.6451961417796781, 85.93495381676980571 ) ) ; +#4046 = ORIENTED_EDGE ( 'NONE', *, *, #3346, .F. ) ; +#4047 = CARTESIAN_POINT ( 'NONE', ( 6.035092514208784564, 177.2417361255070603, 101.0397482620736156 ) ) ; +#4048 = ORIENTED_EDGE ( 'NONE', *, *, #38078, .T. ) ; +#4049 = CARTESIAN_POINT ( 'NONE', ( 8.471266708538822243, 150.8425416249367004, 96.01200669677277233 ) ) ; +#4050 = DIRECTION ( 'NONE', ( -0.0005884949961181962360, 0.2249510543439063315, -0.9743698870671262391 ) ) ; +#4051 = CARTESIAN_POINT ( 'NONE', ( -45.98255491755426050, 185.1241532521533770, 105.4988869918989707 ) ) ; +#4052 = CARTESIAN_POINT ( 'NONE', ( 77.66065009075275327, 193.3992594998515244, 188.4681838635439419 ) ) ; +#4053 = LINE ( 'NONE', #795, #23644 ) ; +#4054 = EDGE_LOOP ( 'NONE', ( #16507, #1133, #10858, #7815 ) ) ; +#4055 = CARTESIAN_POINT ( 'NONE', ( 15.94054573232656047, 152.1434801212134857, 184.5792362023208284 ) ) ; +#4056 = CARTESIAN_POINT ( 'NONE', ( 35.55352252815201552, 111.2706431035999941, 87.24631085531800068 ) ) ; +#4057 = CARTESIAN_POINT ( 'NONE', ( 13.76437287132147169, 125.3330071254293898, 174.7699841533003564 ) ) ; +#4058 = CARTESIAN_POINT ( 'NONE', ( -35.95026569344999956, 191.6735383353999964, 104.0297955518999942 ) ) ; +#4059 = EDGE_LOOP ( 'NONE', ( #39536, #37006, #1773, #16711 ) ) ; +#4060 = VECTOR ( 'NONE', #9549, 1000.000000000000114 ) ; +#4061 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421484904, 126.1293544849782222, 91.84293499097150004 ) ) ; +#4062 = AXIS2_PLACEMENT_3D ( 'NONE', #35112, #25966, #389 ) ; +#4063 = AXIS2_PLACEMENT_3D ( 'NONE', #2448, #33297, #7954 ) ; +#4064 = DIRECTION ( 'NONE', ( -0.7933532970003738249, -0.5930762008556724751, -0.1372995488602875847 ) ) ; +#4065 = EDGE_CURVE ( 'NONE', #23158, #7827, #31402, .T. ) ; +#4066 = CARTESIAN_POINT ( 'NONE', ( -20.33182997993345964, 160.1345059202187713, 99.37190935997061558 ) ) ; +#4067 = PLANE ( 'NONE', #10912 ) ; +#4068 = EDGE_CURVE ( 'NONE', #35965, #15629, #15432, .T. ) ; +#4069 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#4070 = CARTESIAN_POINT ( 'NONE', ( -2.314308651363000013, 209.1937053114000378, 73.71695174304001341 ) ) ; +#4071 = CARTESIAN_POINT ( 'NONE', ( 38.31494853206999807, 118.7332877682000003, 90.10250374566000175 ) ) ; +#4072 = VERTEX_POINT ( 'NONE', #13205 ) ; +#4073 = EDGE_CURVE ( 'NONE', #20063, #25514, #14566, .T. ) ; +#4074 = CARTESIAN_POINT ( 'NONE', ( 27.38311190280682794, 119.8998877726164665, 171.4645808398473150 ) ) ; +#4075 = PLANE ( 'NONE', #10414 ) ; +#4076 = CARTESIAN_POINT ( 'NONE', ( -41.44764783254269958, 120.6681368631575850, 88.04954071273041905 ) ) ; +#4077 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #23595, #10934 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4078 = CARTESIAN_POINT ( 'NONE', ( 2.712461541526598463, 209.0473112905976905, 75.81951506724567480 ) ) ; +#4079 = ORIENTED_EDGE ( 'NONE', *, *, #34688, .F. ) ; +#4080 = EDGE_CURVE ( 'NONE', #24155, #35141, #16746, .T. ) ; +#4081 = EDGE_LOOP ( 'NONE', ( #24321, #7626, #36721, #32201 ) ) ; +#4082 = FACE_OUTER_BOUND ( 'NONE', #22958, .T. ) ; +#4083 = CIRCLE ( 'NONE', #14570, 2.500000007063326368 ) ; +#4084 = CARTESIAN_POINT ( 'NONE', ( -25.02112241941476611, 129.9358920626651752, 92.74501084285195418 ) ) ; +#4085 = DIRECTION ( 'NONE', ( -0.7933530821293308666, -0.5932640870757668328, -0.1364866662427074440 ) ) ; +#4086 = CARTESIAN_POINT ( 'NONE', ( 15.66680653501490283, 138.4328626290368618, 91.94536332186872585 ) ) ; +#4087 = ORIENTED_EDGE ( 'NONE', *, *, #19454, .F. ) ; +#4088 = VERTEX_POINT ( 'NONE', #715 ) ; +#4089 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927741987662, 0.0005734119022070274189 ) ) ; +#4090 = VECTOR ( 'NONE', #13858, 1000.000000000000114 ) ; +#4091 = LINE ( 'NONE', #32524, #3173 ) ; +#4092 = CARTESIAN_POINT ( 'NONE', ( -35.78755354827145396, 207.5618092979057678, 77.16841347661691941 ) ) ; +#4093 = CARTESIAN_POINT ( 'NONE', ( -22.49823373577465446, 160.0620215113764857, 99.69865297419991634 ) ) ; +#4094 = ORIENTED_EDGE ( 'NONE', *, *, #6040, .T. ) ; +#4095 = FACE_OUTER_BOUND ( 'NONE', #19162, .T. ) ; +#4096 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39041, #17351, #33511, #29862 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4097 = ORIENTED_EDGE ( 'NONE', *, *, #33070, .T. ) ; +#4098 = LINE ( 'NONE', #16777, #32465 ) ; +#4099 = PLANE ( 'NONE', #3229 ) ; +#4100 = LINE ( 'NONE', #7378, #39923 ) ; +#4101 = ORIENTED_EDGE ( 'NONE', *, *, #7198, .T. ) ; +#4102 = CARTESIAN_POINT ( 'NONE', ( -2.603750836884000108, 191.0374824654000179, 104.1011186467000016 ) ) ; +#4103 = LINE ( 'NONE', #7789, #33602 ) ; +#4104 = LINE ( 'NONE', #39880, #30922 ) ; +#4105 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250900735, 132.4055461762762604, 92.79778151960539390 ) ) ; +#4106 = VERTEX_POINT ( 'NONE', #3776 ) ; +#4107 = CARTESIAN_POINT ( 'NONE', ( -25.50863078827237018, 208.7343152597242977, 75.72119809267951496 ) ) ; +#4108 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999904787, 177.0581688368729374, 100.5408937735694224 ) ) ; +#4109 = VERTEX_POINT ( 'NONE', #32408 ) ; +#4110 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; +#4111 = AXIS2_PLACEMENT_3D ( 'NONE', #28390, #37384, #33903 ) ; +#4112 = EDGE_CURVE ( 'NONE', #29855, #9171, #23008, .T. ) ; +#4113 = EDGE_CURVE ( 'NONE', #26453, #18640, #22413, .T. ) ; +#4114 = ORIENTED_EDGE ( 'NONE', *, *, #38665, .F. ) ; +#4115 = CARTESIAN_POINT ( 'NONE', ( -35.95556595676193723, 218.5902260770999987, 73.58022043445957650 ) ) ; +#4116 = ADVANCED_FACE ( 'NONE', ( #34835 ), #35431, .T. ) ; +#4117 = VECTOR ( 'NONE', #23570, 1000.000000000000114 ) ; +#4118 = EDGE_CURVE ( 'NONE', #19190, #19220, #38685, .T. ) ; +#4119 = CARTESIAN_POINT ( 'NONE', ( 2.598437061832757689, 190.9999997773007578, 162.9812745352361389 ) ) ; +#4120 = CARTESIAN_POINT ( 'NONE', ( 37.96380763661293400, 191.4135383555317844, 104.3344495138068595 ) ) ; +#4121 = CARTESIAN_POINT ( 'NONE', ( 22.50193259072577945, 153.6096650756881274, 98.01077209009481805 ) ) ; +#4122 = AXIS2_PLACEMENT_3D ( 'NONE', #39106, #26456, #19884 ) ; +#4123 = ORIENTED_EDGE ( 'NONE', *, *, #34629, .F. ) ; +#4124 = ADVANCED_FACE ( 'NONE', ( #19903 ), #13795, .T. ) ; +#4125 = CARTESIAN_POINT ( 'NONE', ( 25.67739237361999827, 120.5334253433999976, 90.20131454888000633 ) ) ; +#4126 = LINE ( 'NONE', #672, #14964 ) ; +#4128 = CARTESIAN_POINT ( 'NONE', ( -12.40501934898651903, 154.3261979101877159, 95.28942457974159197 ) ) ; +#4127 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971562627 ) ) ; +#4129 = EDGE_CURVE ( 'NONE', #3510, #28860, #23766, .T. ) ; +#4130 = ORIENTED_EDGE ( 'NONE', *, *, #23122, .F. ) ; +#4131 = LINE ( 'NONE', #25851, #10169 ) ; +#4132 = CARTESIAN_POINT ( 'NONE', ( 38.35802587332594982, 118.7131882838841364, 87.66888804344846164 ) ) ; +#4133 = DIRECTION ( 'NONE', ( -0.6087604442381534531, -0.7731007285209676727, -0.1781178966059141500 ) ) ; +#4134 = CARTESIAN_POINT ( 'NONE', ( -13.83205090666964487, 150.4111610999959225, 179.9705989584246595 ) ) ; +#4135 = ORIENTED_EDGE ( 'NONE', *, *, #38297, .T. ) ; +#4136 = ORIENTED_EDGE ( 'NONE', *, *, #19082, .F. ) ; +#4137 = CARTESIAN_POINT ( 'NONE', ( 38.54429663914000059, 119.2351694718000061, 90.41614767503999417 ) ) ; +#4138 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#4139 = EDGE_CURVE ( 'NONE', #3107, #5073, #31843, .T. ) ; +#4140 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989908600, 0.1373964268091705798 ) ) ; +#4141 = DIRECTION ( 'NONE', ( 0.0002393071182785257178, 0.2252352986010041636, -0.9743043687658490271 ) ) ; +#4142 = CARTESIAN_POINT ( 'NONE', ( -2.300291980288000193, 191.0028055148000021, 106.1754316641000173 ) ) ; +#4143 = AXIS2_PLACEMENT_3D ( 'NONE', #17594, #13735, #26226 ) ; +#4144 = ORIENTED_EDGE ( 'NONE', *, *, #26355, .F. ) ; +#4145 = ORIENTED_EDGE ( 'NONE', *, *, #21153, .F. ) ; +#4146 = CARTESIAN_POINT ( 'NONE', ( 14.29577276298495825, 129.3448226987248688, 92.24270346485123184 ) ) ; +#4147 = CARTESIAN_POINT ( 'NONE', ( -12.63249231614464385, 177.7398399100670190, 100.7376584407296889 ) ) ; +#4148 = DIRECTION ( 'NONE', ( 0.0005884949961207905150, -0.2249510543439056653, 0.9743698870671265722 ) ) ; +#4149 = AXIS2_PLACEMENT_3D ( 'NONE', #12698, #19018, #18412 ) ; +#4150 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#4151 = ORIENTED_EDGE ( 'NONE', *, *, #27567, .T. ) ; +#4152 = DIRECTION ( 'NONE', ( -0.0005884949961251158311, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#4153 = ORIENTED_EDGE ( 'NONE', *, *, #11487, .T. ) ; +#4154 = CARTESIAN_POINT ( 'NONE', ( -13.49823352873892013, 173.8382768105483080, 102.8767958496218426 ) ) ; +#4155 = ORIENTED_EDGE ( 'NONE', *, *, #18392, .T. ) ; +#4156 = DIRECTION ( 'NONE', ( -0.0006039748319391919761, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#4157 = CARTESIAN_POINT ( 'NONE', ( -0.3440673525092000640, 189.1687001887999884, 105.6068241919000172 ) ) ; +#4158 = CARTESIAN_POINT ( 'NONE', ( -41.28986358703587456, 120.5685454323574817, 90.59221360106587895 ) ) ; +#4159 = CARTESIAN_POINT ( 'NONE', ( -2.435715612982877420, 190.9805827069217798, 106.3103827067138951 ) ) ; +#4160 = VERTEX_POINT ( 'NONE', #5757 ) ; +#4161 = ORIENTED_EDGE ( 'NONE', *, *, #12838, .F. ) ; +#4162 = ADVANCED_FACE ( 'NONE', ( #21102 ), #11518, .F. ) ; +#4163 = CARTESIAN_POINT ( 'NONE', ( -25.99272521086959387, 191.9759150222000130, 101.9371462950079774 ) ) ; +#4164 = EDGE_CURVE ( 'NONE', #11241, #7852, #23494, .T. ) ; +#4165 = CARTESIAN_POINT ( 'NONE', ( 19.79191328487740975, 119.7876596114540320, 175.4710310665177531 ) ) ; +#4166 = CARTESIAN_POINT ( 'NONE', ( 19.32153195108318755, 125.7880423541971311, 175.3576964661925217 ) ) ; +#4167 = AXIS2_PLACEMENT_3D ( 'NONE', #3407, #22445, #4205 ) ; +#4168 = CARTESIAN_POINT ( 'NONE', ( -45.34134577087812801, 120.7154725862561406, 105.4905015689576402 ) ) ; +#4169 = ORIENTED_EDGE ( 'NONE', *, *, #29013, .T. ) ; +#4170 = CC_DESIGN_DATE_AND_TIME_ASSIGNMENT ( #6104, #18556, ( #14451 ) ) ; +#4171 = CARTESIAN_POINT ( 'NONE', ( 23.32767345890041000, 115.6131156702012532, 89.75388588320586791 ) ) ; +#4172 = AXIS2_PLACEMENT_3D ( 'NONE', #13703, #26192, #10250 ) ; +#4173 = CARTESIAN_POINT ( 'NONE', ( -38.27202037554999947, 118.0785410800999955, 89.55555236154999932 ) ) ; +#4174 = EDGE_LOOP ( 'NONE', ( #30071, #30307, #39314, #16735 ) ) ; +#4175 = LINE ( 'NONE', #16651, #32796 ) ; +#4176 = ORIENTED_EDGE ( 'NONE', *, *, #37909, .F. ) ; +#4177 = CARTESIAN_POINT ( 'NONE', ( 9.000881520060126206, 160.1177476481799431, 96.61358080770237677 ) ) ; +#4178 = CARTESIAN_POINT ( 'NONE', ( -9.152368341089999859, 181.3125747747000105, 104.3400940192999968 ) ) ; +#4179 = CARTESIAN_POINT ( 'NONE', ( -29.44951657505878728, 160.9899919687744330, 187.1078845272746776 ) ) ; +#4180 = FACE_OUTER_BOUND ( 'NONE', #30971, .T. ) ; +#4181 = ORIENTED_EDGE ( 'NONE', *, *, #4544, .F. ) ; +#4182 = ORIENTED_EDGE ( 'NONE', *, *, #19408, .T. ) ; +#4183 = CARTESIAN_POINT ( 'NONE', ( -20.33170840607064633, 173.9106082832947493, 102.5524983983761445 ) ) ; +#4184 = ORIENTED_EDGE ( 'NONE', *, *, #27591, .T. ) ; +#4185 = ORIENTED_EDGE ( 'NONE', *, *, #7180, .T. ) ; +#4186 = ORIENTED_EDGE ( 'NONE', *, *, #23255, .T. ) ; +#4187 = FACE_BOUND ( 'NONE', #33089, .T. ) ; +#4188 = EDGE_CURVE ( 'NONE', #12815, #6603, #29798, .T. ) ; +#4189 = FACE_OUTER_BOUND ( 'NONE', #33949, .T. ) ; +#4190 = ORIENTED_EDGE ( 'NONE', *, *, #27164, .F. ) ; +#4191 = VERTEX_POINT ( 'NONE', #17801 ) ; +#4192 = CARTESIAN_POINT ( 'NONE', ( -48.18983608578390232, 82.56060091850311267, 289.7643016034785433 ) ) ; +#4193 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17335, #7742, #16741, #35732 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4194 = CARTESIAN_POINT ( 'NONE', ( 36.06237288312285472, 191.9759150222000130, 101.8996665707895488 ) ) ; +#4195 = CARTESIAN_POINT ( 'NONE', ( 35.40691481614999958, 112.8575867658999954, 87.09914284068000256 ) ) ; +#4196 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250612725, 132.8554482850445311, 90.84904174543022748 ) ) ; +#4197 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606776115838874, 137.3532831589803322, 178.0585834212922123 ) ) ; +#4198 = CC_DESIGN_APPROVAL ( #30192, ( #14451 ) ) ; +#4199 = AXIS2_PLACEMENT_3D ( 'NONE', #12632, #3023, #21660 ) ; +#4200 = CARTESIAN_POINT ( 'NONE', ( -18.71851310314255556, 125.9964326179262883, 174.7342168340691444 ) ) ; +#4201 = VERTEX_POINT ( 'NONE', #14969 ) ; +#4202 = CARTESIAN_POINT ( 'NONE', ( 27.75720308144000015, 124.8885774052999977, 88.64001580753000553 ) ) ; +#4203 = AXIS2_PLACEMENT_3D ( 'NONE', #4163, #32404, #32592 ) ; +#4204 = AXIS2_PLACEMENT_3D ( 'NONE', #5481, #23488, #7946 ) ; +#4205 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#4206 = CARTESIAN_POINT ( 'NONE', ( 15.59057381647033580, 147.4113417082091928, 179.2674225712073053 ) ) ; +#4207 = CIRCLE ( 'NONE', #37529, 2.000000000000011546 ) ; +#4208 = CARTESIAN_POINT ( 'NONE', ( 3.724081451453682856, 175.3147317747299496, 100.3200250948046772 ) ) ; +#4209 = CARTESIAN_POINT ( 'NONE', ( 3.785823397764000564, 171.3080482585999960, 102.0225523146000057 ) ) ; +#4210 = VERTEX_POINT ( 'NONE', #30295 ) ; +#4211 = LINE ( 'NONE', #35078, #22659 ) ; +#4212 = CARTESIAN_POINT ( 'NONE', ( 0.6150485984469488132, 189.0007186515956334, 103.6819504671993570 ) ) ; +#4213 = CARTESIAN_POINT ( 'NONE', ( 36.46626233178599819, 191.7780397924495617, 104.3563079202803010 ) ) ; +#4214 = CARTESIAN_POINT ( 'NONE', ( 12.63850258338070454, 130.2470009342416688, 92.65524625922149937 ) ) ; +#4215 = EDGE_CURVE ( 'NONE', #36508, #7897, #4322, .T. ) ; +#4216 = FACE_OUTER_BOUND ( 'NONE', #8258, .T. ) ; +#4217 = EDGE_CURVE ( 'NONE', #39537, #18545, #33553, .T. ) ; +#4218 = CARTESIAN_POINT ( 'NONE', ( -20.01418606989972204, 209.7097173109508503, 78.07055141587061087 ) ) ; +#4219 = CARTESIAN_POINT ( 'NONE', ( -4.037441716916447376, 168.3837378232288131, 99.04296232367518371 ) ) ; +#4220 = CARTESIAN_POINT ( 'NONE', ( 20.48021663872660625, 209.7101073659619601, 73.54617496015868028 ) ) ; +#4221 = ORIENTED_EDGE ( 'NONE', *, *, #21274, .T. ) ; +#4222 = EDGE_CURVE ( 'NONE', #31021, #31197, #2071, .T. ) ; +#4223 = CIRCLE ( 'NONE', #34890, 2.000000000000011546 ) ; +#4224 = CARTESIAN_POINT ( 'NONE', ( 3.046672840550818329, 207.8686389444351050, 77.27521480614490201 ) ) ; +#4225 = CONICAL_SURFACE ( 'NONE', #6197, 2.500000000022427393, 0.7853981634179985072 ) ; +#4226 = AXIS2_PLACEMENT_3D ( 'NONE', #15107, #9173, #21846 ) ; +#4227 = ORIENTED_EDGE ( 'NONE', *, *, #22709, .T. ) ; +#4228 = CARTESIAN_POINT ( 'NONE', ( -37.72490114302640762, 118.1295962051366644, 87.71953816704314022 ) ) ; +#4229 = CARTESIAN_POINT ( 'NONE', ( 0.5984363816331808028, 189.0000000000002842, 162.9824824855311931 ) ) ; +#4230 = CARTESIAN_POINT ( 'NONE', ( -37.26906488761501635, 185.6725334949844353, 105.6202278399714203 ) ) ; +#4231 = CARTESIAN_POINT ( 'NONE', ( 20.33633106218516318, 118.1105547769028021, 89.92091325015400116 ) ) ; +#4232 = VECTOR ( 'NONE', #31470, 1000.000000000000000 ) ; +#4233 = DIRECTION ( 'NONE', ( -0.7072759766252937341, -0.1592272936566909713, 0.6887723585071506838 ) ) ; +#4234 = CARTESIAN_POINT ( 'NONE', ( 40.01726673357607211, 182.7482725554044976, 105.5615746506993844 ) ) ; +#4235 = CARTESIAN_POINT ( 'NONE', ( 16.14865643636807846, 151.1202562712145152, 184.8374432047714606 ) ) ; +#4236 = ORIENTED_EDGE ( 'NONE', *, *, #11255, .F. ) ; +#4237 = CARTESIAN_POINT ( 'NONE', ( -2.585505525763999835, 209.4244858662999889, 75.73377336996000508 ) ) ; +#4238 = EDGE_CURVE ( 'NONE', #34827, #17792, #3645, .T. ) ; +#4239 = CARTESIAN_POINT ( 'NONE', ( 37.60707583988345704, 118.6216986129650479, 87.24507056057791488 ) ) ; +#4240 = CARTESIAN_POINT ( 'NONE', ( -23.16262457356699400, 49.03856518996145297, 291.5725335800685798 ) ) ; +#4241 = CARTESIAN_POINT ( 'NONE', ( 3.847675889067868393, 147.9886445650915618, 129.7371189396918680 ) ) ; +#4242 = ORIENTED_EDGE ( 'NONE', *, *, #25948, .F. ) ; +#4243 = DIRECTION ( 'NONE', ( 0.0005884965786932929224, -0.2255194605963585786, 0.9742384854665229188 ) ) ; +#4244 = CARTESIAN_POINT ( 'NONE', ( 3.756546640233114243, 136.7315605858967444, 94.07002193663585388 ) ) ; +#4245 = EDGE_LOOP ( 'NONE', ( #34445, #35515, #4979 ) ) ; +#4246 = CARTESIAN_POINT ( 'NONE', ( -39.01517791770809396, 88.99230595947560118, 291.5821081250562656 ) ) ; +#4247 = ORIENTED_EDGE ( 'NONE', *, *, #24577, .F. ) ; +#4248 = CARTESIAN_POINT ( 'NONE', ( 36.24343983389131552, 191.9507376470629367, 106.3940752163002088 ) ) ; +#4249 = EDGE_CURVE ( 'NONE', #35941, #22242, #36976, .T. ) ; +#4250 = CARTESIAN_POINT ( 'NONE', ( -3.668404233967317740, 183.5617789224675676, 104.5994755554405486 ) ) ; +#4251 = CARTESIAN_POINT ( 'NONE', ( -30.07053858951977432, 176.7377855870873873, 103.0399784982492264 ) ) ; +#4252 = DIRECTION ( 'NONE', ( 0.6087611434178766823, 0.7731004625452562173, 0.1781166614241080082 ) ) ; +#4253 = ORIENTED_EDGE ( 'NONE', *, *, #246, .T. ) ; +#4254 = EDGE_CURVE ( 'NONE', #37266, #34131, #32761, .T. ) ; +#4255 = CARTESIAN_POINT ( 'NONE', ( -47.98131261778327428, 61.12730635085708286, 282.5875218042072561 ) ) ; +#4256 = CARTESIAN_POINT ( 'NONE', ( -3.537408990743386550, 175.5045353393659866, 100.1734741104028643 ) ) ; +#4257 = VECTOR ( 'NONE', #2294, 1000.000000000000000 ) ; +#4258 = AXIS2_PLACEMENT_3D ( 'NONE', #4976, #11531, #32399 ) ; +#4259 = CARTESIAN_POINT ( 'NONE', ( -27.19720299916742690, 110.6131156702000027, 88.78421099472409139 ) ) ; +#4260 = CIRCLE ( 'NONE', #32984, 2.000000000000008882 ) ; +#4261 = DIRECTION ( 'NONE', ( -0.1943643238945204910, 0.07321898756438906253, -0.9781929714821465671 ) ) ; +#4262 = ORIENTED_EDGE ( 'NONE', *, *, #257, .F. ) ; +#4263 = ORIENTED_EDGE ( 'NONE', *, *, #12493, .F. ) ; +#4264 = AXIS2_PLACEMENT_3D ( 'NONE', #40370, #18684, #11985 ) ; +#4265 = EDGE_CURVE ( 'NONE', #32727, #23839, #34694, .T. ) ; +#4266 = VERTEX_POINT ( 'NONE', #5546 ) ; +#4267 = CARTESIAN_POINT ( 'NONE', ( -43.29998184106858616, 127.8267059849638230, 94.32171495544167783 ) ) ; +#4268 = ADVANCED_FACE ( 'NONE', ( #11903 ), #33758, .T. ) ; +#4269 = ADVANCED_FACE ( 'NONE', ( #2882 ), #15366, .F. ) ; +#4270 = CARTESIAN_POINT ( 'NONE', ( -20.08022789467965552, 137.4838439665992667, 91.40569571491579381 ) ) ; +#4271 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #35996, #14155 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4272 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#4273 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564847 ) ) ; +#4274 = CARTESIAN_POINT ( 'NONE', ( -2.787442205325794120, 209.0946219730610380, 75.98264626556951384 ) ) ; +#4275 = CARTESIAN_POINT ( 'NONE', ( 38.52450977667000132, 119.0470807367999981, 87.58348493723001127 ) ) ; +#4276 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5691, #15687, #18945, #2636 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4277 = CARTESIAN_POINT ( 'NONE', ( -2.794087745591999905, 209.4352313944999935, 73.18598115729000142 ) ) ; +#4278 = CARTESIAN_POINT ( 'NONE', ( 38.17455783781999656, 118.9402821446000047, 90.39771198626000626 ) ) ; +#4279 = ORIENTED_EDGE ( 'NONE', *, *, #15643, .F. ) ; +#4280 = CARTESIAN_POINT ( 'NONE', ( -18.76885123896627050, 125.8224625306723112, 175.1047239809785765 ) ) ; +#4281 = VECTOR ( 'NONE', #22831, 1000.000000000000227 ) ; +#4282 = CARTESIAN_POINT ( 'NONE', ( -36.34570124670982949, 191.6079946775634824, 106.4159430361022913 ) ) ; +#4283 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 132.6352630048999970, 91.80276880046000088 ) ) ; +#4284 = VECTOR ( 'NONE', #33152, 1000.000000000000000 ) ; +#4286 = ORIENTED_EDGE ( 'NONE', *, *, #4027, .T. ) ; +#4285 = CARTESIAN_POINT ( 'NONE', ( 25.49934386937603392, 120.6644425437606287, 88.00825483662825377 ) ) ; +#4287 = AXIS2_PLACEMENT_3D ( 'NONE', #32259, #29393, #38983 ) ; +#4288 = ORIENTED_EDGE ( 'NONE', *, *, #25301, .T. ) ; +#4289 = EDGE_LOOP ( 'NONE', ( #38892, #29341, #27081, #29680 ) ) ; +#4290 = EDGE_CURVE ( 'NONE', #35055, #11987, #10837, .T. ) ; +#4291 = ORIENTED_EDGE ( 'NONE', *, *, #34002, .F. ) ; +#4292 = CARTESIAN_POINT ( 'NONE', ( -20.49970531959032627, 138.0793279501024813, 92.05657955141926152 ) ) ; +#4293 = VECTOR ( 'NONE', #16958, 1000.000000000000000 ) ; +#4294 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927789170785, -0.0005734119022072707138 ) ) ; +#4295 = ORIENTED_EDGE ( 'NONE', *, *, #17129, .F. ) ; +#4296 = VERTEX_POINT ( 'NONE', #18801 ) ; +#4297 = CARTESIAN_POINT ( 'NONE', ( 38.34044226084490248, 118.6974003961651789, 90.05067387323349237 ) ) ; +#4298 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971576505 ) ) ; +#4299 = CARTESIAN_POINT ( 'NONE', ( -38.27190134952000022, 118.9739902352999934, 87.58185624361999544 ) ) ; +#4300 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#4301 = CARTESIAN_POINT ( 'NONE', ( 8.622920946291438682, 209.7096369262764597, 76.05329660143564752 ) ) ; +#4302 = ORIENTED_EDGE ( 'NONE', *, *, #26089, .T. ) ; +#4303 = DIRECTION ( 'NONE', ( 0.1706442583057913853, 1.252691005673331343E-14, 0.9853327037641987918 ) ) ; +#4304 = EDGE_CURVE ( 'NONE', #17992, #28125, #12484, .T. ) ; +#4305 = ORIENTED_EDGE ( 'NONE', *, *, #27778, .F. ) ; +#4306 = DIRECTION ( 'NONE', ( 2.734944080625583540E-13, -0.9743700558967669512, -0.2249510928440471014 ) ) ; +#4307 = CARTESIAN_POINT ( 'NONE', ( -2.938441476483304005, 191.9759150222000130, 101.9232220854011928 ) ) ; +#4308 = FACE_OUTER_BOUND ( 'NONE', #39346, .T. ) ; +#4309 = CARTESIAN_POINT ( 'NONE', ( -39.76913700811847718, 164.9864764582079033, 182.8973725837718121 ) ) ; +#4310 = ORIENTED_EDGE ( 'NONE', *, *, #19504, .F. ) ; +#4311 = ADVANCED_FACE ( 'NONE', ( #418 ), #19417, .T. ) ; +#4312 = CARTESIAN_POINT ( 'NONE', ( 35.54494089926004108, 209.7096602146001487, 73.03703587511542139 ) ) ; +#4313 = CARTESIAN_POINT ( 'NONE', ( 19.99933118494021755, 196.5785306413737601, 103.8628508136982731 ) ) ; +#4314 = EDGE_CURVE ( 'NONE', #36902, #30574, #3275, .T. ) ; +#4315 = VECTOR ( 'NONE', #22065, 1000.000000000000114 ) ; +#4316 = ORIENTED_EDGE ( 'NONE', *, *, #6163, .T. ) ; +#4317 = CARTESIAN_POINT ( 'NONE', ( -20.16545193449732309, 118.1202296371234581, 90.11267470310258432 ) ) ; +#4318 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391911088 ) ) ; +#4319 = CIRCLE ( 'NONE', #385, 2.500000720456942105 ) ; +#4320 = EDGE_CURVE ( 'NONE', #39497, #15288, #25587, .T. ) ; +#4321 = ORIENTED_EDGE ( 'NONE', *, *, #29941, .T. ) ; +#4322 = CIRCLE ( 'NONE', #32413, 2.499999999386279370 ) ; +#4323 = EDGE_CURVE ( 'NONE', #23972, #15470, #12279, .T. ) ; +#4324 = CIRCLE ( 'NONE', #37010, 59.40509898897001051 ) ; +#4325 = ORIENTED_EDGE ( 'NONE', *, *, #2686, .T. ) ; +#4326 = DIRECTION ( 'NONE', ( 1.387778780764727741E-15, 0.9743700557921591843, 0.2249510932971534038 ) ) ; +#4327 = ORIENTED_EDGE ( 'NONE', *, *, #4551, .F. ) ; +#4328 = AXIS2_PLACEMENT_3D ( 'NONE', #30847, #8149, #14496 ) ; +#4329 = CARTESIAN_POINT ( 'NONE', ( -26.03994625616386571, 191.1138689880127117, 103.7907643604723802 ) ) ; +#4330 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673776705, 151.8594835319893548, 95.21744457848066645 ) ) ; +#4331 = CARTESIAN_POINT ( 'NONE', ( -19.99292196337442107, 118.8155724060715812, 94.27986157945176160 ) ) ; +#4332 = ORIENTED_EDGE ( 'NONE', *, *, #20062, .F. ) ; +#4333 = CARTESIAN_POINT ( 'NONE', ( 26.01047000073999982, 120.4380107313999986, 90.52133411668999941 ) ) ; +#4334 = CARTESIAN_POINT ( 'NONE', ( -16.53940709779629259, 123.0792221378318203, 172.1887768675690040 ) ) ; +#4336 = CARTESIAN_POINT ( 'NONE', ( -10.60967616682832926, 153.7228291392860626, 95.14904155532032348 ) ) ; +#4335 = DIRECTION ( 'NONE', ( -0.0004161288024547640796, 0.8480480897973101673, -0.5299191110235157431 ) ) ; +#4337 = VERTEX_POINT ( 'NONE', #34739 ) ; +#4338 = CARTESIAN_POINT ( 'NONE', ( -2.287398478804171909, 189.4306113881276588, 103.3878077086402385 ) ) ; +#4339 = AXIS2_PLACEMENT_3D ( 'NONE', #4580, #32990, #563 ) ; +#4340 = CARTESIAN_POINT ( 'NONE', ( -36.11017946864552641, 191.9687029343600102, 104.4208442067391189 ) ) ; +#4341 = CARTESIAN_POINT ( 'NONE', ( 42.33356330404532031, 170.6397506934769126, 189.3563035634615233 ) ) ; +#4342 = EDGE_LOOP ( 'NONE', ( #22975, #28649, #9937, #2324 ) ) ; +#4343 = AXIS2_PLACEMENT_3D ( 'NONE', #35355, #7362, #1233 ) ; +#4344 = AXIS2_PLACEMENT_3D ( 'NONE', #10200, #21857, #18966 ) ; +#4345 = ORIENTED_EDGE ( 'NONE', *, *, #22172, .F. ) ; +#4346 = DIRECTION ( 'NONE', ( 0.0005884949961224280940, -0.2249510543439061094, 0.9743698870671263501 ) ) ; +#4347 = DIRECTION ( 'NONE', ( 0.0005884949961204437871, -0.2249510543439066645, 0.9743698870671262391 ) ) ; +#4348 = CARTESIAN_POINT ( 'NONE', ( -44.95738950158257552, 124.6557125506502359, 91.20127123669165314 ) ) ; +#4349 = DIRECTION ( 'NONE', ( 0.6087614883550946931, -0.7730004026499607273, -0.1785492307423602321 ) ) ; +#4350 = EDGE_CURVE ( 'NONE', #11228, #30753, #6948, .T. ) ; +#4351 = CIRCLE ( 'NONE', #26593, 4.500000000438258319 ) ; +#4352 = ORIENTED_EDGE ( 'NONE', *, *, #33118, .F. ) ; +#4353 = EDGE_CURVE ( 'NONE', #16874, #6030, #21, .T. ) ; +#4354 = VERTEX_POINT ( 'NONE', #6741 ) ; +#4355 = EDGE_CURVE ( 'NONE', #30329, #31352, #1542, .T. ) ; +#4356 = CARTESIAN_POINT ( 'NONE', ( -23.36055974375966571, 134.8407614670647661, 93.36323390285753021 ) ) ; +#4357 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#4358 = VERTEX_POINT ( 'NONE', #6542 ) ; +#4359 = EDGE_CURVE ( 'NONE', #20666, #7827, #20018, .T. ) ; +#4360 = DIRECTION ( 'NONE', ( -9.251858538484500274E-15, -1.000000000000000000, 1.387778780772674962E-14 ) ) ; +#4361 = EDGE_CURVE ( 'NONE', #6068, #15877, #40071, .T. ) ; +#4362 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825886666129127, 0.0005734119031577724354 ) ) ; +#4363 = CARTESIAN_POINT ( 'NONE', ( 3.080804039577430320, 190.8472066119958868, 106.8075773176640837 ) ) ; +#4364 = ORIENTED_EDGE ( 'NONE', *, *, #3230, .F. ) ; +#4365 = CARTESIAN_POINT ( 'NONE', ( -30.07323508668966738, 135.0961509773328544, 91.10847914731613173 ) ) ; +#4366 = EDGE_CURVE ( 'NONE', #19459, #14180, #30507, .T. ) ; +#4367 = CARTESIAN_POINT ( 'NONE', ( -45.92960031148149369, 125.5172539323009886, 88.65860258904321256 ) ) ; +#4368 = LINE ( 'NONE', #39934, #9801 ) ; +#4369 = CARTESIAN_POINT ( 'NONE', ( 44.84982446188305261, 177.0778658525795493, 147.7896410935606184 ) ) ; +#4370 = VECTOR ( 'NONE', #21150, 999.9999999999998863 ) ; +#4371 = ORIENTED_EDGE ( 'NONE', *, *, #37374, .F. ) ; +#4372 = VERTEX_POINT ( 'NONE', #37634 ) ; +#4373 = CARTESIAN_POINT ( 'NONE', ( -24.53767847806265223, 116.1139939875861131, 87.78242264549591312 ) ) ; +#4374 = CARTESIAN_POINT ( 'NONE', ( 21.15131189037067827, 213.4625898340589742, 73.04572922002022040 ) ) ; +#4375 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31981, #34803, #25454, #6606 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4376 = AXIS2_PLACEMENT_3D ( 'NONE', #14465, #23871, #33245 ) ; +#4377 = CARTESIAN_POINT ( 'NONE', ( 20.80759478759580361, 212.3488673824964792, 75.54571959206188581 ) ) ; +#4378 = ADVANCED_FACE ( 'NONE', ( #13301 ), #19013, .F. ) ; +#4379 = CARTESIAN_POINT ( 'NONE', ( -42.11868374227395861, 189.5899118835476713, 106.5956137111014499 ) ) ; +#4380 = ORIENTED_EDGE ( 'NONE', *, *, #308, .T. ) ; +#4381 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971568733 ) ) ; +#4382 = CARTESIAN_POINT ( 'NONE', ( -35.56838832268000061, 112.3995020750000009, 90.16785085327001070 ) ) ; +#4383 = VERTEX_POINT ( 'NONE', #31503 ) ; +#4384 = CARTESIAN_POINT ( 'NONE', ( 3.062676760973492840, 191.1124749746149121, 103.7728652720017095 ) ) ; +#4385 = EDGE_LOOP ( 'NONE', ( #17630, #21125, #38299, #2953 ) ) ; +#4386 = CARTESIAN_POINT ( 'NONE', ( 0.5459373229760942081, 209.0000000000000000, 76.05817489712759993 ) ) ; +#4387 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490320223031, 156.2427122711505092, 96.23754757942438687 ) ) ; +#4388 = CARTESIAN_POINT ( 'NONE', ( 29.35339269389225336, 109.9231769193005448, 185.5806642568865357 ) ) ; +#4389 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971553745 ) ) ; +#4390 = ORIENTED_EDGE ( 'NONE', *, *, #15280, .F. ) ; +#4391 = VERTEX_POINT ( 'NONE', #35136 ) ; +#4392 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#4393 = ORIENTED_EDGE ( 'NONE', *, *, #26223, .T. ) ; +#4394 = ORIENTED_EDGE ( 'NONE', *, *, #29168, .F. ) ; +#4395 = CARTESIAN_POINT ( 'NONE', ( -6.036111313236179221, 177.3878382371900955, 100.9543767415334230 ) ) ; +#4396 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457974481995, -32.89481530046831637, 142.2936922234670760 ) ) ; +#4397 = CARTESIAN_POINT ( 'NONE', ( 19.48130215079870453, 124.7230702991837319, 177.6103480138636428 ) ) ; +#4398 = ADVANCED_FACE ( 'NONE', ( #32112 ), #4067, .T. ) ; +#4399 = VECTOR ( 'NONE', #5574, 1000.000000000000114 ) ; +#4400 = ORIENTED_EDGE ( 'NONE', *, *, #5210, .T. ) ; +#4401 = LINE ( 'NONE', #3593, #31105 ) ; +#4402 = EDGE_CURVE ( 'NONE', #15440, #1631, #25185, .T. ) ; +#4403 = DIRECTION ( 'NONE', ( 0.7933535320750287889, -0.5931614265262138419, -0.1369295264925107780 ) ) ; +#4404 = LINE ( 'NONE', #17063, #24813 ) ; +#4405 = CARTESIAN_POINT ( 'NONE', ( 36.33629891371000298, 191.7501006589000383, 104.2401080745000002 ) ) ; +#4406 = ADVANCED_FACE ( 'NONE', ( #16541 ), #35900, .F. ) ; +#4407 = DIRECTION ( 'NONE', ( 0.6087116037913345989, -0.7730376917437173923, -0.1785578633197842657 ) ) ; +#4408 = AXIS2_PLACEMENT_3D ( 'NONE', #1178, #35913, #29811 ) ; +#4409 = ORIENTED_EDGE ( 'NONE', *, *, #7125, .F. ) ; +#4410 = LINE ( 'NONE', #10369, #18619 ) ; +#4411 = CARTESIAN_POINT ( 'NONE', ( -23.35926900925013427, 176.8944240928315708, 103.2853824253334523 ) ) ; +#4412 = ORIENTED_EDGE ( 'NONE', *, *, #2496, .T. ) ; +#4413 = EDGE_CURVE ( 'NONE', #6773, #25855, #22010, .T. ) ; +#4414 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#4415 = CARTESIAN_POINT ( 'NONE', ( 16.29673443576292513, 122.7881700461012571, 174.3527752401433872 ) ) ; +#4416 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474989196751357, 155.7928101624825672, 98.18628735359796167 ) ) ; +#4417 = CARTESIAN_POINT ( 'NONE', ( -21.82845865523656315, 182.3067054805563316, 104.3206871860773504 ) ) ; +#4418 = ORIENTED_EDGE ( 'NONE', *, *, #24760, .F. ) ; +#4420 = ADVANCED_FACE ( 'NONE', ( #29645 ), #25280, .F. ) ; +#4419 = CARTESIAN_POINT ( 'NONE', ( -15.10714335811488773, 183.0966620568070198, 101.9332428217494027 ) ) ; +#4421 = CARTESIAN_POINT ( 'NONE', ( 0.7148223346852035087, 189.0057347121541795, 103.6850123720776367 ) ) ; +#4422 = CARTESIAN_POINT ( 'NONE', ( 14.35428732803441321, 191.5259372390380292, 103.8615007246684172 ) ) ; +#4423 = DIRECTION ( 'NONE', ( -0.0002393071182786160318, -0.2252352986010024705, 0.9743043687658494711 ) ) ; +#4424 = VERTEX_POINT ( 'NONE', #4477 ) ; +#4425 = CARTESIAN_POINT ( 'NONE', ( -25.36091826042000008, 191.5596352517000014, 104.5375569756999994 ) ) ; +#4426 = EDGE_CURVE ( 'NONE', #29005, #14963, #10244, .T. ) ; +#4427 = CARTESIAN_POINT ( 'NONE', ( 15.59065710782569703, 147.2783093503222460, 179.8436489142887922 ) ) ; +#4428 = CARTESIAN_POINT ( 'NONE', ( 26.14599041829999848, 192.0602195719000065, 103.7684055290999936 ) ) ; +#4429 = EDGE_CURVE ( 'NONE', #17707, #35463, #14160, .T. ) ; +#4430 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #31692, #581 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4431 = LINE ( 'NONE', #19757, #29125 ) ; +#4432 = ORIENTED_EDGE ( 'NONE', *, *, #2034, .F. ) ; +#4433 = CARTESIAN_POINT ( 'NONE', ( -42.86870032173014522, 121.2410338499262537, 90.70283413665809746 ) ) ; +#4434 = AXIS2_PLACEMENT_3D ( 'NONE', #24567, #30892, #9016 ) ; +#4435 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29945, #32991, #33608, #11957 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.003684369078374031495, 0.004391610992028501664 ), + .UNSPECIFIED. ) ; +#4436 = AXIS2_PLACEMENT_3D ( 'NONE', #4997, #24447, #39746 ) ; +#4437 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 103.5647597712388261, 168.7177032462348620 ) ) ; +#4438 = ORIENTED_EDGE ( 'NONE', *, *, #35483, .T. ) ; +#4439 = CARTESIAN_POINT ( 'NONE', ( -38.04444379205944671, 118.4867705051282627, 87.71485106921780073 ) ) ; +#4440 = CARTESIAN_POINT ( 'NONE', ( -4.037441716908935163, 137.2418790766312782, 91.85329641515465937 ) ) ; +#4441 = CARTESIAN_POINT ( 'NONE', ( 37.85090698586000002, 191.1231049499999983, 106.1818745881000154 ) ) ; +#4442 = CARTESIAN_POINT ( 'NONE', ( 36.08395475670999986, 192.1923109830999863, 104.3567733717000010 ) ) ; +#4443 = CARTESIAN_POINT ( 'NONE', ( -16.52323579073919646, 152.1899771268108452, 181.4476381748975768 ) ) ; +#4444 = CARTESIAN_POINT ( 'NONE', ( 13.50189226125813846, 187.9430574696029907, 103.3793715338758972 ) ) ; +#4445 = EDGE_LOOP ( 'NONE', ( #20342, #20335, #2484, #38003, #14410, #25276, #18791, #16038 ) ) ; +#4446 = ORIENTED_EDGE ( 'NONE', *, *, #19041, .F. ) ; +#4447 = LINE ( 'NONE', #38588, #8859 ) ; +#4448 = CARTESIAN_POINT ( 'NONE', ( 35.81039908593225363, 115.0592316559111765, 87.24615570831635125 ) ) ; +#4449 = EDGE_LOOP ( 'NONE', ( #1491, #27730, #29795, #18220 ) ) ; +#4450 = DIRECTION ( 'NONE', ( -0.7075059890727370959, -1.651605043716707640E-15, -0.7067073477941262505 ) ) ; +#4451 = ADVANCED_FACE ( 'NONE', ( #32311 ), #28541, .F. ) ; +#4452 = CARTESIAN_POINT ( 'NONE', ( -45.01366707977943094, 130.2508973098130411, 92.82981015662352320 ) ) ; +#4453 = EDGE_CURVE ( 'NONE', #4711, #1188, #15254, .T. ) ; +#4454 = ORIENTED_EDGE ( 'NONE', *, *, #19388, .F. ) ; +#4455 = CARTESIAN_POINT ( 'NONE', ( 20.00013814902157350, 147.4939005714190046, 93.69263431585608259 ) ) ; +#4456 = ORIENTED_EDGE ( 'NONE', *, *, #12135, .T. ) ; +#4457 = LINE ( 'NONE', #2019, #35313 ) ; +#4458 = AXIS2_PLACEMENT_3D ( 'NONE', #11490, #23975, #36430 ) ; +#4459 = CARTESIAN_POINT ( 'NONE', ( -12.63649281425979254, 129.9703308616587947, 92.23232912629561042 ) ) ; +#4460 = CARTESIAN_POINT ( 'NONE', ( 23.36190162741788967, 177.7945445883550519, 100.6858769593398080 ) ) ; +#4461 = CARTESIAN_POINT ( 'NONE', ( 39.72744443561925465, 107.0407409438602855, 185.0027117538028278 ) ) ; +#4462 = ORIENTED_EDGE ( 'NONE', *, *, #29773, .F. ) ; +#4463 = FACE_OUTER_BOUND ( 'NONE', #8606, .T. ) ; +#4464 = CARTESIAN_POINT ( 'NONE', ( -30.07171558059459215, 177.1876876956736169, 101.0912387261568028 ) ) ; +#4465 = CARTESIAN_POINT ( 'NONE', ( -14.99989747112629068, 176.2176057258887454, 100.5160767531280328 ) ) ; +#4466 = ORIENTED_EDGE ( 'NONE', *, *, #7136, .F. ) ; +#4467 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #15857, #517 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4468 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#4469 = ORIENTED_EDGE ( 'NONE', *, *, #27304, .T. ) ; +#4470 = CARTESIAN_POINT ( 'NONE', ( 25.51935971830618399, 191.1026097824055796, 106.3227842531489671 ) ) ; +#4471 = CARTESIAN_POINT ( 'NONE', ( 4.404236726960877313, 130.7136275758185491, 89.82787981506024266 ) ) ; +#4472 = EDGE_CURVE ( 'NONE', #32173, #26941, #32706, .T. ) ; +#4473 = CARTESIAN_POINT ( 'NONE', ( 36.71352342385499412, 115.7387982162421025, 89.70104857119935104 ) ) ; +#4474 = CARTESIAN_POINT ( 'NONE', ( 1.447658035600616788, 152.0519508786576353, 130.6788418761141486 ) ) ; +#4475 = CARTESIAN_POINT ( 'NONE', ( 15.50147166558119594, 185.3474886484798390, 105.0001610792874942 ) ) ; +#4476 = CARTESIAN_POINT ( 'NONE', ( -25.99272572791733182, 191.9759150222000130, 101.9371462953202609 ) ) ; +#4477 = CARTESIAN_POINT ( 'NONE', ( 21.83022404666562366, 176.4985800024501259, 100.9007981789296053 ) ) ; +#4478 = AXIS2_PLACEMENT_3D ( 'NONE', #3298, #21732, #21329 ) ; +#4479 = CARTESIAN_POINT ( 'NONE', ( 38.29551853473000733, 119.2077387477000059, 87.35949975440999538 ) ) ; +#4480 = CARTESIAN_POINT ( 'NONE', ( 39.06524929025407999, 190.3639766107277751, 106.6572273908310677 ) ) ; +#4481 = CARTESIAN_POINT ( 'NONE', ( 38.48852289050999786, 118.5536772429999957, 89.80770094992000452 ) ) ; +#4482 = ORIENTED_EDGE ( 'NONE', *, *, #34053, .T. ) ; +#4483 = ADVANCED_FACE ( 'NONE', ( #29037 ), #13500, .F. ) ; +#4484 = CARTESIAN_POINT ( 'NONE', ( 40.67360545558243956, 184.2591260079552740, 105.2468408042174275 ) ) ; +#4485 = AXIS2_PLACEMENT_3D ( 'NONE', #38418, #22701, #16145 ) ; +#4486 = CARTESIAN_POINT ( 'NONE', ( 29.17699550212986637, 209.7096486318000075, 76.04088245540252444 ) ) ; +#4487 = CYLINDRICAL_SURFACE ( 'NONE', #724, 5.249999999999986677 ) ; +#4488 = AXIS2_PLACEMENT_3D ( 'NONE', #38285, #22766, #16006 ) ; +#4489 = VECTOR ( 'NONE', #20515, 999.9999999999998863 ) ; +#4490 = LINE ( 'NONE', #13909, #34944 ) ; +#4491 = ORIENTED_EDGE ( 'NONE', *, *, #17129, .T. ) ; +#4492 = ORIENTED_EDGE ( 'NONE', *, *, #37377, .T. ) ; +#4493 = ORIENTED_EDGE ( 'NONE', *, *, #31850, .F. ) ; +#4494 = CARTESIAN_POINT ( 'NONE', ( 26.03373140117899709, 191.5260202047026041, 103.8544635878054976 ) ) ; +#4495 = CARTESIAN_POINT ( 'NONE', ( -2.533214444037978907, 209.6150328728459442, 73.39336733046577876 ) ) ; +#4496 = DIRECTION ( 'NONE', ( 0.6087614810001754639, -0.7729390313185934280, -0.1788147452386056602 ) ) ; +#4497 = EDGE_CURVE ( 'NONE', #28807, #3459, #19570, .T. ) ; +#4498 = ORIENTED_EDGE ( 'NONE', *, *, #8836, .F. ) ; +#4499 = EDGE_CURVE ( 'NONE', #3242, #27979, #26918, .T. ) ; +#4500 = ORIENTED_EDGE ( 'NONE', *, *, #33577, .F. ) ; +#4501 = CARTESIAN_POINT ( 'NONE', ( 38.22623376675434059, 118.8155667128057615, 90.24469678293085906 ) ) ; +#4502 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#4503 = CARTESIAN_POINT ( 'NONE', ( -38.39793200855000066, 118.8574776149000058, 87.72185305345000472 ) ) ; +#4504 = CARTESIAN_POINT ( 'NONE', ( -35.92375300345999989, 114.4806295604000042, 87.65586600601000100 ) ) ; +#4505 = ORIENTED_EDGE ( 'NONE', *, *, #16051, .T. ) ; +#4506 = EDGE_CURVE ( 'NONE', #34607, #726, #27355, .T. ) ; +#4507 = CYLINDRICAL_SURFACE ( 'NONE', #21898, 48.00000000000002132 ) ; +#4508 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#4509 = DIRECTION ( 'NONE', ( 0.6087613186456907188, -0.7729176985478710682, -0.1789074850089337476 ) ) ; +#4510 = CARTESIAN_POINT ( 'NONE', ( -12.63718560774618105, 181.5628715657541079, 104.1854011749896216 ) ) ; +#4511 = ORIENTED_EDGE ( 'NONE', *, *, #27801, .T. ) ; +#4512 = CARTESIAN_POINT ( 'NONE', ( -0.6019272315500000525, 188.9987428910999938, 103.6847776933999938 ) ) ; +#4513 = LINE ( 'NONE', #7383, #17920 ) ; +#4514 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#4515 = CONICAL_SURFACE ( 'NONE', #16906, 2.502999999899097716, 0.7853981634646929333 ) ; +#4516 = VECTOR ( 'NONE', #29498, 999.9999999999998863 ) ; +#4517 = ORIENTED_EDGE ( 'NONE', *, *, #3230, .T. ) ; +#4518 = CARTESIAN_POINT ( 'NONE', ( -2.421663575686999970, 209.3771755197000175, 75.56751031131001639 ) ) ; +#4519 = CARTESIAN_POINT ( 'NONE', ( 19.98271455780751538, 210.1680415111135574, 76.04531988083382998 ) ) ; +#4520 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28746, #22626, #35050, #6857, #1125, #7057, #31828, #32023, #729, #3982, #19915, #28552, #25294, #37736, #16066, #19332, #9748 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999954481, 0.1874999999999938938, 0.2499999999999923395, 0.3749999999999933387, 0.4999999999999943379, 0.6249999999999953371, 0.7499999999999963363, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4521 = ORIENTED_EDGE ( 'NONE', *, *, #17086, .F. ) ; +#4522 = VECTOR ( 'NONE', #3729, 1000.000000000000114 ) ; +#4523 = VERTEX_POINT ( 'NONE', #17145 ) ; +#4524 = ORIENTED_EDGE ( 'NONE', *, *, #33158, .F. ) ; +#4525 = DIRECTION ( 'NONE', ( 5.741067343745209959E-12, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#4526 = FACE_OUTER_BOUND ( 'NONE', #28474, .T. ) ; +#4527 = ORIENTED_EDGE ( 'NONE', *, *, #32169, .F. ) ; +#4528 = LINE ( 'NONE', #10898, #19927 ) ; +#4529 = ORIENTED_EDGE ( 'NONE', *, *, #26306, .F. ) ; +#4530 = EDGE_CURVE ( 'NONE', #29413, #27492, #8789, .T. ) ; +#4531 = CARTESIAN_POINT ( 'NONE', ( 25.50082892276000024, 120.2986139677999944, 89.97792380045000016 ) ) ; +#4532 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #25498, #13018 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4533 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384972194 ) ) ; +#4535 = CARTESIAN_POINT ( 'NONE', ( -11.62476157916481512, 154.1189553150826725, 95.24110759181746744 ) ) ; +#4534 = CARTESIAN_POINT ( 'NONE', ( 20.48167212851781827, 208.5384972688564176, 75.82337149459281989 ) ) ; +#4536 = AXIS2_PLACEMENT_3D ( 'NONE', #7582, #38651, #16972 ) ; +#4537 = EDGE_CURVE ( 'NONE', #3655, #7336, #21257, .T. ) ; +#4538 = CIRCLE ( 'NONE', #15010, 7.499999999921035609 ) ; +#4539 = EDGE_LOOP ( 'NONE', ( #32447, #38436, #21477, #14127 ) ) ; +#4540 = VECTOR ( 'NONE', #9474, 1000.000000000000114 ) ; +#4541 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930882562 ) ) ; +#4542 = AXIS2_PLACEMENT_3D ( 'NONE', #23594, #26271, #4569 ) ; +#4543 = CARTESIAN_POINT ( 'NONE', ( -8.191411997281301538, 151.3128155192395354, 94.76223611369431410 ) ) ; +#4544 = EDGE_CURVE ( 'NONE', #10087, #30803, #30054, .T. ) ; +#4545 = EDGE_CURVE ( 'NONE', #7229, #34227, #12391, .T. ) ; +#4546 = VECTOR ( 'NONE', #24985, 999.9999999999998863 ) ; +#4547 = EDGE_LOOP ( 'NONE', ( #35614, #28333, #29158 ) ) ; +#4549 = ADVANCED_FACE ( 'NONE', ( #33503 ), #5711, .T. ) ; +#4548 = CARTESIAN_POINT ( 'NONE', ( 38.73814783011000173, 119.0754946943000050, 90.11438996249999889 ) ) ; +#4550 = CARTESIAN_POINT ( 'NONE', ( -36.73985734004195791, 117.5510141980808072, 87.28997424524052917 ) ) ; +#4551 = EDGE_CURVE ( 'NONE', #22040, #33315, #39127, .T. ) ; +#4552 = LINE ( 'NONE', #22586, #14830 ) ; +#4553 = FACE_OUTER_BOUND ( 'NONE', #29748, .T. ) ; +#4554 = CARTESIAN_POINT ( 'NONE', ( 36.32029408017999828, 191.7179464608000217, 104.1934018853000055 ) ) ; +#4555 = EDGE_LOOP ( 'NONE', ( #37973, #19035, #30475, #11294 ) ) ; +#4556 = ORIENTED_EDGE ( 'NONE', *, *, #16534, .F. ) ; +#4557 = CARTESIAN_POINT ( 'NONE', ( -12.63686179124978892, 177.3887316568832659, 100.9570573941570473 ) ) ; +#4558 = CARTESIAN_POINT ( 'NONE', ( 15.89469151744206421, 147.4449134593691610, 177.3586166299334650 ) ) ; +#4559 = EDGE_LOOP ( 'NONE', ( #9659, #25662, #38768, #1875, #32378, #37292, #37581, #10521, #4991, #31295 ) ) ; +#4560 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #31919, #10246, #818, #25985 ), + ( #7345, #32314, #25590, #34740 ), + ( #614, #13302, #28639, #19210 ), + ( #1015, #4277, #3467, #22316 ), + ( #10032, #22110, #419, #4070 ), + ( #10446, #16542, #25788, #25379 ), + ( #16751, #214, #38235, #19420 ), + ( #31504, #38428, #22714, #12695 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.1683202481699999919, 0.000000000000000000, 0.3333334569363999855, 0.6666668616933999481, 1.000000000000000000, 1.164202491116000049 ), + ( -3.140553228863999869E-07, 0.9999999710371000328 ), + .UNSPECIFIED. ) ; +#4561 = CARTESIAN_POINT ( 'NONE', ( -35.43083629604420537, 192.6084089038419904, 106.9106422785019959 ) ) ; +#4562 = CARTESIAN_POINT ( 'NONE', ( -39.42815928026088557, 120.3902238028007616, 87.47100753998802247 ) ) ; +#4563 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#4564 = ORIENTED_EDGE ( 'NONE', *, *, #9036, .F. ) ; +#4565 = CYLINDRICAL_SURFACE ( 'NONE', #1389, 4.999999999999994671 ) ; +#4566 = AXIS2_PLACEMENT_3D ( 'NONE', #21644, #40219, #21840 ) ; +#4567 = ADVANCED_FACE ( 'NONE', ( #2245 ), #35675, .F. ) ; +#4568 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#4569 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825889831406412, 0.0005734119030863655793 ) ) ; +#4570 = CARTESIAN_POINT ( 'NONE', ( -5.960622339528989677, 163.5635530557085247, 97.41814418763185301 ) ) ; +#4571 = AXIS2_PLACEMENT_3D ( 'NONE', #6649, #3784, #34847 ) ; +#4572 = ORIENTED_EDGE ( 'NONE', *, *, #29672, .F. ) ; +#4573 = AXIS2_PLACEMENT_3D ( 'NONE', #22055, #3224, #40234 ) ; +#4574 = CARTESIAN_POINT ( 'NONE', ( -25.50129508846853099, 118.1132512059233335, 87.78307593003776788 ) ) ; +#4575 = CARTESIAN_POINT ( 'NONE', ( -15.49823494792000034, 157.9289540101000284, 99.20196762495000087 ) ) ; +#4576 = CARTESIAN_POINT ( 'NONE', ( -12.63809828823728232, 131.0198806733800438, 89.90888323108799796 ) ) ; +#4577 = VERTEX_POINT ( 'NONE', #40238 ) ; +#4578 = ADVANCED_FACE ( 'NONE', ( #24123 ), #27613, .F. ) ; +#4579 = DIRECTION ( 'NONE', ( 0.2808154964431652245, -1.219838484668546832E-14, -0.9597617709397361363 ) ) ; +#4581 = CARTESIAN_POINT ( 'NONE', ( -37.93206066660999909, 118.8229955981000074, 90.44873202908000565 ) ) ; +#4580 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250093319, 179.6252109630997893, 101.6466942237284456 ) ) ; +#4583 = EDGE_LOOP ( 'NONE', ( #4900, #11547, #37783, #19485 ) ) ; +#4582 = EDGE_CURVE ( 'NONE', #8036, #7563, #24336, .T. ) ; +#4584 = VERTEX_POINT ( 'NONE', #30661 ) ; +#4585 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#4586 = EDGE_CURVE ( 'NONE', #17427, #15772, #27812, .T. ) ; +#4587 = CARTESIAN_POINT ( 'NONE', ( -12.63810005728112529, 131.0234914809575741, 89.90663177300498887 ) ) ; +#4588 = DIRECTION ( 'NONE', ( -0.0006039748319392047697, 6.984862132708257173E-19, -0.9999998176071845934 ) ) ; +#4589 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218858604, 82.27946979429611929, 297.5295786860745579 ) ) ; +#4590 = DIRECTION ( 'NONE', ( -0.0005884949961138158424, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#4591 = ORIENTED_EDGE ( 'NONE', *, *, #4129, .F. ) ; +#4592 = ORIENTED_EDGE ( 'NONE', *, *, #7931, .T. ) ; +#4593 = CARTESIAN_POINT ( 'NONE', ( -5.023244955357182739, 181.7489884665435511, 101.6160173790793664 ) ) ; +#4594 = VERTEX_POINT ( 'NONE', #2660 ) ; +#4595 = EDGE_LOOP ( 'NONE', ( #2154, #14283, #6161, #18251 ) ) ; +#4597 = EDGE_CURVE ( 'NONE', #12222, #22101, #23624, .T. ) ; +#4596 = CARTESIAN_POINT ( 'NONE', ( -25.99976593112455348, 118.8155677978001705, 90.28348901843737906 ) ) ; +#4599 = VECTOR ( 'NONE', #22797, 1000.000000000000114 ) ; +#4598 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265225566, -0.1368326740407719011 ) ) ; +#4600 = CARTESIAN_POINT ( 'NONE', ( 2.538357414086000130, 209.1910662834000050, 73.57953838714999506 ) ) ; +#4601 = ORIENTED_EDGE ( 'NONE', *, *, #8292, .F. ) ; +#4602 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21526, #2506, #39489, #27663 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4603 = CIRCLE ( 'NONE', #12440, 4.500000000381400689 ) ; +#4604 = EDGE_LOOP ( 'NONE', ( #33445, #38098, #5649, #26664 ) ) ; +#4605 = LINE ( 'NONE', #27124, #18663 ) ; +#4606 = VECTOR ( 'NONE', #15142, 1000.000000000000227 ) ; +#4607 = CARTESIAN_POINT ( 'NONE', ( -15.49852918272448576, 137.6306203012457843, 94.00257521259531757 ) ) ; +#4608 = CARTESIAN_POINT ( 'NONE', ( 38.07634149388000111, 118.5735798831999972, 87.56817451646001871 ) ) ; +#4609 = CARTESIAN_POINT ( 'NONE', ( 25.50067444836711772, 120.1830342791591733, 89.91912185905974297 ) ) ; +#4610 = CARTESIAN_POINT ( 'NONE', ( 2.945216860577655638, 209.7036681624458083, 76.05698929380193363 ) ) ; +#4611 = ORIENTED_EDGE ( 'NONE', *, *, #8001, .F. ) ; +#4612 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265228896, 0.1368326740407718456 ) ) ; +#4613 = FACE_OUTER_BOUND ( 'NONE', #7396, .T. ) ; +#4614 = EDGE_LOOP ( 'NONE', ( #23557, #6512, #5327, #22758 ) ) ; +#4615 = CARTESIAN_POINT ( 'NONE', ( 0.6034525440803617524, 188.6132189102335985, 103.1973517498306450 ) ) ; +#4616 = CARTESIAN_POINT ( 'NONE', ( 16.14434960484450343, 151.5098951869006783, 180.2135683096318246 ) ) ; +#4617 = CARTESIAN_POINT ( 'NONE', ( 20.49930103516235746, 196.1188360154283430, 103.6658478038365558 ) ) ; +#4618 = CARTESIAN_POINT ( 'NONE', ( 46.07705293508445266, 185.2595815743947014, 105.4745506663921475 ) ) ; +#4619 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #4904, #17360, #10657, #17162 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.994645287853319182, 6.088140294281147114 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9028133655217900344, 0.9028133655217900344, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#4620 = ORIENTED_EDGE ( 'NONE', *, *, #15228, .T. ) ; +#4621 = LINE ( 'NONE', #35889, #19368 ) ; +#4622 = DIRECTION ( 'NONE', ( 0.9808256175858699466, 0.000000000000000000, -0.1948874236252736147 ) ) ; +#4623 = PLANE ( 'NONE', #2591 ) ; +#4624 = VERTEX_POINT ( 'NONE', #36385 ) ; +#4625 = FACE_OUTER_BOUND ( 'NONE', #26882, .T. ) ; +#4626 = ORIENTED_EDGE ( 'NONE', *, *, #18612, .T. ) ; +#4627 = CARTESIAN_POINT ( 'NONE', ( -25.61315145657999892, 191.8113400482999964, 104.3089204063000039 ) ) ; +#4628 = DIRECTION ( 'NONE', ( -0.6087613186456907188, -0.7730177010543248795, -0.1784749023741044327 ) ) ; +#4629 = CARTESIAN_POINT ( 'NONE', ( -24.27915398407497705, 213.2748068212543444, 73.57307564708263214 ) ) ; +#4630 = CIRCLE ( 'NONE', #13146, 2.250000000041454840 ) ; +#4631 = CONICAL_SURFACE ( 'NONE', #24251, 2.503164102235868604, 0.7853981633414612862 ) ; +#4632 = CARTESIAN_POINT ( 'NONE', ( -37.54329503931378298, 86.59195937703771051, 280.9751938861189728 ) ) ; +#4633 = EDGE_CURVE ( 'NONE', #34336, #33189, #29370, .T. ) ; +#4634 = VERTEX_POINT ( 'NONE', #8382 ) ; +#4635 = CONICAL_SURFACE ( 'NONE', #22291, 2.502999999978117618, 0.7853981634080025032 ) ; +#4636 = CARTESIAN_POINT ( 'NONE', ( -14.99833314732373246, 182.5837072631661613, 104.7226143053096052 ) ) ; +#4637 = EDGE_CURVE ( 'NONE', #14862, #37986, #20592, .T. ) ; +#4638 = CONICAL_SURFACE ( 'NONE', #29458, 4.999996804348348256, 0.7853981633997131340 ) ; +#4639 = EDGE_CURVE ( 'NONE', #19409, #9106, #1079, .T. ) ; +#4640 = CARTESIAN_POINT ( 'NONE', ( -20.00000588364686038, 174.5066637885302896, 99.95304239614711150 ) ) ; +#4641 = LINE ( 'NONE', #14467, #19072 ) ; +#4642 = FACE_OUTER_BOUND ( 'NONE', #137, .T. ) ; +#4643 = CARTESIAN_POINT ( 'NONE', ( 5.664743062628560644, 181.1015080686150895, 104.4647125381774941 ) ) ; +#4644 = CARTESIAN_POINT ( 'NONE', ( 37.82160095445000536, 190.5065482114999895, 106.5662966441000208 ) ) ; +#4645 = CARTESIAN_POINT ( 'NONE', ( 31.07270177211735174, 177.5903766379979629, 100.6341249661810906 ) ) ; +#4646 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474989203096108, 155.7928101624825956, 98.18628735359794746 ) ) ; +#4647 = PLANE ( 'NONE', #12545 ) ; +#4648 = CARTESIAN_POINT ( 'NONE', ( -38.36244646033240002, 118.8225362708849389, 87.71978071755118833 ) ) ; +#4649 = ORIENTED_EDGE ( 'NONE', *, *, #9461, .F. ) ; +#4651 = EDGE_CURVE ( 'NONE', #9324, #37873, #32446, .T. ) ; +#4650 = CARTESIAN_POINT ( 'NONE', ( -5.668553076709809346, 181.6128662714581310, 104.1507415746884391 ) ) ; +#4652 = PLANE ( 'NONE', #13230 ) ; +#4653 = CARTESIAN_POINT ( 'NONE', ( 37.35926580955523946, 118.3178168644534196, 87.24522023162664652 ) ) ; +#4654 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501101346, 129.6135529957512063, 92.66635095646515197 ) ) ; +#4655 = ORIENTED_EDGE ( 'NONE', *, *, #9943, .T. ) ; +#4656 = LINE ( 'NONE', #10217, #33096 ) ; +#4657 = CARTESIAN_POINT ( 'NONE', ( 3.780283637447459100, 136.7368630678065529, 94.04685604330656190 ) ) ; +#4658 = VECTOR ( 'NONE', #34180, 1000.000000000000114 ) ; +#4659 = ORIENTED_EDGE ( 'NONE', *, *, #34319, .T. ) ; +#4660 = EDGE_CURVE ( 'NONE', #39586, #13672, #448, .T. ) ; +#4661 = CIRCLE ( 'NONE', #30777, 6.000000000000001776 ) ; +#4662 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394469186868, 3.303562273565746580E-12, 297.5584364845187224 ) ) ; +#4663 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748615030, 134.6026445760790295, 93.28327864748658271 ) ) ; +#4664 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825940274355384, 0.0005734119019191435528 ) ) ; +#4665 = EDGE_LOOP ( 'NONE', ( #36301, #1335, #30452, #34959 ) ) ; +#4666 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825940409482753, 0.0005734119019167828110 ) ) ; +#4667 = CARTESIAN_POINT ( 'NONE', ( 3.608059120702661104, 167.8427776935849636, 101.4051864878073559 ) ) ; +#4668 = CYLINDRICAL_SURFACE ( 'NONE', #27965, 4.999999999999990230 ) ; +#4669 = CARTESIAN_POINT ( 'NONE', ( 21.25891437287570440, 136.8714408223384567, 91.75249562560091476 ) ) ; +#4670 = CARTESIAN_POINT ( 'NONE', ( 15.75161875086000052, 184.8197207970999898, 105.1347412410000004 ) ) ; +#4671 = VERTEX_POINT ( 'NONE', #34695 ) ; +#4672 = CARTESIAN_POINT ( 'NONE', ( 16.56077817173662936, 151.9932236380383586, 182.4670194890501875 ) ) ; +#4673 = CARTESIAN_POINT ( 'NONE', ( 12.63727515886041175, 181.9878585597662948, 102.0677450848580463 ) ) ; +#4674 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; +#4675 = ORIENTED_EDGE ( 'NONE', *, *, #32407, .F. ) ; +#4676 = CYLINDRICAL_SURFACE ( 'NONE', #38623, 2.000000000000001332 ) ; +#4677 = ORIENTED_EDGE ( 'NONE', *, *, #5684, .T. ) ; +#4678 = CYLINDRICAL_SURFACE ( 'NONE', #27073, 1.999999999999999112 ) ; +#4679 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #16926, #599 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4680 = FACE_OUTER_BOUND ( 'NONE', #40139, .T. ) ; +#4681 = CARTESIAN_POINT ( 'NONE', ( -30.06407784565124430, 177.7873364699197793, 100.7165267053679969 ) ) ; +#4682 = CARTESIAN_POINT ( 'NONE', ( -19.28424117596089715, 124.3280322740279189, 178.4026130020181427 ) ) ; +#4683 = ADVANCED_FACE ( 'NONE', ( #28203 ), #31993, .F. ) ; +#4684 = AXIS2_PLACEMENT_3D ( 'NONE', #24970, #12085, #9019 ) ; +#4685 = EDGE_CURVE ( 'NONE', #8959, #25850, #7400, .T. ) ; +#4686 = CARTESIAN_POINT ( 'NONE', ( 18.98784741603935089, 148.4369364876176292, 183.7046361175107450 ) ) ; +#4687 = AXIS2_PLACEMENT_3D ( 'NONE', #20364, #26524, #32840 ) ; +#4688 = CARTESIAN_POINT ( 'NONE', ( -13.49823352275769395, 126.1251030033876361, 91.86135017785642276 ) ) ; +#4689 = AXIS2_PLACEMENT_3D ( 'NONE', #3178, #2794, #34250 ) ; +#4690 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#4691 = DIRECTION ( 'NONE', ( 0.0006039748319385316970, 1.156831349449291921E-15, 0.9999998176071845934 ) ) ; +#4692 = CARTESIAN_POINT ( 'NONE', ( 20.50147102596341853, 119.8278772368997380, 89.87074405082867656 ) ) ; +#4693 = ORIENTED_EDGE ( 'NONE', *, *, #39082, .F. ) ; +#4694 = CARTESIAN_POINT ( 'NONE', ( 3.499881480001497458, 128.5116462485979696, 89.66216756041531255 ) ) ; +#4695 = CARTESIAN_POINT ( 'NONE', ( -0.02805196447938418727, 127.1761617620222893, 297.5585619722723436 ) ) ; +#4696 = CARTESIAN_POINT ( 'NONE', ( -25.86970796406206574, 117.9463803759205405, 170.9998979181758614 ) ) ; +#4697 = FACE_OUTER_BOUND ( 'NONE', #24415, .T. ) ; +#4698 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8212, #16980, #23543, #1669 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 2.414395626052624255, 2.591408619140276759 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973905707491301786, 0.9973905707491301786, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#4699 = DIRECTION ( 'NONE', ( -0.6087611427445811518, -0.7731004622513006908, -0.1781166650011639374 ) ) ; +#4700 = ORIENTED_EDGE ( 'NONE', *, *, #10844, .T. ) ; +#4701 = ORIENTED_EDGE ( 'NONE', *, *, #8546, .T. ) ; +#4702 = ORIENTED_EDGE ( 'NONE', *, *, #28163, .F. ) ; +#4703 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971561239 ) ) ; +#4704 = CARTESIAN_POINT ( 'NONE', ( 15.83331839798551499, 138.4673770510489135, 91.78223853853539538 ) ) ; +#4705 = ORIENTED_EDGE ( 'NONE', *, *, #40044, .T. ) ; +#4706 = CARTESIAN_POINT ( 'NONE', ( -14.55129768904543930, 135.1122403316443581, 93.93374132341575944 ) ) ; +#4707 = EDGE_CURVE ( 'NONE', #24392, #26636, #5457, .T. ) ; +#4708 = CARTESIAN_POINT ( 'NONE', ( -13.49659569010611548, 187.5255899304984553, 105.8396958350310939 ) ) ; +#4709 = DIRECTION ( 'NONE', ( -0.0005884949961240770570, 0.2255194585872583313, -0.9742384859325510238 ) ) ; +#4710 = CARTESIAN_POINT ( 'NONE', ( -19.15235677364794142, 125.6631553015295992, 176.1837327014617358 ) ) ; +#4711 = VERTEX_POINT ( 'NONE', #28595 ) ; +#4712 = CARTESIAN_POINT ( 'NONE', ( -76.10866181110002060, 156.0153766034999876, 97.25733412651000265 ) ) ; +#4713 = ORIENTED_EDGE ( 'NONE', *, *, #4039, .F. ) ; +#4714 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858958, 183.1686750955933576, 104.5300206044594091 ) ) ; +#4715 = AXIS2_PLACEMENT_3D ( 'NONE', #31285, #34335, #28036 ) ; +#4716 = CARTESIAN_POINT ( 'NONE', ( 5.669295872926322311, 130.1822457206637296, 92.55708892453651515 ) ) ; +#4717 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384972194 ) ) ; +#4718 = CYLINDRICAL_SURFACE ( 'NONE', #28864, 6.000000000000008882 ) ; +#4719 = AXIS2_PLACEMENT_3D ( 'NONE', #12505, #30734, #27884 ) ; +#4720 = ORIENTED_EDGE ( 'NONE', *, *, #37380, .T. ) ; +#4721 = CARTESIAN_POINT ( 'NONE', ( -19.70071604027683065, 149.4445624503525778, 181.7665744593643637 ) ) ; +#4722 = VECTOR ( 'NONE', #26344, 1000.000000000000227 ) ; +#4723 = LINE ( 'NONE', #13139, #19202 ) ; +#4724 = CARTESIAN_POINT ( 'NONE', ( 28.46875780327905403, 130.1006733151145909, 92.40864205061642167 ) ) ; +#4725 = CARTESIAN_POINT ( 'NONE', ( 26.07306197714198248, 120.9961311236103541, 90.65024403513507423 ) ) ; +#4726 = EDGE_LOOP ( 'NONE', ( #39149, #865 ) ) ; +#4727 = ORIENTED_EDGE ( 'NONE', *, *, #16050, .F. ) ; +#4728 = CARTESIAN_POINT ( 'NONE', ( -20.33367336965308780, 118.1180462047051947, 87.61411334273522300 ) ) ; +#4729 = CARTESIAN_POINT ( 'NONE', ( -34.95638760651608834, 217.7719116314000019, 73.57961695566839921 ) ) ; +#4730 = ORIENTED_EDGE ( 'NONE', *, *, #12578, .T. ) ; +#4731 = VERTEX_POINT ( 'NONE', #22062 ) ; +#4732 = ORIENTED_EDGE ( 'NONE', *, *, #19926, .T. ) ; +#4733 = ORIENTED_EDGE ( 'NONE', *, *, #15698, .F. ) ; +#4734 = EDGE_CURVE ( 'NONE', #20205, #38824, #20073, .T. ) ; +#4735 = CARTESIAN_POINT ( 'NONE', ( 3.054829480853488377, 190.6506292567034677, 106.7451573915843284 ) ) ; +#4736 = ADVANCED_FACE ( 'NONE', ( #19161 ), #37004, .T. ) ; +#4737 = CARTESIAN_POINT ( 'NONE', ( -27.86428169786740128, 186.6957439683559699, 105.3359119473810068 ) ) ; +#4738 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714601725811, 0.5299193037554699170 ) ) ; +#4739 = CARTESIAN_POINT ( 'NONE', ( -15.10714335811488773, 183.0966620568070198, 101.9332428217494027 ) ) ; +#4740 = CIRCLE ( 'NONE', #19756, 2.499999999999997335 ) ; +#4741 = ORIENTED_EDGE ( 'NONE', *, *, #33856, .T. ) ; +#4742 = CARTESIAN_POINT ( 'NONE', ( 27.53514821939999990, 124.1339620642999932, 91.20273972887000014 ) ) ; +#4743 = FACE_OUTER_BOUND ( 'NONE', #21558, .T. ) ; +#4744 = VECTOR ( 'NONE', #12600, 1000.000000000000000 ) ; +#4746 = CARTESIAN_POINT ( 'NONE', ( -30.05378920129078679, 185.1945982732621303, 102.9397691308601566 ) ) ; +#4745 = DIRECTION ( 'NONE', ( 0.0004161288024550070493, -0.8480480897973143861, 0.5299191110235090818 ) ) ; +#4747 = ORIENTED_EDGE ( 'NONE', *, *, #12626, .T. ) ; +#4748 = CIRCLE ( 'NONE', #22430, 5.000000000000007994 ) ; +#4749 = ORIENTED_EDGE ( 'NONE', *, *, #37098, .F. ) ; +#4750 = ORIENTED_EDGE ( 'NONE', *, *, #25837, .F. ) ; +#4751 = CARTESIAN_POINT ( 'NONE', ( 29.05442967595000070, 110.6131156702000027, 88.75023641814000541 ) ) ; +#4752 = FACE_OUTER_BOUND ( 'NONE', #38629, .T. ) ; +#4753 = LINE ( 'NONE', #27071, #636 ) ; +#4754 = VERTEX_POINT ( 'NONE', #22268 ) ; +#4755 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25584, #212, #31718, #12692, #9237, #37830, #28835, #10029, #6541, #13300, #25184, #25376, #9434, #19011, #9841, #38030, #6740 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000004636014, 0.1875000000007515932, 0.2187500000008642531, 0.2343750000008895107, 0.2500000000009147683, 0.3750000000009675594, 0.4375000000009690582, 0.4687500000009482970, 0.5000000000009274803, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4756 = ORIENTED_EDGE ( 'NONE', *, *, #27221, .T. ) ; +#4757 = CARTESIAN_POINT ( 'NONE', ( -38.40287610445658117, 121.6088961281960366, 92.88326245006905424 ) ) ; +#4758 = VERTEX_POINT ( 'NONE', #31668 ) ; +#4759 = CARTESIAN_POINT ( 'NONE', ( -35.60095806785000860, 192.5993474919999926, 106.7397797018000034 ) ) ; +#4760 = AXIS2_PLACEMENT_3D ( 'NONE', #31564, #6797, #12961 ) ; +#4761 = ADVANCED_FACE ( 'NONE', ( #34891 ), #3628, .T. ) ; +#4762 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #316, #37938, #25694, #34837, #32213, #31822, #13402, #37729, #34646, #3778 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4763 = AXIS2_PLACEMENT_3D ( 'NONE', #17058, #14226, #17668 ) ; +#4764 = CARTESIAN_POINT ( 'NONE', ( 3.080804014109543854, 190.8472021536144609, 106.8075760281446236 ) ) ; +#4765 = ORIENTED_EDGE ( 'NONE', *, *, #31076, .F. ) ; +#4766 = DIRECTION ( 'NONE', ( -0.0006039748319390056018, -1.156901198131326670E-14, -0.9999998176071845934 ) ) ; +#4767 = ADVANCED_FACE ( 'NONE', ( #32265 ), #10396, .T. ) ; +#4768 = AXIS2_PLACEMENT_3D ( 'NONE', #37306, #34023, #27928 ) ; +#4769 = CARTESIAN_POINT ( 'NONE', ( 15.66685957430246212, 126.7291730765401638, 89.24329869400926896 ) ) ; +#4770 = DIRECTION ( 'NONE', ( 0.0005884949961203373185, -0.2249510543439093846, 0.9743698870671255730 ) ) ; +#4771 = CARTESIAN_POINT ( 'NONE', ( 40.67331120850098358, 184.3716013758799761, 104.7596565504592547 ) ) ; +#4772 = ORIENTED_EDGE ( 'NONE', *, *, #34850, .T. ) ; +#4773 = EDGE_CURVE ( 'NONE', #39471, #13855, #20683, .T. ) ; +#4774 = EDGE_CURVE ( 'NONE', #662, #23150, #33696, .T. ) ; +#4775 = LINE ( 'NONE', #2138, #40137 ) ; +#4776 = CARTESIAN_POINT ( 'NONE', ( 30.44722896069117724, 127.1067747388918434, 88.97944275832713856 ) ) ; +#4777 = ADVANCED_FACE ( 'NONE', ( #19965 ), #39185, .T. ) ; +#4778 = ADVANCED_FACE ( 'NONE', ( #4028 ), #26738, .F. ) ; +#4779 = VERTEX_POINT ( 'NONE', #7102 ) ; +#4780 = CARTESIAN_POINT ( 'NONE', ( 33.46336677059740339, 81.57552323989831677, 288.3251734967106472 ) ) ; +#4782 = CARTESIAN_POINT ( 'NONE', ( -36.24326983097000010, 115.8895241964000036, 90.15716172436000875 ) ) ; +#4781 = DIRECTION ( 'NONE', ( -0.000000000000000000, -1.000000000000000000, 0.000000000000000000 ) ) ; +#4783 = ORIENTED_EDGE ( 'NONE', *, *, #8463, .T. ) ; +#4784 = VECTOR ( 'NONE', #27425, 1000.000000000000000 ) ; +#4785 = ORIENTED_EDGE ( 'NONE', *, *, #25640, .T. ) ; +#4786 = CARTESIAN_POINT ( 'NONE', ( 16.88249520722548169, 148.9778306577506726, 176.8903484419645622 ) ) ; +#4787 = CARTESIAN_POINT ( 'NONE', ( -13.49987458194983425, 124.7394176591053423, 88.97259030931672896 ) ) ; +#4788 = CARTESIAN_POINT ( 'NONE', ( -13.49946409159211669, 123.8765466711892742, 91.17938207915341309 ) ) ; +#4790 = ORIENTED_EDGE ( 'NONE', *, *, #1742, .F. ) ; +#4789 = AXIS2_PLACEMENT_3D ( 'NONE', #29716, #23175, #10915 ) ; +#4791 = EDGE_LOOP ( 'NONE', ( #23565, #27285, #37128 ) ) ; +#4792 = DIRECTION ( 'NONE', ( -0.6087614115774880874, 0.7730004600455407937, 0.1785492440296698458 ) ) ; +#4793 = VERTEX_POINT ( 'NONE', #4640 ) ; +#4794 = ORIENTED_EDGE ( 'NONE', *, *, #22573, .F. ) ; +#4795 = ORIENTED_EDGE ( 'NONE', *, *, #13893, .F. ) ; +#4796 = CARTESIAN_POINT ( 'NONE', ( 14.35597858069445465, 190.8513438264349134, 106.7846703957270904 ) ) ; +#4797 = CIRCLE ( 'NONE', #15274, 5.500000707771594222 ) ; +#4798 = EDGE_CURVE ( 'NONE', #32100, #1393, #16497, .T. ) ; +#4799 = CARTESIAN_POINT ( 'NONE', ( 2.802951049184000176, 209.5843744970999865, 73.22346325304999937 ) ) ; +#4800 = ORIENTED_EDGE ( 'NONE', *, *, #34899, .F. ) ; +#4801 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#4802 = CARTESIAN_POINT ( 'NONE', ( -36.03544878659999995, 191.6081880703000024, 104.0158779490000001 ) ) ; +#4803 = CARTESIAN_POINT ( 'NONE', ( -26.00229023349000101, 120.8686760094000050, 87.57325582845000156 ) ) ; +#4804 = VERTEX_POINT ( 'NONE', #4833 ) ; +#4805 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; +#4806 = CARTESIAN_POINT ( 'NONE', ( 22.77977433793355999, 158.3069438176785582, 96.18720162681876218 ) ) ; +#4807 = DIRECTION ( 'NONE', ( 0.0005884949961228161299, -0.2249510543439076360, 0.9743698870671260170 ) ) ; +#4808 = VERTEX_POINT ( 'NONE', #10996 ) ; +#4809 = ADVANCED_FACE ( 'NONE', ( #32069 ), #7295, .T. ) ; +#4810 = CARTESIAN_POINT ( 'NONE', ( -20.51863885680050359, 209.7097602209678939, 75.57089512796630970 ) ) ; +#4811 = FACE_OUTER_BOUND ( 'NONE', #2519, .T. ) ; +#4812 = CARTESIAN_POINT ( 'NONE', ( 20.50021201310788044, 195.1792461124052522, 105.0717163744397595 ) ) ; +#4813 = CARTESIAN_POINT ( 'NONE', ( 45.47174799569548753, 185.9669337813575396, 105.9176514305813441 ) ) ; +#4814 = ORIENTED_EDGE ( 'NONE', *, *, #27015, .F. ) ; +#4815 = CARTESIAN_POINT ( 'NONE', ( 17.27337838772892553, 121.3064376902564589, 177.4324028043064345 ) ) ; +#4816 = EDGE_CURVE ( 'NONE', #7173, #5222, #12701, .T. ) ; +#4817 = CARTESIAN_POINT ( 'NONE', ( 5.674778016381245571, 131.0223034755605909, 89.89838139801142347 ) ) ; +#4818 = VECTOR ( 'NONE', #11603, 1000.000000000000000 ) ; +#4819 = CARTESIAN_POINT ( 'NONE', ( 31.60023222786816177, 135.4070683171111966, 90.89502048698429348 ) ) ; +#4820 = EDGE_CURVE ( 'NONE', #7212, #31691, #11776, .T. ) ; +#4821 = ORIENTED_EDGE ( 'NONE', *, *, #6904, .F. ) ; +#4822 = ORIENTED_EDGE ( 'NONE', *, *, #17708, .T. ) ; +#4823 = VECTOR ( 'NONE', #30884, 1000.000000000000000 ) ; +#4824 = CARTESIAN_POINT ( 'NONE', ( -26.12881852497000068, 191.7883093318000078, 103.7920838617999948 ) ) ; +#4825 = EDGE_CURVE ( 'NONE', #15715, #33368, #1573, .T. ) ; +#4826 = PLANE ( 'NONE', #15348 ) ; +#4827 = CARTESIAN_POINT ( 'NONE', ( -23.34729099692994936, 213.5902299287207029, 73.57263793552689890 ) ) ; +#4828 = CARTESIAN_POINT ( 'NONE', ( -6.612072173594106393E-14, 161.0393699423707972, 99.91070331020887352 ) ) ; +#4829 = AXIS2_PLACEMENT_3D ( 'NONE', #4662, #985, #25963 ) ; +#4830 = CARTESIAN_POINT ( 'NONE', ( 22.78190537993189224, 158.0318634473625536, 98.86050528674346083 ) ) ; +#4831 = ORIENTED_EDGE ( 'NONE', *, *, #15459, .T. ) ; +#4832 = CARTESIAN_POINT ( 'NONE', ( 20.00176513866536965, 118.9456690639568990, 90.18052439326535819 ) ) ; +#4833 = CARTESIAN_POINT ( 'NONE', ( -14.55129769642598703, 176.2445762652153007, 103.4298910492225616 ) ) ; +#4834 = CARTESIAN_POINT ( 'NONE', ( -15.46321445985169873, 124.1316392283082450, 152.4730753928283775 ) ) ; +#4835 = DIRECTION ( 'NONE', ( 0.0001358648856691746900, 0.9743700647852248098, 0.2249510133143870216 ) ) ; +#4836 = CARTESIAN_POINT ( 'NONE', ( 22.50059290207999396, 154.2095289565698124, 95.41246725570897524 ) ) ; +#4837 = CARTESIAN_POINT ( 'NONE', ( 36.42681392942999707, 191.0436009519999914, 106.6811892480999973 ) ) ; +#4838 = DIRECTION ( 'NONE', ( -0.0006039748319391919761, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#4839 = DIRECTION ( 'NONE', ( -0.0005884949961254009763, 0.2249510543439060262, -0.9743698870671263501 ) ) ; +#4840 = PLANE ( 'NONE', #39581 ) ; +#4841 = EDGE_LOOP ( 'NONE', ( #30503, #5723, #15797, #17645 ) ) ; +#4842 = VECTOR ( 'NONE', #35743, 1000.000000000000227 ) ; +#4843 = VECTOR ( 'NONE', #16490, 1000.000000000000114 ) ; +#4844 = DIRECTION ( 'NONE', ( 0.0006039748319395906373, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#4845 = CARTESIAN_POINT ( 'NONE', ( 3.585551889548043825, 144.2098241759302084, 92.99688381113877256 ) ) ; +#4846 = VECTOR ( 'NONE', #30654, 1000.000000000000114 ) ; +#4847 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709481474, 77.27946979429643193, 322.5205145037752459 ) ) ; +#4848 = AXIS2_PLACEMENT_3D ( 'NONE', #25316, #28769, #9768 ) ; +#4849 = ORIENTED_EDGE ( 'NONE', *, *, #25384, .F. ) ; +#4850 = DIRECTION ( 'NONE', ( 0.0005884949961258187194, -0.2249510543439062760, 0.9743698870671264611 ) ) ; +#4851 = VECTOR ( 'NONE', #2459, 1000.000000000000227 ) ; +#4852 = EDGE_LOOP ( 'NONE', ( #11713, #11540, #13674, #1694 ) ) ; +#4853 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #18008, #5133, #33760 ), + ( #17606, #9032, #27473 ), + ( #39895, #32947, #5759 ), + ( #30715, #14568, #11703 ) ), + .UNSPECIFIED., .F., .F., .T. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), + ( 3, 3 ), + ( 0.003213125900859597692, 0.003266714168266309296 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.7110173697362405232, 1.000000000000000000), + ( 1.000000000000000000, 0.7097605058162677061, 1.000000000000000000), + ( 1.000000000000000000, 0.7084892703251066681, 1.000000000000000000), + ( 1.000000000000000000, 0.7072031799626566917, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#4854 = DIRECTION ( 'NONE', ( 0.0002393071182785071779, 0.2252352986010040525, -0.9743043687658491381 ) ) ; +#4855 = CARTESIAN_POINT ( 'NONE', ( -17.26213291099019997, 152.2612616225560771, 183.6636115490260863 ) ) ; +#4856 = ORIENTED_EDGE ( 'NONE', *, *, #17035, .T. ) ; +#4857 = CARTESIAN_POINT ( 'NONE', ( 25.46575390506999881, 213.5902260771000272, 32.39311599089000282 ) ) ; +#4858 = EDGE_CURVE ( 'NONE', #23757, #3973, #13458, .T. ) ; +#4859 = ADVANCED_FACE ( 'NONE', ( #25941 ), #7704, .T. ) ; +#4860 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; +#4862 = ADVANCED_FACE ( 'NONE', ( #1367 ), #22682, .T. ) ; +#4861 = FACE_OUTER_BOUND ( 'NONE', #36235, .T. ) ; +#4863 = DIRECTION ( 'NONE', ( -0.0005884949961278631994, 0.2249510543439048327, -0.9743698870671267942 ) ) ; +#4865 = EDGE_CURVE ( 'NONE', #12760, #1525, #38997, .T. ) ; +#4864 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1691, #32953, #24191, #4950 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4866 = LINE ( 'NONE', #11414, #15044 ) ; +#4867 = CARTESIAN_POINT ( 'NONE', ( -3.669581230394507898, 185.7947741359049019, 103.0623953380812168 ) ) ; +#4868 = ORIENTED_EDGE ( 'NONE', *, *, #29196, .F. ) ; +#4869 = LINE ( 'NONE', #35119, #34924 ) ; +#4870 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#4871 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2427, #39813, #24917, #14891, #36754, #15094, #31226, #8762, #33677, #5685, #18132 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998300804, 0.3749999999997295497, 0.4374999999996792011, 0.4687499999996728728, 0.4999999999996664890, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4872 = CARTESIAN_POINT ( 'NONE', ( 47.95588533879620741, 89.40266445833195519, 291.5248371983224729 ) ) ; +#4873 = EDGE_CURVE ( 'NONE', #35062, #26640, #28569, .T. ) ; +#4874 = ORIENTED_EDGE ( 'NONE', *, *, #3431, .F. ) ; +#4875 = CARTESIAN_POINT ( 'NONE', ( -45.68381200445116264, 124.6973070541615414, 92.04274264343763434 ) ) ; +#4876 = ORIENTED_EDGE ( 'NONE', *, *, #22580, .F. ) ; +#4877 = CARTESIAN_POINT ( 'NONE', ( 3.666638755385807080, 126.6906504152049706, 89.41269982467663624 ) ) ; +#4878 = CARTESIAN_POINT ( 'NONE', ( -43.71968941974858325, 120.3868516857203872, 91.27386099642183126 ) ) ; +#4879 = AXIS2_PLACEMENT_3D ( 'NONE', #30339, #17032, #32986 ) ; +#4880 = CYLINDRICAL_SURFACE ( 'NONE', #16341, 2.500000000000002220 ) ; +#4881 = CARTESIAN_POINT ( 'NONE', ( -28.38456979805999936, 125.0358147611000135, 91.22736114040000643 ) ) ; +#4882 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#4883 = EDGE_CURVE ( 'NONE', #7762, #2748, #38330, .T. ) ; +#4884 = CIRCLE ( 'NONE', #10129, 6.500001087336261030 ) ; +#4885 = CONICAL_SURFACE ( 'NONE', #8855, 6.503080706119665599, 0.7853981633713218447 ) ; +#4886 = PLANE ( 'NONE', #23453 ) ; +#4887 = CARTESIAN_POINT ( 'NONE', ( -45.56069752896866731, 133.9656849080258496, 337.3347232553839490 ) ) ; +#4888 = AXIS2_PLACEMENT_3D ( 'NONE', #28157, #24292, #25095 ) ; +#4889 = CARTESIAN_POINT ( 'NONE', ( -19.99850934198748931, 160.0545621481389844, 99.69532483852709959 ) ) ; +#4890 = DIRECTION ( 'NONE', ( 0.0005884949961179900208, -0.2249510543439076360, 0.9743698870671260170 ) ) ; +#4891 = ADVANCED_FACE ( 'NONE', ( #27760 ), #39995, .F. ) ; +#4892 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319381716335 ) ) ; +#4893 = CARTESIAN_POINT ( 'NONE', ( 3.333080673702689456, 183.2502631384639074, 101.9575669988970645 ) ) ; +#4894 = ORIENTED_EDGE ( 'NONE', *, *, #37346, .F. ) ; +#4895 = CARTESIAN_POINT ( 'NONE', ( -1.237265163634357679, 156.7699511568839625, 100.9789453716980177 ) ) ; +#4896 = CARTESIAN_POINT ( 'NONE', ( -20.49957633237145060, 118.5814696803204384, 87.78009030275359237 ) ) ; +#4897 = CARTESIAN_POINT ( 'NONE', ( -23.36013443158915237, 136.6763330450122567, 94.30332275863374036 ) ) ; +#4899 = EDGE_LOOP ( 'NONE', ( #25926, #35599, #35510, #21481, #22707 ) ) ; +#4898 = CARTESIAN_POINT ( 'NONE', ( 37.28139794753688108, 124.9423866440358069, 93.60865750304402866 ) ) ; +#4900 = ORIENTED_EDGE ( 'NONE', *, *, #20691, .F. ) ; +#4901 = ORIENTED_EDGE ( 'NONE', *, *, #5947, .F. ) ; +#4902 = ORIENTED_EDGE ( 'NONE', *, *, #18297, .T. ) ; +#4903 = CARTESIAN_POINT ( 'NONE', ( -23.35526879455558813, 177.7631879465995723, 100.7283305276877172 ) ) ; +#4904 = CARTESIAN_POINT ( 'NONE', ( 29.37172806597842722, 112.1957651408767873, 175.8423023756299131 ) ) ; +#4905 = CYLINDRICAL_SURFACE ( 'NONE', #31141, 2.000000000000011546 ) ; +#4906 = ORIENTED_EDGE ( 'NONE', *, *, #7920, .T. ) ; +#4907 = AXIS2_PLACEMENT_3D ( 'NONE', #1930, #14400, #27907 ) ; +#4908 = DIRECTION ( 'NONE', ( -0.0005884949961246456127, 0.2249510543439063592, -0.9743698870671262391 ) ) ; +#4909 = CIRCLE ( 'NONE', #27803, 2.499999999994544364 ) ; +#4910 = CIRCLE ( 'NONE', #37579, 2.000000000004209522 ) ; +#4911 = CARTESIAN_POINT ( 'NONE', ( 26.73277628323574717, 120.3821797830261033, 171.5759152015846496 ) ) ; +#4912 = ORIENTED_EDGE ( 'NONE', *, *, #38928, .T. ) ; +#4913 = CIRCLE ( 'NONE', #13422, 2.000000000000011546 ) ; +#4914 = LINE ( 'NONE', #14337, #12744 ) ; +#4915 = EDGE_CURVE ( 'NONE', #28666, #24015, #39638, .T. ) ; +#4916 = ORIENTED_EDGE ( 'NONE', *, *, #35733, .T. ) ; +#4917 = EDGE_CURVE ( 'NONE', #29169, #21974, #33658, .T. ) ; +#4918 = CARTESIAN_POINT ( 'NONE', ( -27.80047107912594484, 149.4166296170034514, 291.5753347231419639 ) ) ; +#4919 = AXIS2_PLACEMENT_3D ( 'NONE', #31077, #31266, #40056 ) ; +#4920 = EDGE_CURVE ( 'NONE', #34430, #10571, #24288, .T. ) ; +#4921 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.894780628693970840E-14, 0.9999998176071847045 ) ) ; +#4922 = CARTESIAN_POINT ( 'NONE', ( -3.169795749769255711, 186.0607901153434511, 102.6103559709178654 ) ) ; +#4923 = CARTESIAN_POINT ( 'NONE', ( -35.93925692342736511, 191.9759150222000130, 101.9431537509079817 ) ) ; +#4924 = ORIENTED_EDGE ( 'NONE', *, *, #25161, .F. ) ; +#4925 = CARTESIAN_POINT ( 'NONE', ( -2.438021043067000182, 190.8225405149999858, 104.2122243419999990 ) ) ; +#4926 = CARTESIAN_POINT ( 'NONE', ( 0.6371225951570861357, 189.0073665696679655, 103.6986168510260029 ) ) ; +#4927 = CARTESIAN_POINT ( 'NONE', ( -35.95543229855000078, 209.7096535459000108, 75.16162026493999804 ) ) ; +#4928 = CARTESIAN_POINT ( 'NONE', ( 26.00087991994412917, 120.1719190573502090, 90.46000324774034596 ) ) ; +#4929 = EDGE_CURVE ( 'NONE', #33034, #15187, #8122, .T. ) ; +#4930 = ORIENTED_EDGE ( 'NONE', *, *, #25348, .T. ) ; +#4931 = CARTESIAN_POINT ( 'NONE', ( -2.454332449978999797, 209.0617968418999908, 75.63992803070000548 ) ) ; +#4932 = ORIENTED_EDGE ( 'NONE', *, *, #33295, .F. ) ; +#4933 = VERTEX_POINT ( 'NONE', #15072 ) ; +#4934 = EDGE_CURVE ( 'NONE', #15039, #19726, #30303, .T. ) ; +#4935 = ORIENTED_EDGE ( 'NONE', *, *, #22812, .T. ) ; +#4936 = AXIS2_PLACEMENT_3D ( 'NONE', #16718, #787, #22689 ) ; +#4937 = ORIENTED_EDGE ( 'NONE', *, *, #38025, .T. ) ; +#4938 = AXIS2_PLACEMENT_3D ( 'NONE', #30721, #4949, #5353 ) ; +#4939 = CARTESIAN_POINT ( 'NONE', ( -38.94691154124904386, 128.1851843107897650, 89.27032559287691527 ) ) ; +#4940 = CARTESIAN_POINT ( 'NONE', ( -39.75024793617362917, 128.4756217986020488, 92.41677646255658374 ) ) ; +#4941 = EDGE_CURVE ( 'NONE', #32409, #34827, #11803, .T. ) ; +#4942 = VERTEX_POINT ( 'NONE', #8534 ) ; +#4943 = CARTESIAN_POINT ( 'NONE', ( 25.99877525812749468, 118.1153592017238338, 87.25208168324967062 ) ) ; +#4944 = VECTOR ( 'NONE', #29797, 1000.000000000000114 ) ; +#4945 = VERTEX_POINT ( 'NONE', #2795 ) ; +#4946 = CIRCLE ( 'NONE', #19930, 2.000000000000011546 ) ; +#4947 = CARTESIAN_POINT ( 'NONE', ( 26.02941144344040580, 120.6378765363000269, 90.57112595491780382 ) ) ; +#4948 = CARTESIAN_POINT ( 'NONE', ( -43.27414346572250992, 128.2423119564918466, 92.36504097611086195 ) ) ; +#4950 = CARTESIAN_POINT ( 'NONE', ( -23.35464359634993770, 177.7881151143831744, 100.7126876897662697 ) ) ; +#4949 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#4951 = ORIENTED_EDGE ( 'NONE', *, *, #21619, .T. ) ; +#4952 = ORIENTED_EDGE ( 'NONE', *, *, #12729, .T. ) ; +#4953 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6962, #16762, #1431, #20232, #23124, #22926 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#4954 = VERTEX_POINT ( 'NONE', #17502 ) ; +#4955 = LINE ( 'NONE', #29916, #23090 ) ; +#4956 = CARTESIAN_POINT ( 'NONE', ( -21.82845856935587037, 135.5369429020799146, 93.52303473086848840 ) ) ; +#4957 = CARTESIAN_POINT ( 'NONE', ( 20.33347830596183314, 160.6696382356835500, 97.07619954612073343 ) ) ; +#4958 = ORIENTED_EDGE ( 'NONE', *, *, #170, .T. ) ; +#4959 = ORIENTED_EDGE ( 'NONE', *, *, #14903, .T. ) ; +#4960 = VECTOR ( 'NONE', #19342, 1000.000000000000000 ) ; +#4962 = ADVANCED_FACE ( 'NONE', ( #39787 ), #5659, .F. ) ; +#4961 = CARTESIAN_POINT ( 'NONE', ( -2.438083998875509639, 190.8225490817534933, 104.2121631052086315 ) ) ; +#4963 = DIRECTION ( 'NONE', ( -0.0006039748319388572829, -3.099784637799882324E-15, -0.9999998176071847045 ) ) ; +#4964 = EDGE_CURVE ( 'NONE', #19017, #35125, #7839, .T. ) ; +#4965 = VECTOR ( 'NONE', #7970, 1000.000000000000114 ) ; +#4966 = AXIS2_PLACEMENT_3D ( 'NONE', #32012, #1311, #13595 ) ; +#4967 = CARTESIAN_POINT ( 'NONE', ( 15.14910835783079079, 187.7483930415743316, 102.9889057178500735 ) ) ; +#4968 = ORIENTED_EDGE ( 'NONE', *, *, #21192, .T. ) ; +#4969 = CARTESIAN_POINT ( 'NONE', ( 30.06788789467000456, 135.1647620141970094, 91.17105285833032724 ) ) ; +#4970 = CARTESIAN_POINT ( 'NONE', ( -37.85985168709885329, 117.8113977611419187, 89.71713298447978957 ) ) ; +#4971 = AXIS2_PLACEMENT_3D ( 'NONE', #34610, #1084, #31579 ) ; +#4972 = AXIS2_PLACEMENT_3D ( 'NONE', #22992, #35615, #35415 ) ; +#4973 = CARTESIAN_POINT ( 'NONE', ( 3.074439616337855785, 190.7388267800502035, 106.7754277006573176 ) ) ; +#4974 = EDGE_LOOP ( 'NONE', ( #3301, #4821, #20854, #3357 ) ) ; +#4975 = CARTESIAN_POINT ( 'NONE', ( 39.10488449847447612, 118.9309680717053084, 89.68369243349377484 ) ) ; +#4976 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000094147, 179.7424522644965634, 101.1388664480874269 ) ) ; +#4977 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555133 ) ) ; +#4978 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825711345, 184.4051477319173955, 104.7783766748929821 ) ) ; +#4979 = ORIENTED_EDGE ( 'NONE', *, *, #405, .F. ) ; +#4980 = FACE_OUTER_BOUND ( 'NONE', #34228, .T. ) ; +#4981 = CARTESIAN_POINT ( 'NONE', ( 29.40506628721518112, 160.9732782815168832, 187.1184765030605774 ) ) ; +#4982 = EDGE_CURVE ( 'NONE', #27492, #39268, #27873, .T. ) ; +#4983 = ORIENTED_EDGE ( 'NONE', *, *, #31456, .F. ) ; +#4984 = FACE_OUTER_BOUND ( 'NONE', #41, .T. ) ; +#4985 = AXIS2_PLACEMENT_3D ( 'NONE', #13712, #20034, #32519 ) ; +#4986 = AXIS2_PLACEMENT_3D ( 'NONE', #6905, #9790, #9583 ) ; +#4988 = LINE ( 'NONE', #11328, #10941 ) ; +#4987 = CARTESIAN_POINT ( 'NONE', ( 13.73173069815889491, 135.3487696960925177, 90.89235331452654520 ) ) ; +#4989 = VERTEX_POINT ( 'NONE', #39382 ) ; +#4990 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24362, #36811, #6127, #18184 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0007138690537832477175, 0.0007171792812430367522 ), + .UNSPECIFIED. ) ; +#4991 = ORIENTED_EDGE ( 'NONE', *, *, #22290, .F. ) ; +#4993 = AXIS2_PLACEMENT_3D ( 'NONE', #6783, #13542, #23149 ) ; +#4992 = CARTESIAN_POINT ( 'NONE', ( 2.826471639010999848, 209.6751949233000403, 75.93526320658999396 ) ) ; +#4994 = ADVANCED_FACE ( 'NONE', ( #5861 ), #27271, .F. ) ; +#4995 = CARTESIAN_POINT ( 'NONE', ( 37.26718118745528585, 191.0824230493275309, 106.2979611257835728 ) ) ; +#4996 = VECTOR ( 'NONE', #20154, 1000.000000000000000 ) ; +#4997 = CARTESIAN_POINT ( 'NONE', ( 22.33189175409000171, 129.8624845047999941, 92.69946294856001145 ) ) ; +#4998 = EDGE_LOOP ( 'NONE', ( #32196, #39454, #5406, #33594, #984 ) ) ; +#4999 = ORIENTED_EDGE ( 'NONE', *, *, #4355, .T. ) ; +#5000 = DIRECTION ( 'NONE', ( -4.163336342379951730E-15, 0.9743700557921592953, 0.2249510932971524324 ) ) ; +#5001 = EDGE_LOOP ( 'NONE', ( #29660, #16036, #28721, #13477 ) ) ; +#5002 = ORIENTED_EDGE ( 'NONE', *, *, #22573, .T. ) ; +#5003 = CARTESIAN_POINT ( 'NONE', ( -20.89128718923779005, 182.4208812217193838, 104.8596338257292757 ) ) ; +#5004 = CARTESIAN_POINT ( 'NONE', ( 19.38724966413716189, 125.5510095562851234, 178.4140686402664642 ) ) ; +#5005 = CARTESIAN_POINT ( 'NONE', ( 37.33357129172325273, 105.3428449184722098, 178.5087748212203280 ) ) ; +#5006 = ORIENTED_EDGE ( 'NONE', *, *, #8236, .F. ) ; +#5007 = ORIENTED_EDGE ( 'NONE', *, *, #27898, .F. ) ; +#5008 = FACE_OUTER_BOUND ( 'NONE', #35108, .T. ) ; +#5009 = CARTESIAN_POINT ( 'NONE', ( -35.97269354704000222, 191.6488110232999986, 104.0237207920000060 ) ) ; +#5010 = CARTESIAN_POINT ( 'NONE', ( 38.06764886506999801, 191.3258868949000089, 104.1925984591000116 ) ) ; +#5011 = ADVANCED_FACE ( 'NONE', ( #30814 ), #20704, .T. ) ; +#5012 = CARTESIAN_POINT ( 'NONE', ( -25.84266698421999919, 121.0534836917999968, 87.78695595496000692 ) ) ; +#5013 = EDGE_CURVE ( 'NONE', #6603, #39814, #5239, .T. ) ; +#5014 = CARTESIAN_POINT ( 'NONE', ( 76.10630783111388098, 156.2604783515451743, 96.19568201158742227 ) ) ; +#5015 = ORIENTED_EDGE ( 'NONE', *, *, #20286, .F. ) ; +#5016 = DIRECTION ( 'NONE', ( -0.0005884949961208443998, 0.2249510543439059429, -0.9743698870671263501 ) ) ; +#5017 = CARTESIAN_POINT ( 'NONE', ( -23.35945886576643815, 176.9432781775398951, 103.3635654750831776 ) ) ; +#5018 = ORIENTED_EDGE ( 'NONE', *, *, #29815, .F. ) ; +#5019 = AXIS2_PLACEMENT_3D ( 'NONE', #37706, #22189, #5835 ) ; +#5020 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 132.9679238121742912, 90.36185680194377312 ) ) ; +#5021 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; +#5022 = AXIS2_PLACEMENT_3D ( 'NONE', #1189, #1385, #10612 ) ; +#5023 = CARTESIAN_POINT ( 'NONE', ( -6.273952199476604541, 148.6532986828639480, 94.48918149448384440 ) ) ; +#5024 = CARTESIAN_POINT ( 'NONE', ( 45.54189549626755706, 185.8919662543875688, 105.8359296185758751 ) ) ; +#5025 = VECTOR ( 'NONE', #34063, 1000.000000000000000 ) ; +#5026 = EDGE_LOOP ( 'NONE', ( #15933, #25656, #30106, #28174 ) ) ; +#5027 = CARTESIAN_POINT ( 'NONE', ( -19.39687658205970422, 126.0855016948991221, 176.0882538048638537 ) ) ; +#5028 = CARTESIAN_POINT ( 'NONE', ( 2.178827133561953122, 189.8211730161134767, 103.9204081209391006 ) ) ; +#5029 = FACE_OUTER_BOUND ( 'NONE', #35071, .T. ) ; +#5030 = ORIENTED_EDGE ( 'NONE', *, *, #37844, .T. ) ; +#5031 = FACE_OUTER_BOUND ( 'NONE', #5026, .T. ) ; +#5032 = PLANE ( 'NONE', #30343 ) ; +#5033 = FACE_OUTER_BOUND ( 'NONE', #33367, .T. ) ; +#5034 = CARTESIAN_POINT ( 'NONE', ( 26.19519609312000341, 191.4049078856000108, 103.6787492708999991 ) ) ; +#5035 = CARTESIAN_POINT ( 'NONE', ( 17.17610773255657719, 152.4992089640258826, 182.3747067827581532 ) ) ; +#5036 = CARTESIAN_POINT ( 'NONE', ( 6.027366378080522225, 134.9354931969997153, 90.82302421546900462 ) ) ; +#5037 = EDGE_LOOP ( 'NONE', ( #12728, #39319, #16071, #17387 ) ) ; +#5038 = CARTESIAN_POINT ( 'NONE', ( 2.562619485644860973, 196.1181876864285698, 103.6781880485148406 ) ) ; +#5039 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; +#5040 = CARTESIAN_POINT ( 'NONE', ( -3.631817828491611166, 137.3302548163418066, 91.45691583842069861 ) ) ; +#5041 = EDGE_CURVE ( 'NONE', #28826, #13796, #28356, .T. ) ; +#5042 = CIRCLE ( 'NONE', #38355, 6.000000000000001776 ) ; +#5043 = CARTESIAN_POINT ( 'NONE', ( -20.99003731125718986, 183.0888586945435463, 104.5007462684889248 ) ) ; +#5044 = CARTESIAN_POINT ( 'NONE', ( 21.24456206835106542, 171.9013578063823502, 152.1279856333677571 ) ) ; +#5045 = DIRECTION ( 'NONE', ( 0.0001408404346093821877, -0.2255194953558360971, 0.9742386449830559014 ) ) ; +#5046 = CARTESIAN_POINT ( 'NONE', ( 21.70855119580487269, 123.2009557436313401, 176.5136632602473981 ) ) ; +#5047 = CIRCLE ( 'NONE', #1796, 59.40509898823097501 ) ; +#5048 = ORIENTED_EDGE ( 'NONE', *, *, #27359, .T. ) ; +#5049 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142367503004439, 137.4659008082804519, 177.5714312369109393 ) ) ; +#5050 = EDGE_CURVE ( 'NONE', #38350, #1917, #39591, .T. ) ; +#5051 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; +#5052 = EDGE_LOOP ( 'NONE', ( #3303, #3213, #30735, #24751, #14796, #12802, #1867, #871, #33846, #11687, #32379, #37912, #38796, #5697, #7798, #9395, #18469, #25829, #2877, #24278, #13059, #32292, #8896, #36825, #4185, #25847, #37070 ) ) ; +#5053 = CARTESIAN_POINT ( 'NONE', ( 5.665157511863806228, 181.8548547649002387, 101.8603694440876950 ) ) ; +#5054 = EDGE_CURVE ( 'NONE', #32409, #5601, #3735, .T. ) ; +#5055 = EDGE_CURVE ( 'NONE', #17992, #36832, #22416, .T. ) ; +#5056 = ORIENTED_EDGE ( 'NONE', *, *, #30095, .T. ) ; +#5057 = ADVANCED_FACE ( 'NONE', ( #25491 ), #28348, .T. ) ; +#5058 = EDGE_CURVE ( 'NONE', #25194, #13591, #23945, .T. ) ; +#5059 = CARTESIAN_POINT ( 'NONE', ( 20.00028792540915035, 151.9820690596619102, 94.72877128701482263 ) ) ; +#5060 = DIRECTION ( 'NONE', ( -0.8135696865073147599, 0.000000000000000000, 0.5814674240199442234 ) ) ; +#5061 = ORIENTED_EDGE ( 'NONE', *, *, #16050, .T. ) ; +#5062 = DIRECTION ( 'NONE', ( -0.7942820423213359238, -0.5918950211223032998, -0.1370267171630252523 ) ) ; +#5063 = CARTESIAN_POINT ( 'NONE', ( -14.78462263661723597, 175.5939430572494757, 102.0824664216037263 ) ) ; +#5064 = CARTESIAN_POINT ( 'NONE', ( 3.064326251946869473, 190.8646446422509939, 106.7945608832239657 ) ) ; +#5065 = LINE ( 'NONE', #30443, #34591 ) ; +#5066 = CARTESIAN_POINT ( 'NONE', ( 6.042308921164076807, 177.7921139377573638, 100.6958234779730645 ) ) ; +#5067 = VERTEX_POINT ( 'NONE', #16060 ) ; +#5068 = VERTEX_POINT ( 'NONE', #28547 ) ; +#5069 = CARTESIAN_POINT ( 'NONE', ( -5.633767562759513403, 157.0637020868425395, 100.6797548176731993 ) ) ; +#5070 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31400, #19107, #6431, #3367 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.001173009038358866895, 0.007810755923537757509 ), + .UNSPECIFIED. ) ; +#5071 = DIRECTION ( 'NONE', ( 0.0005884949961254158299, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#5072 = CARTESIAN_POINT ( 'NONE', ( 44.99182355356327179, 85.19921574553130483, 291.3598206077773511 ) ) ; +#5073 = VERTEX_POINT ( 'NONE', #40195 ) ; +#5074 = CIRCLE ( 'NONE', #23370, 4.500000000002243539 ) ; +#5075 = CARTESIAN_POINT ( 'NONE', ( 17.25788849119799195, 152.5371962406647413, 182.4889206688251306 ) ) ; +#5076 = ORIENTED_EDGE ( 'NONE', *, *, #9461, .T. ) ; +#5077 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825951923653446, 0.0005734119016496685723 ) ) ; +#5078 = CARTESIAN_POINT ( 'NONE', ( -42.24295683378286981, 121.5717801413329653, 91.17935236647853969 ) ) ; +#5079 = VECTOR ( 'NONE', #19917, 1000.000000000000114 ) ; +#5080 = CARTESIAN_POINT ( 'NONE', ( 6.035541027891230925, 134.8446529991751390, 93.34637782540107764 ) ) ; +#5081 = PLANE ( 'NONE', #16284 ) ; +#5082 = CARTESIAN_POINT ( 'NONE', ( -20.02002437005085511, 209.7095682957761085, 73.07054393135327075 ) ) ; +#5083 = DIRECTION ( 'NONE', ( -0.0006039748319386378404, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#5084 = LINE ( 'NONE', #8581, #1915 ) ; +#5085 = CARTESIAN_POINT ( 'NONE', ( -25.64334719397065498, 209.7118774246391695, 73.44058178187695773 ) ) ; +#5086 = CARTESIAN_POINT ( 'NONE', ( 6.038444123889645354, 177.0265160856394004, 103.4736887629186270 ) ) ; +#5087 = FACE_OUTER_BOUND ( 'NONE', #38449, .T. ) ; +#5088 = CARTESIAN_POINT ( 'NONE', ( 39.12645029865999646, 118.7985587775000056, 89.52831436418999544 ) ) ; +#5089 = EDGE_LOOP ( 'NONE', ( #15011, #9465, #19436, #19453 ) ) ; +#5090 = CARTESIAN_POINT ( 'NONE', ( 26.07574513491999824, 130.1628104229000087, 92.50996139529000573 ) ) ; +#5091 = CARTESIAN_POINT ( 'NONE', ( -2.438441567505833518, 191.9759150222000130, 101.9229200979927867 ) ) ; +#5092 = EDGE_CURVE ( 'NONE', #12760, #40342, #18708, .T. ) ; +#5093 = CARTESIAN_POINT ( 'NONE', ( -25.84017946953396461, 190.8761128457341272, 106.6436155876561429 ) ) ; +#5094 = CYLINDRICAL_SURFACE ( 'NONE', #3235, 2.250000000000011102 ) ; +#5095 = ADVANCED_FACE ( 'NONE', ( #12586 ), #34648, .T. ) ; +#5096 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#5097 = ORIENTED_EDGE ( 'NONE', *, *, #37560, .T. ) ; +#5098 = EDGE_LOOP ( 'NONE', ( #2920, #4677, #40264, #7119 ) ) ; +#5099 = CARTESIAN_POINT ( 'NONE', ( -2.675754854896591262, 189.9858645893802986, 103.5162325917308834 ) ) ; +#5100 = EDGE_CURVE ( 'NONE', #26291, #37554, #26399, .T. ) ; +#5101 = EDGE_LOOP ( 'NONE', ( #30764, #29319, #8004, #29324 ) ) ; +#5102 = CARTESIAN_POINT ( 'NONE', ( 42.43787138009228244, 189.9416574239004376, 106.2771675705110823 ) ) ; +#5103 = EDGE_CURVE ( 'NONE', #1836, #19924, #13000, .T. ) ; +#5104 = CIRCLE ( 'NONE', #5764, 1.999999999874873424 ) ; +#5105 = CARTESIAN_POINT ( 'NONE', ( -28.42905095578378649, 115.9590670314987193, 152.9217692738434380 ) ) ; +#5106 = ORIENTED_EDGE ( 'NONE', *, *, #22858, .T. ) ; +#5107 = CARTESIAN_POINT ( 'NONE', ( -14.42373139518885417, 135.2541458085655961, 93.79537502748391375 ) ) ; +#5108 = ADVANCED_FACE ( 'NONE', ( #3182 ), #38502, .F. ) ; +#5109 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048997459, 187.6642686534307245, 106.0792573255209419 ) ) ; +#5110 = ORIENTED_EDGE ( 'NONE', *, *, #20677, .T. ) ; +#5111 = CARTESIAN_POINT ( 'NONE', ( -0.4540624946310913290, 209.0000000000000000, 76.05877887198174392 ) ) ; +#5112 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; +#5113 = CARTESIAN_POINT ( 'NONE', ( -6.611727627915328530E-14, 161.0393699423707972, 99.91070331020888773 ) ) ; +#5114 = DIRECTION ( 'NONE', ( 1.156372029607614051E-16, 0.9743043966640312359, 0.2252353050503803356 ) ) ; +#5115 = CARTESIAN_POINT ( 'NONE', ( -20.01839671862364867, 211.0902260915352429, 76.07059681904712534 ) ) ; +#5116 = VERTEX_POINT ( 'NONE', #1515 ) ; +#5117 = CARTESIAN_POINT ( 'NONE', ( -0.6435036550759100082, 188.6095499604300016, 103.1959319992260049 ) ) ; +#5118 = CARTESIAN_POINT ( 'NONE', ( 0.5626206141546249428, 189.0089373245590423, 103.6956312891909846 ) ) ; +#5119 = CARTESIAN_POINT ( 'NONE', ( -36.01634936736067516, 191.1431690495213616, 106.8733999024287300 ) ) ; +#5120 = VERTEX_POINT ( 'NONE', #19714 ) ; +#5121 = FACE_OUTER_BOUND ( 'NONE', #16820, .T. ) ; +#5122 = EDGE_LOOP ( 'NONE', ( #25480, #26834, #13359, #15133, #10111, #37567 ) ) ; +#5123 = CIRCLE ( 'NONE', #22141, 2.500000000003625988 ) ; +#5124 = VECTOR ( 'NONE', #6937, 1000.000000000000227 ) ; +#5125 = VERTEX_POINT ( 'NONE', #29150 ) ; +#5126 = AXIS2_PLACEMENT_3D ( 'NONE', #19266, #868, #7002 ) ; +#5127 = ORIENTED_EDGE ( 'NONE', *, *, #18751, .T. ) ; +#5128 = CARTESIAN_POINT ( 'NONE', ( 21.73156077531386288, 213.2744565895932851, 73.54538933777284626 ) ) ; +#5129 = VECTOR ( 'NONE', #26078, 1000.000000000000000 ) ; +#5130 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552150381, 77.14301703112145958, 291.5584375788748162 ) ) ; +#5131 = CARTESIAN_POINT ( 'NONE', ( -42.13403640304736086, 120.7957551389193185, 90.64517896386178109 ) ) ; +#5132 = EDGE_LOOP ( 'NONE', ( #18258, #22607, #18180, #13030 ) ) ; +#5133 = CARTESIAN_POINT ( 'NONE', ( 44.87338937966080010, 186.7839235692700868, 105.8491573445734133 ) ) ; +#5134 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 82.27946979429631824, 312.5857197240630967 ) ) ; +#5135 = ORIENTED_EDGE ( 'NONE', *, *, #30469, .T. ) ; +#5136 = EDGE_CURVE ( 'NONE', #34012, #38457, #14613, .T. ) ; +#5137 = CARTESIAN_POINT ( 'NONE', ( 25.73070893625000011, 121.0294910055999935, 90.31596527812001796 ) ) ; +#5138 = EDGE_CURVE ( 'NONE', #10571, #20739, #4988, .T. ) ; +#5139 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.274821093756980468E-14, 0.9999998176071847045 ) ) ; +#5140 = ADVANCED_FACE ( 'NONE', ( #18058 ), #36384, .T. ) ; +#5141 = EDGE_CURVE ( 'NONE', #38824, #30359, #24236, .T. ) ; +#5143 = CARTESIAN_POINT ( 'NONE', ( -42.99989013480271183, 189.1985352993988556, 106.4377309217844072 ) ) ; +#5142 = CARTESIAN_POINT ( 'NONE', ( 44.53164522189504737, 188.5976176822237278, 105.9040318422177194 ) ) ; +#5144 = ORIENTED_EDGE ( 'NONE', *, *, #32714, .F. ) ; +#5145 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27694, #2328, #33793, #14807 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0008896472904070360128, 0.004888313434849526212 ), + .UNSPECIFIED. ) ; +#5146 = ORIENTED_EDGE ( 'NONE', *, *, #35102, .F. ) ; +#5147 = ADVANCED_FACE ( 'NONE', ( #17655 ), #8061, .F. ) ; +#5148 = ORIENTED_EDGE ( 'NONE', *, *, #27987, .T. ) ; +#5149 = DIRECTION ( 'NONE', ( 0.9999998268367131793, 0.0001323826278427382556, -0.0005734120540847093992 ) ) ; +#5150 = EDGE_CURVE ( 'NONE', #21825, #34607, #27100, .T. ) ; +#5151 = CARTESIAN_POINT ( 'NONE', ( 22.78045900286101499, 164.6403492429683126, 97.64938332809994392 ) ) ; +#5152 = LINE ( 'NONE', #39099, #30509 ) ; +#5153 = CARTESIAN_POINT ( 'NONE', ( -25.50804057823069471, 190.9260211217805363, 106.3128357153982648 ) ) ; +#5154 = CARTESIAN_POINT ( 'NONE', ( 36.32716782976999781, 191.7164159702000177, 104.1917411218000069 ) ) ; +#5155 = VERTEX_POINT ( 'NONE', #15018 ) ; +#5156 = VECTOR ( 'NONE', #16638, 1000.000000000000114 ) ; +#5157 = ORIENTED_EDGE ( 'NONE', *, *, #28380, .T. ) ; +#5158 = AXIS2_PLACEMENT_3D ( 'NONE', #21674, #39646, #2846 ) ; +#5159 = CARTESIAN_POINT ( 'NONE', ( -2.437851586972803020, 194.2771770550226336, 102.8997479777824537 ) ) ; +#5160 = AXIS2_PLACEMENT_3D ( 'NONE', #4331, #32944, #16800 ) ; +#5161 = CARTESIAN_POINT ( 'NONE', ( 14.56365463500893398, 188.1150310587336776, 103.0739043884865396 ) ) ; +#5162 = ORIENTED_EDGE ( 'NONE', *, *, #35833, .F. ) ; +#5163 = EDGE_LOOP ( 'NONE', ( #34603, #37252, #7307, #1194, #4968, #20958, #19693, #38326, #14277 ) ) ; +#5164 = CARTESIAN_POINT ( 'NONE', ( 30.06796867041454746, 135.0793120097469568, 91.03430416376022549 ) ) ; +#5165 = ORIENTED_EDGE ( 'NONE', *, *, #14587, .F. ) ; +#5166 = CARTESIAN_POINT ( 'NONE', ( 19.46094516130095542, 125.6747539604571813, 178.4426934156100231 ) ) ; +#5167 = ORIENTED_EDGE ( 'NONE', *, *, #26064, .F. ) ; +#5168 = DIRECTION ( 'NONE', ( 0.0004161288024558960951, 0.5299192578740949955, 0.8480479980348919478 ) ) ; +#5169 = VERTEX_POINT ( 'NONE', #21151 ) ; +#5170 = CARTESIAN_POINT ( 'NONE', ( -20.51858740271092429, 206.4917143845494252, 74.92147872994014790 ) ) ; +#5171 = CARTESIAN_POINT ( 'NONE', ( -46.39481885264477512, 125.2269168869080431, 89.10500611615424305 ) ) ; +#5172 = CARTESIAN_POINT ( 'NONE', ( 46.05118615274398763, 124.8743111081185049, 91.53352630994533001 ) ) ; +#5173 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971546806 ) ) ; +#5174 = ORIENTED_EDGE ( 'NONE', *, *, #22841, .F. ) ; +#5175 = CARTESIAN_POINT ( 'NONE', ( 25.99051299129742887, 207.8021718666841764, 73.39534836237326942 ) ) ; +#5176 = CARTESIAN_POINT ( 'NONE', ( 2.563067459505969481, 191.9759150222000130, 104.4198997672286708 ) ) ; +#5177 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364886824597, 136.5649596138813706, 181.4686487119530511 ) ) ; +#5178 = VECTOR ( 'NONE', #22943, 1000.000000000000114 ) ; +#5179 = ORIENTED_EDGE ( 'NONE', *, *, #491, .T. ) ; +#5180 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10346, #4171, #16648, #3974, #7443, #28346, #15851, #25695, #22816, #29147 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5181 = CIRCLE ( 'NONE', #18233, 4.999999999999990230 ) ; +#5182 = CONICAL_SURFACE ( 'NONE', #28700, 3.003059068065875081, 0.7854054309186528915 ) ; +#5183 = CARTESIAN_POINT ( 'NONE', ( -2.938441474952925514, 191.9759150222000130, 101.9232220853079411 ) ) ; +#5184 = EDGE_CURVE ( 'NONE', #5512, #3137, #4435, .T. ) ; +#5185 = VECTOR ( 'NONE', #34738, 999.9999999999998863 ) ; +#5186 = CARTESIAN_POINT ( 'NONE', ( -13.49852954173680430, 160.1760870560666774, 99.20639934581299713 ) ) ; +#5187 = EDGE_LOOP ( 'NONE', ( #8760, #19564, #2157, #16227, #7379, #39558, #36903, #25790, #9273, #40122, #33208, #8498 ) ) ; +#5188 = ORIENTED_EDGE ( 'NONE', *, *, #14077, .T. ) ; +#5189 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#5190 = ORIENTED_EDGE ( 'NONE', *, *, #32956, .F. ) ; +#5191 = CARTESIAN_POINT ( 'NONE', ( 36.04675231538612223, 209.7096534091000137, 76.03673329443569173 ) ) ; +#5192 = CARTESIAN_POINT ( 'NONE', ( -13.73975480783703773, 149.7280840183275927, 179.8128424031955603 ) ) ; +#5193 = CARTESIAN_POINT ( 'NONE', ( -0.4375226734455109900, 188.8043241971669204, 103.4389957040046539 ) ) ; +#5194 = ORIENTED_EDGE ( 'NONE', *, *, #13343, .T. ) ; +#5195 = ORIENTED_EDGE ( 'NONE', *, *, #5376, .F. ) ; +#5196 = CARTESIAN_POINT ( 'NONE', ( 3.064505435595261229, 190.8915653482034998, 106.8005998850467222 ) ) ; +#5197 = ORIENTED_EDGE ( 'NONE', *, *, #13296, .T. ) ; +#5198 = ORIENTED_EDGE ( 'NONE', *, *, #37884, .T. ) ; +#5199 = ORIENTED_EDGE ( 'NONE', *, *, #39016, .T. ) ; +#5200 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#5201 = CARTESIAN_POINT ( 'NONE', ( 39.70674893776387648, 114.9516458920610660, 150.7368254606779772 ) ) ; +#5202 = CARTESIAN_POINT ( 'NONE', ( -2.851221542150457200, 209.7096659646922774, 76.06022685436926167 ) ) ; +#5203 = VERTEX_POINT ( 'NONE', #29747 ) ; +#5204 = ORIENTED_EDGE ( 'NONE', *, *, #40086, .T. ) ; +#5205 = FACE_OUTER_BOUND ( 'NONE', #32107, .T. ) ; +#5206 = CARTESIAN_POINT ( 'NONE', ( -35.63362683194999647, 191.6206829176000213, 103.7794803856000101 ) ) ; +#5207 = ORIENTED_EDGE ( 'NONE', *, *, #1595, .T. ) ; +#5208 = DIRECTION ( 'NONE', ( 0.0005884949961241434102, -0.2249510543439057764, 0.9743698870671265722 ) ) ; +#5209 = CIRCLE ( 'NONE', #37889, 7.500000206705061068 ) ; +#5210 = EDGE_CURVE ( 'NONE', #32100, #7892, #17450, .T. ) ; +#5211 = VERTEX_POINT ( 'NONE', #30348 ) ; +#5212 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319368615920 ) ) ; +#5213 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552156487, 3.781093664149108639E-12, 291.5584375788758393 ) ) ; +#5214 = LINE ( 'NONE', #17682, #9120 ) ; +#5215 = EDGE_LOOP ( 'NONE', ( #17258, #13683, #22093, #5897 ) ) ; +#5216 = CIRCLE ( 'NONE', #6530, 1.999999999967367437 ) ; +#5217 = CARTESIAN_POINT ( 'NONE', ( -6.037312566745338671, 134.5332731853788175, 93.54687357718964336 ) ) ; +#5218 = VECTOR ( 'NONE', #27412, 1000.000000000000000 ) ; +#5219 = CARTESIAN_POINT ( 'NONE', ( 25.49921019565536184, 118.1133140256443426, 87.75227232668940758 ) ) ; +#5220 = CARTESIAN_POINT ( 'NONE', ( 20.00004282447493864, 191.5259056233101091, 103.8580927373495371 ) ) ; +#5221 = CARTESIAN_POINT ( 'NONE', ( 14.17036435349962353, 176.4975660804189488, 100.9051904591885886 ) ) ; +#5222 = VERTEX_POINT ( 'NONE', #24019 ) ; +#5223 = CARTESIAN_POINT ( 'NONE', ( -48.18983608578390232, 82.56060091850311267, 289.7643016034785433 ) ) ; +#5224 = CARTESIAN_POINT ( 'NONE', ( 1.929693795520588839, 189.5261676399869089, 103.8354463821101064 ) ) ; +#5225 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19598, #19400, #32290, #16520 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5226 = CARTESIAN_POINT ( 'NONE', ( -13.83205090675506455, 124.7811071190511285, 174.0455584609973414 ) ) ; +#5227 = ORIENTED_EDGE ( 'NONE', *, *, #18892, .F. ) ; +#5228 = LINE ( 'NONE', #14453, #39945 ) ; +#5229 = EDGE_LOOP ( 'NONE', ( #34543, #3721, #9929, #35438 ) ) ; +#5230 = ORIENTED_EDGE ( 'NONE', *, *, #21051, .T. ) ; +#5231 = CARTESIAN_POINT ( 'NONE', ( 3.044059411013400940, 209.1882909079368744, 73.07656864438033040 ) ) ; +#5232 = CARTESIAN_POINT ( 'NONE', ( -35.62164487996323459, 209.7096534849600289, 75.91335251043651056 ) ) ; +#5233 = CARTESIAN_POINT ( 'NONE', ( 25.38734224913000048, 191.4305716074000259, 104.4940156361000021 ) ) ; +#5234 = DIRECTION ( 'NONE', ( -0.6319545750169662801, -0.7750053350989876133, 0.0003816847278651969611 ) ) ; +#5235 = ORIENTED_EDGE ( 'NONE', *, *, #35321, .T. ) ; +#5236 = CARTESIAN_POINT ( 'NONE', ( -15.10537787283572619, 182.4218088933851050, 104.8563524828814764 ) ) ; +#5237 = EDGE_CURVE ( 'NONE', #20022, #1098, #16152, .T. ) ; +#5238 = ADVANCED_FACE ( 'NONE', ( #30148 ), #5599, .F. ) ; +#5239 = LINE ( 'NONE', #36335, #5710 ) ; +#5240 = CONICAL_SURFACE ( 'NONE', #20273, 2.749999999949247709, 0.7853981633862016087 ) ; +#5241 = AXIS2_PLACEMENT_3D ( 'NONE', #28367, #18937, #31434 ) ; +#5242 = CYLINDRICAL_SURFACE ( 'NONE', #15296, 2.000000000000014655 ) ; +#5243 = CARTESIAN_POINT ( 'NONE', ( 3.667031087184732474, 183.8629715334667480, 103.2961752168644409 ) ) ; +#5244 = EDGE_CURVE ( 'NONE', #34253, #26260, #31815, .T. ) ; +#5245 = CONICAL_SURFACE ( 'NONE', #28136, 2.999999999884520374, 0.7853981634033615489 ) ; +#5246 = CARTESIAN_POINT ( 'NONE', ( 20.16676440252237157, 184.9321535431011228, 102.5067456869941651 ) ) ; +#5247 = FACE_OUTER_BOUND ( 'NONE', #29467, .T. ) ; +#5248 = CONICAL_SURFACE ( 'NONE', #22267, 2.502994210670941744, 0.7853981633984441491 ) ; +#5249 = CARTESIAN_POINT ( 'NONE', ( 13.46662727487878719, 154.4076626936201251, 95.29260641077831906 ) ) ; +#5250 = LINE ( 'NONE', #39390, #26002 ) ; +#5251 = DIRECTION ( 'NONE', ( -0.6087614115774878654, -0.7729348350621346730, -0.1788331191967953149 ) ) ; +#5252 = CARTESIAN_POINT ( 'NONE', ( 0.05300952315392960107, 83.21792371834001756, 87.76775236679999637 ) ) ; +#5253 = ORIENTED_EDGE ( 'NONE', *, *, #11627, .T. ) ; +#5254 = CARTESIAN_POINT ( 'NONE', ( -26.01077944034773282, 209.7097224531575534, 73.07398733611859143 ) ) ; +#5255 = CARTESIAN_POINT ( 'NONE', ( 3.952994205079280565, 144.1211950466918097, 93.35308613109434361 ) ) ; +#5256 = CARTESIAN_POINT ( 'NONE', ( -32.40504396064814330, 136.4748265295417582, 91.18018952198957550 ) ) ; +#5257 = EDGE_LOOP ( 'NONE', ( #14779, #6425, #5813, #25680 ) ) ; +#5258 = DIRECTION ( 'NONE', ( 0.0005884949961239157278, -0.2249510543439051935, 0.9743698870671265722 ) ) ; +#5259 = ORIENTED_EDGE ( 'NONE', *, *, #10906, .F. ) ; +#5260 = CARTESIAN_POINT ( 'NONE', ( -39.52796655470999809, 119.7636465605999945, 87.83956657257000700 ) ) ; +#5261 = CARTESIAN_POINT ( 'NONE', ( -16.42102836926336806, 151.9104391475223963, 184.3463035859948036 ) ) ; +#5262 = ORIENTED_EDGE ( 'NONE', *, *, #8756, .T. ) ; +#5263 = CARTESIAN_POINT ( 'NONE', ( 36.13238095029493735, 191.1563762242305131, 106.8320446025870893 ) ) ; +#5264 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33499, #39833, #14508, #26785 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5265 = CARTESIAN_POINT ( 'NONE', ( -5.669876942565291955, 126.8023652021145722, 88.92780583867599375 ) ) ; +#5266 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557957380992, -0.2249510932816513320 ) ) ; +#5267 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000094502, 179.7424522643958653, 101.1388664480904396 ) ) ; +#5268 = CARTESIAN_POINT ( 'NONE', ( 39.42035703641028022, 114.3667165859880015, 151.6079144922757109 ) ) ; +#5269 = CARTESIAN_POINT ( 'NONE', ( 6.039606680401115923, 177.7921203572399804, 100.6958205443672085 ) ) ; +#5270 = ORIENTED_EDGE ( 'NONE', *, *, #12049, .F. ) ; +#5271 = CIRCLE ( 'NONE', #3319, 2.499999999945343720 ) ; +#5272 = CARTESIAN_POINT ( 'NONE', ( 38.49152248112999786, 119.0204481247999979, 87.57880690499000309 ) ) ; +#5273 = AXIS2_PLACEMENT_3D ( 'NONE', #22791, #12982, #31796 ) ; +#5274 = DIRECTION ( 'NONE', ( -0.0005884949961250434064, 0.2249510543439061094, -0.9743698870671263501 ) ) ; +#5275 = CARTESIAN_POINT ( 'NONE', ( -35.96311564216326673, 218.5902260770998282, 61.08022271436995965 ) ) ; +#5276 = ADVANCED_FACE ( 'NONE', ( #27309 ), #19386, .T. ) ; +#5277 = CONICAL_SURFACE ( 'NONE', #11785, 6.499999999903893766, 0.7853981634197682027 ) ; +#5278 = VERTEX_POINT ( 'NONE', #26890 ) ; +#5279 = VECTOR ( 'NONE', #34277, 1000.000000000000114 ) ; +#5280 = DIRECTION ( 'NONE', ( -0.6087614115774879764, -0.7729348350621345620, -0.1788331191967953704 ) ) ; +#5281 = EDGE_LOOP ( 'NONE', ( #28177, #5863, #28718, #40358 ) ) ; +#5282 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; +#5283 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#5284 = DIRECTION ( 'NONE', ( 1.850371707731960504E-14, -1.000000000000000000, 1.387778780798970378E-14 ) ) ; +#5285 = CARTESIAN_POINT ( 'NONE', ( -41.29162907220920431, 121.2433985071746605, 87.66910399198238224 ) ) ; +#5286 = CARTESIAN_POINT ( 'NONE', ( -25.02141864464750753, 181.5306254107395887, 104.1434434358392735 ) ) ; +#5287 = EDGE_CURVE ( 'NONE', #25208, #21069, #25391, .T. ) ; +#5288 = CARTESIAN_POINT ( 'NONE', ( 36.05503269261969734, 112.4664341864257437, 89.74600809124632406 ) ) ; +#5289 = CARTESIAN_POINT ( 'NONE', ( -20.00017858637951207, 184.9560350789418237, 102.3655360699851400 ) ) ; +#5290 = CARTESIAN_POINT ( 'NONE', ( 3.499876110998302980, 184.0507947266270321, 102.4843871410976135 ) ) ; +#5291 = EDGE_CURVE ( 'NONE', #37651, #35508, #12227, .T. ) ; +#5292 = EDGE_CURVE ( 'NONE', #37091, #29223, #35033, .T. ) ; +#5293 = CARTESIAN_POINT ( 'NONE', ( -25.76767330085639429, 209.7106972169785877, 73.31640534608830251 ) ) ; +#5294 = EDGE_CURVE ( 'NONE', #25248, #7054, #40286, .T. ) ; +#5295 = CARTESIAN_POINT ( 'NONE', ( 6.037029121800269849, 176.9361410009001929, 103.3290594646711185 ) ) ; +#5296 = EDGE_CURVE ( 'NONE', #25074, #12430, #25045, .T. ) ; +#5297 = CARTESIAN_POINT ( 'NONE', ( -38.93814858684476121, 191.0388300950886560, 103.7812318162937686 ) ) ; +#5298 = CARTESIAN_POINT ( 'NONE', ( 38.96805248119999732, 118.9657793131000005, 89.82484713342999783 ) ) ; +#5299 = CARTESIAN_POINT ( 'NONE', ( 25.50964488085134008, 191.7826714808669237, 105.0633093220635033 ) ) ; +#5300 = CARTESIAN_POINT ( 'NONE', ( -42.47220679908992480, 189.9442792002049316, 106.2657712603332385 ) ) ; +#5301 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#5302 = FACE_OUTER_BOUND ( 'NONE', #2344, .T. ) ; +#5303 = AXIS2_PLACEMENT_3D ( 'NONE', #34869, #18730, #19547 ) ; +#5304 = CARTESIAN_POINT ( 'NONE', ( -20.49973909911777881, 191.9757886370473443, 104.4339460251406706 ) ) ; +#5305 = ORIENTED_EDGE ( 'NONE', *, *, #25685, .T. ) ; +#5306 = VERTEX_POINT ( 'NONE', #37486 ) ; +#5307 = CARTESIAN_POINT ( 'NONE', ( -16.55192910790513849, 122.5029194652213107, 174.6229610647038726 ) ) ; +#5308 = CONICAL_SURFACE ( 'NONE', #22315, 2.503000006812882816, 0.7853981634117586097 ) ; +#5309 = ORIENTED_EDGE ( 'NONE', *, *, #10406, .T. ) ; +#5310 = CARTESIAN_POINT ( 'NONE', ( -23.36089161421036309, 177.5428730706524334, 100.8660013147756302 ) ) ; +#5311 = DIRECTION ( 'NONE', ( 6.591949208711879581E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#5312 = ORIENTED_EDGE ( 'NONE', *, *, #23390, .T. ) ; +#5313 = ORIENTED_EDGE ( 'NONE', *, *, #34053, .F. ) ; +#5314 = LINE ( 'NONE', #36603, #33550 ) ; +#5315 = EDGE_CURVE ( 'NONE', #40156, #28075, #39048, .T. ) ; +#5316 = CARTESIAN_POINT ( 'NONE', ( -38.01211212650550664, 119.1971871873620472, 87.30118044812934386 ) ) ; +#5317 = CARTESIAN_POINT ( 'NONE', ( -23.36589107377781005, 134.9158523539519194, 90.81477344275025132 ) ) ; +#5318 = CARTESIAN_POINT ( 'NONE', ( 16.59040448417249891, 121.5622698803751121, 177.2309519810485767 ) ) ; +#5319 = ORIENTED_EDGE ( 'NONE', *, *, #28879, .T. ) ; +#5320 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620728018, 0.0004744508866335543488 ) ) ; +#5321 = ORIENTED_EDGE ( 'NONE', *, *, #16356, .T. ) ; +#5322 = DIRECTION ( 'NONE', ( -0.5988683521957647304, 0.8008474865655316188, 0.000000000000000000 ) ) ; +#5323 = CARTESIAN_POINT ( 'NONE', ( -44.77033340054011745, 167.6031324061906673, 188.6329174925582777 ) ) ; +#5324 = CARTESIAN_POINT ( 'NONE', ( -15.99998378297181745, 127.7446958148473186, 89.15477705487283799 ) ) ; +#5325 = CARTESIAN_POINT ( 'NONE', ( -12.63796699598845308, 181.2087211845504839, 104.4066993005394863 ) ) ; +#5326 = ORIENTED_EDGE ( 'NONE', *, *, #2009, .F. ) ; +#5327 = ORIENTED_EDGE ( 'NONE', *, *, #37158, .T. ) ; +#5328 = CARTESIAN_POINT ( 'NONE', ( -12.63662704360904065, 183.5606839279895155, 104.6046393389179059 ) ) ; +#5329 = CARTESIAN_POINT ( 'NONE', ( 0.7372372423313999779, 188.7528568893999932, 103.3644243068000179 ) ) ; +#5330 = CARTESIAN_POINT ( 'NONE', ( -35.46134654744881232, 192.4113187253241506, 106.9240966051354746 ) ) ; +#5331 = EDGE_CURVE ( 'NONE', #39755, #29108, #33098, .T. ) ; +#5332 = EDGE_LOOP ( 'NONE', ( #1258, #20466, #24460, #23207, #14639 ) ) ; +#5333 = CONICAL_SURFACE ( 'NONE', #749, 2.499989690268706877, 0.7853981633751526692 ) ; +#5334 = CARTESIAN_POINT ( 'NONE', ( 30.05533549523401149, 104.1131156702010969, 90.24963216969922541 ) ) ; +#5335 = VERTEX_POINT ( 'NONE', #34406 ) ; +#5336 = AXIS2_PLACEMENT_3D ( 'NONE', #38374, #37979, #19563 ) ; +#5337 = EDGE_CURVE ( 'NONE', #28941, #35790, #18547, .T. ) ; +#5338 = CONICAL_SURFACE ( 'NONE', #24957, 40.50000000000311928, 0.7853981633973105003 ) ; +#5339 = CARTESIAN_POINT ( 'NONE', ( -16.56444619814642394, 122.4978951069579125, 174.6020624745778491 ) ) ; +#5340 = EDGE_CURVE ( 'NONE', #6484, #407, #31167, .T. ) ; +#5341 = ORIENTED_EDGE ( 'NONE', *, *, #19591, .F. ) ; +#5342 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23527, #27021, #39659, #4708, #30077, #39256, #1855, #14334, #11461, #35763, #17979 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000003156364, 0.3750000000004984901, 0.4375000000005899170, 0.4687500000005980771, 0.5000000000006062928, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5343 = ORIENTED_EDGE ( 'NONE', *, *, #8121, .F. ) ; +#5344 = DIRECTION ( 'NONE', ( -0.0004161288024356094256, -0.5299192578742120130, -0.8480479980348188951 ) ) ; +#5345 = CARTESIAN_POINT ( 'NONE', ( -37.60604071504999979, 191.4600945531000207, 104.1578384304000053 ) ) ; +#5346 = DIRECTION ( 'NONE', ( -0.6087611427424929333, -0.7731004630501246977, -0.1781166615410725018 ) ) ; +#5347 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319384230599 ) ) ; +#5348 = ORIENTED_EDGE ( 'NONE', *, *, #25354, .F. ) ; +#5349 = CARTESIAN_POINT ( 'NONE', ( -6.035968307203201988, 174.6790541867032971, 103.0665008558034117 ) ) ; +#5350 = ORIENTED_EDGE ( 'NONE', *, *, #23458, .T. ) ; +#5351 = CARTESIAN_POINT ( 'NONE', ( 26.49737273317900232, 122.3640048392010016, 90.97099765724030362 ) ) ; +#5352 = CARTESIAN_POINT ( 'NONE', ( -35.55286435437628256, 191.9058181829571481, 103.9437009855516294 ) ) ; +#5354 = CARTESIAN_POINT ( 'NONE', ( -15.49852919254797179, 185.3436308334966895, 105.0179936564814511 ) ) ; +#5353 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927678092104, 0.0005734119022099723288 ) ) ; +#5355 = ORIENTED_EDGE ( 'NONE', *, *, #32402, .T. ) ; +#5356 = CARTESIAN_POINT ( 'NONE', ( 3.535986888874630196, 143.5554623264248733, 95.87208321593506355 ) ) ; +#5357 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26569, #23485, #39820, #3012, #11836, #27786, #27990, #5477, #30843, #27599, #27400, #30643 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000002464140, 0.3750000000003541056, 0.4375000000004172218, 0.4687500000004241607, 0.4843750000004030665, 0.5000000000003819167, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5358 = EDGE_LOOP ( 'NONE', ( #26687, #8427, #7870 ) ) ; +#5359 = CARTESIAN_POINT ( 'NONE', ( 19.99983023451520836, 117.9120932992704951, 87.25570489572297106 ) ) ; +#5360 = DIRECTION ( 'NONE', ( 0.0006039748319383107366, 1.234791622901071989E-14, 0.9999998176071845934 ) ) ; +#5361 = AXIS2_PLACEMENT_3D ( 'NONE', #12673, #33741, #33936 ) ; +#5362 = ORIENTED_EDGE ( 'NONE', *, *, #3858, .F. ) ; +#5364 = AXIS2_PLACEMENT_3D ( 'NONE', #21409, #28143, #6047 ) ; +#5363 = CARTESIAN_POINT ( 'NONE', ( -11.79201011660654785, 125.8410499982071400, 176.6171124943543873 ) ) ; +#5365 = AXIS2_PLACEMENT_3D ( 'NONE', #23608, #29545, #11549 ) ; +#5366 = DIRECTION ( 'NONE', ( -0.0005884950603321816021, 0.2249510543244929439, -0.9743698870715694627 ) ) ; +#5367 = CARTESIAN_POINT ( 'NONE', ( -33.33102413683000975, 226.1502260771000010, 73.32863523137000072 ) ) ; +#5368 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#5369 = ORIENTED_EDGE ( 'NONE', *, *, #15021, .F. ) ; +#5370 = VERTEX_POINT ( 'NONE', #28109 ) ; +#5371 = CARTESIAN_POINT ( 'NONE', ( -25.99272572791733182, 191.9759150222000130, 101.9371462953202609 ) ) ; +#5372 = CARTESIAN_POINT ( 'NONE', ( -38.93887205695440201, 183.6185768692615170, 102.5812822814675087 ) ) ; +#5373 = VERTEX_POINT ( 'NONE', #9900 ) ; +#5374 = FACE_OUTER_BOUND ( 'NONE', #3434, .T. ) ; +#5375 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35063, #740, #13621, #35456, #19932, #31839 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.006198667244160495360, 0.007464447912241703106, 0.008730228580322910853 ), + .UNSPECIFIED. ) ; +#5376 = EDGE_CURVE ( 'NONE', #16629, #21126, #5809, .T. ) ; +#5377 = EDGE_CURVE ( 'NONE', #39751, #27737, #9309, .T. ) ; +#5378 = EDGE_CURVE ( 'NONE', #33167, #3122, #16591, .T. ) ; +#5379 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22194, #38122, #6423, #34621, #3550, #10121, #35018, #3955, #19500, #31387 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5380 = ADVANCED_FACE ( 'NONE', ( #16010 ), #6597, .F. ) ; +#5381 = CARTESIAN_POINT ( 'NONE', ( 2.967800897092010448, 190.0831160609456276, 106.6319593653253719 ) ) ; +#5382 = ORIENTED_EDGE ( 'NONE', *, *, #23776, .T. ) ; +#5383 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#5384 = DIRECTION ( 'NONE', ( 0.0006039748319385908944, 1.293414132305980107E-14, 0.9999998176071845934 ) ) ; +#5385 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15923, #588, #28416, #12882, #19396, #29009, #25355, #16724, #3851, #19781, #29222, #25559, #37807, #9813, #34715, #6717, #32285, #1192, #19180, #16328 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999998811784, 0.1874999999998311906, 0.2187499999998049893, 0.2343749999998032130, 0.2499999999998014366, 0.4999999999998957501, 0.6249999999999429345, 0.6874999999999665823, 0.7187499999999783507, 0.7343749999999795719, 0.7499999999999809042, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5386 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; +#5387 = CARTESIAN_POINT ( 'NONE', ( 22.78281254372720355, 153.7346105515276804, 98.21050616309901216 ) ) ; +#5388 = ORIENTED_EDGE ( 'NONE', *, *, #15640, .T. ) ; +#5389 = AXIS2_PLACEMENT_3D ( 'NONE', #25102, #8755, #18927 ) ; +#5390 = LINE ( 'NONE', #20939, #13388 ) ; +#5391 = DIRECTION ( 'NONE', ( 0.6087614115774887535, 0.7729348350621332298, 0.1788331191967985623 ) ) ; +#5392 = EDGE_CURVE ( 'NONE', #22698, #5155, #21991, .T. ) ; +#5393 = AXIS2_PLACEMENT_3D ( 'NONE', #22025, #6066, #15281 ) ; +#5394 = ORIENTED_EDGE ( 'NONE', *, *, #34085, .F. ) ; +#5395 = CARTESIAN_POINT ( 'NONE', ( -5.668029527664558032, 188.1161524041082203, 103.2806162949214013 ) ) ; +#5396 = ORIENTED_EDGE ( 'NONE', *, *, #36012, .F. ) ; +#5398 = DIRECTION ( 'NONE', ( 0.1305262051638081400, -0.9658997602660276405, -0.2236080563923530939 ) ) ; +#5397 = FACE_OUTER_BOUND ( 'NONE', #11297, .T. ) ; +#5399 = ORIENTED_EDGE ( 'NONE', *, *, #19629, .F. ) ; +#5400 = EDGE_CURVE ( 'NONE', #10049, #4424, #15099, .T. ) ; +#5401 = ORIENTED_EDGE ( 'NONE', *, *, #395, .T. ) ; +#5402 = VERTEX_POINT ( 'NONE', #19272 ) ; +#5403 = CARTESIAN_POINT ( 'NONE', ( 2.351541002293000115, 209.4594558450999955, 75.42326402205000591 ) ) ; +#5404 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319380485765 ) ) ; +#5405 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#5406 = ORIENTED_EDGE ( 'NONE', *, *, #30788, .T. ) ; +#5407 = ORIENTED_EDGE ( 'NONE', *, *, #10705, .T. ) ; +#5408 = CARTESIAN_POINT ( 'NONE', ( 20.00192081821563761, 126.7670151487632353, 91.98617178303544506 ) ) ; +#5409 = ORIENTED_EDGE ( 'NONE', *, *, #7380, .F. ) ; +#5410 = VERTEX_POINT ( 'NONE', #1477 ) ; +#5411 = LINE ( 'NONE', #33008, #15249 ) ; +#5412 = FACE_OUTER_BOUND ( 'NONE', #8523, .T. ) ; +#5413 = DIRECTION ( 'NONE', ( 0.0005884949961299158110, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#5414 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319695600, 89.65051019401549581, 291.5295797804316180 ) ) ; +#5415 = VECTOR ( 'NONE', #18816, 1000.000000000000000 ) ; +#5416 = ORIENTED_EDGE ( 'NONE', *, *, #38665, .T. ) ; +#5417 = EDGE_LOOP ( 'NONE', ( #35754, #22565, #30953, #8626, #6229, #18770, #2772, #4800, #26250, #28550, #22265 ) ) ; +#5418 = DIRECTION ( 'NONE', ( -0.9999998268366113718, -0.0001323826667115919479, 0.0005734122222537812747 ) ) ; +#5419 = CARTESIAN_POINT ( 'NONE', ( -35.56489546672000301, 192.4169749659000104, 104.0136898731999935 ) ) ; +#5420 = DIRECTION ( 'NONE', ( -0.0005884949961251158311, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#5421 = ORIENTED_EDGE ( 'NONE', *, *, #28609, .F. ) ; +#5422 = VECTOR ( 'NONE', #18276, 1000.000000000000114 ) ; +#5423 = CARTESIAN_POINT ( 'NONE', ( -1.247069977563740384, 153.6904434798544514, 100.2674314307152628 ) ) ; +#5424 = FACE_OUTER_BOUND ( 'NONE', #31910, .T. ) ; +#5425 = ORIENTED_EDGE ( 'NONE', *, *, #17974, .T. ) ; +#5426 = CARTESIAN_POINT ( 'NONE', ( 2.607514698226610861, 189.6744051077729978, 103.4411355290657184 ) ) ; +#5427 = EDGE_CURVE ( 'NONE', #5601, #31792, #22968, .T. ) ; +#5428 = EDGE_CURVE ( 'NONE', #8771, #19923, #13963, .T. ) ; +#5429 = CARTESIAN_POINT ( 'NONE', ( 20.22996898690999856, 210.3997738015999914, 73.29629337437999936 ) ) ; +#5430 = CARTESIAN_POINT ( 'NONE', ( -3.857669709864375296, 167.8924508806730955, 101.1652248471848878 ) ) ; +#5431 = ORIENTED_EDGE ( 'NONE', *, *, #38889, .T. ) ; +#5432 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971546529 ) ) ; +#5433 = CARTESIAN_POINT ( 'NONE', ( 1.765308310976175799, 189.4019637521823824, 103.7997217045437992 ) ) ; +#5434 = PLANE ( 'NONE', #578 ) ; +#5435 = EDGE_CURVE ( 'NONE', #34827, #12793, #18467, .T. ) ; +#5436 = VERTEX_POINT ( 'NONE', #10699 ) ; +#5437 = CARTESIAN_POINT ( 'NONE', ( 35.93233219525675537, 108.6927157154615031, 168.7346187899305221 ) ) ; +#5438 = ORIENTED_EDGE ( 'NONE', *, *, #24583, .F. ) ; +#5439 = CARTESIAN_POINT ( 'NONE', ( 22.78222448783898813, 147.4012051316309737, 96.74832440307339709 ) ) ; +#5440 = CARTESIAN_POINT ( 'NONE', ( -2.373302774618340827, 209.5677226285648942, 73.55993759090392814 ) ) ; +#5441 = CARTESIAN_POINT ( 'NONE', ( 36.08146340137000152, 116.0255615537000011, 90.39360793564999597 ) ) ; +#5442 = EDGE_CURVE ( 'NONE', #35255, #30695, #32368, .T. ) ; +#5443 = CARTESIAN_POINT ( 'NONE', ( -21.48251327031369939, 213.0894491055004210, 75.57141013448118372 ) ) ; +#5444 = CIRCLE ( 'NONE', #4760, 2.499999999999997335 ) ; +#5445 = CARTESIAN_POINT ( 'NONE', ( -30.06407215524082943, 177.1126099298436714, 103.6397089757105192 ) ) ; +#5446 = ORIENTED_EDGE ( 'NONE', *, *, #27859, .F. ) ; +#5447 = CIRCLE ( 'NONE', #8042, 4.500000000492645036 ) ; +#5448 = CARTESIAN_POINT ( 'NONE', ( 2.896031416032872396, 196.4250263690624365, 103.8082216141275325 ) ) ; +#5449 = EDGE_CURVE ( 'NONE', #39374, #5743, #38038, .T. ) ; +#5450 = AXIS2_PLACEMENT_3D ( 'NONE', #12823, #37752, #31636 ) ; +#5451 = CARTESIAN_POINT ( 'NONE', ( -23.00078011532012212, 115.1133396198523968, 87.28167119284988473 ) ) ; +#5452 = PLANE ( 'NONE', #9462 ) ; +#5453 = FACE_OUTER_BOUND ( 'NONE', #29480, .T. ) ; +#5454 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; +#5455 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923337649, 151.9719590600774097, 94.73025963079751932 ) ) ; +#5456 = CARTESIAN_POINT ( 'NONE', ( -39.69719626944747404, 124.2805046067504122, 88.36931224150116293 ) ) ; +#5457 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25136, #3423, #28005, #37585 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5458 = DIRECTION ( 'NONE', ( 0.9999998176018447538, 2.041100424550427796E-09, -0.0006039836729574345631 ) ) ; +#5459 = DIRECTION ( 'NONE', ( 0.0002393071182784984501, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#5460 = ORIENTED_EDGE ( 'NONE', *, *, #32117, .T. ) ; +#5461 = CARTESIAN_POINT ( 'NONE', ( 27.07873119645540783, 119.5134203564188198, 171.3751642805570157 ) ) ; +#5462 = CARTESIAN_POINT ( 'NONE', ( -30.39593890779433494, 134.9159342868063902, 90.81907737499864197 ) ) ; +#5463 = ORIENTED_EDGE ( 'NONE', *, *, #21090, .T. ) ; +#5464 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999904787, 182.4172041435091955, 101.7781247866528531 ) ) ; +#5465 = VERTEX_POINT ( 'NONE', #28894 ) ; +#5466 = CARTESIAN_POINT ( 'NONE', ( -39.51669770417000649, 120.2152126645000010, 87.60169382661999293 ) ) ; +#5467 = CARTESIAN_POINT ( 'NONE', ( 25.51044001015309703, 191.4790671403759745, 106.3785283636754855 ) ) ; +#5468 = DIRECTION ( 'NONE', ( -0.0004161288024657918251, 0.8480480897829454356, -0.5299191110465040211 ) ) ; +#5469 = ORIENTED_EDGE ( 'NONE', *, *, #16529, .F. ) ; +#5470 = FACE_OUTER_BOUND ( 'NONE', #8860, .T. ) ; +#5471 = CARTESIAN_POINT ( 'NONE', ( 20.16676685501600019, 138.4782451641996488, 91.78201644681476523 ) ) ; +#5472 = DIRECTION ( 'NONE', ( -0.7856637149787868424, 0.6186538021912832974, 0.000000000000000000 ) ) ; +#5473 = ADVANCED_FACE ( 'NONE', ( #34994 ), #10303, .T. ) ; +#5474 = AXIS2_PLACEMENT_3D ( 'NONE', #28, #30719, #12490 ) ; +#5475 = EDGE_CURVE ( 'NONE', #16595, #23382, #30226, .T. ) ; +#5476 = CARTESIAN_POINT ( 'NONE', ( -12.16667563857975942, 125.0476480134844195, 178.7711262641263659 ) ) ; +#5477 = CARTESIAN_POINT ( 'NONE', ( -5.670789482781440682, 124.5559286933783483, 88.67279856817222594 ) ) ; +#5478 = VERTEX_POINT ( 'NONE', #29500 ) ; +#5479 = CARTESIAN_POINT ( 'NONE', ( 39.24285237467999821, 119.6631188639999976, 87.65313480276999769 ) ) ; +#5480 = CONICAL_SURFACE ( 'NONE', #33554, 2.503000000093201560, 0.7853981634628647290 ) ; +#5481 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; +#5482 = DIRECTION ( 'NONE', ( -0.7075229215369958080, -9.360719863004943371E-05, -0.7066903895889957710 ) ) ; +#5483 = DIRECTION ( 'NONE', ( 0.5635853613747644486, -0.8260577610420147820, -0.0003403914359935476352 ) ) ; +#5484 = ORIENTED_EDGE ( 'NONE', *, *, #19094, .F. ) ; +#5485 = FACE_OUTER_BOUND ( 'NONE', #276, .T. ) ; +#5486 = FACE_OUTER_BOUND ( 'NONE', #1489, .T. ) ; +#5487 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#5488 = CARTESIAN_POINT ( 'NONE', ( 2.941278393888057341, 209.7096877029368613, 73.05672770647804271 ) ) ; +#5489 = CARTESIAN_POINT ( 'NONE', ( -23.79325425886786505, 213.9958348113663646, 73.07287461175785381 ) ) ; +#5490 = DIRECTION ( 'NONE', ( -0.0005122663767566810198, 0.5297425686469459105, -0.8481583275229307439 ) ) ; +#5491 = CARTESIAN_POINT ( 'NONE', ( -25.63717913679842297, 209.7120637380510857, 73.44674248724354015 ) ) ; +#5492 = CARTESIAN_POINT ( 'NONE', ( 20.14857755624994340, 209.7095273962098645, 75.87932221801115418 ) ) ; +#5493 = EDGE_CURVE ( 'NONE', #20878, #37162, #10093, .T. ) ; +#5494 = CALENDAR_DATE ( 2025, 24, 6 ) ; +#5495 = CARTESIAN_POINT ( 'NONE', ( -23.05439898571000512, 211.0902260770999987, 13.53038997162000001 ) ) ; +#5496 = AXIS2_PLACEMENT_3D ( 'NONE', #14488, #26973, #10818 ) ; +#5497 = CARTESIAN_POINT ( 'NONE', ( 30.31510162847516909, 185.4752933756049629, 102.6260100505549104 ) ) ; +#5498 = CARTESIAN_POINT ( 'NONE', ( 25.50924745143719718, 191.9344736266071436, 104.4056993596765039 ) ) ; +#5499 = CARTESIAN_POINT ( 'NONE', ( -39.05638795867287882, 135.6127962752709095, 291.5821330148877450 ) ) ; +#5500 = CARTESIAN_POINT ( 'NONE', ( 2.547144911090980735, 209.7096538831000032, 78.05696658266604970 ) ) ; +#5501 = AXIS2_PLACEMENT_3D ( 'NONE', #29042, #22717, #619 ) ; +#5502 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971546529 ) ) ; +#5503 = VERTEX_POINT ( 'NONE', #7205 ) ; +#5504 = ORIENTED_EDGE ( 'NONE', *, *, #12830, .T. ) ; +#5505 = CARTESIAN_POINT ( 'NONE', ( -16.54674137764969899, 122.5082657265542849, 174.6175140616275883 ) ) ; +#5506 = VERTEX_POINT ( 'NONE', #26041 ) ; +#5507 = CARTESIAN_POINT ( 'NONE', ( 38.46700359482129272, 118.8212168396402717, 87.67371270529410765 ) ) ; +#5508 = EDGE_CURVE ( 'NONE', #15039, #13511, #7004, .T. ) ; +#5509 = FACE_OUTER_BOUND ( 'NONE', #27066, .T. ) ; +#5510 = CARTESIAN_POINT ( 'NONE', ( 56.51967809335915405, 71.57350793124206234, 282.5210433287024898 ) ) ; +#5511 = EDGE_LOOP ( 'NONE', ( #25686, #16343, #12509, #141 ) ) ; +#5512 = VERTEX_POINT ( 'NONE', #35595 ) ; +#5513 = CARTESIAN_POINT ( 'NONE', ( 15.50147166925602527, 127.1825504195482353, 91.57172455528431954 ) ) ; +#5514 = EDGE_CURVE ( 'NONE', #2544, #31532, #7612, .T. ) ; +#5515 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#5516 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#5517 = CARTESIAN_POINT ( 'NONE', ( 0.5641566756163646223, 188.3875244735902470, 106.2241826918301228 ) ) ; +#5518 = ORIENTED_EDGE ( 'NONE', *, *, #20373, .T. ) ; +#5519 = CARTESIAN_POINT ( 'NONE', ( 23.68458193633980713, 135.2968916886795228, 91.38751720632359365 ) ) ; +#5520 = DIRECTION ( 'NONE', ( 0.0004161288024633573576, -0.8480480897834431486, 0.5299191110457075471 ) ) ; +#5521 = CARTESIAN_POINT ( 'NONE', ( 23.36642197761798911, 177.0299567763120194, 103.4655879047946456 ) ) ; +#5522 = ADVANCED_FACE ( 'NONE', ( #23374 ), #39671, .F. ) ; +#5523 = EDGE_CURVE ( 'NONE', #35141, #5410, #20957, .T. ) ; +#5524 = DIRECTION ( 'NONE', ( 0.0005884949961229730140, -0.2249510543439056098, 0.9743698870671265722 ) ) ; +#5525 = CARTESIAN_POINT ( 'NONE', ( 36.37174737416455628, 116.2078075011454530, 90.24581721519344057 ) ) ; +#5526 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749105660, 132.4103119505516872, 92.77713868769167505 ) ) ; +#5527 = LOCAL_TIME ( 14, 25, 27.00000000000000000, #11652 ) ; +#5528 = VECTOR ( 'NONE', #34244, 999.9999999999998863 ) ; +#5529 = ADVANCED_FACE ( 'NONE', ( #39493 ), #11501, .F. ) ; +#5530 = VERTEX_POINT ( 'NONE', #11097 ) ; +#5531 = CARTESIAN_POINT ( 'NONE', ( -25.36909684671000065, 191.4049634124000079, 104.5096523423000008 ) ) ; +#5532 = FACE_OUTER_BOUND ( 'NONE', #2520, .T. ) ; +#5533 = VECTOR ( 'NONE', #31656, 1000.000000000000000 ) ; +#5534 = VECTOR ( 'NONE', #10677, 1000.000000000000114 ) ; +#5535 = CARTESIAN_POINT ( 'NONE', ( 26.00089628489983085, 120.1297184594761518, 90.45026046038573497 ) ) ; +#5536 = VERTEX_POINT ( 'NONE', #39290 ) ; +#5537 = VECTOR ( 'NONE', #39191, 1000.000000000000000 ) ; +#5538 = ORIENTED_EDGE ( 'NONE', *, *, #26400, .T. ) ; +#5539 = LINE ( 'NONE', #17998, #6776 ) ; +#5540 = ORIENTED_EDGE ( 'NONE', *, *, #27419, .T. ) ; +#5541 = EDGE_LOOP ( 'NONE', ( #2777, #5135, #30651, #13342 ) ) ; +#5542 = CARTESIAN_POINT ( 'NONE', ( -38.72644908288000209, 118.7070105194000007, 89.71289965706000658 ) ) ; +#5543 = ORIENTED_EDGE ( 'NONE', *, *, #29558, .F. ) ; +#5544 = CARTESIAN_POINT ( 'NONE', ( -35.95650388587999657, 192.3880382931000383, 106.6208529457999958 ) ) ; +#5545 = CARTESIAN_POINT ( 'NONE', ( 13.50012729195547934, 124.7429919913152929, 88.95710818440272760 ) ) ; +#5546 = CARTESIAN_POINT ( 'NONE', ( 35.54675198585685791, 209.7096512551739238, 76.03703539298859937 ) ) ; +#5547 = EDGE_CURVE ( 'NONE', #31532, #29127, #12923, .T. ) ; +#5548 = ORIENTED_EDGE ( 'NONE', *, *, #4917, .T. ) ; +#5549 = CARTESIAN_POINT ( 'NONE', ( 37.23595206341339292, 125.7280132836212090, 91.73594320339621788 ) ) ; +#5550 = ORIENTED_EDGE ( 'NONE', *, *, #40413, .F. ) ; +#5551 = CARTESIAN_POINT ( 'NONE', ( 26.34089362906999909, 122.4733679560000041, 90.82008448493999708 ) ) ; +#5552 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250100069, 179.6252109631261646, 101.6466942236143041 ) ) ; +#5554 = PLANE ( 'NONE', #20730 ) ; +#5553 = DIRECTION ( 'NONE', ( 0.0005884949961187157857, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#5555 = CONICAL_SURFACE ( 'NONE', #36255, 6.500000447167895601, 0.7853981634102744636 ) ; +#5556 = ORIENTED_EDGE ( 'NONE', *, *, #29532, .T. ) ; +#5557 = DIRECTION ( 'NONE', ( -0.7933533411653341805, -0.5931840316264885837, -0.1368326740407639630 ) ) ; +#5558 = CIRCLE ( 'NONE', #21249, 2.499999999950359264 ) ; +#5559 = CIRCLE ( 'NONE', #39499, 5.000000000000007994 ) ; +#5560 = ORIENTED_EDGE ( 'NONE', *, *, #12785, .F. ) ; +#5561 = EDGE_CURVE ( 'NONE', #4634, #29235, #20431, .T. ) ; +#5562 = CARTESIAN_POINT ( 'NONE', ( -25.50117313779839279, 120.2777482656007493, 87.94978106211669910 ) ) ; +#5563 = VECTOR ( 'NONE', #31686, 1000.000000000000114 ) ; +#5564 = ORIENTED_EDGE ( 'NONE', *, *, #1574, .F. ) ; +#5565 = CARTESIAN_POINT ( 'NONE', ( 0.04412548967591382182, 271.9029643396000324, 73.05847743168912700 ) ) ; +#5566 = EDGE_CURVE ( 'NONE', #35793, #21265, #21489, .T. ) ; +#5567 = DIRECTION ( 'NONE', ( 1.067522139063650355E-15, 0.9743700557921582961, 0.2249510932971566790 ) ) ; +#5568 = DIRECTION ( 'NONE', ( 0.0005884949961218503226, -0.2249510543439091348, 0.9743698870671257950 ) ) ; +#5569 = CARTESIAN_POINT ( 'NONE', ( 3.534327104360340588, 144.2236672556986434, 92.94748474794259607 ) ) ; +#5570 = CARTESIAN_POINT ( 'NONE', ( -12.64096629072132671, 135.0031918988153734, 90.94602447020258751 ) ) ; +#5571 = ADVANCED_FACE ( 'NONE', ( #21111 ), #20698, .T. ) ; +#5572 = ORIENTED_EDGE ( 'NONE', *, *, #124, .T. ) ; +#5573 = ORIENTED_EDGE ( 'NONE', *, *, #1047, .T. ) ; +#5574 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#5575 = EDGE_CURVE ( 'NONE', #5306, #28078, #9649, .T. ) ; +#5576 = CARTESIAN_POINT ( 'NONE', ( 26.90034969837000034, 124.4338129124000005, 88.87781188249999786 ) ) ; +#5577 = EDGE_CURVE ( 'NONE', #3576, #15604, #4864, .T. ) ; +#5578 = ORIENTED_EDGE ( 'NONE', *, *, #12097, .T. ) ; +#5579 = CARTESIAN_POINT ( 'NONE', ( 14.78718619285897518, 182.9114187639047486, 104.4381813414848779 ) ) ; +#5580 = EDGE_CURVE ( 'NONE', #14577, #5875, #3074, .T. ) ; +#5581 = CARTESIAN_POINT ( 'NONE', ( 1.064777206855000102, 189.0415535920000139, 105.7486712733000047 ) ) ; +#5582 = AXIS2_PLACEMENT_3D ( 'NONE', #9248, #27874, #21918 ) ; +#5583 = LINE ( 'NONE', #24005, #722 ) ; +#5584 = AXIS2_PLACEMENT_3D ( 'NONE', #36217, #1261, #20270 ) ; +#5585 = CARTESIAN_POINT ( 'NONE', ( 13.49905878177554364, 124.6099297501443317, 88.74416486964138073 ) ) ; +#5586 = CIRCLE ( 'NONE', #26415, 6.500001099658025083 ) ; +#5587 = FACE_OUTER_BOUND ( 'NONE', #3068, .T. ) ; +#5588 = DIRECTION ( 'NONE', ( -0.7947985590179719173, 0.5913221741348984040, 0.1365039814779489546 ) ) ; +#5589 = AXIS2_PLACEMENT_3D ( 'NONE', #15679, #29780, #7273 ) ; +#5590 = EDGE_LOOP ( 'NONE', ( #18035, #24839, #8901, #9170 ) ) ; +#5591 = FACE_OUTER_BOUND ( 'NONE', #2999, .T. ) ; +#5592 = VECTOR ( 'NONE', #30790, 1000.000000000000114 ) ; +#5593 = CARTESIAN_POINT ( 'NONE', ( 15.99974815555098218, 138.5019114137554936, 91.61902897505088106 ) ) ; +#5594 = CARTESIAN_POINT ( 'NONE', ( -31.70415073521903082, 226.4002260770974715, 75.57765305100397768 ) ) ; +#5595 = EDGE_LOOP ( 'NONE', ( #35106, #28631, #35319 ) ) ; +#5596 = CARTESIAN_POINT ( 'NONE', ( 29.77977117171763055, 126.9465717267340352, 89.45601389182257890 ) ) ; +#5597 = ORIENTED_EDGE ( 'NONE', *, *, #14768, .T. ) ; +#5599 = PLANE ( 'NONE', #1767 ) ; +#5598 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#5600 = ORIENTED_EDGE ( 'NONE', *, *, #13285, .F. ) ; +#5601 = VERTEX_POINT ( 'NONE', #5354 ) ; +#5602 = CARTESIAN_POINT ( 'NONE', ( -39.04920027559904838, 183.0116935643604563, 105.0069995834368228 ) ) ; +#5603 = ORIENTED_EDGE ( 'NONE', *, *, #5895, .T. ) ; +#5604 = EDGE_CURVE ( 'NONE', #1116, #8838, #14787, .T. ) ; +#5605 = CARTESIAN_POINT ( 'NONE', ( 2.828495721917000161, 209.6693846176999898, 75.93556339497999375 ) ) ; +#5606 = ADVANCED_FACE ( 'NONE', ( #1896 ), #28594, .F. ) ; +#5607 = AXIS2_PLACEMENT_3D ( 'NONE', #34076, #18522, #31031 ) ; +#5608 = FACE_OUTER_BOUND ( 'NONE', #32326, .T. ) ; +#5609 = CARTESIAN_POINT ( 'NONE', ( -19.73768723704201378, 124.3505960279316014, 178.1528323905962452 ) ) ; +#5610 = ADVANCED_FACE ( 'NONE', ( #2104 ), #5554, .T. ) ; +#5611 = CARTESIAN_POINT ( 'NONE', ( 3.534086375177905914, 137.3581944094399603, 91.36238397499714381 ) ) ; +#5612 = VERTEX_POINT ( 'NONE', #27060 ) ; +#5613 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #11736, #24222 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5614 = AXIS2_PLACEMENT_3D ( 'NONE', #21213, #33868, #33665 ) ; +#5615 = ORIENTED_EDGE ( 'NONE', *, *, #7829, .T. ) ; +#5616 = CARTESIAN_POINT ( 'NONE', ( -43.94897559503611717, 113.3760414272567658, 85.85438615327556988 ) ) ; +#5617 = VERTEX_POINT ( 'NONE', #17810 ) ; +#5618 = EDGE_LOOP ( 'NONE', ( #3910, #37937, #40251, #23418, #39200 ) ) ; +#5619 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -3.519737326604822600E-16, 0.0006039748319386522603 ) ) ; +#5620 = EDGE_CURVE ( 'NONE', #26666, #2464, #32764, .T. ) ; +#5621 = CARTESIAN_POINT ( 'NONE', ( -15.49970618472456074, 126.6879451655382809, 89.42365126055415203 ) ) ; +#5622 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#5623 = AXIS2_PLACEMENT_3D ( 'NONE', #21167, #33622, #15235 ) ; +#5624 = ADVANCED_FACE ( 'NONE', ( #14179 ), #26649, .T. ) ; +#5625 = VERTEX_POINT ( 'NONE', #9249 ) ; +#5626 = ORIENTED_EDGE ( 'NONE', *, *, #17035, .F. ) ; +#5627 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#5628 = CARTESIAN_POINT ( 'NONE', ( 37.31639193983529879, 111.9096183688354245, 150.0649592369359766 ) ) ; +#5629 = CARTESIAN_POINT ( 'NONE', ( -35.99558150418999958, 191.6334676936000108, 104.0208552518000005 ) ) ; +#5630 = ORIENTED_EDGE ( 'NONE', *, *, #22122, .T. ) ; +#5631 = CARTESIAN_POINT ( 'NONE', ( -14.31241256655965621, 191.5260885035135061, 103.8788496152396306 ) ) ; +#5632 = ORIENTED_EDGE ( 'NONE', *, *, #4188, .F. ) ; +#5633 = ADVANCED_FACE ( 'NONE', ( #37248 ), #21721, .T. ) ; +#5634 = ORIENTED_EDGE ( 'NONE', *, *, #14347, .F. ) ; +#5635 = LINE ( 'NONE', #15448, #13456 ) ; +#5636 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#5637 = ORIENTED_EDGE ( 'NONE', *, *, #13151, .F. ) ; +#5638 = CARTESIAN_POINT ( 'NONE', ( -0.4376666143244844487, 188.6124751099401351, 103.1978086576974221 ) ) ; +#5639 = CARTESIAN_POINT ( 'NONE', ( -14.46549242823763670, 124.5535847925790591, 88.41711846462007429 ) ) ; +#5640 = ADVANCED_FACE ( 'NONE', ( #33965 ), #2717, .F. ) ; +#5641 = PLANE ( 'NONE', #34833 ) ; +#5642 = CARTESIAN_POINT ( 'NONE', ( -38.95171367412964258, 118.8959113292413008, 89.72644992023717236 ) ) ; +#5643 = CARTESIAN_POINT ( 'NONE', ( 20.50086710772547249, 118.1127836709285077, 88.42196848232048012 ) ) ; +#5644 = VECTOR ( 'NONE', #37114, 1000.000000000000000 ) ; +#5645 = VERTEX_POINT ( 'NONE', #33768 ) ; +#5646 = DIRECTION ( 'NONE', ( 0.0006039748319378514686, 1.190362635753271326E-14, 0.9999998176071847045 ) ) ; +#5647 = ORIENTED_EDGE ( 'NONE', *, *, #14388, .T. ) ; +#5648 = VERTEX_POINT ( 'NONE', #11914 ) ; +#5649 = ORIENTED_EDGE ( 'NONE', *, *, #10944, .T. ) ; +#5650 = CARTESIAN_POINT ( 'NONE', ( -14.16977587005254158, 182.7576216332787737, 102.3675551592481696 ) ) ; +#5651 = VECTOR ( 'NONE', #22329, 1000.000000000000000 ) ; +#5652 = CARTESIAN_POINT ( 'NONE', ( -77.86614104348858234, 192.3476576144325350, 194.3451165138085912 ) ) ; +#5653 = VECTOR ( 'NONE', #3570, 999.9999999999998863 ) ; +#5654 = CARTESIAN_POINT ( 'NONE', ( 36.79269875112999699, 115.7237157444999980, 89.55271142270001405 ) ) ; +#5655 = CARTESIAN_POINT ( 'NONE', ( -27.41839611513448460, 124.6006531081595341, 91.00156934076623827 ) ) ; +#5656 = ORIENTED_EDGE ( 'NONE', *, *, #36113, .T. ) ; +#5657 = FACE_OUTER_BOUND ( 'NONE', #34842, .T. ) ; +#5658 = VECTOR ( 'NONE', #9172, 1000.000000000000000 ) ; +#5659 = PLANE ( 'NONE', #18726 ) ; +#5660 = ORIENTED_EDGE ( 'NONE', *, *, #23966, .F. ) ; +#5661 = CARTESIAN_POINT ( 'NONE', ( 37.40434350968867250, 145.4460227941551409, 282.5393146728916918 ) ) ; +#5662 = EDGE_CURVE ( 'NONE', #9884, #7887, #5822, .T. ) ; +#5663 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971581223 ) ) ; +#5664 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422595305, 173.8425259979994166, 102.8583906001885140 ) ) ; +#5665 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38855, #10871, #26614, #37021 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5666 = EDGE_CURVE ( 'NONE', #19822, #27218, #31263, .T. ) ; +#5667 = CARTESIAN_POINT ( 'NONE', ( 13.49999901743118969, 185.9104161957919530, 102.5624987652265645 ) ) ; +#5668 = EDGE_CURVE ( 'NONE', #39268, #17481, #11184, .T. ) ; +#5669 = CARTESIAN_POINT ( 'NONE', ( -39.52795649239820364, 119.7636651699444172, 87.83955215443023690 ) ) ; +#5670 = VERTEX_POINT ( 'NONE', #18218 ) ; +#5671 = VERTEX_POINT ( 'NONE', #25749 ) ; +#5672 = CARTESIAN_POINT ( 'NONE', ( 5.696483686681999892, 176.3366685932843154, 152.9217693939943388 ) ) ; +#5673 = DIRECTION ( 'NONE', ( 0.0005884949961234528818, -0.2249510543439066368, 0.9743698870671262391 ) ) ; +#5674 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10720, #26875, #33173, #32587 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5675 = CARTESIAN_POINT ( 'NONE', ( -19.32883136058536522, 148.6341161399039379, 180.6975394149132796 ) ) ; +#5676 = CARTESIAN_POINT ( 'NONE', ( -30.07831637853678686, 134.9151858147922667, 90.81876078434068233 ) ) ; +#5677 = CIRCLE ( 'NONE', #22675, 6.000000000000007994 ) ; +#5678 = ORIENTED_EDGE ( 'NONE', *, *, #37060, .T. ) ; +#5679 = DIRECTION ( 'NONE', ( 0.0005559617641631810821, -0.3907311284876849311, 0.9205046855596428212 ) ) ; +#5680 = CARTESIAN_POINT ( 'NONE', ( -22.99922046160000022, 115.1130721137993191, 90.28167579205376114 ) ) ; +#5681 = ORIENTED_EDGE ( 'NONE', *, *, #13249, .T. ) ; +#5682 = CARTESIAN_POINT ( 'NONE', ( -38.17065836694000325, 119.3614639495999938, 87.31205330151000510 ) ) ; +#5683 = AXIS2_PLACEMENT_3D ( 'NONE', #28790, #770, #32849 ) ; +#5684 = EDGE_CURVE ( 'NONE', #37846, #15841, #18416, .T. ) ; +#5685 = CARTESIAN_POINT ( 'NONE', ( -5.668533004880120352, 130.5151097924451733, 90.22088404420168217 ) ) ; +#5686 = VERTEX_POINT ( 'NONE', #15181 ) ; +#5687 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559851 ) ) ; +#5688 = VECTOR ( 'NONE', #2116, 1000.000000000000114 ) ; +#5689 = FACE_OUTER_BOUND ( 'NONE', #28900, .T. ) ; +#5690 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#5691 = CARTESIAN_POINT ( 'NONE', ( -19.99984748064912665, 127.7403057018771904, 89.15611954941233819 ) ) ; +#5692 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567068 ) ) ; +#5693 = EDGE_LOOP ( 'NONE', ( #10719, #10088, #39604, #40167 ) ) ; +#5694 = CARTESIAN_POINT ( 'NONE', ( 38.45096419866000304, 119.7540675949999951, 87.16908489566000640 ) ) ; +#5695 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#5696 = CARTESIAN_POINT ( 'NONE', ( 36.80935782333227735, 191.6100133775751146, 104.3431987054480459 ) ) ; +#5697 = ORIENTED_EDGE ( 'NONE', *, *, #20109, .F. ) ; +#5698 = CARTESIAN_POINT ( 'NONE', ( -46.07067374065479015, 125.2897427003481567, 91.71631631010059493 ) ) ; +#5699 = ORIENTED_EDGE ( 'NONE', *, *, #33075, .F. ) ; +#5700 = ORIENTED_EDGE ( 'NONE', *, *, #1156, .F. ) ; +#5701 = CARTESIAN_POINT ( 'NONE', ( 15.83511149127399698, 173.8757477943649974, 102.6937136768388257 ) ) ; +#5702 = CARTESIAN_POINT ( 'NONE', ( -43.37573184873028964, 120.5133568975543312, 91.89801145053407083 ) ) ; +#5703 = CARTESIAN_POINT ( 'NONE', ( 3.667815739887069881, 126.2406713584936568, 91.36142183053807742 ) ) ; +#5704 = DIRECTION ( 'NONE', ( 0.7933531821873445189, -0.5930539082291854669, -0.1373964710147356216 ) ) ; +#5705 = DIRECTION ( 'NONE', ( 0.0004161288024593278660, -0.8480480897937284768, 0.5299191110292476026 ) ) ; +#5706 = LINE ( 'NONE', #2656, #13641 ) ; +#5707 = VECTOR ( 'NONE', #8459, 1000.000000000000114 ) ; +#5708 = CARTESIAN_POINT ( 'NONE', ( 20.49908935505346719, 194.2769733015968541, 102.8866291927022303 ) ) ; +#5709 = CARTESIAN_POINT ( 'NONE', ( -35.44629553207012407, 109.6131156415000021, 90.28919351360151779 ) ) ; +#5710 = VECTOR ( 'NONE', #17709, 1000.000000000000000 ) ; +#5711 = PLANE ( 'NONE', #9594 ) ; +#5712 = DATE_AND_TIME ( #33504, #33599 ) ; +#5713 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; +#5714 = CARTESIAN_POINT ( 'NONE', ( -35.45668950278280818, 209.7096538831000032, 73.07991903448129278 ) ) ; +#5715 = CARTESIAN_POINT ( 'NONE', ( 16.85259243521460704, 122.7321277142430063, 172.1167388318093572 ) ) ; +#5716 = CARTESIAN_POINT ( 'NONE', ( -20.29046413099899127, 184.3514851594299273, 105.0052445737425586 ) ) ; +#5717 = CARTESIAN_POINT ( 'NONE', ( 25.99214295446221357, 205.1071317750680123, 76.08915132579089402 ) ) ; +#5718 = CARTESIAN_POINT ( 'NONE', ( 37.18342556898939932, 191.4809961130700344, 104.2937016655759805 ) ) ; +#5719 = EDGE_CURVE ( 'NONE', #27492, #31838, #18614, .T. ) ; +#5720 = VERTEX_POINT ( 'NONE', #36846 ) ; +#5721 = CARTESIAN_POINT ( 'NONE', ( 36.30754780179999841, 190.7605496600999970, 106.8997039823000108 ) ) ; +#5722 = ORIENTED_EDGE ( 'NONE', *, *, #17043, .F. ) ; +#5723 = ORIENTED_EDGE ( 'NONE', *, *, #10947, .T. ) ; +#5724 = DIRECTION ( 'NONE', ( -0.6087614115774880874, -0.7729348350621346730, -0.1788331191967949541 ) ) ; +#5725 = ORIENTED_EDGE ( 'NONE', *, *, #36215, .F. ) ; +#5726 = CARTESIAN_POINT ( 'NONE', ( 5.668111463870241451, 127.9108406804157454, 92.26213812171604900 ) ) ; +#5727 = FACE_BOUND ( 'NONE', #36456, .T. ) ; +#5728 = CARTESIAN_POINT ( 'NONE', ( 17.17601495924390775, 152.1789494465686516, 183.7587347276876812 ) ) ; +#5729 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#5730 = EDGE_LOOP ( 'NONE', ( #26613, #22029, #19134, #17066, #32985 ) ) ; +#5731 = CARTESIAN_POINT ( 'NONE', ( -39.44182108252999797, 119.8420607383000061, 90.56257358771001975 ) ) ; +#5732 = DIRECTION ( 'NONE', ( 1.156504871743948528E-16, 0.9743043966640312359, 0.2252353050503803078 ) ) ; +#5733 = CARTESIAN_POINT ( 'NONE', ( -20.51767729163077547, 205.5669979433283743, 76.31342074382325791 ) ) ; +#5734 = DIRECTION ( 'NONE', ( -0.0005884949961230158400, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#5735 = CARTESIAN_POINT ( 'NONE', ( -14.55294119842380063, 130.1498083917327904, 89.70916153464222020 ) ) ; +#5736 = ORIENTED_EDGE ( 'NONE', *, *, #2090, .T. ) ; +#5737 = CARTESIAN_POINT ( 'NONE', ( -35.95435800709800844, 218.5902260770999987, 75.58022006963935269 ) ) ; +#5738 = VECTOR ( 'NONE', #1810, 1000.000000000000114 ) ; +#5739 = CARTESIAN_POINT ( 'NONE', ( -19.46367937371129742, 126.2449231135791052, 175.9963188856066267 ) ) ; +#5740 = CYLINDRICAL_SURFACE ( 'NONE', #18928, 1.650000000000002798 ) ; +#5741 = VECTOR ( 'NONE', #16807, 1000.000000000000000 ) ; +#5742 = DIRECTION ( 'NONE', ( -0.1305262051639064502, 0.9658997602660150950, 0.2236080563923502629 ) ) ; +#5743 = VERTEX_POINT ( 'NONE', #16505 ) ; +#5744 = EDGE_LOOP ( 'NONE', ( #6873, #31869, #9717, #23290 ) ) ; +#5745 = EDGE_CURVE ( 'NONE', #34643, #29469, #35734, .T. ) ; +#5746 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498903273, 181.7471167548486903, 104.6805916159352137 ) ) ; +#5747 = CARTESIAN_POINT ( 'NONE', ( 0.5732654918656009402, 188.9939624363879886, 103.6998360806250048 ) ) ; +#5748 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#5749 = VERTEX_POINT ( 'NONE', #21531 ) ; +#5750 = ORIENTED_EDGE ( 'NONE', *, *, #40363, .F. ) ; +#5751 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391913256 ) ) ; +#5752 = ORIENTED_EDGE ( 'NONE', *, *, #36644, .F. ) ; +#5753 = CARTESIAN_POINT ( 'NONE', ( 25.49064341928363220, 210.1701501020666853, 73.54307249209045949 ) ) ; +#5754 = EDGE_CURVE ( 'NONE', #15470, #9488, #35067, .T. ) ; +#5755 = CARTESIAN_POINT ( 'NONE', ( -36.54980801557999825, 191.4575972176000391, 105.7985015051000062 ) ) ; +#5756 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173593504, 151.8558615133134708, 95.23291569143458446 ) ) ; +#5757 = CARTESIAN_POINT ( 'NONE', ( 21.33595229338290622, 124.0143879427035642, 174.3475635039766587 ) ) ; +#5758 = ORIENTED_EDGE ( 'NONE', *, *, #36505, .F. ) ; +#5759 = CARTESIAN_POINT ( 'NONE', ( 44.87942421866700471, 186.3432610492434662, 107.7775111143619142 ) ) ; +#5760 = CARTESIAN_POINT ( 'NONE', ( -3.169881662145332513, 128.5839160399947332, 89.34077473205128683 ) ) ; +#5761 = CARTESIAN_POINT ( 'NONE', ( -25.50006458888940131, 118.8155663869242886, 89.78318340809063614 ) ) ; +#5762 = ORIENTED_EDGE ( 'NONE', *, *, #18024, .F. ) ; +#5763 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#5764 = AXIS2_PLACEMENT_3D ( 'NONE', #37562, #6881, #748 ) ; +#5765 = CARTESIAN_POINT ( 'NONE', ( -35.66122680783149690, 191.7745722628655187, 103.9336186430080176 ) ) ; +#5766 = EDGE_CURVE ( 'NONE', #39184, #26493, #37039, .T. ) ; +#5767 = EDGE_CURVE ( 'NONE', #8220, #38190, #12305, .T. ) ; +#5768 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20427, #32907, #29857, #1839 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.003684369075596064403, 0.004391610989047198960 ), + .UNSPECIFIED. ) ; +#5770 = CARTESIAN_POINT ( 'NONE', ( 37.82238896534387607, 118.1203242141574918, 87.67403663391523594 ) ) ; +#5769 = DIRECTION ( 'NONE', ( 0.9999998268368104348, 0.0001323825905645391462, -0.0005734118926139947789 ) ) ; +#5771 = VERTEX_POINT ( 'NONE', #12496 ) ; +#5772 = ORIENTED_EDGE ( 'NONE', *, *, #34404, .T. ) ; +#5773 = CARTESIAN_POINT ( 'NONE', ( -37.56217811679143637, 145.6431275960571838, 282.5778664123586168 ) ) ; +#5774 = ORIENTED_EDGE ( 'NONE', *, *, #8636, .T. ) ; +#5775 = ORIENTED_EDGE ( 'NONE', *, *, #29219, .F. ) ; +#5776 = CARTESIAN_POINT ( 'NONE', ( 39.09835378390000216, 119.0620695200999961, 89.83136319784000534 ) ) ; +#5777 = LINE ( 'NONE', #24605, #25703 ) ; +#5778 = CARTESIAN_POINT ( 'NONE', ( -14.62254490296892406, 128.1170529630574606, 179.5121082275731794 ) ) ; +#5779 = DIRECTION ( 'NONE', ( 4.163336342344344915E-15, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#5780 = CARTESIAN_POINT ( 'NONE', ( 30.11206992270177807, 130.4288502407819692, 89.74660688778928375 ) ) ; +#5781 = CARTESIAN_POINT ( 'NONE', ( 25.50039747045966365, 119.1573732123225113, 89.75239197219917742 ) ) ; +#5782 = VERTEX_POINT ( 'NONE', #37446 ) ; +#5783 = EDGE_LOOP ( 'NONE', ( #38464, #33748, #26417, #34769 ) ) ; +#5784 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#5785 = FACE_OUTER_BOUND ( 'NONE', #34693, .T. ) ; +#5786 = ORIENTED_EDGE ( 'NONE', *, *, #25535, .F. ) ; +#5787 = AXIS2_PLACEMENT_3D ( 'NONE', #15726, #11879, #40261 ) ; +#5788 = CARTESIAN_POINT ( 'NONE', ( 35.63003517211246418, 209.7096550727324598, 75.95365185415883502 ) ) ; +#5789 = AXIS2_PLACEMENT_3D ( 'NONE', #2874, #15354, #40277 ) ; +#5790 = AXIS2_PLACEMENT_3D ( 'NONE', #18456, #15605, #12532 ) ; +#5791 = CARTESIAN_POINT ( 'NONE', ( 0.5640584298180999490, 188.5916829849000180, 106.0617877117999939 ) ) ; +#5792 = FACE_OUTER_BOUND ( 'NONE', #16554, .T. ) ; +#5793 = AXIS2_PLACEMENT_3D ( 'NONE', #18465, #15428, #12353 ) ; +#5794 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385907860 ) ) ; +#5795 = CARTESIAN_POINT ( 'NONE', ( -19.99799082025366204, 173.8313734241264967, 102.8761342917995734 ) ) ; +#5796 = CARTESIAN_POINT ( 'NONE', ( -24.30274708465592326, 117.2756935949167314, 170.8452364414067688 ) ) ; +#5797 = ADVANCED_FACE ( 'NONE', ( #21919 ), #7678, .T. ) ; +#5798 = ORIENTED_EDGE ( 'NONE', *, *, #12471, .T. ) ; +#5799 = CARTESIAN_POINT ( 'NONE', ( 25.99030006218819366, 209.2225090305980473, 73.04280209862368167 ) ) ; +#5800 = CARTESIAN_POINT ( 'NONE', ( -19.99827944177191341, 118.8155627782461181, 90.27982142893266371 ) ) ; +#5801 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142367503004439, 137.4659008082804519, 177.5714312369109393 ) ) ; +#5802 = ADVANCED_FACE ( 'NONE', ( #38395 ), #10799, .F. ) ; +#5803 = ORIENTED_EDGE ( 'NONE', *, *, #398, .F. ) ; +#5804 = CARTESIAN_POINT ( 'NONE', ( 28.46561332783693743, 183.4529609800732146, 105.0712386042130646 ) ) ; +#5805 = ORIENTED_EDGE ( 'NONE', *, *, #32312, .F. ) ; +#5806 = ADVANCED_FACE ( 'NONE', ( #32668 ), #24678, .T. ) ; +#5807 = EDGE_CURVE ( 'NONE', #15536, #14606, #26343, .T. ) ; +#5809 = LINE ( 'NONE', #18460, #25310 ) ; +#5808 = LINE ( 'NONE', #36273, #12221 ) ; +#5810 = ADVANCED_FACE ( 'NONE', ( #13658 ), #8991, .F. ) ; +#5811 = EDGE_LOOP ( 'NONE', ( #23345, #24443, #13633, #12618 ) ) ; +#5812 = AXIS2_PLACEMENT_3D ( 'NONE', #38795, #16914, #7724 ) ; +#5813 = ORIENTED_EDGE ( 'NONE', *, *, #35630, .F. ) ; +#5814 = CARTESIAN_POINT ( 'NONE', ( 25.49121397285902191, 206.8604079607866595, 74.53252332260622381 ) ) ; +#5815 = EDGE_CURVE ( 'NONE', #20529, #12363, #36414, .T. ) ; +#5816 = ORIENTED_EDGE ( 'NONE', *, *, #411, .F. ) ; +#5817 = CARTESIAN_POINT ( 'NONE', ( 3.183378028902000167, 209.2131121278000023, 76.25807972613000629 ) ) ; +#5818 = AXIS2_PLACEMENT_3D ( 'NONE', #8932, #39985, #30800 ) ; +#5819 = LINE ( 'NONE', #27716, #7876 ) ; +#5820 = CARTESIAN_POINT ( 'NONE', ( 12.64462803911309408, 177.7679548982654865, 100.7076870104759223 ) ) ; +#5821 = ORIENTED_EDGE ( 'NONE', *, *, #19804, .T. ) ; +#5822 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24399, #28797, #5770, #34167, #38203, #16314, #5965, #31123 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 4 ), + ( 0.000000000000000000, 1.269409900111855138E-06, 0.2500142417030432607, 0.5000095022491750640, 0.7500047627954068430, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5823 = EDGE_LOOP ( 'NONE', ( #2305, #5394 ) ) ; +#5824 = VECTOR ( 'NONE', #35739, 1000.000000000000114 ) ; +#5825 = EDGE_LOOP ( 'NONE', ( #36942, #1535, #20911, #38405, #1058, #19499 ) ) ; +#5826 = ORIENTED_EDGE ( 'NONE', *, *, #19600, .T. ) ; +#5827 = CARTESIAN_POINT ( 'NONE', ( -76.10777906860100472, 155.6779500220206387, 98.71888895707797928 ) ) ; +#5828 = CARTESIAN_POINT ( 'NONE', ( -15.49852919137054741, 126.2381079287689403, 91.37240600825562353 ) ) ; +#5829 = CARTESIAN_POINT ( 'NONE', ( -15.03362232203068771, 151.2943605774707407, 177.4366870137986609 ) ) ; +#5830 = ORIENTED_EDGE ( 'NONE', *, *, #11301, .F. ) ; +#5831 = EDGE_LOOP ( 'NONE', ( #30957, #11071, #12403, #5989 ) ) ; +#5832 = ORIENTED_EDGE ( 'NONE', *, *, #6211, .T. ) ; +#5833 = FACE_OUTER_BOUND ( 'NONE', #30484, .T. ) ; +#5834 = CARTESIAN_POINT ( 'NONE', ( -35.95668941153999754, 211.4999999999000124, 73.08022102179994306 ) ) ; +#5835 = DIRECTION ( 'NONE', ( 0.6773442687123943928, 0.7356661890031861439, 0.000000000000000000 ) ) ; +#5836 = CARTESIAN_POINT ( 'NONE', ( -27.65267440593000003, 124.6459337409000057, 88.44632915393999895 ) ) ; +#5837 = ORIENTED_EDGE ( 'NONE', *, *, #35780, .F. ) ; +#5838 = ORIENTED_EDGE ( 'NONE', *, *, #26407, .F. ) ; +#5839 = ADVANCED_FACE ( 'NONE', ( #7303 ), #37057, .T. ) ; +#5840 = CARTESIAN_POINT ( 'NONE', ( -21.10564552771868918, 182.7447230726116914, 104.5924260504270222 ) ) ; +#5841 = PLANE ( 'NONE', #27454 ) ; +#5842 = ORIENTED_EDGE ( 'NONE', *, *, #28086, .T. ) ; +#5843 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; +#5844 = CARTESIAN_POINT ( 'NONE', ( -15.99999440082457447, 126.8010213445309660, 88.93691041956509480 ) ) ; +#5845 = CARTESIAN_POINT ( 'NONE', ( 40.29675614866165745, 187.8287955346809213, 108.1243603913822824 ) ) ; +#5846 = CARTESIAN_POINT ( 'NONE', ( -15.49852918272448576, 137.6306203012457843, 94.00257521259531757 ) ) ; +#5847 = EDGE_CURVE ( 'NONE', #1172, #4372, #959, .T. ) ; +#5848 = VECTOR ( 'NONE', #8377, 1000.000000000000227 ) ; +#5849 = ORIENTED_EDGE ( 'NONE', *, *, #18889, .F. ) ; +#5850 = CARTESIAN_POINT ( 'NONE', ( 23.78175299703032408, 115.1895619078190833, 90.25342125631841839 ) ) ; +#5851 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#5852 = PLANE ( 'NONE', #10127 ) ; +#5853 = AXIS2_PLACEMENT_3D ( 'NONE', #10494, #22961, #26237 ) ; +#5854 = CARTESIAN_POINT ( 'NONE', ( 38.21082481197999670, 118.9849248355999976, 90.40249913504000290 ) ) ; +#5855 = EDGE_CURVE ( 'NONE', #5116, #13604, #19413, .T. ) ; +#5856 = CARTESIAN_POINT ( 'NONE', ( -29.66394945108131864, 181.9788733209050520, 101.6839728573242070 ) ) ; +#5857 = EDGE_LOOP ( 'NONE', ( #33533, #32165, #35246, #8949 ) ) ; +#5858 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#5859 = VERTEX_POINT ( 'NONE', #23068 ) ; +#5860 = EDGE_CURVE ( 'NONE', #3824, #3701, #5047, .T. ) ; +#5861 = FACE_OUTER_BOUND ( 'NONE', #33148, .T. ) ; +#5862 = ADVANCED_FACE ( 'NONE', ( #10402 ), #1374, .T. ) ; +#5863 = ORIENTED_EDGE ( 'NONE', *, *, #4453, .F. ) ; +#5864 = CARTESIAN_POINT ( 'NONE', ( 0.5623190733617040582, 188.6124699482102756, 103.1972064621602527 ) ) ; +#5865 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825881520, 173.9561929685035011, 102.3660449494794875 ) ) ; +#5866 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749098554, 132.4103119504792119, 92.77713868755240867 ) ) ; +#5867 = DIRECTION ( 'NONE', ( 0.0005884949961248158324, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#5868 = LINE ( 'NONE', #6262, #33683 ) ; +#5869 = VERTEX_POINT ( 'NONE', #36125 ) ; +#5871 = AXIS2_PLACEMENT_3D ( 'NONE', #29226, #6932, #16332 ) ; +#5870 = CARTESIAN_POINT ( 'NONE', ( -22.49975369487818710, 158.6756590294297382, 96.81282609783636417 ) ) ; +#5872 = CIRCLE ( 'NONE', #9151, 2.500000000000002220 ) ; +#5873 = CARTESIAN_POINT ( 'NONE', ( -26.74382575616715130, 120.3580507813137075, 171.5572023280520000 ) ) ; +#5874 = AXIS2_PLACEMENT_3D ( 'NONE', #30004, #20382, #4838 ) ; +#5875 = VERTEX_POINT ( 'NONE', #32272 ) ; +#5876 = CARTESIAN_POINT ( 'NONE', ( 30.06786877912685441, 134.3922893418122442, 93.61725361227318842 ) ) ; +#5877 = AXIS2_PLACEMENT_3D ( 'NONE', #33509, #36998, #39437 ) ; +#5878 = CARTESIAN_POINT ( 'NONE', ( -21.15906699444968453, 115.7109002682168466, 90.28056438547068296 ) ) ; +#5879 = ORIENTED_EDGE ( 'NONE', *, *, #38382, .T. ) ; +#5880 = CARTESIAN_POINT ( 'NONE', ( -2.937322199011638268, 191.1124755427409809, 103.7764892006471058 ) ) ; +#5881 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173423507, 174.4013293029843794, 100.4379480074635751 ) ) ; +#5882 = ORIENTED_EDGE ( 'NONE', *, *, #3615, .T. ) ; +#5883 = CARTESIAN_POINT ( 'NONE', ( -45.25641640995738868, 187.0376772300918162, 105.9402203223797585 ) ) ; +#5884 = FACE_OUTER_BOUND ( 'NONE', #10332, .T. ) ; +#5885 = CARTESIAN_POINT ( 'NONE', ( -38.16347685272999968, 118.8553488218999945, 90.29083592950999559 ) ) ; +#5886 = CARTESIAN_POINT ( 'NONE', ( 18.86495409459369199, 125.7426432556772937, 175.2080514493007399 ) ) ; +#5887 = CARTESIAN_POINT ( 'NONE', ( 3.312914662172945945, 125.9807902387186687, 88.73587715203963455 ) ) ; +#5888 = ORIENTED_EDGE ( 'NONE', *, *, #26086, .T. ) ; +#5889 = CARTESIAN_POINT ( 'NONE', ( 39.65541091293999898, 120.3034690318000060, 87.52491919870999482 ) ) ; +#5890 = CARTESIAN_POINT ( 'NONE', ( 30.80503333159449042, 110.6131156702000027, 89.74917927975997145 ) ) ; +#5891 = DIRECTION ( 'NONE', ( 0.0002267487151011638629, 0.6230052038431761474, 0.7822176580526309930 ) ) ; +#5892 = EDGE_CURVE ( 'NONE', #8895, #34116, #20384, .T. ) ; +#5893 = ADVANCED_FACE ( 'NONE', ( #29603 ), #25981, .F. ) ; +#5894 = CARTESIAN_POINT ( 'NONE', ( -16.26675888613999277, 147.1900965690931571, 179.8154315105366265 ) ) ; +#5895 = EDGE_CURVE ( 'NONE', #23591, #6503, #16102, .T. ) ; +#5896 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #2579, #9312 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5897 = ORIENTED_EDGE ( 'NONE', *, *, #15367, .F. ) ; +#5898 = PLANE ( 'NONE', #21189 ) ; +#5899 = ADVANCED_FACE ( 'NONE', ( #35492 ), #29410, .F. ) ; +#5900 = FACE_OUTER_BOUND ( 'NONE', #31378, .T. ) ; +#5901 = CARTESIAN_POINT ( 'NONE', ( -38.90873939381000213, 209.7096538831000032, 152.4718672074000381 ) ) ; +#5902 = CONICAL_SURFACE ( 'NONE', #34, 6.500002405954553808, 0.7853981634096851572 ) ; +#5903 = CARTESIAN_POINT ( 'NONE', ( -38.93887205695098430, 183.6185768681206696, 102.5812822866380429 ) ) ; +#5904 = EDGE_CURVE ( 'NONE', #37986, #38350, #30819, .T. ) ; +#5905 = CIRCLE ( 'NONE', #28758, 6.000000000022998492 ) ; +#5906 = VECTOR ( 'NONE', #24118, 999.9999999999998863 ) ; +#5907 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29608, #35502, #13861, #1185 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5908 = CARTESIAN_POINT ( 'NONE', ( 20.31497364642072512, 209.7094416523713107, 75.71273011267322772 ) ) ; +#5909 = EDGE_CURVE ( 'NONE', #8706, #15284, #24894, .T. ) ; +#5910 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 181.0156285263394409, 104.5149534146525951 ) ) ; +#5911 = CARTESIAN_POINT ( 'NONE', ( -14.16977588484152939, 129.7240516297933368, 90.12378855087145268 ) ) ; +#5912 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; +#5913 = CARTESIAN_POINT ( 'NONE', ( -20.51958837602166952, 211.0905570355220391, 74.23756124933424871 ) ) ; +#5914 = CARTESIAN_POINT ( 'NONE', ( 36.67803983362900055, 191.3737267936979833, 106.3776180154320201 ) ) ; +#5915 = CARTESIAN_POINT ( 'NONE', ( 36.74530222242999855, 191.5590816579000091, 106.2291238966000009 ) ) ; +#5916 = ORIENTED_EDGE ( 'NONE', *, *, #21926, .T. ) ; +#5917 = EDGE_LOOP ( 'NONE', ( #38129, #4733, #22457, #38667 ) ) ; +#5918 = EDGE_CURVE ( 'NONE', #37217, #22040, #33867, .T. ) ; +#5919 = FACE_OUTER_BOUND ( 'NONE', #31099, .T. ) ; +#5920 = FACE_OUTER_BOUND ( 'NONE', #39683, .T. ) ; +#5921 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#5922 = CARTESIAN_POINT ( 'NONE', ( 16.88646150490552955, 151.9945395218822739, 184.0188689872561554 ) ) ; +#5923 = CARTESIAN_POINT ( 'NONE', ( -32.07406512675382970, 176.8455996186746404, 100.5003186764579368 ) ) ; +#5924 = ORIENTED_EDGE ( 'NONE', *, *, #16133, .F. ) ; +#5925 = CARTESIAN_POINT ( 'NONE', ( -39.48405827645999722, 119.1504450973999951, 89.61452043577999405 ) ) ; +#5926 = CONICAL_SURFACE ( 'NONE', #35288, 2.503075499750329502, 0.7853981633711295540 ) ; +#5927 = CIRCLE ( 'NONE', #22923, 59.40509898897000340 ) ; +#5928 = CARTESIAN_POINT ( 'NONE', ( -22.49970497326267349, 138.0793299450762106, 92.05778796167568601 ) ) ; +#5929 = DIRECTION ( 'NONE', ( -0.6087611427445811518, -0.7731004622513008018, -0.1781166650011639652 ) ) ; +#5930 = EDGE_LOOP ( 'NONE', ( #34742, #3478, #32070, #14518 ) ) ; +#5931 = CARTESIAN_POINT ( 'NONE', ( 29.37172806597842722, 112.1957651408767873, 175.8423023756299131 ) ) ; +#5932 = AXIS2_PLACEMENT_3D ( 'NONE', #36897, #430, #21374 ) ; +#5933 = AXIS2_PLACEMENT_3D ( 'NONE', #27565, #31006, #2972 ) ; +#5934 = LINE ( 'NONE', #18389, #34819 ) ; +#5935 = DIRECTION ( 'NONE', ( 0.0004161288024595938208, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#5936 = DIRECTION ( 'NONE', ( 0.0004161288024539961934, 0.5299192578740949955, 0.8480479980348919478 ) ) ; +#5937 = LINE ( 'NONE', #15346, #16399 ) ; +#5938 = CARTESIAN_POINT ( 'NONE', ( 26.00352093159665756, 118.1131156702000169, 90.25513476933149093 ) ) ; +#5939 = ORIENTED_EDGE ( 'NONE', *, *, #22108, .F. ) ; +#5940 = ORIENTED_EDGE ( 'NONE', *, *, #15806, .F. ) ; +#5941 = CARTESIAN_POINT ( 'NONE', ( -27.97052338342000155, 187.2447426445999952, 103.2870855110000008 ) ) ; +#5942 = CARTESIAN_POINT ( 'NONE', ( 2.028511351659660455, 189.6362499608300141, 103.8782587184760189 ) ) ; +#5943 = FACE_OUTER_BOUND ( 'NONE', #5831, .T. ) ; +#5944 = EDGE_CURVE ( 'NONE', #33123, #28125, #6366, .T. ) ; +#5945 = VERTEX_POINT ( 'NONE', #39598 ) ; +#5946 = CARTESIAN_POINT ( 'NONE', ( -3.824228238827691584, 136.7434104837603002, 94.00818167131841108 ) ) ; +#5947 = EDGE_CURVE ( 'NONE', #14526, #11101, #2611, .T. ) ; +#5948 = EDGE_LOOP ( 'NONE', ( #12381, #36746, #36957, #22814 ) ) ; +#5949 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8368, #14710, #5072, #4872 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.749868521873144678, 3.288573094609483327 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8122409435129915867, 0.8122409435129915867, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#5950 = CC_DESIGN_PERSON_AND_ORGANIZATION_ASSIGNMENT ( #18158, #12060, ( #37519 ) ) ; +#5951 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921577410, 0.2249510932971593713 ) ) ; +#5952 = AXIS2_PLACEMENT_3D ( 'NONE', #27984, #24920, #5687 ) ; +#5953 = CARTESIAN_POINT ( 'NONE', ( 35.04675250840001155, 225.9002260768477583, 76.03733726937247184 ) ) ; +#5954 = CARTESIAN_POINT ( 'NONE', ( 42.46126417412090603, 102.4384360438650674, 173.5898619844123516 ) ) ; +#5955 = CARTESIAN_POINT ( 'NONE', ( 39.14109227172561134, 77.12646253814384067, 290.6753325472866436 ) ) ; +#5956 = CONICAL_SURFACE ( 'NONE', #19661, 7.003070832701193460, 0.7853905227103019637 ) ; +#5957 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749900286, 179.6299767372254621, 101.6260513916172670 ) ) ; +#5958 = CARTESIAN_POINT ( 'NONE', ( -36.13007122617000277, 190.7921904634999919, 106.9513591670999944 ) ) ; +#5959 = EDGE_LOOP ( 'NONE', ( #10864, #16900, #28610, #34071 ) ) ; +#5960 = CARTESIAN_POINT ( 'NONE', ( 13.49481983871936386, 124.3681642032378534, 88.35737770391504853 ) ) ; +#5961 = AXIS2_PLACEMENT_3D ( 'NONE', #12721, #15981, #446 ) ; +#5962 = FACE_OUTER_BOUND ( 'NONE', #30271, .T. ) ; +#5963 = CARTESIAN_POINT ( 'NONE', ( -14.55306305638819886, 182.5568561273574630, 101.8082842025129366 ) ) ; +#5965 = CARTESIAN_POINT ( 'NONE', ( 36.05207512480546939, 113.4195156597768062, 87.73930006848613061 ) ) ; +#5964 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -3.486209987973606947E-16, -0.0006039748319386279742 ) ) ; +#5966 = EDGE_LOOP ( 'NONE', ( #14795, #539, #18872, #2125, #28676 ) ) ; +#5967 = ORIENTED_EDGE ( 'NONE', *, *, #18525, .F. ) ; +#5968 = EDGE_CURVE ( 'NONE', #4945, #26517, #34068, .T. ) ; +#5969 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28853, #19632, #7767, #32128 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5970 = ORIENTED_EDGE ( 'NONE', *, *, #6163, .F. ) ; +#5971 = CARTESIAN_POINT ( 'NONE', ( 21.02805964049290210, 115.8422386153537218, 87.25508387092705220 ) ) ; +#5972 = EDGE_LOOP ( 'NONE', ( #33639, #39478, #3992, #39684 ) ) ; +#5973 = CARTESIAN_POINT ( 'NONE', ( -11.79202345736525892, 125.7774812735008254, 176.8918472601677365 ) ) ; +#5974 = CARTESIAN_POINT ( 'NONE', ( -40.95517856246386401, 220.4002260740000168, 75.58324044005986764 ) ) ; +#5975 = CARTESIAN_POINT ( 'NONE', ( 35.04645051036201409, 220.4002260771000010, 75.53733736045833780 ) ) ; +#5976 = CARTESIAN_POINT ( 'NONE', ( 25.50042068489791092, 119.4947997981225143, 89.79082806718720633 ) ) ; +#5977 = EDGE_LOOP ( 'NONE', ( #26616, #7154, #889, #26715 ) ) ; +#5978 = EDGE_LOOP ( 'NONE', ( #9525, #33678, #28269, #23564 ) ) ; +#5979 = CARTESIAN_POINT ( 'NONE', ( 33.42108704067000247, 226.1502260771000010, 75.78831908486999680 ) ) ; +#5980 = AXIS2_PLACEMENT_3D ( 'NONE', #9871, #7584, #34768 ) ; +#5981 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10044, #36690, #9856, #22327 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5982 = CARTESIAN_POINT ( 'NONE', ( 47.95588533879620741, 89.40266445833195519, 291.5248371983224729 ) ) ; +#5983 = ORIENTED_EDGE ( 'NONE', *, *, #8065, .T. ) ; +#5984 = CARTESIAN_POINT ( 'NONE', ( -36.51249493859999973, 191.4347527150000303, 106.3954561580000018 ) ) ; +#5985 = AXIS2_PLACEMENT_3D ( 'NONE', #4887, #29241, #1213 ) ; +#5986 = DIRECTION ( 'NONE', ( 0.0006039748319389448864, 1.387638830454547823E-14, 0.9999998176071845934 ) ) ; +#5987 = CARTESIAN_POINT ( 'NONE', ( -23.36052865740974838, 181.6105241605473282, 104.1608863659234885 ) ) ; +#5988 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39858, #36804, #8806, #21275, #933, #4397, #32232 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 4 ), + ( 0.0005016376834197731199, 0.001216693642771546954, 0.002475153169198318886 ), + .UNSPECIFIED. ) ; +#5989 = ORIENTED_EDGE ( 'NONE', *, *, #12151, .T. ) ; +#5990 = EDGE_CURVE ( 'NONE', #35941, #6111, #5250, .T. ) ; +#5991 = CARTESIAN_POINT ( 'NONE', ( 1.796908679885000026, 188.6799599361000048, 106.2909706032000088 ) ) ; +#5992 = EDGE_CURVE ( 'NONE', #28895, #9915, #36540, .T. ) ; +#5993 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#5994 = CARTESIAN_POINT ( 'NONE', ( -45.01543256409814120, 130.9257504736116289, 89.90670049556989341 ) ) ; +#5995 = DIRECTION ( 'NONE', ( -0.0005884949961203977085, 0.2249510542986902784, -0.9743698870775652221 ) ) ; +#5996 = DIRECTION ( 'NONE', ( 0.7764773693108221186, -0.5342314611987211137, -0.3341850397812930473 ) ) ; +#5997 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36541, #8340, #30420, #2207 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#5998 = VERTEX_POINT ( 'NONE', #11392 ) ; +#5999 = CARTESIAN_POINT ( 'NONE', ( -2.853038766185818087, 209.7096500570610544, 73.06022702708840200 ) ) ; +#6000 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#6001 = CARTESIAN_POINT ( 'NONE', ( -85.24348513260991922, 108.2328939675489039, 25.03902193712222513 ) ) ; +#6002 = EDGE_LOOP ( 'NONE', ( #14338, #13408, #4466 ) ) ; +#6003 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7730, #7327, #38603, #38799 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6004 = CARTESIAN_POINT ( 'NONE', ( 16.37235661304711698, 121.4990984041977669, 177.3555196612732914 ) ) ; +#6005 = ORIENTED_EDGE ( 'NONE', *, *, #2632, .F. ) ; +#6007 = CARTESIAN_POINT ( 'NONE', ( -3.169886429704571462, 127.9892485439772543, 89.20349298771401436 ) ) ; +#6006 = DIRECTION ( 'NONE', ( -0.0005884949961255136249, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#6008 = ORIENTED_EDGE ( 'NONE', *, *, #38008, .F. ) ; +#6009 = CIRCLE ( 'NONE', #19684, 2.000000000000011546 ) ; +#6010 = ORIENTED_EDGE ( 'NONE', *, *, #17784, .F. ) ; +#6011 = ADVANCED_FACE ( 'NONE', ( #12216 ), #24701, .T. ) ; +#6012 = AXIS2_PLACEMENT_3D ( 'NONE', #40396, #21420, #15075 ) ; +#6013 = LINE ( 'NONE', #37296, #28812 ) ; +#6014 = ORIENTED_EDGE ( 'NONE', *, *, #6613, .T. ) ; +#6015 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048993906, 181.0091974213519848, 104.5428127881224043 ) ) ; +#6016 = CARTESIAN_POINT ( 'NONE', ( -31.70566062302000887, 225.9002260770971873, 73.07765350693868811 ) ) ; +#6017 = CARTESIAN_POINT ( 'NONE', ( -3.786117645261999787, 171.3070458651999957, 102.0268941565000205 ) ) ; +#6018 = ORIENTED_EDGE ( 'NONE', *, *, #16645, .T. ) ; +#6019 = VERTEX_POINT ( 'NONE', #21628 ) ; +#6020 = EDGE_LOOP ( 'NONE', ( #29186, #25965, #2146, #40316 ) ) ; +#6021 = CARTESIAN_POINT ( 'NONE', ( 2.519724450483999956, 189.0000000000000000, 32.65697486330000032 ) ) ; +#6022 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#6023 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -3.869599770875634371E-16, -0.0006039748319386379488 ) ) ; +#6024 = CYLINDRICAL_SURFACE ( 'NONE', #30699, 1.749999999999998446 ) ; +#6025 = EDGE_LOOP ( 'NONE', ( #33784, #4352, #6859, #5399 ) ) ; +#6026 = EDGE_CURVE ( 'NONE', #12880, #18436, #34124, .T. ) ; +#6027 = ORIENTED_EDGE ( 'NONE', *, *, #21424, .T. ) ; +#6028 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319385907860 ) ) ; +#6029 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; +#6030 = VERTEX_POINT ( 'NONE', #30418 ) ; +#6031 = CARTESIAN_POINT ( 'NONE', ( 45.16687593781013277, 180.7102929186874576, 104.0827134509707719 ) ) ; +#6032 = EDGE_CURVE ( 'NONE', #8808, #1228, #6064, .T. ) ; +#6033 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364886824597, 136.5649596138813706, 181.4686487119530511 ) ) ; +#6034 = CARTESIAN_POINT ( 'NONE', ( -40.53910299374540926, 190.0772126196563931, 106.7391449377395958 ) ) ; +#6035 = ORIENTED_EDGE ( 'NONE', *, *, #15409, .T. ) ; +#6036 = AXIS2_PLACEMENT_3D ( 'NONE', #12035, #37175, #24518 ) ; +#6037 = CARTESIAN_POINT ( 'NONE', ( 0.2289920495087351959, 188.6124736079447928, 103.1974058479635374 ) ) ; +#6038 = EDGE_CURVE ( 'NONE', #32912, #7007, #11644, .T. ) ; +#6039 = CARTESIAN_POINT ( 'NONE', ( -15.69890139841092669, 125.5937060352607944, 88.65799436637878728 ) ) ; +#6040 = EDGE_CURVE ( 'NONE', #3145, #6533, #39049, .T. ) ; +#6041 = VECTOR ( 'NONE', #34175, 1000.000000000000114 ) ; +#6042 = EDGE_CURVE ( 'NONE', #27010, #30572, #24295, .T. ) ; +#6043 = CONICAL_SURFACE ( 'NONE', #28898, 2.250000000020516921, 0.7853981633778843729 ) ; +#6044 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#6045 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#6046 = ORIENTED_EDGE ( 'NONE', *, *, #7180, .F. ) ; +#6047 = DIRECTION ( 'NONE', ( 0.0006039748319386249384, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#6048 = VERTEX_POINT ( 'NONE', #12015 ) ; +#6049 = ORIENTED_EDGE ( 'NONE', *, *, #12450, .F. ) ; +#6050 = DIRECTION ( 'NONE', ( 4.139050213799733023E-13, 0.9743700557921592953, 0.2249510932971530708 ) ) ; +#6051 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; +#6052 = CARTESIAN_POINT ( 'NONE', ( 35.67718874540000229, 112.3973804366000167, 90.12490527673999452 ) ) ; +#6053 = CARTESIAN_POINT ( 'NONE', ( -29.47137614685608753, 181.8899047795460717, 101.6633165379169697 ) ) ; +#6054 = DIRECTION ( 'NONE', ( -0.7075227796380204603, 0.1590644278876734985, -0.6885564784925463089 ) ) ; +#6055 = ORIENTED_EDGE ( 'NONE', *, *, #5287, .F. ) ; +#6056 = CARTESIAN_POINT ( 'NONE', ( -37.83658322688275888, 190.9636381155321203, 106.3289620680116343 ) ) ; +#6057 = ORIENTED_EDGE ( 'NONE', *, *, #28657, .F. ) ; +#6058 = CARTESIAN_POINT ( 'NONE', ( -23.36190171889898082, 184.1216419186661710, 102.1748637788190450 ) ) ; +#6059 = CARTESIAN_POINT ( 'NONE', ( -38.03412148675000282, 118.9059103988000174, 90.43955447022000271 ) ) ; +#6060 = CARTESIAN_POINT ( 'NONE', ( 13.50029502672841275, 127.6322554542020100, 89.62414723470079991 ) ) ; +#6061 = ORIENTED_EDGE ( 'NONE', *, *, #9506, .F. ) ; +#6062 = FACE_OUTER_BOUND ( 'NONE', #6980, .T. ) ; +#6063 = DIRECTION ( 'NONE', ( -0.0005884949961236305826, 0.2249510543439055266, -0.9743698870671265722 ) ) ; +#6064 = LINE ( 'NONE', #33461, #28620 ) ; +#6065 = VECTOR ( 'NONE', #16464, 1000.000000000000114 ) ; +#6066 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#6067 = CARTESIAN_POINT ( 'NONE', ( -36.36961419606605972, 116.4217524378240824, 90.28975117483606994 ) ) ; +#6068 = VERTEX_POINT ( 'NONE', #36341 ) ; +#6069 = CARTESIAN_POINT ( 'NONE', ( -5.639490866605999742, 172.5096616001999905, 152.4718672074000381 ) ) ; +#6070 = FACE_OUTER_BOUND ( 'NONE', #33628, .T. ) ; +#6071 = ADVANCED_FACE ( 'NONE', ( #8339 ), #31900, .T. ) ; +#6072 = ORIENTED_EDGE ( 'NONE', *, *, #17515, .T. ) ; +#6073 = CARTESIAN_POINT ( 'NONE', ( 22.78079777786205540, 154.0096890380606851, 95.53720361524960936 ) ) ; +#6074 = DIRECTION ( 'NONE', ( -0.0005884949961279498272, 0.2249510543439066645, -0.9743698870671262391 ) ) ; +#6075 = ORIENTED_EDGE ( 'NONE', *, *, #36215, .T. ) ; +#6076 = DIRECTION ( 'NONE', ( -0.0005734119072324118244, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#6077 = ADVANCED_FACE ( 'NONE', ( #11812 ), #26670, .T. ) ; +#6078 = CARTESIAN_POINT ( 'NONE', ( -3.658524238769305548, 143.5629147409079849, 95.75245122380474072 ) ) ; +#6079 = ORIENTED_EDGE ( 'NONE', *, *, #10743, .T. ) ; +#6080 = CARTESIAN_POINT ( 'NONE', ( -38.54565956053704667, 119.1564759897554211, 90.30561907418552892 ) ) ; +#6081 = ADVANCED_FACE ( 'NONE', ( #33664 ), #6396, .F. ) ; +#6082 = CARTESIAN_POINT ( 'NONE', ( 3.645681218333928442, 167.8503244431992982, 101.3682716064896141 ) ) ; +#6083 = CARTESIAN_POINT ( 'NONE', ( -25.61249488107000261, 191.4936735446000000, 106.5346214470000064 ) ) ; +#6084 = CARTESIAN_POINT ( 'NONE', ( 30.07074129078960922, 176.7765392974760630, 103.0547703579528189 ) ) ; +#6085 = EDGE_CURVE ( 'NONE', #40349, #23346, #39479, .T. ) ; +#6086 = CARTESIAN_POINT ( 'NONE', ( 3.166350953592421025, 126.8041585549839709, 88.92605846951083493 ) ) ; +#6087 = ADVANCED_FACE ( 'NONE', ( #13015 ), #40402, .F. ) ; +#6088 = ORIENTED_EDGE ( 'NONE', *, *, #14347, .T. ) ; +#6089 = CARTESIAN_POINT ( 'NONE', ( 3.534327104360340588, 144.2236672556986434, 92.94748474794259607 ) ) ; +#6090 = CARTESIAN_POINT ( 'NONE', ( 37.34687875379296429, 164.7440994830517411, 197.7708186323690995 ) ) ; +#6091 = CIRCLE ( 'NONE', #22419, 2.000000001263195770 ) ; +#6092 = CARTESIAN_POINT ( 'NONE', ( -15.94446068766880487, 121.2107412334159591, 177.4020268254936923 ) ) ; +#6093 = CARTESIAN_POINT ( 'NONE', ( 20.33359772957916789, 151.9013818374707796, 95.05201010367687786 ) ) ; +#6094 = ORIENTED_EDGE ( 'NONE', *, *, #27288, .T. ) ; +#6095 = CIRCLE ( 'NONE', #222, 6.500001124525312868 ) ; +#6096 = LINE ( 'NONE', #30453, #3530 ) ; +#6097 = CARTESIAN_POINT ( 'NONE', ( 19.62707591446529065, 149.3912708485596568, 181.6576907650956230 ) ) ; +#6098 = CARTESIAN_POINT ( 'NONE', ( 24.26115219290281644, 213.8084469570644046, 73.04385095440355258 ) ) ; +#6099 = CARTESIAN_POINT ( 'NONE', ( 19.98059076253610300, 209.7097557544199162, 73.04669817794425057 ) ) ; +#6100 = VECTOR ( 'NONE', #17581, 1000.000000000000000 ) ; +#6101 = CARTESIAN_POINT ( 'NONE', ( -25.50198239243739806, 190.9621235434596542, 106.3177461849878114 ) ) ; +#6102 = CARTESIAN_POINT ( 'NONE', ( 44.91030012776904812, 180.8423815822312974, 104.4554649243456339 ) ) ; +#6103 = CARTESIAN_POINT ( 'NONE', ( -12.63885905074691252, 181.8641958648152013, 101.8896919015048042 ) ) ; +#6104 = DATE_AND_TIME ( #30247, #9447 ) ; +#6105 = CYLINDRICAL_SURFACE ( 'NONE', #27887, 4.999999999999990230 ) ; +#6106 = CARTESIAN_POINT ( 'NONE', ( 25.05527577951534468, 181.6921585128408765, 101.5847744912912418 ) ) ; +#6107 = LINE ( 'NONE', #15520, #18535 ) ; +#6108 = CARTESIAN_POINT ( 'NONE', ( 20.00016034875645943, 127.4394136103090887, 89.06260552501319694 ) ) ; +#6109 = CARTESIAN_POINT ( 'NONE', ( 37.18424073381000028, 191.2020551955000087, 105.6433944051999987 ) ) ; +#6110 = CARTESIAN_POINT ( 'NONE', ( 35.79896412904000158, 191.3773265435000042, 107.0072713659999977 ) ) ; +#6111 = VERTEX_POINT ( 'NONE', #3189 ) ; +#6112 = VERTEX_POINT ( 'NONE', #3580 ) ; +#6113 = CARTESIAN_POINT ( 'NONE', ( 15.95616423589712340, 121.8747789553152785, 174.5819126748912709 ) ) ; +#6114 = VECTOR ( 'NONE', #7998, 1000.000000000000000 ) ; +#6115 = CARTESIAN_POINT ( 'NONE', ( -20.18830040110167090, 184.9181145972527531, 102.5501949385248679 ) ) ; +#6116 = VECTOR ( 'NONE', #177, 1000.000000000000227 ) ; +#6117 = EDGE_CURVE ( 'NONE', #20878, #32946, #37742, .T. ) ; +#6118 = EDGE_CURVE ( 'NONE', #1973, #30537, #9662, .T. ) ; +#6119 = FACE_OUTER_BOUND ( 'NONE', #9003, .T. ) ; +#6120 = CARTESIAN_POINT ( 'NONE', ( -29.91365887524281320, 126.3524082176346610, 91.57855139315392989 ) ) ; +#6121 = EDGE_CURVE ( 'NONE', #24812, #12942, #34258, .T. ) ; +#6122 = AXIS2_PLACEMENT_3D ( 'NONE', #4196, #15532, #29369 ) ; +#6123 = VERTEX_POINT ( 'NONE', #3785 ) ; +#6124 = CARTESIAN_POINT ( 'NONE', ( 16.84438044484771879, 125.8148033517563249, 178.9876133819932136 ) ) ; +#6125 = CARTESIAN_POINT ( 'NONE', ( -42.36701999636228777, 171.7704926474248737, 184.4650328233902599 ) ) ; +#6126 = CARTESIAN_POINT ( 'NONE', ( -20.00074514949506010, 193.6646176325368458, 103.0738027862439310 ) ) ; +#6127 = CARTESIAN_POINT ( 'NONE', ( 17.33132192515028436, 121.2638944594648791, 177.4233360669502133 ) ) ; +#6128 = VERTEX_POINT ( 'NONE', #25497 ) ; +#6129 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6130 = DIRECTION ( 'NONE', ( -0.0004161288024517756931, 0.8480480897992000999, -0.5299191110204911626 ) ) ; +#6131 = CARTESIAN_POINT ( 'NONE', ( 20.53365435870338018, 147.8783930214090390, 152.4730821390034805 ) ) ; +#6132 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17996, #14151, #39881, #5330, #24168, #11477, #30500, #2282, #33339, #36623, #7791, #36206, #8208, #27037, #20676, #17788, #20258, #5119, #33135, #39272, #23961, #17590, #30283 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 2, 1, 2, 2, 2, 2, 2, 1, 4 ), + ( 0.000000000000000000, 0.1249999999999444888, 0.1874999999999157618, 0.2499999999998870348, 0.3749999999998629430, 0.4374999999998688827, 0.4687499999998721023, 0.4999999999998753220, 0.7499999999998643307, 0.7812499999998687716, 0.8124999999998732125, 0.8749999999999034106, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6133 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#6134 = ADVANCED_FACE ( 'NONE', ( #16262 ), #3385, .F. ) ; +#6135 = VERTEX_POINT ( 'NONE', #2992 ) ; +#6136 = LINE ( 'NONE', #28823, #37642 ) ; +#6137 = CARTESIAN_POINT ( 'NONE', ( 2.723234776511000099, 191.0360723070999995, 104.1040072879000036 ) ) ; +#6138 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#6139 = ORIENTED_EDGE ( 'NONE', *, *, #863, .F. ) ; +#6140 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#6141 = ORIENTED_EDGE ( 'NONE', *, *, #34991, .T. ) ; +#6142 = EDGE_CURVE ( 'NONE', #29201, #38952, #11620, .T. ) ; +#6143 = LINE ( 'NONE', #809, #7390 ) ; +#6144 = VECTOR ( 'NONE', #10434, 1000.000000000000114 ) ; +#6145 = AXIS2_PLACEMENT_3D ( 'NONE', #11195, #5039, #30000 ) ; +#6146 = CARTESIAN_POINT ( 'NONE', ( 20.00118831922474527, 194.3293166618819612, 106.3477151517464421 ) ) ; +#6147 = CIRCLE ( 'NONE', #31648, 1.999999999520721161 ) ; +#6148 = CARTESIAN_POINT ( 'NONE', ( -36.23924049691999727, 191.8477165461999903, 104.2143108436000034 ) ) ; +#6149 = CARTESIAN_POINT ( 'NONE', ( -17.09037752892578865, 152.4702182831101709, 182.2569833114785069 ) ) ; +#6150 = DIRECTION ( 'NONE', ( 0.0006039748319382907873, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#6151 = CARTESIAN_POINT ( 'NONE', ( 23.67998985452990368, 134.9222885997251637, 90.78792508986444432 ) ) ; +#6152 = CARTESIAN_POINT ( 'NONE', ( -37.02430110774999861, 191.2881234072000041, 106.2406684328999944 ) ) ; +#6153 = EDGE_LOOP ( 'NONE', ( #24792, #36700, #3111, #30133 ) ) ; +#6154 = FACE_OUTER_BOUND ( 'NONE', #5823, .T. ) ; +#6155 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13702, #10645, #7553, #33102, #7752, #20023, #38826, #30249, #34110, #27208 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999995559, 0.4999999999999991118, 0.7499999999999995559, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6156 = CARTESIAN_POINT ( 'NONE', ( -35.98778029410813417, 191.5265872904686830, 103.8920147005603951 ) ) ; +#6157 = CARTESIAN_POINT ( 'NONE', ( 33.97007310651787293, 92.28421717967789561, 297.5380279566514901 ) ) ; +#6159 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#6158 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; +#6160 = EDGE_LOOP ( 'NONE', ( #6817, #37546, #40431 ) ) ; +#6161 = ORIENTED_EDGE ( 'NONE', *, *, #21370, .T. ) ; +#6162 = EDGE_CURVE ( 'NONE', #33088, #39067, #17248, .T. ) ; +#6163 = EDGE_CURVE ( 'NONE', #26442, #30446, #32421, .T. ) ; +#6164 = ORIENTED_EDGE ( 'NONE', *, *, #7353, .F. ) ; +#6165 = EDGE_CURVE ( 'NONE', #12599, #15031, #11144, .T. ) ; +#6166 = EDGE_LOOP ( 'NONE', ( #14043, #29546, #20434, #25121 ) ) ; +#6167 = CARTESIAN_POINT ( 'NONE', ( 8.330750903747036418, 160.8464898286100322, 99.51904042281638851 ) ) ; +#6168 = CARTESIAN_POINT ( 'NONE', ( 26.71438282722398938, 124.3231695455690442, 88.85220642046358819 ) ) ; +#6169 = LINE ( 'NONE', #15573, #25898 ) ; +#6170 = CARTESIAN_POINT ( 'NONE', ( 39.31311957223007880, 119.5494579213072370, 87.74834752111200942 ) ) ; +#6171 = CARTESIAN_POINT ( 'NONE', ( 30.81681382182493678, 129.4130655731118509, 89.51166882856213647 ) ) ; +#6172 = AXIS2_PLACEMENT_3D ( 'NONE', #13397, #17031, #25885 ) ; +#6173 = CIRCLE ( 'NONE', #4848, 2.499999999897516645 ) ; +#6174 = CARTESIAN_POINT ( 'NONE', ( -12.63880466802784319, 135.2324181042121438, 91.31286148751507881 ) ) ; +#6175 = VERTEX_POINT ( 'NONE', #23416 ) ; +#6176 = DIRECTION ( 'NONE', ( 0.0005884949961226190220, -0.2249510543439057486, 0.9743698870671265722 ) ) ; +#6177 = VERTEX_POINT ( 'NONE', #32025 ) ; +#6178 = CARTESIAN_POINT ( 'NONE', ( 1.222756100067673213, 143.4876838778120884, 158.5675586475568366 ) ) ; +#6179 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #10193, #32258, #16696, #29197 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.712388980384698556, 6.103777378942509380 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8450726411000299976, 0.8450726411000299976, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#6180 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#6181 = ADVANCED_FACE ( 'NONE', ( #4180 ), #35855, .F. ) ; +#6182 = ORIENTED_EDGE ( 'NONE', *, *, #12041, .F. ) ; +#6183 = CARTESIAN_POINT ( 'NONE', ( 35.91764861553071597, 209.7096530691624139, 75.66569077816501476 ) ) ; +#6184 = CARTESIAN_POINT ( 'NONE', ( 2.623782561446397654, 189.6978541430437417, 103.4465393410279717 ) ) ; +#6185 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191947214049181, 0.8480481395922153665 ) ) ; +#6186 = FACE_OUTER_BOUND ( 'NONE', #23889, .T. ) ; +#6187 = ORIENTED_EDGE ( 'NONE', *, *, #123, .F. ) ; +#6188 = CARTESIAN_POINT ( 'NONE', ( 2.325038912688802473, 189.0644929844613387, 106.3859680065207982 ) ) ; +#6189 = VERTEX_POINT ( 'NONE', #19720 ) ; +#6190 = EDGE_CURVE ( 'NONE', #40149, #7358, #32599, .T. ) ; +#6191 = CARTESIAN_POINT ( 'NONE', ( 41.04524146632582671, 220.4002260741250154, 73.53371387615798938 ) ) ; +#6192 = CARTESIAN_POINT ( 'NONE', ( 36.15379333015832941, 191.4992728616623765, 103.8421784115979563 ) ) ; +#6193 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6194 = ORIENTED_EDGE ( 'NONE', *, *, #18740, .T. ) ; +#6195 = CARTESIAN_POINT ( 'NONE', ( 23.35635955975471134, 181.6919812636757285, 101.5857449861623110 ) ) ; +#6196 = CARTESIAN_POINT ( 'NONE', ( -20.04876416055233435, 127.0750181908596517, 92.02969372391483205 ) ) ; +#6197 = AXIS2_PLACEMENT_3D ( 'NONE', #26274, #38711, #23198 ) ; +#6198 = AXIS2_PLACEMENT_3D ( 'NONE', #20566, #29984, #14449 ) ; +#6199 = ORIENTED_EDGE ( 'NONE', *, *, #27291, .T. ) ; +#6200 = CARTESIAN_POINT ( 'NONE', ( -5.668307419685251425, 188.0500116628189744, 103.3219457577105800 ) ) ; +#6201 = ORIENTED_EDGE ( 'NONE', *, *, #35683, .F. ) ; +#6202 = CIRCLE ( 'NONE', #29067, 6.500000000014392043 ) ; +#6204 = CARTESIAN_POINT ( 'NONE', ( 0.5625159773845863631, 188.8708249854730354, 103.5219946925948591 ) ) ; +#6203 = DIRECTION ( 'NONE', ( -0.0005884949961159111715, 0.2249510543439030286, -0.9743698870671271273 ) ) ; +#6205 = EDGE_LOOP ( 'NONE', ( #2441, #25111, #24247, #24960, #2468, #33938, #10568, #296, #15964, #3962, #13991 ) ) ; +#6206 = VERTEX_POINT ( 'NONE', #7865 ) ; +#6207 = ORIENTED_EDGE ( 'NONE', *, *, #35203, .F. ) ; +#6208 = CARTESIAN_POINT ( 'NONE', ( 2.584181958089999842, 209.5884796122000182, 75.67830153580999308 ) ) ; +#6209 = CARTESIAN_POINT ( 'NONE', ( 41.83291673182624493, 184.0748290677734929, 107.2083188323588132 ) ) ; +#6210 = PLANE ( 'NONE', #35796 ) ; +#6211 = EDGE_CURVE ( 'NONE', #14392, #39304, #23018, .T. ) ; +#6212 = VERTEX_POINT ( 'NONE', #38727 ) ; +#6213 = ADVANCED_FACE ( 'NONE', ( #26695 ), #7058, .F. ) ; +#6214 = ORIENTED_EDGE ( 'NONE', *, *, #9410, .T. ) ; +#6215 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#6216 = CARTESIAN_POINT ( 'NONE', ( -19.73786857073881151, 124.3510898702264171, 178.1525024657645986 ) ) ; +#6217 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; +#6218 = CARTESIAN_POINT ( 'NONE', ( -23.36170564740000088, 182.0604262666973341, 102.2121465930607371 ) ) ; +#6219 = ORIENTED_EDGE ( 'NONE', *, *, #27501, .F. ) ; +#6220 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15174, #11493, #31308, #22109 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6221 = ORIENTED_EDGE ( 'NONE', *, *, #27831, .T. ) ; +#6222 = CARTESIAN_POINT ( 'NONE', ( -23.36013623391100325, 183.4467887557270842, 105.0979734400102217 ) ) ; +#6223 = CARTESIAN_POINT ( 'NONE', ( 76.10777906860903386, 155.6827192487146760, 98.62805563713385482 ) ) ; +#6224 = CARTESIAN_POINT ( 'NONE', ( 14.55294048017762698, 182.5605668518259392, 101.7915615195478409 ) ) ; +#6225 = AXIS2_PLACEMENT_3D ( 'NONE', #18451, #34398, #2922 ) ; +#6226 = ORIENTED_EDGE ( 'NONE', *, *, #3255, .T. ) ; +#6227 = FACE_OUTER_BOUND ( 'NONE', #9719, .T. ) ; +#6228 = CARTESIAN_POINT ( 'NONE', ( -40.71505848696708085, 189.9242018305782551, 106.7973272910517863 ) ) ; +#6229 = ORIENTED_EDGE ( 'NONE', *, *, #4254, .T. ) ; +#6230 = AXIS2_PLACEMENT_3D ( 'NONE', #17803, #1890, #36221 ) ; +#6231 = VECTOR ( 'NONE', #18643, 1000.000000000000114 ) ; +#6232 = VECTOR ( 'NONE', #17880, 1000.000000000000114 ) ; +#6233 = CARTESIAN_POINT ( 'NONE', ( -35.43807705578637268, 196.5784392935932203, 103.8965070399753614 ) ) ; +#6234 = CARTESIAN_POINT ( 'NONE', ( -5.666773900267269681, 187.4652808147925214, 105.7370325349066320 ) ) ; +#6235 = EDGE_CURVE ( 'NONE', #34668, #16043, #10681, .T. ) ; +#6236 = CARTESIAN_POINT ( 'NONE', ( 42.43787138009228244, 189.9416574239004376, 106.2771675705110823 ) ) ; +#6237 = CARTESIAN_POINT ( 'NONE', ( 26.03373140117899709, 191.5260202047026041, 103.8544635878054976 ) ) ; +#6238 = EDGE_LOOP ( 'NONE', ( #14738, #36571, #22603, #2015 ) ) ; +#6239 = CARTESIAN_POINT ( 'NONE', ( 21.72603247161529438, 129.4256177271351760, 92.59897021125679828 ) ) ; +#6240 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26425, #29890, #10882, #7386 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6241 = ORIENTED_EDGE ( 'NONE', *, *, #3518, .F. ) ; +#6242 = CARTESIAN_POINT ( 'NONE', ( 19.98483764167631094, 211.0849390754169974, 73.04592155476974824 ) ) ; +#6243 = FACE_OUTER_BOUND ( 'NONE', #14533, .T. ) ; +#6244 = CARTESIAN_POINT ( 'NONE', ( 38.55824950455000533, 118.6163727090000037, 89.80334989176999727 ) ) ; +#6245 = ORIENTED_EDGE ( 'NONE', *, *, #18916, .T. ) ; +#6246 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#6247 = VERTEX_POINT ( 'NONE', #28949 ) ; +#6248 = EDGE_CURVE ( 'NONE', #1973, #14528, #7662, .T. ) ; +#6249 = VECTOR ( 'NONE', #35506, 1000.000000000000114 ) ; +#6250 = VECTOR ( 'NONE', #4699, 1000.000000000000000 ) ; +#6251 = CONICAL_SURFACE ( 'NONE', #28483, 6.000000000213348450, 0.7853981633778843729 ) ; +#6252 = CARTESIAN_POINT ( 'NONE', ( -38.17814356823000566, 118.7082741531000067, 90.14969561450999436 ) ) ; +#6253 = ORIENTED_EDGE ( 'NONE', *, *, #10117, .F. ) ; +#6255 = VECTOR ( 'NONE', #7862, 1000.000000000000000 ) ; +#6254 = CARTESIAN_POINT ( 'NONE', ( 37.23701003965144452, 122.4655498436707859, 105.8628478846491987 ) ) ; +#6256 = CYLINDRICAL_SURFACE ( 'NONE', #13724, 2.000000000000014655 ) ; +#6257 = CARTESIAN_POINT ( 'NONE', ( -33.60903683397481956, 163.7527748289998328, 189.3325253559470696 ) ) ; +#6258 = AXIS2_PLACEMENT_3D ( 'NONE', #23639, #16330, #4612 ) ; +#6259 = CARTESIAN_POINT ( 'NONE', ( -21.65625503477336977, 158.4439038514896936, 96.24565958992596393 ) ) ; +#6260 = ADVANCED_FACE ( 'NONE', ( #10356 ), #29262, .T. ) ; +#6261 = EDGE_CURVE ( 'NONE', #16791, #20537, #21463, .T. ) ; +#6262 = CARTESIAN_POINT ( 'NONE', ( -30.01596277575672289, 112.8237990546615066, 152.1988939502894880 ) ) ; +#6263 = ORIENTED_EDGE ( 'NONE', *, *, #12922, .T. ) ; +#6264 = EDGE_CURVE ( 'NONE', #20739, #1497, #20099, .T. ) ; +#6265 = CARTESIAN_POINT ( 'NONE', ( 1.145067044774861653, 189.0860242507255009, 105.7614945720849846 ) ) ; +#6266 = CARTESIAN_POINT ( 'NONE', ( 26.00071577175129889, 119.4206015363792517, 90.28654347840240746 ) ) ; +#6267 = EDGE_LOOP ( 'NONE', ( #39503, #6312, #7454, #9969 ) ) ; +#6268 = CARTESIAN_POINT ( 'NONE', ( -29.78271245060107830, 185.5388541528431290, 103.0190830191734648 ) ) ; +#6269 = CARTESIAN_POINT ( 'NONE', ( -22.49783753475205472, 153.7286132221404955, 98.23646823715600362 ) ) ; +#6270 = VERTEX_POINT ( 'NONE', #23215 ) ; +#6271 = FACE_OUTER_BOUND ( 'NONE', #26555, .T. ) ; +#6272 = FACE_OUTER_BOUND ( 'NONE', #39393, .T. ) ; +#6273 = LINE ( 'NONE', #37362, #35174 ) ; +#6274 = ORIENTED_EDGE ( 'NONE', *, *, #28574, .F. ) ; +#6275 = FACE_OUTER_BOUND ( 'NONE', #23756, .T. ) ; +#6276 = LINE ( 'NONE', #40216, #38141 ) ; +#6277 = CARTESIAN_POINT ( 'NONE', ( 42.97429946896744468, 67.83849343097567441, 322.0145824706445978 ) ) ; +#6278 = CARTESIAN_POINT ( 'NONE', ( 30.07353398222051055, 177.0661537567726782, 103.5182483147875985 ) ) ; +#6279 = CARTESIAN_POINT ( 'NONE', ( -37.56217811679143637, 145.6431275960571838, 282.5778664123586168 ) ) ; +#6280 = AXIS2_PLACEMENT_3D ( 'NONE', #15267, #25285, #16054 ) ; +#6281 = ORIENTED_EDGE ( 'NONE', *, *, #30615, .F. ) ; +#6282 = CARTESIAN_POINT ( 'NONE', ( 29.19927575800447173, 163.6433483284885426, 97.41533068389654204 ) ) ; +#6283 = CARTESIAN_POINT ( 'NONE', ( -37.67574118798827243, 118.8155645602721222, 87.29053938956874958 ) ) ; +#6284 = PLANE ( 'NONE', #551 ) ; +#6285 = CIRCLE ( 'NONE', #21346, 2.249999999963659292 ) ; +#6286 = CARTESIAN_POINT ( 'NONE', ( -16.53001031479427141, 121.8780329720448066, 177.6173573199974953 ) ) ; +#6287 = CIRCLE ( 'NONE', #33050, 59.40509992922265781 ) ; +#6288 = ORIENTED_EDGE ( 'NONE', *, *, #5604, .F. ) ; +#6289 = FACE_OUTER_BOUND ( 'NONE', #2289, .T. ) ; +#6290 = CARTESIAN_POINT ( 'NONE', ( 17.03953122770531081, 121.4984955427919431, 177.4945558973374204 ) ) ; +#6291 = CARTESIAN_POINT ( 'NONE', ( 23.37288949314423192, 214.0898084988432686, 73.04438744281617346 ) ) ; +#6292 = FACE_OUTER_BOUND ( 'NONE', #9846, .T. ) ; +#6293 = CARTESIAN_POINT ( 'NONE', ( -27.26501486794000328, 187.3490569909000101, 105.6591404369000031 ) ) ; +#6294 = ORIENTED_EDGE ( 'NONE', *, *, #12041, .T. ) ; +#6295 = EDGE_CURVE ( 'NONE', #14325, #37725, #32809, .T. ) ; +#6296 = CARTESIAN_POINT ( 'NONE', ( -19.44534545229788591, 148.3863058741690679, 180.5858969458773515 ) ) ; +#6297 = ADVANCED_FACE ( 'NONE', ( #17052 ), #29908, .T. ) ; +#6298 = PLANE ( 'NONE', #31471 ) ; +#6299 = PLANE ( 'NONE', #12195 ) ; +#6300 = LINE ( 'NONE', #40242, #6116 ) ; +#6301 = CARTESIAN_POINT ( 'NONE', ( -39.35534632512823805, 129.4524480647742450, 89.54659771444076455 ) ) ; +#6302 = AXIS2_PLACEMENT_3D ( 'NONE', #18080, #34034, #21987 ) ; +#6303 = FACE_OUTER_BOUND ( 'NONE', #39372, .T. ) ; +#6304 = CARTESIAN_POINT ( 'NONE', ( 36.18931669942080021, 192.0080903167539930, 104.3523514206140135 ) ) ; +#6305 = EDGE_CURVE ( 'NONE', #1726, #29530, #7703, .T. ) ; +#6306 = CIRCLE ( 'NONE', #29182, 2.250000000000011102 ) ; +#6307 = EDGE_CURVE ( 'NONE', #17938, #4160, #8702, .T. ) ; +#6308 = VERTEX_POINT ( 'NONE', #27718 ) ; +#6310 = ORIENTED_EDGE ( 'NONE', *, *, #14619, .T. ) ; +#6309 = CARTESIAN_POINT ( 'NONE', ( 36.64635057513000049, 191.2562995250000029, 106.4472677424000011 ) ) ; +#6311 = VECTOR ( 'NONE', #7911, 999.9999999999998863 ) ; +#6312 = ORIENTED_EDGE ( 'NONE', *, *, #31768, .T. ) ; +#6313 = ORIENTED_EDGE ( 'NONE', *, *, #29519, .T. ) ; +#6314 = ADVANCED_FACE ( 'NONE', ( #24242 ), #20762, .F. ) ; +#6315 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173122415, 160.6259891653180034, 97.25765956939861212 ) ) ; +#6316 = EDGE_CURVE ( 'NONE', #39083, #23549, #36067, .T. ) ; +#6317 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#6318 = AXIS2_PLACEMENT_3D ( 'NONE', #1284, #38494, #32185 ) ; +#6319 = FACE_OUTER_BOUND ( 'NONE', #7371, .T. ) ; +#6320 = CARTESIAN_POINT ( 'NONE', ( 26.00056762447263026, 118.1139028608674408, 90.25209678512123901 ) ) ; +#6321 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25928, #10581, #38562, #13440 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6322 = ORIENTED_EDGE ( 'NONE', *, *, #30652, .T. ) ; +#6323 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640293485, -0.2252353050503884957 ) ) ; +#6324 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -7.822507694019388974E-18, -0.0006039748319385908944 ) ) ; +#6325 = FACE_OUTER_BOUND ( 'NONE', #30263, .T. ) ; +#6326 = ORIENTED_EDGE ( 'NONE', *, *, #39907, .T. ) ; +#6327 = CARTESIAN_POINT ( 'NONE', ( -35.62767240713339589, 77.14301703112144537, 291.5800621566117456 ) ) ; +#6328 = DIRECTION ( 'NONE', ( 0.9999998176071900335, 9.143184980527326943E-12, -0.0006039748227977436356 ) ) ; +#6329 = DIRECTION ( 'NONE', ( -0.0005884949961206199700, 0.2249510543439050825, -0.9743698870671266832 ) ) ; +#6330 = FACE_OUTER_BOUND ( 'NONE', #30773, .T. ) ; +#6331 = CARTESIAN_POINT ( 'NONE', ( 15.50029467836134778, 127.6324160061193567, 89.62297635127647766 ) ) ; +#6332 = ORIENTED_EDGE ( 'NONE', *, *, #16578, .T. ) ; +#6333 = CARTESIAN_POINT ( 'NONE', ( -25.50870663471662780, 209.7066555246269104, 75.57407794464953099 ) ) ; +#6334 = EDGE_CURVE ( 'NONE', #26262, #16596, #22091, .T. ) ; +#6335 = CARTESIAN_POINT ( 'NONE', ( 2.504779437822759913, 190.4797426592519969, 104.1230114428459927 ) ) ; +#6336 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; +#6337 = AXIS2_PLACEMENT_3D ( 'NONE', #36680, #8693, #18057 ) ; +#6338 = VERTEX_POINT ( 'NONE', #1947 ) ; +#6339 = ORIENTED_EDGE ( 'NONE', *, *, #36327, .F. ) ; +#6340 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775999513 ) ) ; +#6341 = ORIENTED_EDGE ( 'NONE', *, *, #28562, .F. ) ; +#6342 = VECTOR ( 'NONE', #8331, 1000.000000000000000 ) ; +#6343 = CARTESIAN_POINT ( 'NONE', ( 15.10714335843527145, 176.3834766976846993, 100.3651329064352922 ) ) ; +#6344 = CARTESIAN_POINT ( 'NONE', ( -17.26183278765846651, 121.5203170840806024, 176.4533299693686956 ) ) ; +#6345 = CARTESIAN_POINT ( 'NONE', ( -77.81044467944656162, 193.2853083808247163, 188.4036545891195544 ) ) ; +#6346 = ADVANCED_FACE ( 'NONE', ( #33000 ), #27528, .T. ) ; +#6347 = CARTESIAN_POINT ( 'NONE', ( 35.54795982457387993, 209.7096538831000032, 78.03703491738708919 ) ) ; +#6348 = CARTESIAN_POINT ( 'NONE', ( -16.54861044420561100, 152.4810896450478879, 181.7854491407948672 ) ) ; +#6349 = CARTESIAN_POINT ( 'NONE', ( -3.503014828629882782, 185.8319201473011901, 102.8998220731232749 ) ) ; +#6350 = EDGE_CURVE ( 'NONE', #2177, #16493, #33151, .T. ) ; +#6351 = CARTESIAN_POINT ( 'NONE', ( -12.63675505126982657, 134.8421811116586753, 93.35708474409203461 ) ) ; +#6352 = CARTESIAN_POINT ( 'NONE', ( 25.49062502244311190, 209.7098837966309475, 73.54308088453358039 ) ) ; +#6353 = ORIENTED_EDGE ( 'NONE', *, *, #11756, .T. ) ; +#6354 = EDGE_CURVE ( 'NONE', #27892, #6456, #12955, .T. ) ; +#6355 = LINE ( 'NONE', #24596, #40089 ) ; +#6356 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6413, #15436, #40353, #9302, #21779, #3348, #9912, #18672, #15622, #22381 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998718248, 0.3749999999998139266, 0.4374999999998159805, 0.4999999999998180344, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6357 = CARTESIAN_POINT ( 'NONE', ( -20.01839195877885302, 210.6282793158955258, 76.07066396527223162 ) ) ; +#6358 = LINE ( 'NONE', #37048, #37920 ) ; +#6359 = DIRECTION ( 'NONE', ( -0.0006039748319386279742, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#6360 = VERTEX_POINT ( 'NONE', #11335 ) ; +#6361 = ADVANCED_FACE ( 'NONE', ( #30358 ), #31215, .F. ) ; +#6362 = ORIENTED_EDGE ( 'NONE', *, *, #37178, .T. ) ; +#6363 = VECTOR ( 'NONE', #22343, 1000.000000000000000 ) ; +#6364 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319364164186 ) ) ; +#6365 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971580945 ) ) ; +#6366 = CIRCLE ( 'NONE', #20074, 2.250000000024274360 ) ; +#6367 = ORIENTED_EDGE ( 'NONE', *, *, #18349, .F. ) ; +#6368 = DIRECTION ( 'NONE', ( 0.0006039748319382295299, -5.238646599373848640E-18, 0.9999998176071845934 ) ) ; +#6369 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37762, #951, #28972, #34679, #6883, #32056, #28579, #157, #348, #35278, #7280, #19145, #751, #12617 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999976685, 0.2499999999999953371, 0.4999999999999906741, 0.6249999999999947820, 0.7499999999999988898, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6370 = CARTESIAN_POINT ( 'NONE', ( 23.68575892633012003, 134.8469895808620436, 93.33625697840975022 ) ) ; +#6371 = CARTESIAN_POINT ( 'NONE', ( -30.45075997731206030, 185.6036007986156449, 102.5212824999076986 ) ) ; +#6372 = CARTESIAN_POINT ( 'NONE', ( 26.00891783773975874, 196.5784392904109836, 103.8593946022765522 ) ) ; +#6373 = ORIENTED_EDGE ( 'NONE', *, *, #10986, .T. ) ; +#6374 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363196006660E-14, -0.9999998176071844824 ) ) ; +#6375 = ORIENTED_EDGE ( 'NONE', *, *, #23032, .F. ) ; +#6376 = PLANE ( 'NONE', #16147 ) ; +#6377 = CARTESIAN_POINT ( 'NONE', ( 39.06385346265498981, 191.4135374074515994, 104.3337792663689072 ) ) ; +#6378 = EDGE_LOOP ( 'NONE', ( #27072, #21920, #21904, #21195, #15708 ) ) ; +#6379 = CARTESIAN_POINT ( 'NONE', ( -13.50000077923288977, 160.7384646933283250, 96.77047462218374108 ) ) ; +#6380 = CARTESIAN_POINT ( 'NONE', ( 0.8004895499858137864, 188.6246619147358672, 103.1998745706487455 ) ) ; +#6381 = PLANE ( 'NONE', #33172 ) ; +#6382 = ORIENTED_EDGE ( 'NONE', *, *, #16404, .F. ) ; +#6383 = CARTESIAN_POINT ( 'NONE', ( -3.503014745918749728, 128.5096117803557263, 89.66592193050738047 ) ) ; +#6384 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#6385 = ORIENTED_EDGE ( 'NONE', *, *, #2931, .F. ) ; +#6386 = CARTESIAN_POINT ( 'NONE', ( -37.19447980817694344, 79.23804072928820119, 291.5810084690210715 ) ) ; +#6387 = CARTESIAN_POINT ( 'NONE', ( 36.47675288263859983, 191.3241625203926617, 103.8015559370109884 ) ) ; +#6388 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#6389 = EDGE_CURVE ( 'NONE', #16772, #28262, #8375, .T. ) ; +#6390 = EDGE_CURVE ( 'NONE', #28118, #38719, #33817, .T. ) ; +#6391 = VECTOR ( 'NONE', #1445, 1000.000000000000227 ) ; +#6392 = ORIENTED_EDGE ( 'NONE', *, *, #29404, .F. ) ; +#6393 = EDGE_CURVE ( 'NONE', #1613, #29278, #26756, .T. ) ; +#6394 = CARTESIAN_POINT ( 'NONE', ( -4.037441716916447376, 168.3837378232288131, 99.04296232367518371 ) ) ; +#6395 = CARTESIAN_POINT ( 'NONE', ( 3.535986888874630196, 143.5554623264248733, 95.87208321593506355 ) ) ; +#6396 = CONICAL_SURFACE ( 'NONE', #1169, 2.502993757559606625, 0.7853981634100110076 ) ; +#6397 = DIRECTION ( 'NONE', ( -0.0006039748319401620118, -1.156691652267356444E-14, -0.9999998176071847045 ) ) ; +#6398 = ORIENTED_EDGE ( 'NONE', *, *, #37836, .F. ) ; +#6399 = EDGE_CURVE ( 'NONE', #12650, #1917, #34533, .T. ) ; +#6400 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921598504, 0.2249510932971504895 ) ) ; +#6401 = CARTESIAN_POINT ( 'NONE', ( -4.081258675555402782, 191.9912574625914488, 28.07874682001180489 ) ) ; +#6402 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28221, #28018, #18767, #187 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6403 = CARTESIAN_POINT ( 'NONE', ( -16.04815022346086906, 121.3122077256701630, 177.4254579244168042 ) ) ; +#6404 = ORIENTED_EDGE ( 'NONE', *, *, #14552, .T. ) ; +#6405 = ORIENTED_EDGE ( 'NONE', *, *, #8658, .F. ) ; +#6406 = CARTESIAN_POINT ( 'NONE', ( 39.71730849539001440, 182.4927982134933302, 106.8443253198619374 ) ) ; +#6407 = FACE_OUTER_BOUND ( 'NONE', #21966, .T. ) ; +#6408 = DIRECTION ( 'NONE', ( 0.1305262860326017182, 0.9659620395529877612, 0.2233388161452626308 ) ) ; +#6409 = EDGE_LOOP ( 'NONE', ( #13560, #26454, #7385, #6373 ) ) ; +#6410 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #8781, #33697, #11849 ), + ( #36375, #36573, #7389 ), + ( #10489, #2444, #19850 ), + ( #24329, #39829, #8374 ), + ( #4878, #17744, #35384 ), + ( #17336, #23917, #36772 ), + ( #8160, #30238, #21245 ), + ( #5702, #2649, #1822 ), + ( #20835, #26778, #21044 ), + ( #39227, #27197, #11230 ), + ( #23705, #2237, #30454 ), + ( #36158, #20626, #11643 ), + ( #24117, #5078, #30039 ), + ( #26988, #39423, #8577 ), + ( #34690, #18356, #359 ), + ( #33900, #15510, #28197 ) ), + .UNSPECIFIED., .F., .F., .T. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 2, 2, 2, 2, 2, 2, 4 ), + ( 3, 3 ), + ( 0.000000000000000000, 0.0004331055251506400771, 0.0008662110503012801542, 0.001299316575451920286, 0.001732422100602560308, 0.002165527625753200548, 0.002598633150903840571, 0.003464844201205120617 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.9092867158778993320, 1.000000000000000000), + ( 1.000000000000000000, 0.9092804009989405856, 1.000000000000000000), + ( 1.000000000000000000, 0.9074037354123881682, 1.000000000000000000), + ( 1.000000000000000000, 0.9002689965790705573, 1.000000000000000000), + ( 1.000000000000000000, 0.8949769825019651126, 1.000000000000000000), + ( 1.000000000000000000, 0.8820425834865006642, 1.000000000000000000), + ( 1.000000000000000000, 0.8742515007032405361, 1.000000000000000000), + ( 1.000000000000000000, 0.8572113049951757269, 1.000000000000000000), + ( 1.000000000000000000, 0.8479470991237200161, 1.000000000000000000), + ( 1.000000000000000000, 0.8282165362286774135, 1.000000000000000000), + ( 1.000000000000000000, 0.8177144993102715143, 1.000000000000000000), + ( 1.000000000000000000, 0.7963522215910799895, 1.000000000000000000), + ( 1.000000000000000000, 0.7854072817249182492, 1.000000000000000000), + ( 1.000000000000000000, 0.7518798169611724536, 1.000000000000000000), + ( 1.000000000000000000, 0.7291766701141920715, 1.000000000000000000), + ( 1.000000000000000000, 0.7071067811880478171, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#6411 = ORIENTED_EDGE ( 'NONE', *, *, #15634, .T. ) ; +#6412 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#6413 = CARTESIAN_POINT ( 'NONE', ( 13.50164015315887411, 187.2961052408047067, 105.4512425975207464 ) ) ; +#6414 = LINE ( 'NONE', #18473, #26784 ) ; +#6415 = ORIENTED_EDGE ( 'NONE', *, *, #29362, .F. ) ; +#6416 = VECTOR ( 'NONE', #22144, 1000.000000000000114 ) ; +#6417 = ORIENTED_EDGE ( 'NONE', *, *, #5860, .F. ) ; +#6418 = CARTESIAN_POINT ( 'NONE', ( -5.669636259340673945, 124.1935939972654666, 90.97742688201675776 ) ) ; +#6419 = CARTESIAN_POINT ( 'NONE', ( -39.03036842917153137, 121.1728496031133631, 123.5553118490634432 ) ) ; +#6420 = CARTESIAN_POINT ( 'NONE', ( -26.15780381216999828, 122.1014796219999994, 87.85799570823000693 ) ) ; +#6421 = VECTOR ( 'NONE', #10703, 999.9999999999998863 ) ; +#6422 = ORIENTED_EDGE ( 'NONE', *, *, #10435, .F. ) ; +#6423 = CARTESIAN_POINT ( 'NONE', ( -20.58515596502575562, 211.7448734286233503, 73.57093710791899355 ) ) ; +#6424 = CARTESIAN_POINT ( 'NONE', ( -21.21399091017794802, 175.8930158889867528, 100.7869902896899816 ) ) ; +#6425 = ORIENTED_EDGE ( 'NONE', *, *, #23203, .T. ) ; +#6426 = DIRECTION ( 'NONE', ( -0.0004161288024436979533, 0.8480480898119694411, -0.5299191110000558425 ) ) ; +#6427 = CARTESIAN_POINT ( 'NONE', ( -44.50693014258958158, 206.7304000571328118, 28.20407784316371647 ) ) ; +#6428 = LINE ( 'NONE', #9121, #2304 ) ; +#6429 = CARTESIAN_POINT ( 'NONE', ( -18.59070810293174603, 148.9276284220111393, 180.2165354988448200 ) ) ; +#6430 = VERTEX_POINT ( 'NONE', #5611 ) ; +#6431 = CARTESIAN_POINT ( 'NONE', ( -42.96540792352757876, 112.9275286064121104, 127.4010142069958675 ) ) ; +#6432 = ORIENTED_EDGE ( 'NONE', *, *, #13071, .T. ) ; +#6433 = EDGE_CURVE ( 'NONE', #4210, #38012, #27316, .T. ) ; +#6434 = CARTESIAN_POINT ( 'NONE', ( 28.90184376448340942, 77.14301703112161590, 291.5410879458182762 ) ) ; +#6435 = EDGE_CURVE ( 'NONE', #18083, #32425, #12759, .T. ) ; +#6436 = CARTESIAN_POINT ( 'NONE', ( -38.37150668424000344, 119.0019429191000029, 87.62653263106000168 ) ) ; +#6437 = CARTESIAN_POINT ( 'NONE', ( 42.70335351170635363, 189.5620346758765038, 106.3836115623159344 ) ) ; +#6438 = CIRCLE ( 'NONE', #29312, 2.000000000021789237 ) ; +#6439 = CARTESIAN_POINT ( 'NONE', ( 15.99999439207489615, 185.9093013714976053, 102.5638074086867846 ) ) ; +#6440 = ORIENTED_EDGE ( 'NONE', *, *, #14301, .F. ) ; +#6441 = LINE ( 'NONE', #37936, #1711 ) ; +#6442 = EDGE_LOOP ( 'NONE', ( #2576, #9139, #16922, #11968 ) ) ; +#6443 = CIRCLE ( 'NONE', #37139, 1.999999999999994893 ) ; +#6444 = CONICAL_SURFACE ( 'NONE', #29320, 2.499999999987272403, 0.7853981633679723018 ) ; +#6445 = CARTESIAN_POINT ( 'NONE', ( -25.89015350293919582, 209.7107532057999606, 73.19407301408074318 ) ) ; +#6446 = AXIS2_PLACEMENT_3D ( 'NONE', #23006, #17650, #8266 ) ; +#6447 = CARTESIAN_POINT ( 'NONE', ( 46.23034675843089758, 142.4471217300238663, 290.2939289711846413 ) ) ; +#6448 = CARTESIAN_POINT ( 'NONE', ( 3.667815741532966189, 126.2406713581920599, 91.36142183184406917 ) ) ; +#6449 = ORIENTED_EDGE ( 'NONE', *, *, #25404, .F. ) ; +#6450 = DIRECTION ( 'NONE', ( 0.0004270881509380666254, 0.7071067811865995312, 0.7071066522071742799 ) ) ; +#6451 = CARTESIAN_POINT ( 'NONE', ( 28.18739088310087482, 186.6040837889091506, 105.2826068624289064 ) ) ; +#6452 = CARTESIAN_POINT ( 'NONE', ( -4.037441716908935163, 137.2418790766312782, 91.85329641515465937 ) ) ; +#6453 = CARTESIAN_POINT ( 'NONE', ( -20.30306764003320552, 159.5691140880819034, 96.50461759798676553 ) ) ; +#6454 = LINE ( 'NONE', #15862, #21731 ) ; +#6455 = CARTESIAN_POINT ( 'NONE', ( 39.06393364112096123, 183.1686747593891198, 104.4829110315198193 ) ) ; +#6456 = VERTEX_POINT ( 'NONE', #16216 ) ; +#6457 = EDGE_LOOP ( 'NONE', ( #16423, #25540, #22112, #38273, #21588, #4288, #25727, #22848, #30400, #2047, #32913, #6294, #12775, #17451, #39434 ) ) ; +#6458 = CARTESIAN_POINT ( 'NONE', ( 5.668069803484447888, 187.9566418269450878, 103.3747270639725997 ) ) ; +#6459 = CARTESIAN_POINT ( 'NONE', ( -26.00800983458967508, 191.5260122442129216, 103.8858970416150385 ) ) ; +#6460 = EDGE_CURVE ( 'NONE', #31838, #32027, #31572, .T. ) ; +#6461 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971550137 ) ) ; +#6462 = ORIENTED_EDGE ( 'NONE', *, *, #23332, .T. ) ; +#6463 = CARTESIAN_POINT ( 'NONE', ( 19.98129031103842479, 206.1771145815928321, 74.47467027735100942 ) ) ; +#6464 = ORIENTED_EDGE ( 'NONE', *, *, #26080, .F. ) ; +#6465 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971547361 ) ) ; +#6466 = CIRCLE ( 'NONE', #9761, 2.000000000000000000 ) ; +#6467 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#6468 = LINE ( 'NONE', #3599, #1366 ) ; +#6469 = ORIENTED_EDGE ( 'NONE', *, *, #9328, .F. ) ; +#6470 = CARTESIAN_POINT ( 'NONE', ( -39.42639396830977461, 119.7153704062085353, 90.39411697856569106 ) ) ; +#6471 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6472 = AXIS2_PLACEMENT_3D ( 'NONE', #7810, #23561, #14175 ) ; +#6473 = LINE ( 'NONE', #346, #17501 ) ; +#6474 = CARTESIAN_POINT ( 'NONE', ( 18.99767128196905830, 125.6058446513852118, 175.3475295528536151 ) ) ; +#6475 = VECTOR ( 'NONE', #11699, 1000.000000000000114 ) ; +#6476 = CARTESIAN_POINT ( 'NONE', ( 19.99976926757112849, 160.7481248081381295, 96.75239270071580222 ) ) ; +#6477 = EDGE_LOOP ( 'NONE', ( #7425, #31736 ) ) ; +#6478 = DIRECTION ( 'NONE', ( -6.775747579923947991E-13, 0.9743700560511913134, 0.2249510921751617376 ) ) ; +#6479 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; +#6480 = CARTESIAN_POINT ( 'NONE', ( -1.095994359663330364, 188.4547440274937173, 106.2407042419200138 ) ) ; +#6481 = CARTESIAN_POINT ( 'NONE', ( -11.79202345736525892, 125.7774812735008254, 176.8918472601677365 ) ) ; +#6482 = APPLICATION_CONTEXT ( 'configuration controlled 3d designs of mechanical parts and assemblies' ) ; +#6483 = ADVANCED_FACE ( 'NONE', ( #21972 ), #37141, .F. ) ; +#6484 = VERTEX_POINT ( 'NONE', #273 ) ; +#6485 = LINE ( 'NONE', #15508, #8165 ) ; +#6486 = EDGE_CURVE ( 'NONE', #31222, #34652, #12983, .T. ) ; +#6487 = LINE ( 'NONE', #6290, #11463 ) ; +#6488 = CARTESIAN_POINT ( 'NONE', ( 15.50029467836134778, 127.6324160061193567, 89.62297635127647766 ) ) ; +#6489 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; +#6490 = CARTESIAN_POINT ( 'NONE', ( -15.03362232196302095, 125.0996412702250211, 171.3811097074177212 ) ) ; +#6491 = ORIENTED_EDGE ( 'NONE', *, *, #26519, .T. ) ; +#6492 = EDGE_CURVE ( 'NONE', #20699, #7741, #12966, .T. ) ; +#6493 = CARTESIAN_POINT ( 'NONE', ( -16.29619488456271981, 121.9866529957326691, 177.9438470153492631 ) ) ; +#6494 = CONICAL_SURFACE ( 'NONE', #20180, 5.999999999758604652, 0.7853981633778843729 ) ; +#6495 = LINE ( 'NONE', #31063, #27212 ) ; +#6496 = CARTESIAN_POINT ( 'NONE', ( -35.94780306588808116, 112.9281708003797036, 87.78949364045074333 ) ) ; +#6497 = CARTESIAN_POINT ( 'NONE', ( 31.49993145514000403, 120.4394921222999955, 88.97899963669999579 ) ) ; +#6498 = VECTOR ( 'NONE', #27508, 1000.000000000000114 ) ; +#6499 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560684 ) ) ; +#6500 = FACE_OUTER_BOUND ( 'NONE', #19558, .T. ) ; +#6501 = AXIS2_PLACEMENT_3D ( 'NONE', #7957, #29644, #35948 ) ; +#6503 = VERTEX_POINT ( 'NONE', #37695 ) ; +#6502 = CARTESIAN_POINT ( 'NONE', ( 36.44567169039000021, 191.8783867296999972, 106.2558788317000023 ) ) ; +#6504 = VERTEX_POINT ( 'NONE', #31782 ) ; +#6505 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2252353050503803633, -0.9743043966640312359 ) ) ; +#6506 = ADVANCED_FACE ( 'NONE', ( #9297 ), #21581, .T. ) ; +#6507 = CARTESIAN_POINT ( 'NONE', ( -34.43835868710999648, 129.8549691105999955, 92.73201569149999557 ) ) ; +#6508 = CARTESIAN_POINT ( 'NONE', ( 31.82998378949513452, 157.8941376960632397, 186.4072502462622367 ) ) ; +#6509 = CARTESIAN_POINT ( 'NONE', ( 42.53628601435023171, 136.4453753212296760, 337.8539966295136310 ) ) ; +#6510 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12907, #3679, #13502, #22914, #16161, #3877, #29039, #13105, #22517, #34934, #6950, #16351, #28839, #35340, #8384, #17553, #17149, #36168, #2045, #38822 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999146516, 0.1874999999998761824, 0.2187499999998555877, 0.2343749999998484546, 0.2499999999998413491, 0.4999999999998435696, 0.6249999999998382405, 0.6874999999998356870, 0.7187499999998402389, 0.7343749999998437916, 0.7499999999998472333, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6511 = CARTESIAN_POINT ( 'NONE', ( -35.45668950309346457, 209.7097078344999943, 73.07991903445761750 ) ) ; +#6512 = ORIENTED_EDGE ( 'NONE', *, *, #12097, .F. ) ; +#6513 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10186, #37769, #28979, #3612 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6514 = CARTESIAN_POINT ( 'NONE', ( 3.666638755385807080, 126.6906504152049706, 89.41269982467663624 ) ) ; +#6515 = CARTESIAN_POINT ( 'NONE', ( -12.64386474322367526, 181.0124094291204528, 104.5294403572958544 ) ) ; +#6516 = CARTESIAN_POINT ( 'NONE', ( -37.24902032432657961, 191.4390922065653626, 104.3803261539560481 ) ) ; +#6517 = ORIENTED_EDGE ( 'NONE', *, *, #32442, .T. ) ; +#6518 = CARTESIAN_POINT ( 'NONE', ( -31.70566066713798037, 220.4002260770999726, 73.07765350697074780 ) ) ; +#6519 = EDGE_CURVE ( 'NONE', #6030, #27038, #6805, .T. ) ; +#6520 = FACE_OUTER_BOUND ( 'NONE', #29515, .T. ) ; +#6521 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452351231, -0.1781166614240801693 ) ) ; +#6522 = CARTESIAN_POINT ( 'NONE', ( -39.69379533597580689, 119.8651493286000687, 87.86309706269757669 ) ) ; +#6523 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -1.238758140229870101E-30, 0.0006039748319385906776 ) ) ; +#6524 = ORIENTED_EDGE ( 'NONE', *, *, #10172, .F. ) ; +#6525 = EDGE_CURVE ( 'NONE', #978, #6030, #24651, .T. ) ; +#6526 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#6527 = VECTOR ( 'NONE', #16222, 1000.000000000000227 ) ; +#6528 = CARTESIAN_POINT ( 'NONE', ( 2.554510955381000148, 190.8274375100000100, 104.2205350602999943 ) ) ; +#6529 = CARTESIAN_POINT ( 'NONE', ( 43.17764363794253768, 121.2864334425410533, 90.70693487989220216 ) ) ; +#6530 = AXIS2_PLACEMENT_3D ( 'NONE', #5865, #2801, #40401 ) ; +#6531 = CONICAL_SURFACE ( 'NONE', #29408, 2.503011087841876758, 0.7854316141493700165 ) ; +#6532 = ADVANCED_FACE ( 'NONE', ( #6602 ), #6210, .T. ) ; +#6533 = VERTEX_POINT ( 'NONE', #9094 ) ; +#6534 = CYLINDRICAL_SURFACE ( 'NONE', #25753, 2.000000000000001332 ) ; +#6535 = ORIENTED_EDGE ( 'NONE', *, *, #35262, .F. ) ; +#6536 = ADVANCED_FACE ( 'NONE', ( #37904 ), #14937, .F. ) ; +#6537 = EDGE_CURVE ( 'NONE', #21584, #10351, #28647, .T. ) ; +#6538 = PLANE ( 'NONE', #28191 ) ; +#6539 = ADVANCED_FACE ( 'NONE', ( #19077 ), #34018, .T. ) ; +#6540 = CARTESIAN_POINT ( 'NONE', ( -77.81044467944656162, 193.2853083808247163, 188.4036545891195544 ) ) ; +#6541 = CARTESIAN_POINT ( 'NONE', ( -12.63453555434205100, 177.0107181004119354, 103.4630699979715018 ) ) ; +#6542 = CARTESIAN_POINT ( 'NONE', ( -35.44810745619992787, 112.9281708664996984, 87.28919406064997588 ) ) ; +#6543 = CARTESIAN_POINT ( 'NONE', ( -35.95487748704000097, 225.9002260771000010, 76.08022047461976456 ) ) ; +#6544 = CARTESIAN_POINT ( 'NONE', ( -36.16414195531000075, 190.7651570079000010, 106.9447890395999963 ) ) ; +#6545 = ORIENTED_EDGE ( 'NONE', *, *, #35357, .T. ) ; +#6546 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 9.251858538542969067E-15, 0.0006039748319391911088 ) ) ; +#6547 = CARTESIAN_POINT ( 'NONE', ( -39.78547281363039900, 190.3169928286148718, 106.6940055862042271 ) ) ; +#6548 = DIRECTION ( 'NONE', ( -9.423264860246663790E-14, -0.9743700557562335884, -0.2249510934527640116 ) ) ; +#6549 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8105, #17080, #26937, #26521 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6550 = CARTESIAN_POINT ( 'NONE', ( 14.78617723117088190, 128.6760556706539091, 91.91695949461106352 ) ) ; +#6551 = EDGE_LOOP ( 'NONE', ( #21114, #12897, #23476, #34686 ) ) ; +#6552 = ORIENTED_EDGE ( 'NONE', *, *, #19374, .T. ) ; +#6553 = AXIS2_PLACEMENT_3D ( 'NONE', #32199, #37924, #295 ) ; +#6554 = EDGE_CURVE ( 'NONE', #30696, #36900, #15566, .T. ) ; +#6555 = CONICAL_SURFACE ( 'NONE', #39864, 22.50000000000906653, 0.7853981633972855203 ) ; +#6556 = ORIENTED_EDGE ( 'NONE', *, *, #3762, .F. ) ; +#6557 = CARTESIAN_POINT ( 'NONE', ( -21.44517147737999707, 135.1113278520462586, 93.93769420648519031 ) ) ; +#6558 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30520, #27869, #23981, #5352, #5765, #40298, #11708, #15179, #20899, #17807, #21718, #24188, #14782, #9245, #34163, #27477, #11910, #6156, #33766 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 0.000000000000000000, 0.2499828855947091033, 0.4999852515029006295, 0.6249864344569463492, 0.7499876174109920690, 0.8124897471729031206, 0.8749918769346138880, 0.9062429418155193428, 0.9374940066964148055, 0.9531195391368775249, 0.9687450715773302523, 0.9765578377975616675, 0.9843706040177829797, 0.9921833702380082887, 0.9960897533481199995, 0.9980448766740599442, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6559 = LINE ( 'NONE', #37649, #18055 ) ; +#6560 = ORIENTED_EDGE ( 'NONE', *, *, #39640, .F. ) ; +#6561 = CARTESIAN_POINT ( 'NONE', ( 37.79442059176063395, 218.5902260770999987, 73.53567729060368663 ) ) ; +#6562 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552144553, 153.0051697192221241, 291.5584375788738498 ) ) ; +#6563 = CARTESIAN_POINT ( 'NONE', ( -38.24329037062999959, 118.9457152731000065, 87.57826822584999604 ) ) ; +#6564 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#6565 = ORIENTED_EDGE ( 'NONE', *, *, #24808, .F. ) ; +#6566 = LINE ( 'NONE', #37459, #40171 ) ; +#6567 = EDGE_CURVE ( 'NONE', #13948, #17976, #3341, .T. ) ; +#6568 = ORIENTED_EDGE ( 'NONE', *, *, #22208, .F. ) ; +#6569 = CARTESIAN_POINT ( 'NONE', ( -5.668109638568818553, 181.0132057329783493, 104.5254508863806393 ) ) ; +#6570 = ORIENTED_EDGE ( 'NONE', *, *, #30878, .F. ) ; +#6571 = ORIENTED_EDGE ( 'NONE', *, *, #39539, .T. ) ; +#6572 = ADVANCED_FACE ( 'NONE', ( #34212 ), #16017, .T. ) ; +#6573 = CARTESIAN_POINT ( 'NONE', ( -19.99929890231679153, 195.2358628576933199, 105.7690483904409149 ) ) ; +#6574 = CARTESIAN_POINT ( 'NONE', ( 2.910282181199090878, 190.2536080120511031, 103.5746722162875244 ) ) ; +#6575 = CARTESIAN_POINT ( 'NONE', ( 25.50041447495308233, 118.1134306400200416, 89.75249416949174019 ) ) ; +#6576 = EDGE_CURVE ( 'NONE', #189, #12858, #25049, .T. ) ; +#6577 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21020, #18523, #40017, #11619 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6578 = VERTEX_POINT ( 'NONE', #31978 ) ; +#6579 = CARTESIAN_POINT ( 'NONE', ( -20.61617605269181297, 212.9284424379133611, 73.07095573613224815 ) ) ; +#6580 = CARTESIAN_POINT ( 'NONE', ( -20.02016821360482268, 211.0854730039747267, 73.07052224373646254 ) ) ; +#6581 = ORIENTED_EDGE ( 'NONE', *, *, #11018, .T. ) ; +#6582 = ADVANCED_FACE ( 'NONE', ( #1076 ), #38684, .T. ) ; +#6583 = CIRCLE ( 'NONE', #37941, 22.00000000001092815 ) ; +#6584 = AXIS2_PLACEMENT_3D ( 'NONE', #10647, #29450, #16757 ) ; +#6585 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6586 = FACE_OUTER_BOUND ( 'NONE', #25051, .T. ) ; +#6587 = CARTESIAN_POINT ( 'NONE', ( 16.78949468225133046, 151.7806215848595457, 184.1646548055863093 ) ) ; +#6588 = AXIS2_PLACEMENT_3D ( 'NONE', #27380, #21220, #30010 ) ; +#6589 = VERTEX_POINT ( 'NONE', #10509 ) ; +#6590 = AXIS2_PLACEMENT_3D ( 'NONE', #11215, #35924, #1597 ) ; +#6591 = CARTESIAN_POINT ( 'NONE', ( 2.877595498296891208, 208.9474331469267554, 73.28391261355885433 ) ) ; +#6592 = CARTESIAN_POINT ( 'NONE', ( 13.85386899117346182, 129.1332408048698710, 155.2444354684493533 ) ) ; +#6593 = ORIENTED_EDGE ( 'NONE', *, *, #24713, .F. ) ; +#6594 = LINE ( 'NONE', #28495, #1913 ) ; +#6595 = CARTESIAN_POINT ( 'NONE', ( -20.49852834086299325, 137.6294258426618455, 94.00531932011546132 ) ) ; +#6597 = PLANE ( 'NONE', #7649 ) ; +#6596 = CARTESIAN_POINT ( 'NONE', ( -28.34546150099999906, 186.5535928724000030, 105.4761456043000010 ) ) ; +#6598 = ORIENTED_EDGE ( 'NONE', *, *, #6567, .F. ) ; +#6599 = DIRECTION ( 'NONE', ( 0.0005884949961258899515, -0.2249510543438812404, 0.9743698870671320122 ) ) ; +#6600 = ORIENTED_EDGE ( 'NONE', *, *, #34721, .T. ) ; +#6601 = DIRECTION ( 'NONE', ( -0.0005884951729871207987, 0.2249510544218079611, -0.9743698870490344888 ) ) ; +#6602 = FACE_OUTER_BOUND ( 'NONE', #9956, .T. ) ; +#6603 = VERTEX_POINT ( 'NONE', #19677 ) ; +#6604 = AXIS2_PLACEMENT_3D ( 'NONE', #3055, #16329, #22886 ) ; +#6605 = ORIENTED_EDGE ( 'NONE', *, *, #34846, .F. ) ; +#6606 = CARTESIAN_POINT ( 'NONE', ( 16.00175042068614317, 126.1291850884666559, 91.84138073825745607 ) ) ; +#6607 = CONICAL_SURFACE ( 'NONE', #31447, 3.000000000067766681, 0.7853981634062662254 ) ; +#6608 = DIRECTION ( 'NONE', ( 0.5987319967475644988, 0.8009494341534142414, 0.000000000000000000 ) ) ; +#6609 = CARTESIAN_POINT ( 'NONE', ( -15.99970515225999179, 151.9770228117144484, 94.74935186622352035 ) ) ; +#6610 = CARTESIAN_POINT ( 'NONE', ( 36.21188721582999648, 191.6197133759999929, 104.0153071847000064 ) ) ; +#6611 = EDGE_CURVE ( 'NONE', #15440, #20595, #29503, .T. ) ; +#6612 = EDGE_LOOP ( 'NONE', ( #15870, #19910, #12738, #37323 ) ) ; +#6613 = EDGE_CURVE ( 'NONE', #35621, #35766, #7687, .T. ) ; +#6614 = ORIENTED_EDGE ( 'NONE', *, *, #39919, .F. ) ; +#6615 = CARTESIAN_POINT ( 'NONE', ( -34.98386828774999913, 217.7719116314000019, 28.07991271570000080 ) ) ; +#6616 = EDGE_CURVE ( 'NONE', #3120, #5945, #29106, .T. ) ; +#6617 = CARTESIAN_POINT ( 'NONE', ( 2.519724450483999956, 211.0000000000000000, 32.65697486330000032 ) ) ; +#6618 = EDGE_CURVE ( 'NONE', #17879, #20244, #17448, .T. ) ; +#6619 = CARTESIAN_POINT ( 'NONE', ( -26.02655135031000100, 121.3050034530999994, 87.67404182062000473 ) ) ; +#6620 = VERTEX_POINT ( 'NONE', #16811 ) ; +#6621 = FACE_OUTER_BOUND ( 'NONE', #39456, .T. ) ; +#6622 = ORIENTED_EDGE ( 'NONE', *, *, #947, .F. ) ; +#6623 = EDGE_CURVE ( 'NONE', #28881, #32839, #31602, .T. ) ; +#6624 = CYLINDRICAL_SURFACE ( 'NONE', #24250, 22.50000000000000000 ) ; +#6625 = CARTESIAN_POINT ( 'NONE', ( -13.46391575659845685, 154.4039982810205629, 95.30803284751881677 ) ) ; +#6626 = ORIENTED_EDGE ( 'NONE', *, *, #8913, .F. ) ; +#6627 = DIRECTION ( 'NONE', ( 0.7763856147932154395, -0.5343480027610235661, -0.3342118924985555406 ) ) ; +#6628 = EDGE_CURVE ( 'NONE', #16791, #8036, #13172, .T. ) ; +#6629 = CARTESIAN_POINT ( 'NONE', ( -0.3747130585439999995, 189.1668057001000136, 105.6062578476999931 ) ) ; +#6630 = DIRECTION ( 'NONE', ( -3.474730790243325680E-10, -0.9743700557140873020, -0.2249510936353195101 ) ) ; +#6631 = ORIENTED_EDGE ( 'NONE', *, *, #21429, .F. ) ; +#6632 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; +#6633 = CARTESIAN_POINT ( 'NONE', ( 39.86430758302872590, 77.39023996490196566, 290.9329938034825318 ) ) ; +#6634 = AXIS2_PLACEMENT_3D ( 'NONE', #32144, #1046, #10673 ) ; +#6635 = DIRECTION ( 'NONE', ( 0.0005884949961228156962, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6636 = DIRECTION ( 'NONE', ( -0.0006039748319356123742, 6.151140898304641511E-15, -0.9999998176071847045 ) ) ; +#6637 = AXIS2_PLACEMENT_3D ( 'NONE', #1612, #11227, #2234 ) ; +#6638 = EDGE_CURVE ( 'NONE', #36135, #11474, #23173, .T. ) ; +#6639 = CONICAL_SURFACE ( 'NONE', #9944, 6.500000000082215124, 0.7853981634430716730 ) ; +#6640 = CARTESIAN_POINT ( 'NONE', ( 15.12415969602515986, 146.0659008074709106, 180.8278994957862551 ) ) ; +#6641 = ORIENTED_EDGE ( 'NONE', *, *, #9135, .T. ) ; +#6642 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319398847813 ) ) ; +#6643 = CARTESIAN_POINT ( 'NONE', ( -38.54368346761000197, 118.3571362795999988, 89.55295134938000956 ) ) ; +#6644 = EDGE_LOOP ( 'NONE', ( #14153, #18544, #1231, #20412 ) ) ; +#6645 = LINE ( 'NONE', #725, #22956 ) ; +#6646 = ORIENTED_EDGE ( 'NONE', *, *, #14587, .T. ) ; +#6647 = CARTESIAN_POINT ( 'NONE', ( 8.955013101272822240, 160.1620528194969211, 96.62383716770308695 ) ) ; +#6648 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561517 ) ) ; +#6649 = CARTESIAN_POINT ( 'NONE', ( -31.70415073005799300, 220.4002260771000010, 75.57765305097055375 ) ) ; +#6650 = CARTESIAN_POINT ( 'NONE', ( -3.870368579862465630, 174.7537207775617674, 102.7362565340363005 ) ) ; +#6651 = ORIENTED_EDGE ( 'NONE', *, *, #39033, .T. ) ; +#6652 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265227786, -0.1368326740407719844 ) ) ; +#6653 = VERTEX_POINT ( 'NONE', #32566 ) ; +#6654 = ORIENTED_EDGE ( 'NONE', *, *, #40131, .T. ) ; +#6655 = ORIENTED_EDGE ( 'NONE', *, *, #5136, .T. ) ; +#6656 = CARTESIAN_POINT ( 'NONE', ( 28.90951000791340064, 225.0820812894944822, 76.04104400993735169 ) ) ; +#6657 = CARTESIAN_POINT ( 'NONE', ( -45.01366707977943094, 130.2508973098130411, 92.82981015662352320 ) ) ; +#6658 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; +#6659 = EDGE_CURVE ( 'NONE', #32574, #11409, #13361, .T. ) ; +#6660 = EDGE_LOOP ( 'NONE', ( #20133, #4316, #8903, #8090, #8843, #34201, #10132, #20276 ) ) ; +#6661 = CARTESIAN_POINT ( 'NONE', ( 19.98210856654580780, 205.1070970766282358, 76.09272704596726555 ) ) ; +#6662 = EDGE_CURVE ( 'NONE', #37725, #39374, #28211, .T. ) ; +#6663 = CARTESIAN_POINT ( 'NONE', ( -28.81763517994743751, 225.0820812896716632, 76.07590975914473574 ) ) ; +#6664 = AXIS2_PLACEMENT_3D ( 'NONE', #23344, #1866, #10875 ) ; +#6665 = ADVANCED_FACE ( 'NONE', ( #38293 ), #7408, .F. ) ; +#6666 = ORIENTED_EDGE ( 'NONE', *, *, #9608, .F. ) ; +#6667 = DIRECTION ( 'NONE', ( 0.9999998268368220922, 0.0001323826147821730395, -0.0005734118669949963198 ) ) ; +#6668 = AXIS2_PLACEMENT_3D ( 'NONE', #19510, #15840, #16044 ) ; +#6669 = CONICAL_SURFACE ( 'NONE', #26935, 2.750000000007442491, 0.7853981633308424470 ) ; +#6670 = CARTESIAN_POINT ( 'NONE', ( -40.71080201233111495, 190.8841207850421995, 103.7465862286444178 ) ) ; +#6671 = EDGE_LOOP ( 'NONE', ( #9299, #24254, #4935, #28445, #10488, #25744, #16023, #3980, #7132, #38873, #36627, #18281, #36839 ) ) ; +#6672 = CARTESIAN_POINT ( 'NONE', ( 28.30326266966000048, 125.4564572028999976, 88.94198821295999835 ) ) ; +#6673 = EDGE_CURVE ( 'NONE', #24826, #21867, #35995, .T. ) ; +#6674 = FACE_OUTER_BOUND ( 'NONE', #21790, .T. ) ; +#6675 = PLANE ( 'NONE', #39714 ) ; +#6676 = CARTESIAN_POINT ( 'NONE', ( 3.534343284623258974, 175.3621990150981276, 100.1363906404241675 ) ) ; +#6677 = CARTESIAN_POINT ( 'NONE', ( 5.341513311928848040, 124.3682655131192831, 88.36237119484185598 ) ) ; +#6678 = ORIENTED_EDGE ( 'NONE', *, *, #28897, .F. ) ; +#6680 = EDGE_CURVE ( 'NONE', #2594, #11261, #14076, .T. ) ; +#6679 = CARTESIAN_POINT ( 'NONE', ( -28.46346214431096655, 130.6180201592175933, 90.16776375064561933 ) ) ; +#6681 = FACE_OUTER_BOUND ( 'NONE', #691, .T. ) ; +#6682 = CARTESIAN_POINT ( 'NONE', ( -37.83810969319355166, 191.0388331516561777, 103.7805696149103909 ) ) ; +#6683 = CARTESIAN_POINT ( 'NONE', ( 42.44089075944981460, 185.1190886577203685, 127.1660040187822318 ) ) ; +#6684 = VERTEX_POINT ( 'NONE', #4341 ) ; +#6685 = DIRECTION ( 'NONE', ( 0.0004161288024547961178, 0.5299192578740949955, 0.8480479980348919478 ) ) ; +#6686 = LINE ( 'NONE', #36987, #3622 ) ; +#6687 = FACE_OUTER_BOUND ( 'NONE', #5098, .T. ) ; +#6688 = CARTESIAN_POINT ( 'NONE', ( 19.98197889682855788, 210.1681488827333339, 73.04643546784730290 ) ) ; +#6689 = ADVANCED_FACE ( 'NONE', ( #21708 ), #34737, .T. ) ; +#6690 = CIRCLE ( 'NONE', #10654, 1.999999999512996451 ) ; +#6691 = CARTESIAN_POINT ( 'NONE', ( -26.72558658360999928, 188.4929050110000333, 106.2649942106999958 ) ) ; +#6692 = VERTEX_POINT ( 'NONE', #25374 ) ; +#6693 = CARTESIAN_POINT ( 'NONE', ( 22.50176470575690857, 173.8437174413195123, 102.8532298930652047 ) ) ; +#6694 = VECTOR ( 'NONE', #23269, 999.9999999999998863 ) ; +#6695 = CARTESIAN_POINT ( 'NONE', ( -12.63890180163353527, 181.8404537192973294, 101.8516965491096897 ) ) ; +#6696 = VECTOR ( 'NONE', #25283, 1000.000000000000000 ) ; +#6697 = CARTESIAN_POINT ( 'NONE', ( -29.78271232893557041, 185.5388540720573189, 103.0190829539931059 ) ) ; +#6698 = ORIENTED_EDGE ( 'NONE', *, *, #895, .T. ) ; +#6699 = CARTESIAN_POINT ( 'NONE', ( 15.59065710780900638, 127.6518116318376457, 175.3064835098809056 ) ) ; +#6700 = DIRECTION ( 'NONE', ( 3.053113317596056969E-14, 0.9743700557921590732, 0.2249510932971532096 ) ) ; +#6701 = CARTESIAN_POINT ( 'NONE', ( -2.937264483321980979, 191.5260295968394928, 103.8719657109621295 ) ) ; +#6702 = DIRECTION ( 'NONE', ( 0.0006039748319401620118, 1.156691652267356444E-14, 0.9999998176071847045 ) ) ; +#6703 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34472, #32054, #22845, #31440 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6704 = CARTESIAN_POINT ( 'NONE', ( 36.19631487654000068, 192.5993829527999992, 106.2212666058999986 ) ) ; +#6705 = ORIENTED_EDGE ( 'NONE', *, *, #1074, .T. ) ; +#6706 = ORIENTED_EDGE ( 'NONE', *, *, #11086, .T. ) ; +#6707 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971550969 ) ) ; +#6708 = LINE ( 'NONE', #28603, #18990 ) ; +#6709 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3274, #6947, #6149, #37436, #813, #6348, #12905, #20, #611, #18799 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.0004303995929816994254, 0.0008607991859633988508, 0.001291198778945098222, 0.001721598371926797702 ), + .UNSPECIFIED. ) ; +#6710 = CARTESIAN_POINT ( 'NONE', ( 40.67213421873967860, 184.8215033964496001, 102.8109171582487278 ) ) ; +#6711 = DIRECTION ( 'NONE', ( -0.0005959781126671458411, -0.1621881766265671210, -0.9867596668756980494 ) ) ; +#6712 = VERTEX_POINT ( 'NONE', #9837 ) ; +#6713 = CARTESIAN_POINT ( 'NONE', ( -32.57213854657648255, 175.6744114851244376, 100.2302293651451492 ) ) ; +#6714 = ADVANCED_FACE ( 'NONE', ( #37434 ), #16347, .T. ) ; +#6715 = EDGE_CURVE ( 'NONE', #468, #26246, #15942, .T. ) ; +#6716 = ORIENTED_EDGE ( 'NONE', *, *, #38401, .F. ) ; +#6717 = CARTESIAN_POINT ( 'NONE', ( -4.704802962633507057, 130.8321230753525981, 89.86073829340300279 ) ) ; +#6718 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#6719 = AXIS2_PLACEMENT_3D ( 'NONE', #26438, #4745, #38481 ) ; +#6720 = VERTEX_POINT ( 'NONE', #12903 ) ; +#6721 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; +#6722 = CARTESIAN_POINT ( 'NONE', ( 24.53469179835996172, 103.6131156702607257, 89.75296640900927514 ) ) ; +#6723 = CARTESIAN_POINT ( 'NONE', ( -23.35399029200872079, 130.2187140253622601, 92.63824150152402126 ) ) ; +#6724 = EDGE_CURVE ( 'NONE', #40272, #16030, #11698, .T. ) ; +#6725 = CIRCLE ( 'NONE', #38084, 2.250000000025557778 ) ; +#6726 = CARTESIAN_POINT ( 'NONE', ( -30.06587742563253585, 177.0744528912911733, 103.5787552974134087 ) ) ; +#6727 = LINE ( 'NONE', #38011, #23003 ) ; +#6728 = ORIENTED_EDGE ( 'NONE', *, *, #13005, .F. ) ; +#6729 = CARTESIAN_POINT ( 'NONE', ( -35.93878493987469369, 193.8169247291205863, 102.7246158654084098 ) ) ; +#6730 = AXIS2_PLACEMENT_3D ( 'NONE', #30827, #36748, #27775 ) ; +#6731 = CARTESIAN_POINT ( 'NONE', ( 1.973863911711999819, 189.2113471865000065, 103.4772481592000020 ) ) ; +#6732 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6733 = CARTESIAN_POINT ( 'NONE', ( -37.09244532070999867, 190.9712090824999962, 103.6176582474000014 ) ) ; +#6734 = ORIENTED_EDGE ( 'NONE', *, *, #23204, .T. ) ; +#6735 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#6736 = ORIENTED_EDGE ( 'NONE', *, *, #37601, .F. ) ; +#6737 = CARTESIAN_POINT ( 'NONE', ( 14.78600926606004862, 175.8977815190944796, 100.7663474239818839 ) ) ; +#6738 = CARTESIAN_POINT ( 'NONE', ( -20.02002437005085511, 209.7095682957761085, 73.07054393135327075 ) ) ; +#6739 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#6740 = CARTESIAN_POINT ( 'NONE', ( -12.63650000504985549, 176.7400935515184131, 103.0299816119349714 ) ) ; +#6741 = CARTESIAN_POINT ( 'NONE', ( 25.49063000826092562, 211.0902260967494897, 73.54299573436949800 ) ) ; +#6742 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498900786, 129.6183187699468249, 92.64570812446403636 ) ) ; +#6743 = CARTESIAN_POINT ( 'NONE', ( -37.68723907529999906, 190.5064451007000059, 106.6118794326999932 ) ) ; +#6744 = VECTOR ( 'NONE', #25745, 999.9999999999998863 ) ; +#6745 = ORIENTED_EDGE ( 'NONE', *, *, #12587, .T. ) ; +#6746 = ADVANCED_FACE ( 'NONE', ( #28048 ), #28244, .F. ) ; +#6747 = DIRECTION ( 'NONE', ( -0.0005884949961269576738, 0.2249510543439059429, -0.9743698870671263501 ) ) ; +#6748 = CARTESIAN_POINT ( 'NONE', ( 26.00611526003149621, 118.8155664120999973, 94.25207852681757004 ) ) ; +#6749 = DIRECTION ( 'NONE', ( 0.0005884949961236033691, -0.2249510543439074417, 0.9743698870671260170 ) ) ; +#6750 = AXIS2_PLACEMENT_3D ( 'NONE', #31526, #28460, #3487 ) ; +#6751 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387072293 ) ) ; +#6752 = ORIENTED_EDGE ( 'NONE', *, *, #5475, .T. ) ; +#6753 = EDGE_CURVE ( 'NONE', #9411, #10112, #21907, .T. ) ; +#6754 = CONICAL_SURFACE ( 'NONE', #17198, 59.40509898898601904, 0.7853981633972927368 ) ; +#6755 = EDGE_LOOP ( 'NONE', ( #38697, #11356, #36490, #13350 ) ) ; +#6756 = CARTESIAN_POINT ( 'NONE', ( 5.671965847892154855, 131.0223101898201605, 89.89837914816251896 ) ) ; +#6757 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#6758 = EDGE_CURVE ( 'NONE', #5402, #3978, #19415, .T. ) ; +#6759 = ORIENTED_EDGE ( 'NONE', *, *, #7500, .T. ) ; +#6760 = ADVANCED_FACE ( 'NONE', ( #37630 ), #14967, .F. ) ; +#6761 = ORIENTED_EDGE ( 'NONE', *, *, #40359, .T. ) ; +#6762 = ADVANCED_FACE ( 'NONE', ( #28634 ), #34507, .T. ) ; +#6763 = CARTESIAN_POINT ( 'NONE', ( 15.99970520780110483, 160.7332544674666508, 96.75156078672274873 ) ) ; +#6764 = CYLINDRICAL_SURFACE ( 'NONE', #7722, 1.650000000000002798 ) ; +#6765 = CARTESIAN_POINT ( 'NONE', ( -38.13219187549999845, 119.0756271369999979, 87.44113924395999504 ) ) ; +#6766 = FACE_OUTER_BOUND ( 'NONE', #9867, .T. ) ; +#6767 = DIRECTION ( 'NONE', ( 1.387778780793648170E-15, 0.9743700557921585181, 0.2249510932971560961 ) ) ; +#6768 = ORIENTED_EDGE ( 'NONE', *, *, #5050, .T. ) ; +#6769 = CARTESIAN_POINT ( 'NONE', ( -19.46394955521238401, 125.6772987183395998, 178.4491578239381511 ) ) ; +#6770 = DIRECTION ( 'NONE', ( -0.0005884949961231158034, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#6771 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560684 ) ) ; +#6772 = CARTESIAN_POINT ( 'NONE', ( 3.882702609145003869, 148.9606115484091617, 129.9617790688395473 ) ) ; +#6773 = VERTEX_POINT ( 'NONE', #22310 ) ; +#6774 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999904787, 179.7376864901910949, 101.1595092801111377 ) ) ; +#6775 = CARTESIAN_POINT ( 'NONE', ( 1.135325133094777561, 188.6789995793503749, 103.2122171789744840 ) ) ; +#6776 = VECTOR ( 'NONE', #39681, 1000.000000000000114 ) ; +#6777 = AXIS2_PLACEMENT_3D ( 'NONE', #2021, #38798, #14086 ) ; +#6778 = CARTESIAN_POINT ( 'NONE', ( 39.72739263165712487, 107.0606345199744283, 184.9165446084303426 ) ) ; +#6779 = CARTESIAN_POINT ( 'NONE', ( -16.49952091330321480, 137.4667901650724389, 177.5675841302929712 ) ) ; +#6780 = AXIS2_PLACEMENT_3D ( 'NONE', #32822, #17472, #39349 ) ; +#6781 = ORIENTED_EDGE ( 'NONE', *, *, #8357, .F. ) ; +#6782 = CARTESIAN_POINT ( 'NONE', ( -20.01953265211073685, 211.4835721071765704, 73.07059537846892283 ) ) ; +#6783 = CARTESIAN_POINT ( 'NONE', ( -28.94629671773202162, 110.6131156702000027, 90.28526767707491274 ) ) ; +#6784 = EDGE_LOOP ( 'NONE', ( #12899, #31611, #36886, #18447 ) ) ; +#6785 = CARTESIAN_POINT ( 'NONE', ( -35.95487748704000097, 211.5000000000000000, 76.08022047461994930 ) ) ; +#6786 = DIRECTION ( 'NONE', ( 0.7075235667960845243, -0.1533501899574517824, 0.6898507966713961492 ) ) ; +#6787 = CARTESIAN_POINT ( 'NONE', ( -26.40985164038999855, 123.6457726243000081, 90.64157144546000211 ) ) ; +#6788 = ORIENTED_EDGE ( 'NONE', *, *, #31200, .F. ) ; +#6789 = CARTESIAN_POINT ( 'NONE', ( -25.02259365761911880, 130.4982697376238718, 90.30908595312290288 ) ) ; +#6790 = CARTESIAN_POINT ( 'NONE', ( 26.00067918362605468, 118.8155664802563791, 90.25207353690788636 ) ) ; +#6791 = CARTESIAN_POINT ( 'NONE', ( -34.95668959393816522, 217.7719116313999734, 73.07961704668733205 ) ) ; +#6792 = ORIENTED_EDGE ( 'NONE', *, *, #29342, .F. ) ; +#6793 = ADVANCED_FACE ( 'NONE', ( #25581 ), #12688, .F. ) ; +#6794 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34039, #37507, #6031, #18482 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6795 = CARTESIAN_POINT ( 'NONE', ( -22.78222448642306119, 147.3951726449005264, 96.77445396919445386 ) ) ; +#6796 = CARTESIAN_POINT ( 'NONE', ( 35.56355292868355633, 196.5784392900514206, 103.8536238432368037 ) ) ; +#6798 = CARTESIAN_POINT ( 'NONE', ( 21.44693881909371669, 176.9241929811547038, 100.4861407201621120 ) ) ; +#6797 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.271205363195980628E-14, -0.9999998176071845934 ) ) ; +#6799 = EDGE_CURVE ( 'NONE', #32791, #21410, #3462, .T. ) ; +#6800 = CONICAL_SURFACE ( 'NONE', #15940, 2.499999999883616653, 0.7853981633241470250 ) ; +#6801 = AXIS2_PLACEMENT_3D ( 'NONE', #32879, #39014, #4870 ) ; +#6802 = ORIENTED_EDGE ( 'NONE', *, *, #19560, .T. ) ; +#6803 = FACE_OUTER_BOUND ( 'NONE', #6457, .T. ) ; +#6804 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178617807513E-05, -0.0002331579774917555924 ) ) ; +#6805 = LINE ( 'NONE', #25450, #34485 ) ; +#6807 = ORIENTED_EDGE ( 'NONE', *, *, #26835, .T. ) ; +#6806 = VECTOR ( 'NONE', #23460, 1000.000000000000000 ) ; +#6808 = EDGE_CURVE ( 'NONE', #22688, #38213, #12585, .T. ) ; +#6809 = VERTEX_POINT ( 'NONE', #34931 ) ; +#6810 = EDGE_CURVE ( 'NONE', #16126, #38935, #3869, .T. ) ; +#6811 = CARTESIAN_POINT ( 'NONE', ( 37.34006930806268088, 163.4882083427749819, 203.2693587385582248 ) ) ; +#6812 = EDGE_CURVE ( 'NONE', #35125, #30572, #35170, .T. ) ; +#6813 = CARTESIAN_POINT ( 'NONE', ( 15.89503781251914027, 146.8918091207503949, 179.7543742911328479 ) ) ; +#6814 = CARTESIAN_POINT ( 'NONE', ( 38.65471576631835404, 119.1564763279458816, 90.25899222980254422 ) ) ; +#6815 = CARTESIAN_POINT ( 'NONE', ( 36.41383768445999891, 191.8230841522999981, 104.3713742736999990 ) ) ; +#6816 = ORIENTED_EDGE ( 'NONE', *, *, #31967, .T. ) ; +#6817 = ORIENTED_EDGE ( 'NONE', *, *, #6118, .F. ) ; +#6818 = EDGE_LOOP ( 'NONE', ( #1881, #28724, #18742, #13725 ) ) ; +#6819 = FACE_OUTER_BOUND ( 'NONE', #31979, .T. ) ; +#6820 = CARTESIAN_POINT ( 'NONE', ( -15.49823494792000034, 122.6567579780000017, 91.05873804473000632 ) ) ; +#6821 = PLANE ( 'NONE', #63 ) ; +#6822 = ORIENTED_EDGE ( 'NONE', *, *, #31375, .F. ) ; +#6823 = DIRECTION ( 'NONE', ( 0.6087611434179115433, -0.7728348325624404547, -0.1792657018023851023 ) ) ; +#6824 = ORIENTED_EDGE ( 'NONE', *, *, #31112, .T. ) ; +#6825 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #22009, #31005, #309, #12200 ), + ( #36937, #2971, #9330, #34442 ), + ( #34055, #114, #15843, #15067 ), + ( #21806, #2788, #21199, #12797 ), + ( #2598, #37133, #6436, #27751 ), + ( #24486, #40185, #24686, #28337 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 4 ), + ( 4, 4 ), + ( -0.4155797443374000255, 0.000000000000000000, 1.000000000000000000, 1.415579535702000014 ), + ( -0.2939753932881999932, 1.293974227719999925 ), + .UNSPECIFIED. ) ; +#6826 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971554578 ) ) ; +#6827 = ORIENTED_EDGE ( 'NONE', *, *, #26519, .F. ) ; +#6828 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749898510, 132.8602140592310548, 90.82839891331310866 ) ) ; +#6829 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2945, #12765, #24459, #21587, #15623, #9303, #3349, #15821, #8711, #15035, #40160 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000137668, 0.6250000000000154321, 0.6875000000000102141, 0.7500000000000051070, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6830 = ORIENTED_EDGE ( 'NONE', *, *, #25691, .F. ) ; +#6831 = DIRECTION ( 'NONE', ( 0.0005884949961187157857, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6832 = CIRCLE ( 'NONE', #10762, 5.499999999656733252 ) ; +#6833 = CARTESIAN_POINT ( 'NONE', ( -0.3055502478852999970, 188.2261792854999953, 106.3573352107000005 ) ) ; +#6834 = AXIS2_PLACEMENT_3D ( 'NONE', #29796, #26326, #25933 ) ; +#6835 = AXIS2_PLACEMENT_3D ( 'NONE', #8931, #2782, #12192 ) ; +#6836 = CARTESIAN_POINT ( 'NONE', ( -34.02658427073158975, 128.5584679906816064, 291.5790951394965873 ) ) ; +#6837 = ORIENTED_EDGE ( 'NONE', *, *, #25040, .T. ) ; +#6838 = DIRECTION ( 'NONE', ( 0.0004270746993313995362, -0.7071067811864992780, 0.7071066522153991452 ) ) ; +#6839 = AXIS2_PLACEMENT_3D ( 'NONE', #19121, #35249, #22821 ) ; +#6840 = CARTESIAN_POINT ( 'NONE', ( 35.74718174663996706, 80.85208185161215511, 289.9785332225363277 ) ) ; +#6841 = CARTESIAN_POINT ( 'NONE', ( 22.01449759622806823, 213.9333678484432255, 73.04520787748346322 ) ) ; +#6842 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23024, #3585, #931, #22232, #10362, #32229, #35451, #16663, #4395, #330, #7064 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000004762302, 0.3750000000006487033, 0.4375000000007172596, 0.4687500000007325807, 0.5000000000007478462, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6843 = CARTESIAN_POINT ( 'NONE', ( 19.45344668381049402, 148.4806125025154699, 180.1225407165339050 ) ) ; +#6844 = CARTESIAN_POINT ( 'NONE', ( -41.49855576315250261, 120.6354435048598788, 90.60778428571630627 ) ) ; +#6845 = ADVANCED_FACE ( 'NONE', ( #35130 ), #26733, .T. ) ; +#6846 = ORIENTED_EDGE ( 'NONE', *, *, #39953, .T. ) ; +#6847 = EDGE_CURVE ( 'NONE', #16126, #27040, #10438, .T. ) ; +#6849 = EDGE_CURVE ( 'NONE', #29516, #9324, #21877, .T. ) ; +#6848 = CARTESIAN_POINT ( 'NONE', ( -45.21443695202828650, 123.9403496629249872, 93.41837760747816333 ) ) ; +#6850 = DIRECTION ( 'NONE', ( -0.0004161288024408846113, 0.8480480898094411302, -0.5299191110041020503 ) ) ; +#6852 = ORIENTED_EDGE ( 'NONE', *, *, #36677, .F. ) ; +#6851 = ADVANCED_FACE ( 'NONE', ( #17141 ), #4886, .F. ) ; +#6853 = FACE_OUTER_BOUND ( 'NONE', #8421, .T. ) ; +#6854 = VERTEX_POINT ( 'NONE', #38422 ) ; +#6855 = CARTESIAN_POINT ( 'NONE', ( 37.50056788730638857, 112.0004321268064302, 150.7364408029844469 ) ) ; +#6856 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15236, #34806, #25054, #483 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6857 = CARTESIAN_POINT ( 'NONE', ( -27.81698282089157814, 124.7490784083306607, 88.47031569593407596 ) ) ; +#6858 = CARTESIAN_POINT ( 'NONE', ( 12.63956951859597488, 183.5640300569467342, 104.5901456648895902 ) ) ; +#6859 = ORIENTED_EDGE ( 'NONE', *, *, #7634, .T. ) ; +#6860 = FACE_BOUND ( 'NONE', #988, .T. ) ; +#6861 = ORIENTED_EDGE ( 'NONE', *, *, #12233, .T. ) ; +#6862 = VECTOR ( 'NONE', #40333, 1000.000000000000114 ) ; +#6863 = ORIENTED_EDGE ( 'NONE', *, *, #6994, .F. ) ; +#6864 = EDGE_CURVE ( 'NONE', #8845, #13129, #16742, .T. ) ; +#6865 = CARTESIAN_POINT ( 'NONE', ( 1.706989674805065693, 189.3575274026192119, 105.8396631625953574 ) ) ; +#6866 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; +#6867 = FACE_OUTER_BOUND ( 'NONE', #35880, .T. ) ; +#6868 = ORIENTED_EDGE ( 'NONE', *, *, #3985, .T. ) ; +#6869 = CIRCLE ( 'NONE', #12118, 6.000000000000007994 ) ; +#6870 = ORIENTED_EDGE ( 'NONE', *, *, #1096, .F. ) ; +#6871 = CARTESIAN_POINT ( 'NONE', ( -25.50819987922450238, 205.5673820219388688, 76.31562095576882143 ) ) ; +#6872 = AXIS2_PLACEMENT_3D ( 'NONE', #33718, #33111, #23939 ) ; +#6873 = ORIENTED_EDGE ( 'NONE', *, *, #32737, .T. ) ; +#6874 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178570903572E-05, -0.0002331579774915885982 ) ) ; +#6875 = EDGE_CURVE ( 'NONE', #29957, #21784, #32577, .T. ) ; +#6876 = CARTESIAN_POINT ( 'NONE', ( -20.00083443091425650, 118.1225346402999037, 87.27986429484819553 ) ) ; +#6877 = CARTESIAN_POINT ( 'NONE', ( -22.82371426798999892, 163.2545600168000135, 28.07991271570000080 ) ) ; +#6878 = ORIENTED_EDGE ( 'NONE', *, *, #28837, .F. ) ; +#6879 = CARTESIAN_POINT ( 'NONE', ( 28.04365811438999856, 124.9477242110999953, 88.48236039207999681 ) ) ; +#6880 = DIRECTION ( 'NONE', ( 0.0005884949961166157945, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6881 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6882 = DIRECTION ( 'NONE', ( 0.0005884949961249829080, -0.2249510543439062205, 0.9743698870671264611 ) ) ; +#6883 = CARTESIAN_POINT ( 'NONE', ( 3.661323151892192929, 136.5728955213519100, 91.18104735487531798 ) ) ; +#6884 = ORIENTED_EDGE ( 'NONE', *, *, #1360, .T. ) ; +#6885 = CARTESIAN_POINT ( 'NONE', ( -20.49852830656245928, 127.1805961887959029, 91.59301651814030265 ) ) ; +#6886 = CARTESIAN_POINT ( 'NONE', ( -25.02141666792893560, 130.0483676884890656, 92.25782546781267968 ) ) ; +#6887 = LINE ( 'NONE', #756, #24131 ) ; +#6888 = CIRCLE ( 'NONE', #27826, 5.999999999955290875 ) ; +#6889 = CARTESIAN_POINT ( 'NONE', ( 39.77206948006279674, 161.5605239982007504, 197.5119495795953810 ) ) ; +#6890 = ORIENTED_EDGE ( 'NONE', *, *, #27660, .T. ) ; +#6891 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971552357 ) ) ; +#6892 = CIRCLE ( 'NONE', #19955, 5.000000000044655835 ) ; +#6893 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6894 = DIRECTION ( 'NONE', ( -0.6087611427424929333, -0.7731004630501246977, -0.1781166615410725018 ) ) ; +#6895 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16070, #37741, #38538, #28556 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6896 = CARTESIAN_POINT ( 'NONE', ( -25.71743419941340392, 189.5946358309539903, 106.0021668375359951 ) ) ; +#6897 = EDGE_CURVE ( 'NONE', #38290, #8778, #36481, .T. ) ; +#6898 = ORIENTED_EDGE ( 'NONE', *, *, #6165, .T. ) ; +#6899 = CONICAL_SURFACE ( 'NONE', #30410, 5.999999999954211738, 0.7853981634347277918 ) ; +#6900 = FACE_OUTER_BOUND ( 'NONE', #13969, .T. ) ; +#6901 = EDGE_CURVE ( 'NONE', #18015, #1910, #17933, .T. ) ; +#6902 = EDGE_CURVE ( 'NONE', #39810, #24997, #38232, .T. ) ; +#6903 = CONICAL_SURFACE ( 'NONE', #8254, 2.502994749725878876, 0.7853981634296968162 ) ; +#6904 = EDGE_CURVE ( 'NONE', #9285, #8110, #16441, .T. ) ; +#6905 = CARTESIAN_POINT ( 'NONE', ( 0.5444273858962908053, 208.9999999999988631, 73.55817535324572987 ) ) ; +#6906 = CARTESIAN_POINT ( 'NONE', ( 22.78045900286115000, 164.6403492429171820, 97.64938332832134904 ) ) ; +#6907 = LINE ( 'NONE', #38390, #17190 ) ; +#6908 = DIRECTION ( 'NONE', ( 0.0006039748319385908944, 1.293414132305980107E-14, 0.9999998176071845934 ) ) ; +#6909 = EDGE_CURVE ( 'NONE', #32422, #13026, #16935, .T. ) ; +#6910 = CARTESIAN_POINT ( 'NONE', ( 20.10661668407306735, 127.4128641808344184, 89.16571173669045436 ) ) ; +#6911 = CARTESIAN_POINT ( 'NONE', ( 36.08394249776021212, 192.1905234492190004, 104.3364764196000039 ) ) ; +#6912 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#6913 = LINE ( 'NONE', #3834, #24586 ) ; +#6914 = ORIENTED_EDGE ( 'NONE', *, *, #35275, .T. ) ; +#6915 = ADVANCED_FACE ( 'NONE', ( #20418 ), #16254, .T. ) ; +#6916 = CARTESIAN_POINT ( 'NONE', ( -2.390862647930000140, 209.5043720128000189, 75.55992074799000591 ) ) ; +#6917 = CARTESIAN_POINT ( 'NONE', ( 36.91298638867539239, 117.6615514768335657, 87.24548977321406085 ) ) ; +#6918 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33241, #4827, #1359, #4629, #23863, #26529, #8115, #17291, #11379, #14667 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6919 = CARTESIAN_POINT ( 'NONE', ( 28.36925001313300143, 160.2013931541194722, 186.9397811580082021 ) ) ; +#6920 = CONICAL_SURFACE ( 'NONE', #37599, 59.40509898907522768, 0.7853981633972503262 ) ; +#6921 = EDGE_LOOP ( 'NONE', ( #14187, #2221, #30065, #39110 ) ) ; +#6922 = CARTESIAN_POINT ( 'NONE', ( 5.666806155083023988, 187.7449703091009781, 103.5069947386187295 ) ) ; +#6923 = VECTOR ( 'NONE', #9953, 1000.000000000000114 ) ; +#6924 = EDGE_LOOP ( 'NONE', ( #17680, #5382, #4393, #7373 ) ) ; +#6925 = CARTESIAN_POINT ( 'NONE', ( -42.43581683406742400, 94.00600134306105815, 291.5841741052475413 ) ) ; +#6926 = CARTESIAN_POINT ( 'NONE', ( -28.94659870514799849, 110.6131156702000027, 89.78526776826356581 ) ) ; +#6927 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; +#6928 = CARTESIAN_POINT ( 'NONE', ( -25.75022655317000186, 199.6921533858000259, 89.51711465924999800 ) ) ; +#6929 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971573174 ) ) ; +#6930 = CARTESIAN_POINT ( 'NONE', ( -1.458415330454428283, 144.9404864492411207, 129.0359332385636151 ) ) ; +#6931 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366368657916, 137.4659008082770697, 177.5714312369256049 ) ) ; +#6932 = DIRECTION ( 'NONE', ( 0.0006039748319384539597, 1.295170900108887039E-14, 0.9999998176071845934 ) ) ; +#6933 = CARTESIAN_POINT ( 'NONE', ( 21.98720601892291882, 135.9708336155091501, 91.37308817621079982 ) ) ; +#6934 = ORIENTED_EDGE ( 'NONE', *, *, #7651, .F. ) ; +#6935 = CARTESIAN_POINT ( 'NONE', ( 20.00016034875645943, 127.4394136103090887, 89.06260552501319694 ) ) ; +#6936 = CARTESIAN_POINT ( 'NONE', ( -3.703375335444472949, 176.2270507236910078, 100.3403802001799932 ) ) ; +#6937 = DIRECTION ( 'NONE', ( -0.0006039748319382906789, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#6938 = PLANE ( 'NONE', #34025 ) ; +#6939 = ORIENTED_EDGE ( 'NONE', *, *, #13434, .F. ) ; +#6940 = FACE_OUTER_BOUND ( 'NONE', #14692, .T. ) ; +#6941 = VERTEX_POINT ( 'NONE', #32895 ) ; +#6942 = CARTESIAN_POINT ( 'NONE', ( -20.24971313286999930, 118.4645066358000065, 87.53000830311999891 ) ) ; +#6943 = CONICAL_SURFACE ( 'NONE', #29817, 2.499999999745661228, 0.7853981633575387589 ) ; +#6944 = EDGE_CURVE ( 'NONE', #25826, #20447, #9098, .T. ) ; +#6945 = CARTESIAN_POINT ( 'NONE', ( 23.64615935046051121, 213.5251573336125546, 75.54441360651122750 ) ) ; +#6946 = CIRCLE ( 'NONE', #35672, 8.499999910073746889 ) ; +#6947 = CARTESIAN_POINT ( 'NONE', ( -17.18067142873831443, 152.4961243885515501, 182.3657930501721864 ) ) ; +#6948 = CIRCLE ( 'NONE', #21339, 2.000000000000011546 ) ; +#6949 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6950 = CARTESIAN_POINT ( 'NONE', ( 20.48087218850230329, 207.4145945196426055, 74.16884525731691724 ) ) ; +#6951 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385906776 ) ) ; +#6952 = ORIENTED_EDGE ( 'NONE', *, *, #19491, .T. ) ; +#6953 = AXIS2_PLACEMENT_3D ( 'NONE', #29081, #13144, #12520 ) ; +#6954 = CARTESIAN_POINT ( 'NONE', ( -3.669581230394507898, 185.7947741359049019, 103.0623953380812168 ) ) ; +#6955 = CARTESIAN_POINT ( 'NONE', ( -16.53001031479427141, 121.8780329720448066, 177.6173573199974953 ) ) ; +#6956 = DIRECTION ( 'NONE', ( -0.0005884949961216892102, 0.2249510543439063592, -0.9743698870671262391 ) ) ; +#6957 = VECTOR ( 'NONE', #19000, 1000.000000000000000 ) ; +#6958 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971582333 ) ) ; +#6959 = ORIENTED_EDGE ( 'NONE', *, *, #6399, .F. ) ; +#6960 = VERTEX_POINT ( 'NONE', #20211 ) ; +#6961 = ORIENTED_EDGE ( 'NONE', *, *, #33229, .T. ) ; +#6962 = CARTESIAN_POINT ( 'NONE', ( -26.00898928064792059, 209.7096528057114710, 76.07444037909847623 ) ) ; +#6963 = FACE_OUTER_BOUND ( 'NONE', #24652, .T. ) ; +#6964 = CARTESIAN_POINT ( 'NONE', ( -5.669748535203316564, 124.7404542330243800, 88.96810042129679630 ) ) ; +#6965 = ORIENTED_EDGE ( 'NONE', *, *, #9141, .T. ) ; +#6966 = CARTESIAN_POINT ( 'NONE', ( 0.5444273898015423718, 211.0000000000153761, 73.55817535318051625 ) ) ; +#6967 = ADVANCED_FACE ( 'NONE', ( #20011 ), #32502, .T. ) ; +#6968 = CARTESIAN_POINT ( 'NONE', ( -20.01841854128525711, 211.0875725380936103, 76.07063535483980843 ) ) ; +#6969 = CARTESIAN_POINT ( 'NONE', ( -38.01148413917999846, 119.1977134487000001, 87.30055639309000526 ) ) ; +#6970 = CARTESIAN_POINT ( 'NONE', ( 24.53318186138201185, 109.6131156702000027, 87.25296686492356457 ) ) ; +#6971 = ORIENTED_EDGE ( 'NONE', *, *, #7029, .F. ) ; +#6972 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 82.27946979429644614, 322.5967026918628449 ) ) ; +#6973 = VECTOR ( 'NONE', #34892, 1000.000000000000114 ) ; +#6974 = ORIENTED_EDGE ( 'NONE', *, *, #36984, .T. ) ; +#6975 = DIRECTION ( 'NONE', ( -0.0002393071182776102175, -0.2252352986010028590, 0.9743043687658493601 ) ) ; +#6976 = AXIS2_PLACEMENT_3D ( 'NONE', #25151, #37211, #24555 ) ; +#6977 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#6978 = AXIS2_PLACEMENT_3D ( 'NONE', #33809, #23605, #8484 ) ; +#6979 = DIRECTION ( 'NONE', ( -0.0005884949961212082581, 0.2249510543439042498, -0.9743698870671267942 ) ) ; +#6980 = EDGE_LOOP ( 'NONE', ( #26896, #29395, #16553, #21445, #8056, #24653 ) ) ; +#6981 = DIRECTION ( 'NONE', ( -0.0005884949961213717558, 0.2249510543439036392, -0.9743698870671270162 ) ) ; +#6982 = DIRECTION ( 'NONE', ( -0.0005884949961247530571, 0.2249510543439059984, -0.9743698870671264611 ) ) ; +#6983 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2249510911124609769, 0.9743700461176366678 ) ) ; +#6984 = CARTESIAN_POINT ( 'NONE', ( 2.428754671134000009, 191.0208418608000045, 106.1781663985999984 ) ) ; +#6985 = ORIENTED_EDGE ( 'NONE', *, *, #12704, .F. ) ; +#6986 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#6987 = CARTESIAN_POINT ( 'NONE', ( 22.50109425295000420, 153.5098312371554812, 96.96142690451516444 ) ) ; +#6988 = ORIENTED_EDGE ( 'NONE', *, *, #536, .T. ) ; +#6989 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#6990 = CARTESIAN_POINT ( 'NONE', ( 36.14023722679998230, 191.5080921624359860, 103.8442226955327072 ) ) ; +#6991 = CARTESIAN_POINT ( 'NONE', ( -27.38672108596999877, 124.3235127633000019, 91.06231056098999943 ) ) ; +#6992 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5080, #38276, #30239, #2238, #32892, #36376, #17337, #35735, #2039, #33496 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998623323, 0.3749999999997778999, 0.4374999999998006595, 0.4999999999998234745, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#6993 = EDGE_LOOP ( 'NONE', ( #9081, #29946, #21769, #12557 ) ) ; +#6994 = EDGE_CURVE ( 'NONE', #21808, #37550, #5264, .T. ) ; +#6995 = ADVANCED_FACE ( 'NONE', ( #21252 ), #11648, .T. ) ; +#6996 = CARTESIAN_POINT ( 'NONE', ( 40.92026568131703357, 127.3697701066096357, 89.54698672994854292 ) ) ; +#6997 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971540977 ) ) ; +#6998 = VERTEX_POINT ( 'NONE', #24121 ) ; +#6999 = VERTEX_POINT ( 'NONE', #36580 ) ; +#7000 = ADVANCED_FACE ( 'NONE', ( #33701 ), #28680, .T. ) ; +#7001 = CARTESIAN_POINT ( 'NONE', ( 25.83552483359000007, 120.2784135862000028, 90.31309258643000248 ) ) ; +#7002 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971551525 ) ) ; +#7003 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#7004 = CIRCLE ( 'NONE', #39022, 5.000000000000007994 ) ; +#7006 = CARTESIAN_POINT ( 'NONE', ( -8.050307605157906110, 151.4365984322141117, 94.61967771673485572 ) ) ; +#7005 = LINE ( 'NONE', #3934, #27012 ) ; +#7007 = VERTEX_POINT ( 'NONE', #27200 ) ; +#7008 = FACE_OUTER_BOUND ( 'NONE', #8021, .T. ) ; +#7009 = CARTESIAN_POINT ( 'NONE', ( -35.94137855478952304, 192.3005220655173844, 104.4216532017527612 ) ) ; +#7010 = CARTESIAN_POINT ( 'NONE', ( 25.50924745143719718, 191.9344736266071436, 104.4056993596765039 ) ) ; +#7011 = ORIENTED_EDGE ( 'NONE', *, *, #7634, .F. ) ; +#7012 = EDGE_LOOP ( 'NONE', ( #14743, #29107, #38169, #20035 ) ) ; +#7013 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858247, 183.1686750955933292, 104.5300206044594091 ) ) ; +#7014 = EDGE_CURVE ( 'NONE', #18757, #39205, #5084, .T. ) ; +#7015 = DIRECTION ( 'NONE', ( 0.7857167650892389332, -0.6185862428610306996, -0.0004745532376930883104 ) ) ; +#7016 = CARTESIAN_POINT ( 'NONE', ( -2.300294511845000223, 191.0029775200999893, 106.1754856335000028 ) ) ; +#7017 = ORIENTED_EDGE ( 'NONE', *, *, #5378, .F. ) ; +#7018 = ORIENTED_EDGE ( 'NONE', *, *, #17793, .F. ) ; +#7019 = CARTESIAN_POINT ( 'NONE', ( 31.91041242450083004, 174.4868366864082532, 100.4302623719975571 ) ) ; +#7020 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11494, #23556, #30105, #36435 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7021 = CARTESIAN_POINT ( 'NONE', ( 20.00201742172724551, 173.8530216436687965, 102.8568040933565300 ) ) ; +#7022 = DIRECTION ( 'NONE', ( 0.7933533411653059808, 0.5931840316265239998, 0.1368326740407735942 ) ) ; +#7023 = CARTESIAN_POINT ( 'NONE', ( 30.06862072249006346, 137.3596426728894642, 91.34358413054317793 ) ) ; +#7024 = CARTESIAN_POINT ( 'NONE', ( 20.66773077360686983, 151.6559761831365734, 197.7415732814573630 ) ) ; +#7025 = ORIENTED_EDGE ( 'NONE', *, *, #35039, .F. ) ; +#7026 = CARTESIAN_POINT ( 'NONE', ( -20.00002391410913560, 191.9758546681010785, 103.9335315410770448 ) ) ; +#7027 = ORIENTED_EDGE ( 'NONE', *, *, #26681, .T. ) ; +#7028 = CARTESIAN_POINT ( 'NONE', ( -36.98896915103596683, 116.5316256593857673, 89.73479078397426179 ) ) ; +#7029 = EDGE_CURVE ( 'NONE', #31968, #456, #3773, .T. ) ; +#7030 = AXIS2_PLACEMENT_3D ( 'NONE', #16971, #27028, #5322 ) ; +#7031 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971565125 ) ) ; +#7032 = EDGE_LOOP ( 'NONE', ( #30278, #1295 ) ) ; +#7033 = CARTESIAN_POINT ( 'NONE', ( -13.49852954175317343, 126.2382556819623431, 91.37123216989357388 ) ) ; +#7034 = VECTOR ( 'NONE', #2758, 999.9999999999998863 ) ; +#7035 = EDGE_CURVE ( 'NONE', #12087, #29541, #31273, .T. ) ; +#7036 = CARTESIAN_POINT ( 'NONE', ( -0.5804629561866000431, 188.8452874369000085, 105.8546174481000008 ) ) ; +#7037 = LINE ( 'NONE', #31598, #11718 ) ; +#7038 = VERTEX_POINT ( 'NONE', #39231 ) ; +#7039 = FACE_OUTER_BOUND ( 'NONE', #238, .T. ) ; +#7040 = ORIENTED_EDGE ( 'NONE', *, *, #4651, .T. ) ; +#7042 = EDGE_CURVE ( 'NONE', #23715, #13773, #14561, .T. ) ; +#7041 = FACE_OUTER_BOUND ( 'NONE', #24238, .T. ) ; +#7043 = EDGE_CURVE ( 'NONE', #38112, #2346, #36162, .T. ) ; +#7044 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319402998139 ) ) ; +#7045 = CARTESIAN_POINT ( 'NONE', ( -14.08011580147661235, 129.1601492223334446, 176.8499123979196099 ) ) ; +#7046 = EDGE_CURVE ( 'NONE', #35577, #8041, #5706, .T. ) ; +#7047 = EDGE_CURVE ( 'NONE', #27835, #36593, #24332, .T. ) ; +#7048 = LINE ( 'NONE', #15465, #6696 ) ; +#7049 = DIRECTION ( 'NONE', ( -2.775557561577051799E-15, 0.9743700557921594063, 0.2249510932971529320 ) ) ; +#7050 = ORIENTED_EDGE ( 'NONE', *, *, #32495, .T. ) ; +#7051 = CARTESIAN_POINT ( 'NONE', ( -15.99999440082457447, 126.8010213445309660, 88.93691041956509480 ) ) ; +#7052 = CARTESIAN_POINT ( 'NONE', ( -38.20570836422999861, 118.3771204103999963, 89.85183920540001168 ) ) ; +#7053 = EDGE_LOOP ( 'NONE', ( #31357, #37960, #30571, #36092, #16256, #16402, #20128, #11284 ) ) ; +#7054 = VERTEX_POINT ( 'NONE', #8167 ) ; +#7055 = CARTESIAN_POINT ( 'NONE', ( 30.77698552351368022, 157.1445057580154696, 186.2336950731475156 ) ) ; +#7056 = CIRCLE ( 'NONE', #20095, 2.499999999912043247 ) ; +#7057 = CARTESIAN_POINT ( 'NONE', ( -27.57376195191087476, 124.5212553516985992, 88.41757169004912953 ) ) ; +#7058 = PLANE ( 'NONE', #18781 ) ; +#7059 = VERTEX_POINT ( 'NONE', #36778 ) ; +#7060 = FACE_OUTER_BOUND ( 'NONE', #18874, .T. ) ; +#7061 = VERTEX_POINT ( 'NONE', #30242 ) ; +#7062 = ORIENTED_EDGE ( 'NONE', *, *, #1407, .F. ) ; +#7063 = ORIENTED_EDGE ( 'NONE', *, *, #28889, .F. ) ; +#7064 = CARTESIAN_POINT ( 'NONE', ( -6.037299711039155525, 177.1908694358191099, 101.0774571033729785 ) ) ; +#7065 = CARTESIAN_POINT ( 'NONE', ( -20.49854424914517281, 188.7751534032917675, 105.8132267661662524 ) ) ; +#7066 = ORIENTED_EDGE ( 'NONE', *, *, #18073, .T. ) ; +#7067 = VERTEX_POINT ( 'NONE', #18151 ) ; +#7068 = LINE ( 'NONE', #19537, #8898 ) ; +#7069 = CARTESIAN_POINT ( 'NONE', ( 20.14930667494123639, 207.7151874268069776, 77.19983650213306703 ) ) ; +#7070 = CARTESIAN_POINT ( 'NONE', ( -0.03375341898833555260, -31.76863880746333280, 137.4221703796379188 ) ) ; +#7071 = FACE_OUTER_BOUND ( 'NONE', #20509, .T. ) ; +#7072 = CARTESIAN_POINT ( 'NONE', ( 19.99924631025479727, 193.7259939488269822, 102.9050502291709819 ) ) ; +#7073 = DIRECTION ( 'NONE', ( -0.0004161288024746329518, 0.8480480897661252238, -0.5299191110734220445 ) ) ; +#7074 = CARTESIAN_POINT ( 'NONE', ( 6.035971956738691802, 136.6802200559948517, 94.28648626696401891 ) ) ; +#7075 = ORIENTED_EDGE ( 'NONE', *, *, #4065, .F. ) ; +#7076 = CARTESIAN_POINT ( 'NONE', ( 28.22782016780999825, 125.5652517269000015, 89.13792513741999812 ) ) ; +#7077 = EDGE_CURVE ( 'NONE', #1845, #29762, #39886, .T. ) ; +#7078 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27802, #27609, #37188, #9182, #26330, #13051, #25937, #7292, #764, #19157 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7079 = CARTESIAN_POINT ( 'NONE', ( 30.77440290267000123, 127.9840126060999808, 90.72122795244999338 ) ) ; +#7080 = CARTESIAN_POINT ( 'NONE', ( 17.23194045394322416, 152.8507688340616824, 180.9169451015856396 ) ) ; +#7081 = CARTESIAN_POINT ( 'NONE', ( 16.50035848822895801, 137.3523938021837409, 178.0624305279299335 ) ) ; +#7082 = DIRECTION ( 'NONE', ( -0.000000000000000000, 1.000000000000000000, -1.110223024625155594E-14 ) ) ; +#7083 = ORIENTED_EDGE ( 'NONE', *, *, #16731, .T. ) ; +#7084 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; +#7085 = CIRCLE ( 'NONE', #29947, 22.50000000000899902 ) ; +#7086 = EDGE_CURVE ( 'NONE', #39699, #5211, #2242, .T. ) ; +#7087 = CARTESIAN_POINT ( 'NONE', ( 0.5795578794631678354, 189.0001590438989751, 103.6953544543183483 ) ) ; +#7088 = CARTESIAN_POINT ( 'NONE', ( 36.40558664052492333, 191.8188463803718093, 104.3612499972096117 ) ) ; +#7089 = EDGE_CURVE ( 'NONE', #6247, #20818, #36963, .T. ) ; +#7090 = VECTOR ( 'NONE', #33943, 1000.000000000000114 ) ; +#7091 = CARTESIAN_POINT ( 'NONE', ( 3.501239660417288402, 183.5259502247448893, 104.7579320029620931 ) ) ; +#7092 = AXIS2_PLACEMENT_3D ( 'NONE', #6795, #28892, #34989 ) ; +#7093 = CARTESIAN_POINT ( 'NONE', ( -30.07068226051780613, 136.7886132718092540, 93.81698375422377012 ) ) ; +#7094 = CARTESIAN_POINT ( 'NONE', ( -25.51388077191477066, 211.0902258580313742, 75.57405363378009611 ) ) ; +#7095 = VECTOR ( 'NONE', #19613, 1000.000000000000227 ) ; +#7096 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971594823 ) ) ; +#7097 = CARTESIAN_POINT ( 'NONE', ( -25.50804057823069471, 190.9260211217805363, 106.3128357153982648 ) ) ; +#7098 = EDGE_CURVE ( 'NONE', #11249, #33342, #9206, .T. ) ; +#7099 = CARTESIAN_POINT ( 'NONE', ( 25.75600378562127091, 122.1627709945768601, 90.40662719960204186 ) ) ; +#7100 = ORIENTED_EDGE ( 'NONE', *, *, #27097, .T. ) ; +#7101 = CARTESIAN_POINT ( 'NONE', ( -15.49970617728509481, 174.4013312752846900, 100.4391564138297497 ) ) ; +#7102 = CARTESIAN_POINT ( 'NONE', ( 25.99199080364422443, 211.0901596425212574, 76.04279652306830428 ) ) ; +#7103 = CARTESIAN_POINT ( 'NONE', ( -45.39773774286052088, 124.2994142384970218, 88.45363130071420699 ) ) ; +#7104 = CARTESIAN_POINT ( 'NONE', ( 22.49999746303471682, 151.9741732817970217, 94.72226965095939022 ) ) ; +#7105 = FACE_OUTER_BOUND ( 'NONE', #6477, .T. ) ; +#7106 = CARTESIAN_POINT ( 'NONE', ( 38.04164538826000097, 190.5102620719000015, 106.5668313176000055 ) ) ; +#7107 = CARTESIAN_POINT ( 'NONE', ( 36.08518473800659621, 192.3716602159279887, 106.3932342325000064 ) ) ; +#7108 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950524827, 137.3532831589782006, 178.0585834213013072 ) ) ; +#7109 = CARTESIAN_POINT ( 'NONE', ( -20.89286847790088331, 136.3261294211067138, 91.13890976780785991 ) ) ; +#7110 = ORIENTED_EDGE ( 'NONE', *, *, #23307, .T. ) ; +#7112 = VECTOR ( 'NONE', #22493, 1000.000000000000000 ) ; +#7111 = CARTESIAN_POINT ( 'NONE', ( -2.620872023761000147, 209.0473112116000038, 75.82273478259000399 ) ) ; +#7113 = CARTESIAN_POINT ( 'NONE', ( -15.56603823806943332, 147.4087826307038824, 179.2784924189821822 ) ) ; +#7114 = DIRECTION ( 'NONE', ( 0.5988683521957610667, -0.8008474865655346164, 0.000000000000000000 ) ) ; +#7115 = ORIENTED_EDGE ( 'NONE', *, *, #38518, .F. ) ; +#7116 = DIRECTION ( 'NONE', ( -0.0004161288024542070707, 0.8480480897973143861, -0.5299191110235090818 ) ) ; +#7117 = AXIS2_PLACEMENT_3D ( 'NONE', #28644, #15756, #28058 ) ; +#7118 = VECTOR ( 'NONE', #3130, 1000.000000000000227 ) ; +#7119 = ORIENTED_EDGE ( 'NONE', *, *, #34713, .F. ) ; +#7120 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#7121 = FACE_OUTER_BOUND ( 'NONE', #37080, .T. ) ; +#7122 = CARTESIAN_POINT ( 'NONE', ( -14.29616515061532489, 182.1658140207151462, 104.4546612231253846 ) ) ; +#7123 = EDGE_CURVE ( 'NONE', #19459, #35621, #18439, .T. ) ; +#7124 = EDGE_CURVE ( 'NONE', #1289, #10706, #37804, .T. ) ; +#7125 = EDGE_CURVE ( 'NONE', #25706, #1172, #22153, .T. ) ; +#7126 = CARTESIAN_POINT ( 'NONE', ( -23.35081975911714380, 130.3436102262665486, 92.83812635286813020 ) ) ; +#7127 = EDGE_CURVE ( 'NONE', #21013, #28306, #2139, .T. ) ; +#7128 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9322, #30799, #36717, #22000, #5642, #28140 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 4 ), + ( 0.000000000000000000, 0.3333335430186030734, 0.6666667714093976738, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7129 = CARTESIAN_POINT ( 'NONE', ( -30.06953855927680408, 176.7983674875579538, 103.1369290433998032 ) ) ; +#7130 = CARTESIAN_POINT ( 'NONE', ( 21.72804141255551968, 135.8412665901933281, 91.00123227078390187 ) ) ; +#7131 = ORIENTED_EDGE ( 'NONE', *, *, #30055, .T. ) ; +#7132 = ORIENTED_EDGE ( 'NONE', *, *, #26731, .T. ) ; +#7133 = CARTESIAN_POINT ( 'NONE', ( 16.56083240327746253, 152.2213612066225323, 181.4810637892755381 ) ) ; +#7134 = CARTESIAN_POINT ( 'NONE', ( -5.032525950256758307, 177.5851188099599653, 100.6547177535344133 ) ) ; +#7135 = CARTESIAN_POINT ( 'NONE', ( 3.853642445162356545, 176.5899727902160521, 100.4196031271038976 ) ) ; +#7136 = EDGE_CURVE ( 'NONE', #37750, #36032, #23320, .T. ) ; +#7137 = CARTESIAN_POINT ( 'NONE', ( -35.98473264158000262, 191.6464846952000016, 104.0240790657999952 ) ) ; +#7138 = ORIENTED_EDGE ( 'NONE', *, *, #15184, .T. ) ; +#7139 = FACE_OUTER_BOUND ( 'NONE', #8235, .T. ) ; +#7140 = ORIENTED_EDGE ( 'NONE', *, *, #31296, .T. ) ; +#7141 = EDGE_CURVE ( 'NONE', #2805, #11248, #7438, .T. ) ; +#7142 = VECTOR ( 'NONE', #29069, 1000.000000000000114 ) ; +#7143 = CARTESIAN_POINT ( 'NONE', ( 36.71933013359660691, 115.7525949145573207, 89.70085851803463584 ) ) ; +#7144 = CARTESIAN_POINT ( 'NONE', ( 2.544444642232003950, 209.0637104426000121, 73.60054458572000158 ) ) ; +#7145 = AXIS2_PLACEMENT_3D ( 'NONE', #20344, #19539, #936 ) ; +#7146 = CARTESIAN_POINT ( 'NONE', ( -15.74985326587000145, 127.2158021103000038, 89.28909166873999936 ) ) ; +#7147 = CONICAL_SURFACE ( 'NONE', #11103, 4.999999999912411397, 0.7853981633778838178 ) ; +#7148 = CARTESIAN_POINT ( 'NONE', ( -38.94514605625099080, 127.5103311478221428, 92.19343525405152207 ) ) ; +#7149 = CARTESIAN_POINT ( 'NONE', ( -25.99272582769830819, 191.9759150222000130, 101.9371462954573673 ) ) ; +#7150 = EDGE_CURVE ( 'NONE', #21029, #3248, #14322, .T. ) ; +#7151 = CYLINDRICAL_SURFACE ( 'NONE', #19047, 2.000000000000000000 ) ; +#7152 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#7153 = CARTESIAN_POINT ( 'NONE', ( -37.71819034619999655, 191.1230216278999876, 106.2274880251000013 ) ) ; +#7154 = ORIENTED_EDGE ( 'NONE', *, *, #24808, .T. ) ; +#7155 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#7156 = CARTESIAN_POINT ( 'NONE', ( -36.38117854302612386, 191.5685604296012912, 106.4115501805643476 ) ) ; +#7157 = DIRECTION ( 'NONE', ( 0.6087614115774887535, 0.7729348350621332298, 0.1788331191967985623 ) ) ; +#7158 = CARTESIAN_POINT ( 'NONE', ( 30.07038801304316777, 174.6845315262252143, 103.0427758964743816 ) ) ; +#7159 = VERTEX_POINT ( 'NONE', #32794 ) ; +#7160 = EDGE_LOOP ( 'NONE', ( #23324, #8068, #8182, #1080, #18474, #9596 ) ) ; +#7161 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #7993, #20456, #9225, #2485 ), + ( #12287, #17994, #30698, #5531 ), + ( #36416, #18396, #21697, #20880 ), + ( #27243, #30088, #39464, #34141 ), + ( #9021, #21504, #37226, #30498 ), + ( #15158, #33743, #2277, #27455 ), + ( #30281, #24773, #5941, #14951 ), + ( #40275, #14759, #33337, #33940 ), + ( #39674, #17785, #30898, #36621 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.01895079535701999982, 0.000000000000000000, 0.2500000606983999729, 0.5000001337900999987, 0.7500002068818999446, 1.000000000000000000, 1.019135236371000008 ), + ( 2.695796517459999933E-06, 0.9999450311894000354 ), + .UNSPECIFIED. ) ; +#7162 = ORIENTED_EDGE ( 'NONE', *, *, #29765, .F. ) ; +#7163 = CARTESIAN_POINT ( 'NONE', ( 31.30533522779878908, 110.6131156702000027, 90.24887720121222401 ) ) ; +#7164 = CARTESIAN_POINT ( 'NONE', ( 15.50029466867484551, 138.3983482085316723, 92.10848809867536602 ) ) ; +#7165 = VERTEX_POINT ( 'NONE', #17034 ) ; +#7166 = VERTEX_POINT ( 'NONE', #1309 ) ; +#7167 = CARTESIAN_POINT ( 'NONE', ( -35.95366953732082749, 209.7096538831000032, 78.08022010984795713 ) ) ; +#7168 = VECTOR ( 'NONE', #27678, 999.9999999999998863 ) ; +#7169 = CARTESIAN_POINT ( 'NONE', ( -38.23160862004999672, 118.6973730046999975, 90.09692188751000685 ) ) ; +#7170 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#7171 = CARTESIAN_POINT ( 'NONE', ( -21.79303016557126327, 121.9945052680030670, 152.1817659228955222 ) ) ; +#7172 = DIRECTION ( 'NONE', ( 0.6088160902985568779, -0.7729595817128234181, -0.1785397805306046803 ) ) ; +#7173 = VERTEX_POINT ( 'NONE', #1510 ) ; +#7174 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#7175 = VECTOR ( 'NONE', #21626, 1000.000000000000000 ) ; +#7176 = ORIENTED_EDGE ( 'NONE', *, *, #12369, .F. ) ; +#7178 = EDGE_CURVE ( 'NONE', #11556, #1872, #7851, .T. ) ; +#7177 = CARTESIAN_POINT ( 'NONE', ( -15.10713178427481651, 176.3794795624077096, 100.3824614381103828 ) ) ; +#7179 = FACE_OUTER_BOUND ( 'NONE', #31560, .T. ) ; +#7180 = EDGE_CURVE ( 'NONE', #20943, #7260, #12332, .T. ) ; +#7181 = CARTESIAN_POINT ( 'NONE', ( 20.12333278077425192, 184.3221617671313197, 105.1489674529760237 ) ) ; +#7182 = CARTESIAN_POINT ( 'NONE', ( 30.05382551872783736, 109.6131156702000027, 87.74963262544588360 ) ) ; +#7183 = CARTESIAN_POINT ( 'NONE', ( 41.55515210090072742, 120.2182341932538776, 89.94814927363270840 ) ) ; +#7184 = ORIENTED_EDGE ( 'NONE', *, *, #20540, .T. ) ; +#7185 = CARTESIAN_POINT ( 'NONE', ( -19.99825438583805237, 190.8509747501094580, 106.8052823956111013 ) ) ; +#7186 = DIRECTION ( 'NONE', ( -0.0005884949961246487568, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#7187 = FACE_OUTER_BOUND ( 'NONE', #10825, .T. ) ; +#7188 = EDGE_LOOP ( 'NONE', ( #19763, #9100 ) ) ; +#7189 = ORIENTED_EDGE ( 'NONE', *, *, #7223, .F. ) ; +#7190 = CARTESIAN_POINT ( 'NONE', ( -25.50827005986327478, 207.9228675525097003, 76.25894037447334028 ) ) ; +#7191 = CARTESIAN_POINT ( 'NONE', ( 23.39351881373000097, 165.2216646563843199, 152.9217693939943388 ) ) ; +#7192 = ORIENTED_EDGE ( 'NONE', *, *, #18247, .F. ) ; +#7193 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748320902236156 ) ) ; +#7194 = ORIENTED_EDGE ( 'NONE', *, *, #32269, .F. ) ; +#7195 = CARTESIAN_POINT ( 'NONE', ( 28.46551015877975033, 129.9757720508976888, 92.20876074269682476 ) ) ; +#7196 = CARTESIAN_POINT ( 'NONE', ( 35.88952463556218930, 77.14301703112145958, 291.5368675616688279 ) ) ; +#7197 = AXIS2_PLACEMENT_3D ( 'NONE', #29133, #5168, #36041 ) ; +#7198 = EDGE_CURVE ( 'NONE', #24067, #8293, #17236, .T. ) ; +#7199 = AXIS2_PLACEMENT_3D ( 'NONE', #27777, #22037, #6076 ) ; +#7200 = VERTEX_POINT ( 'NONE', #13994 ) ; +#7201 = CIRCLE ( 'NONE', #8541, 8.499999999972331466 ) ; +#7202 = CARTESIAN_POINT ( 'NONE', ( 26.00781598993299681, 120.3026641870980029, 90.49382190704038464 ) ) ; +#7203 = CYLINDRICAL_SURFACE ( 'NONE', #4488, 59.40509898897001051 ) ; +#7205 = CARTESIAN_POINT ( 'NONE', ( -30.17789690918193202, 185.2730303678106623, 105.5237128568702047 ) ) ; +#7204 = CARTESIAN_POINT ( 'NONE', ( 20.48149273625410061, 209.0618706960821385, 75.63135123663742831 ) ) ; +#7206 = ORIENTED_EDGE ( 'NONE', *, *, #23351, .F. ) ; +#7207 = ORIENTED_EDGE ( 'NONE', *, *, #14624, .F. ) ; +#7208 = LINE ( 'NONE', #3533, #36925 ) ; +#7209 = FACE_OUTER_BOUND ( 'NONE', #26092, .T. ) ; +#7210 = DIRECTION ( 'NONE', ( -0.0005734119072279676797, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#7211 = CARTESIAN_POINT ( 'NONE', ( -35.94740272817028170, 109.6131156707333361, 88.45616250159258698 ) ) ; +#7212 = VERTEX_POINT ( 'NONE', #33182 ) ; +#7213 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1603, #26765, #38800, #20402, #39211, #39409, #8145, #23481, #30025, #17732, #4459 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000001563194, 0.3750000000001783018, 0.4375000000001543765, 0.4687500000001424416, 0.5000000000001304512, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7214 = ORIENTED_EDGE ( 'NONE', *, *, #37738, .F. ) ; +#7215 = CARTESIAN_POINT ( 'NONE', ( 22.78070441975003391, 158.6816533748419147, 96.78686173997256503 ) ) ; +#7216 = CARTESIAN_POINT ( 'NONE', ( 5.669749815053078734, 187.5280698745357881, 105.8286138481728358 ) ) ; +#7217 = FACE_OUTER_BOUND ( 'NONE', #14454, .T. ) ; +#7218 = ORIENTED_EDGE ( 'NONE', *, *, #3079, .T. ) ; +#7219 = ORIENTED_EDGE ( 'NONE', *, *, #17081, .T. ) ; +#7220 = CARTESIAN_POINT ( 'NONE', ( -42.84606607935617006, 121.9225652775318167, 87.84153733356382077 ) ) ; +#7221 = CARTESIAN_POINT ( 'NONE', ( -12.63584100919595876, 177.6275380978030114, 100.8078340518252674 ) ) ; +#7222 = CARTESIAN_POINT ( 'NONE', ( 22.78045900286095815, 148.0760582945906663, 93.82521474193295319 ) ) ; +#7223 = EDGE_CURVE ( 'NONE', #4758, #23777, #1353, .T. ) ; +#7224 = LINE ( 'NONE', #25464, #30748 ) ; +#7225 = CIRCLE ( 'NONE', #22922, 2.499999999942582818 ) ; +#7226 = EDGE_LOOP ( 'NONE', ( #17398, #36910, #8637, #15929 ) ) ; +#7227 = DIRECTION ( 'NONE', ( 0.6075492010474008442, -0.7738441339353225867, -0.1790229724939112477 ) ) ; +#7228 = CIRCLE ( 'NONE', #30103, 4.750000613335879862 ) ; +#7229 = VERTEX_POINT ( 'NONE', #38923 ) ; +#7230 = VECTOR ( 'NONE', #6866, 1000.000000000000227 ) ; +#7231 = VERTEX_POINT ( 'NONE', #8054 ) ; +#7232 = CARTESIAN_POINT ( 'NONE', ( -13.48798776821729639, 154.4042536791194493, 95.30809926299690460 ) ) ; +#7233 = ORIENTED_EDGE ( 'NONE', *, *, #36578, .F. ) ; +#7234 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#7235 = CARTESIAN_POINT ( 'NONE', ( -0.3183892827599000275, 188.5403529200000037, 106.1071648710999966 ) ) ; +#7236 = CARTESIAN_POINT ( 'NONE', ( -30.05378918480198180, 127.2828694672463712, 89.56979071655838709 ) ) ; +#7237 = PLANE ( 'NONE', #18201 ) ; +#7238 = VERTEX_POINT ( 'NONE', #32987 ) ; +#7239 = CARTESIAN_POINT ( 'NONE', ( 10.30723277641929947, 181.6902071446141065, 101.5932328223857439 ) ) ; +#7240 = CARTESIAN_POINT ( 'NONE', ( 21.38683321223914646, 213.6392524122032910, 73.04558697104342002 ) ) ; +#7241 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #12878, #21487, #37410, #21880 ), + .UNSPECIFIED., .F., .F. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.571531679975004536, 3.141592653589798445 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8049111466635359147, 0.8049111466635359147, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#7242 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; +#7243 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24865, #286, #31586, #25060, #31381, #490, #15826, #12180, #33834, #34617, #37115 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000524025, 0.6250000000000566214, 0.6875000000000587308, 0.7500000000000608402, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7244 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#7245 = VERTEX_POINT ( 'NONE', #4981 ) ; +#7246 = CARTESIAN_POINT ( 'NONE', ( 40.07613110354596131, 77.14301703112144537, 291.5343389562696643 ) ) ; +#7247 = VECTOR ( 'NONE', #15096, 1000.000000000000000 ) ; +#7248 = CARTESIAN_POINT ( 'NONE', ( -38.11161765677999824, 118.6427780456999983, 90.14970056747002047 ) ) ; +#7249 = ORIENTED_EDGE ( 'NONE', *, *, #9279, .F. ) ; +#7250 = VECTOR ( 'NONE', #28899, 1000.000000000000114 ) ; +#7251 = ORIENTED_EDGE ( 'NONE', *, *, #13742, .T. ) ; +#7252 = CARTESIAN_POINT ( 'NONE', ( 5.957091414655063311, 149.1468224720344438, 94.08258114083251655 ) ) ; +#7253 = ADVANCED_FACE ( 'NONE', ( #17444 ), #39321, .T. ) ; +#7254 = CARTESIAN_POINT ( 'NONE', ( 35.48442776063147619, 88.13433118093483642, 282.5337480928039895 ) ) ; +#7255 = CARTESIAN_POINT ( 'NONE', ( -13.49977439033965432, 124.1657361220545397, 90.99867658793307612 ) ) ; +#7256 = ORIENTED_EDGE ( 'NONE', *, *, #6142, .F. ) ; +#7257 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3489, #639, #4092, #31530 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7258 = CARTESIAN_POINT ( 'NONE', ( -2.935232621041004020, 190.8511156531020276, 106.7950609103722286 ) ) ; +#7259 = VERTEX_POINT ( 'NONE', #40136 ) ; +#7260 = VERTEX_POINT ( 'NONE', #33598 ) ; +#7261 = CARTESIAN_POINT ( 'NONE', ( 2.563994175896955774, 190.9709097722040099, 106.3045652864306874 ) ) ; +#7262 = EDGE_CURVE ( 'NONE', #19980, #16610, #27399, .T. ) ; +#7263 = DIRECTION ( 'NONE', ( 7.677760455957277161E-18, -1.000000000000000000, 1.271205131337255403E-14 ) ) ; +#7264 = ORIENTED_EDGE ( 'NONE', *, *, #34149, .F. ) ; +#7265 = EDGE_LOOP ( 'NONE', ( #37212, #495, #5048, #5188 ) ) ; +#7266 = CARTESIAN_POINT ( 'NONE', ( -22.49975369487818710, 158.6756590294297382, 96.81282609783636417 ) ) ; +#7268 = EDGE_CURVE ( 'NONE', #36214, #4109, #21356, .T. ) ; +#7267 = DIRECTION ( 'NONE', ( 0.0002393071182782299474, 0.2252352986010034697, -0.9743043687658493601 ) ) ; +#7269 = CARTESIAN_POINT ( 'NONE', ( 43.53526136507346678, 121.9496774062499043, 88.05073105187337035 ) ) ; +#7270 = ADVANCED_FACE ( 'NONE', ( #21760 ), #30642, .F. ) ; +#7271 = CARTESIAN_POINT ( 'NONE', ( 2.943860253156593387, 209.7081874491304063, 76.05616958207551193 ) ) ; +#7272 = EDGE_CURVE ( 'NONE', #8707, #38178, #27513, .T. ) ; +#7273 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#7274 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971574284 ) ) ; +#7275 = VERTEX_POINT ( 'NONE', #11741 ) ; +#7276 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748612898, 181.3724072540864540, 104.0809311256944909 ) ) ; +#7277 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#7278 = CYLINDRICAL_SURFACE ( 'NONE', #32550, 2.000000000000011546 ) ; +#7279 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#7280 = CARTESIAN_POINT ( 'NONE', ( 4.915911327427738620, 135.1711131658586851, 90.85666259926293264 ) ) ; +#7281 = EDGE_LOOP ( 'NONE', ( #19922, #450, #32586, #1005 ) ) ; +#7282 = AXIS2_PLACEMENT_3D ( 'NONE', #36317, #1565, #14252 ) ; +#7283 = CARTESIAN_POINT ( 'NONE', ( -13.46991461394048706, 153.3545038370762654, 97.63149519329859061 ) ) ; +#7284 = AXIS2_PLACEMENT_3D ( 'NONE', #22710, #18797, #19010 ) ; +#7285 = CYLINDRICAL_SURFACE ( 'NONE', #16636, 10.00000000000000533 ) ; +#7286 = LINE ( 'NONE', #25930, #39777 ) ; +#7287 = CARTESIAN_POINT ( 'NONE', ( 12.63725699762741250, 130.1064011942611387, 92.43024055530932515 ) ) ; +#7288 = CARTESIAN_POINT ( 'NONE', ( -25.87061325811000145, 191.8108095213000013, 104.0515899184999995 ) ) ; +#7289 = CARTESIAN_POINT ( 'NONE', ( 20.50029381496701930, 120.2778657622999958, 87.92202511309000101 ) ) ; +#7290 = DIRECTION ( 'NONE', ( 0.0005884949961181263050, -0.2249510543439084131, 0.9743698870671259060 ) ) ; +#7291 = EDGE_CURVE ( 'NONE', #17219, #37866, #34504, .T. ) ; +#7292 = CARTESIAN_POINT ( 'NONE', ( -20.49856733782493379, 192.0038685806965475, 106.4640362600384549 ) ) ; +#7293 = CARTESIAN_POINT ( 'NONE', ( -28.26126760785277625, 125.3518701206620705, 90.14920593263850890 ) ) ; +#7294 = VERTEX_POINT ( 'NONE', #14609 ) ; +#7295 = CYLINDRICAL_SURFACE ( 'NONE', #23969, 59.40509898897001051 ) ; +#7296 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9821, #6933, #16521, #7130 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7297 = VERTEX_POINT ( 'NONE', #33803 ) ; +#7298 = CARTESIAN_POINT ( 'NONE', ( 24.53348384866000131, 103.6131156702000027, 87.75296677360999809 ) ) ; +#7299 = CARTESIAN_POINT ( 'NONE', ( -26.00043888416333004, 191.6093710626577149, 103.9038991438749235 ) ) ; +#7300 = EDGE_CURVE ( 'NONE', #11012, #34614, #13008, .T. ) ; +#7301 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.702666754117757870E-16, 0.0006039748319385827629 ) ) ; +#7302 = CARTESIAN_POINT ( 'NONE', ( 36.08436338837000079, 192.2518954457999882, 105.0333384416999962 ) ) ; +#7303 = FACE_OUTER_BOUND ( 'NONE', #16413, .T. ) ; +#7304 = AXIS2_PLACEMENT_3D ( 'NONE', #994, #3452, #3654 ) ; +#7305 = CARTESIAN_POINT ( 'NONE', ( 35.94834476972000203, 192.8406908178000094, 106.4387586362000064 ) ) ; +#7306 = VERTEX_POINT ( 'NONE', #37084 ) ; +#7307 = ORIENTED_EDGE ( 'NONE', *, *, #12890, .F. ) ; +#7308 = CONICAL_SURFACE ( 'NONE', #806, 2.500001241545478869, 0.7853981633776581095 ) ; +#7309 = CARTESIAN_POINT ( 'NONE', ( -5.669506394645257963, 181.2845812425110523, 104.3558773153669250 ) ) ; +#7310 = CARTESIAN_POINT ( 'NONE', ( -2.787474291791000258, 209.1564175354999975, 75.96280436173999817 ) ) ; +#7311 = ADVANCED_FACE ( 'NONE', ( #11949 ), #27092, .F. ) ; +#7312 = CARTESIAN_POINT ( 'NONE', ( -16.15354643035712812, 122.9157560190214156, 174.2038265287079071 ) ) ; +#7313 = ADVANCED_FACE ( 'NONE', ( #39527 ), #34004, .T. ) ; +#7314 = LINE ( 'NONE', #17111, #35617 ) ; +#7315 = PLANE ( 'NONE', #31117 ) ; +#7316 = VERTEX_POINT ( 'NONE', #2540 ) ; +#7317 = DIRECTION ( 'NONE', ( 0.0005884949961240270753, -0.2249510543439049992, 0.9743698870671265722 ) ) ; +#7318 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #17734, #20404, #14705, #33079 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.612409811267536242, 4.712390161299671476 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9991671675941976583, 0.9991671675941976583, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#7319 = EDGE_CURVE ( 'NONE', #4201, #39778, #11724, .T. ) ; +#7320 = ORIENTED_EDGE ( 'NONE', *, *, #28791, .T. ) ; +#7321 = EDGE_CURVE ( 'NONE', #16953, #9311, #29643, .T. ) ; +#7322 = EDGE_CURVE ( 'NONE', #2067, #32425, #15008, .T. ) ; +#7323 = CARTESIAN_POINT ( 'NONE', ( -28.94810864222802849, 110.6131156702000027, 87.28526822420690223 ) ) ; +#7324 = CARTESIAN_POINT ( 'NONE', ( 29.78035931491814026, 126.7216206972648109, 90.43038213919562907 ) ) ; +#7325 = ORIENTED_EDGE ( 'NONE', *, *, #23176, .T. ) ; +#7326 = CARTESIAN_POINT ( 'NONE', ( -19.99999816303952471, 191.5261162992163690, 103.8822987450886046 ) ) ; +#7327 = CARTESIAN_POINT ( 'NONE', ( 25.83230247200966545, 118.1154253885978278, 87.41886792823243013 ) ) ; +#7328 = LINE ( 'NONE', #19785, #496 ) ; +#7329 = CARTESIAN_POINT ( 'NONE', ( -5.663464557155529988, 131.0206703453534374, 89.90489628355439322 ) ) ; +#7330 = DIRECTION ( 'NONE', ( 0.7933535320750288999, 0.5930759023596230417, 0.1372994799130531074 ) ) ; +#7331 = ORIENTED_EDGE ( 'NONE', *, *, #31677, .T. ) ; +#7332 = DIRECTION ( 'NONE', ( 0.0006039748319356123742, -6.151140898304641511E-15, 0.9999998176071847045 ) ) ; +#7333 = CARTESIAN_POINT ( 'NONE', ( -30.07070568945121281, 177.4624532118801596, 100.9195456647180151 ) ) ; +#7334 = DIRECTION ( 'NONE', ( -0.0004161288024612937414, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#7335 = CARTESIAN_POINT ( 'NONE', ( 38.12150922002388143, 153.0051697192221241, 291.5355194989076608 ) ) ; +#7336 = VERTEX_POINT ( 'NONE', #39938 ) ; +#7337 = AXIS2_PLACEMENT_3D ( 'NONE', #21034, #2637, #17937 ) ; +#7338 = CARTESIAN_POINT ( 'NONE', ( 25.51042451852513082, 191.2901597426282194, 106.3556975140922702 ) ) ; +#7339 = AXIS2_PLACEMENT_3D ( 'NONE', #12274, #31278, #24562 ) ; +#7340 = VECTOR ( 'NONE', #3273, 1000.000000000000000 ) ; +#7341 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#7342 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178587041921E-05, -0.0002331579774917524482 ) ) ; +#7343 = CARTESIAN_POINT ( 'NONE', ( -6.000829975801000415, 123.2470639583000178, 152.4718672074000381 ) ) ; +#7344 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#7345 = CARTESIAN_POINT ( 'NONE', ( -2.957808003804000219, 209.8402624482000078, 72.92550096166999651 ) ) ; +#7346 = CARTESIAN_POINT ( 'NONE', ( 38.36127927543999760, 118.7741772839000163, 90.10271768068000142 ) ) ; +#7347 = ORIENTED_EDGE ( 'NONE', *, *, #3029, .F. ) ; +#7348 = EDGE_CURVE ( 'NONE', #17938, #13095, #8687, .T. ) ; +#7349 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971558741 ) ) ; +#7350 = EDGE_CURVE ( 'NONE', #3701, #9728, #22180, .T. ) ; +#7351 = CARTESIAN_POINT ( 'NONE', ( -20.89282324149344561, 183.0959377177359215, 101.9365769416837253 ) ) ; +#7352 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#7353 = EDGE_CURVE ( 'NONE', #13602, #25001, #30956, .T. ) ; +#7354 = CARTESIAN_POINT ( 'NONE', ( -35.93807696457238166, 196.5784392899485340, 103.8968090359679479 ) ) ; +#7355 = EDGE_LOOP ( 'NONE', ( #36172, #22186, #28510, #35150 ) ) ; +#7356 = ORIENTED_EDGE ( 'NONE', *, *, #14062, .F. ) ; +#7357 = ADVANCED_FACE ( 'NONE', ( #12338 ), #26757, .F. ) ; +#7358 = VERTEX_POINT ( 'NONE', #28292 ) ; +#7359 = DIRECTION ( 'NONE', ( 0.0006039748319373442788, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#7360 = AXIS2_PLACEMENT_3D ( 'NONE', #26743, #23879, #14678 ) ; +#7361 = EDGE_CURVE ( 'NONE', #28042, #28075, #32085, .T. ) ; +#7362 = DIRECTION ( 'NONE', ( 0.0005884949961245723206, -0.2249510543439059984, 0.9743698870671263501 ) ) ; +#7363 = VECTOR ( 'NONE', #39340, 1000.000000000000114 ) ; +#7364 = EDGE_LOOP ( 'NONE', ( #11778, #24765, #33818 ) ) ; +#7365 = CARTESIAN_POINT ( 'NONE', ( 38.45464856030794465, 118.5792329893091051, 89.85665017623614403 ) ) ; +#7366 = EDGE_CURVE ( 'NONE', #9960, #16388, #19061, .T. ) ; +#7367 = AXIS2_PLACEMENT_3D ( 'NONE', #11397, #21217, #14476 ) ; +#7368 = CARTESIAN_POINT ( 'NONE', ( 10.03420395425108680, 168.4982496180414273, 98.54774839040621259 ) ) ; +#7369 = CARTESIAN_POINT ( 'NONE', ( -38.24533459185000339, 118.9468119104000010, 87.58145080328000631 ) ) ; +#7370 = CARTESIAN_POINT ( 'NONE', ( 3.168110071476895495, 118.9434405806654240, 90.19017701310959012 ) ) ; +#7371 = EDGE_LOOP ( 'NONE', ( #37862, #29900, #24267, #8644, #28228, #35190 ) ) ; +#7372 = DIRECTION ( 'NONE', ( 0.0006039748319386177827, 1.312069532538339473E-14, 0.9999998176071847045 ) ) ; +#7373 = ORIENTED_EDGE ( 'NONE', *, *, #11651, .F. ) ; +#7374 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319379440594 ) ) ; +#7375 = CARTESIAN_POINT ( 'NONE', ( -3.168110071482259205, 118.9426017752647766, 90.19381027778268844 ) ) ; +#7376 = CARTESIAN_POINT ( 'NONE', ( 20.19176146692526430, 184.3365261251356344, 105.0819723774979906 ) ) ; +#7377 = CARTESIAN_POINT ( 'NONE', ( -45.68157572959258772, 116.8137947612332681, 122.5502833297559135 ) ) ; +#7378 = CARTESIAN_POINT ( 'NONE', ( 36.05533436145224613, 118.8155634790891355, 90.24600832072235335 ) ) ; +#7379 = ORIENTED_EDGE ( 'NONE', *, *, #3288, .T. ) ; +#7380 = EDGE_CURVE ( 'NONE', #28951, #8754, #22365, .T. ) ; +#7381 = ORIENTED_EDGE ( 'NONE', *, *, #3454, .F. ) ; +#7382 = CARTESIAN_POINT ( 'NONE', ( -0.9823828506576001152, 188.9161183472000118, 103.5350258649999944 ) ) ; +#7383 = CARTESIAN_POINT ( 'NONE', ( -13.63173874120965401, 135.9869460838498583, 148.6427343181233311 ) ) ; +#7384 = CARTESIAN_POINT ( 'NONE', ( 8.329377750328216479, 161.3713756194757991, 97.24551068566299250 ) ) ; +#7385 = ORIENTED_EDGE ( 'NONE', *, *, #25340, .F. ) ; +#7386 = CARTESIAN_POINT ( 'NONE', ( 22.50071842841086678, 154.4094130781474803, 95.28756121982962668 ) ) ; +#7387 = CARTESIAN_POINT ( 'NONE', ( 39.06349078196001301, 191.0388279120988670, 103.7341189576915355 ) ) ; +#7388 = VERTEX_POINT ( 'NONE', #665 ) ; +#7389 = CARTESIAN_POINT ( 'NONE', ( -42.22551659325709750, 120.8118849317876595, 90.64895807725147847 ) ) ; +#7390 = VECTOR ( 'NONE', #25580, 1000.000000000000114 ) ; +#7391 = EDGE_LOOP ( 'NONE', ( #34075, #4097, #9117, #7540, #1463, #24226, #5550, #27776 ) ) ; +#7392 = CIRCLE ( 'NONE', #6750, 2.499999999979839238 ) ; +#7393 = CARTESIAN_POINT ( 'NONE', ( -13.46279686986694202, 157.6279356061011185, 99.13124279942860539 ) ) ; +#7394 = DIRECTION ( 'NONE', ( 0.0005884949961658158049, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#7395 = CONICAL_SURFACE ( 'NONE', #30266, 2.503203150234936114, 0.7853981633958105890 ) ; +#7396 = EDGE_LOOP ( 'NONE', ( #16236, #6088, #24714, #21593, #27351 ) ) ; +#7397 = CARTESIAN_POINT ( 'NONE', ( 25.50043922912999861, 120.2537800310000193, 89.96303717399999300 ) ) ; +#7398 = CARTESIAN_POINT ( 'NONE', ( -21.21399079302519652, 183.3565551017309190, 102.5100844002234197 ) ) ; +#7399 = EDGE_CURVE ( 'NONE', #2188, #24453, #25639, .T. ) ; +#7401 = EDGE_CURVE ( 'NONE', #19373, #27237, #35188, .T. ) ; +#7400 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31460, #37779, #6493, #16110 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 3.763891609993758226E-05, 0.0006616524122018222496 ), + .UNSPECIFIED. ) ; +#7403 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7071067167008887600, -0.7071068456722005013 ) ) ; +#7402 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858958, 190.9636369981938913, 106.3296296870415887 ) ) ; +#7404 = DIRECTION ( 'NONE', ( 0.0005884949961259158639, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#7405 = ORIENTED_EDGE ( 'NONE', *, *, #19791, .T. ) ; +#7406 = DIRECTION ( 'NONE', ( -0.0001358593331183317757, -0.9743721449820399449, -0.2249420028037008579 ) ) ; +#7407 = EDGE_CURVE ( 'NONE', #3978, #5503, #38282, .T. ) ; +#7408 = CYLINDRICAL_SURFACE ( 'NONE', #27366, 2.000000000000014655 ) ; +#7409 = EDGE_LOOP ( 'NONE', ( #36009, #39462, #8813, #20350 ) ) ; +#7410 = EDGE_LOOP ( 'NONE', ( #6545, #9890, #23902, #28764, #34619 ) ) ; +#7411 = CARTESIAN_POINT ( 'NONE', ( 38.60331107998000277, 119.2723712158999945, 90.41971974563000458 ) ) ; +#7412 = CARTESIAN_POINT ( 'NONE', ( 22.78080448403245839, 154.4094593426142978, 95.28739704982865533 ) ) ; +#7413 = EDGE_CURVE ( 'NONE', #24067, #32727, #10144, .T. ) ; +#7414 = DIRECTION ( 'NONE', ( 0.0005884949961219661154, -0.2249510543439071364, 0.9743698870671262391 ) ) ; +#7415 = CARTESIAN_POINT ( 'NONE', ( -16.26709548037662145, 127.8724464670249148, 174.7626211946546277 ) ) ; +#7416 = VECTOR ( 'NONE', #13942, 1000.000000000000227 ) ; +#7417 = VECTOR ( 'NONE', #30667, 1000.000000000000114 ) ; +#7418 = ORIENTED_EDGE ( 'NONE', *, *, #18855, .F. ) ; +#7419 = ORIENTED_EDGE ( 'NONE', *, *, #23671, .F. ) ; +#7420 = CARTESIAN_POINT ( 'NONE', ( -12.63653284181130410, 177.5932570882007155, 100.8292555457751121 ) ) ; +#7421 = CARTESIAN_POINT ( 'NONE', ( 20.16823359922518932, 160.1106230620535484, 99.51315612356997065 ) ) ; +#7422 = CIRCLE ( 'NONE', #23118, 2.000000001207042466 ) ; +#7423 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#7424 = EDGE_CURVE ( 'NONE', #21974, #802, #24275, .T. ) ; +#7425 = ORIENTED_EDGE ( 'NONE', *, *, #5855, .T. ) ; +#7426 = VECTOR ( 'NONE', #37214, 1000.000000000000114 ) ; +#7427 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#7428 = ORIENTED_EDGE ( 'NONE', *, *, #4982, .T. ) ; +#7429 = CARTESIAN_POINT ( 'NONE', ( 3.069838397726039503, 190.8629629326576946, 106.8006141407937122 ) ) ; +#7430 = ORIENTED_EDGE ( 'NONE', *, *, #39169, .T. ) ; +#7431 = CARTESIAN_POINT ( 'NONE', ( 38.97204648811698036, 118.8228816124465368, 89.67376701884533929 ) ) ; +#7432 = CARTESIAN_POINT ( 'NONE', ( -45.59279413748385679, 146.2345503595622347, 284.1924382399986939 ) ) ; +#7433 = CARTESIAN_POINT ( 'NONE', ( 39.72394661644089098, 108.3778670559899524, 179.2109846985112540 ) ) ; +#7434 = CARTESIAN_POINT ( 'NONE', ( -6.273952178503699351, 163.8304651410298334, 97.99310710002680480 ) ) ; +#7435 = ORIENTED_EDGE ( 'NONE', *, *, #32263, .F. ) ; +#7436 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319386088922 ) ) ; +#7437 = CARTESIAN_POINT ( 'NONE', ( 20.92535880089854672, 213.2684201652496370, 73.04586569002432839 ) ) ; +#7438 = LINE ( 'NONE', #29742, #5129 ) ; +#7439 = VECTOR ( 'NONE', #1470, 1000.000000000000227 ) ; +#7440 = AXIS2_PLACEMENT_3D ( 'NONE', #28575, #6471, #28371 ) ; +#7441 = DIRECTION ( 'NONE', ( -0.0005884949961260158274, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#7442 = ORIENTED_EDGE ( 'NONE', *, *, #42, .F. ) ; +#7443 = CARTESIAN_POINT ( 'NONE', ( 24.53687191662514522, 116.1140267896956999, 89.75313255931047252 ) ) ; +#7444 = EDGE_CURVE ( 'NONE', #27950, #31729, #22763, .T. ) ; +#7445 = CONICAL_SURFACE ( 'NONE', #28373, 4.999999999925270444, 0.7853981634119230337 ) ; +#7446 = EDGE_CURVE ( 'NONE', #18386, #11331, #32600, .T. ) ; +#7447 = CARTESIAN_POINT ( 'NONE', ( -35.39949828460999726, 113.9650867045999973, 90.42993924146999518 ) ) ; +#7448 = ORIENTED_EDGE ( 'NONE', *, *, #28664, .T. ) ; +#7449 = ORIENTED_EDGE ( 'NONE', *, *, #4265, .F. ) ; +#7450 = CARTESIAN_POINT ( 'NONE', ( 19.99976926757112849, 160.7481248081381295, 96.75239270071580222 ) ) ; +#7451 = CARTESIAN_POINT ( 'NONE', ( 28.46284161542680025, 187.5721379928345129, 102.9401731420402939 ) ) ; +#7452 = CARTESIAN_POINT ( 'NONE', ( -43.56994142101562062, 121.4012961811330626, 90.41976514615660676 ) ) ; +#7453 = DIRECTION ( 'NONE', ( -0.0005884949961224831714, 0.2249510543439058596, -0.9743698870671263501 ) ) ; +#7454 = ORIENTED_EDGE ( 'NONE', *, *, #11935, .T. ) ; +#7455 = ORIENTED_EDGE ( 'NONE', *, *, #20665, .T. ) ; +#7456 = FACE_BOUND ( 'NONE', #19879, .T. ) ; +#7457 = ORIENTED_EDGE ( 'NONE', *, *, #22633, .T. ) ; +#7458 = EDGE_LOOP ( 'NONE', ( #20616, #13379, #15426, #31316 ) ) ; +#7459 = CARTESIAN_POINT ( 'NONE', ( 1.948921012460900659, 189.5571036615277762, 105.8967624099965263 ) ) ; +#7460 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555410 ) ) ; +#7461 = ORIENTED_EDGE ( 'NONE', *, *, #31431, .T. ) ; +#7462 = ORIENTED_EDGE ( 'NONE', *, *, #29295, .F. ) ; +#7463 = CARTESIAN_POINT ( 'NONE', ( 16.56091750598266543, 123.0789174470862406, 172.1968364805972271 ) ) ; +#7464 = CARTESIAN_POINT ( 'NONE', ( -13.49823340920320724, 157.6238447846168640, 99.13360705319831823 ) ) ; +#7465 = CARTESIAN_POINT ( 'NONE', ( 37.69036451307999869, 118.9411325438999967, 87.11195371982000779 ) ) ; +#7466 = CARTESIAN_POINT ( 'NONE', ( 36.02746032641000085, 191.4413277058000347, 103.6991758580000038 ) ) ; +#7467 = CARTESIAN_POINT ( 'NONE', ( -36.07211921651516917, 123.3571268225337008, 93.28546566300038023 ) ) ; +#7468 = APPROVAL_PERSON_ORGANIZATION ( #21858, #17932, #31062 ) ; +#7469 = AXIS2_PLACEMENT_3D ( 'NONE', #38185, #20163, #35086 ) ; +#7470 = EDGE_CURVE ( 'NONE', #3379, #12341, #11084, .T. ) ; +#7471 = ORIENTED_EDGE ( 'NONE', *, *, #11819, .F. ) ; +#7472 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; +#7473 = DIRECTION ( 'NONE', ( -0.0006039748319385906776, -1.261220487827980362E-14, -0.9999998176071844824 ) ) ; +#7474 = ORIENTED_EDGE ( 'NONE', *, *, #25927, .F. ) ; +#7475 = AXIS2_PLACEMENT_3D ( 'NONE', #37981, #9982, #6891 ) ; +#7476 = CARTESIAN_POINT ( 'NONE', ( -17.26213291099019997, 152.2612616225560771, 183.6636115490260863 ) ) ; +#7477 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; +#7478 = CARTESIAN_POINT ( 'NONE', ( -25.63990465300122779, 116.6810637759212170, 90.28327069913609648 ) ) ; +#7479 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -7.822507694019387433E-18, -0.0006039748319385908944 ) ) ; +#7480 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #32951, #23771, #39087, #17611 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 2.962146847938709193, 4.533316785306447549 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8046497850432340337, 0.8046497850432340337, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#7481 = ORIENTED_EDGE ( 'NONE', *, *, #8546, .F. ) ; +#7482 = PLANE ( 'NONE', #26566 ) ; +#7483 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#7484 = CARTESIAN_POINT ( 'NONE', ( -23.32500208832000155, 123.2470639583000178, 152.4718672074000381 ) ) ; +#7485 = EDGE_CURVE ( 'NONE', #37703, #28359, #16288, .T. ) ; +#7486 = CARTESIAN_POINT ( 'NONE', ( 15.50147166300774160, 151.4095604232323069, 97.16497154471535680 ) ) ; +#7487 = CARTESIAN_POINT ( 'NONE', ( -25.35581857957999929, 191.7922573250999960, 104.5649157546000083 ) ) ; +#7488 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26149, #10205, #28599, #19166, #13462, #29206, #19970, #4231, #1176, #13657 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999945599, 0.3750000000000179301, 0.4375000000000243139, 0.5000000000000307532, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7489 = FACE_OUTER_BOUND ( 'NONE', #35052, .T. ) ; +#7490 = CARTESIAN_POINT ( 'NONE', ( -3.701323146539070130, 168.4576286693920224, 98.71465524754557919 ) ) ; +#7491 = DIRECTION ( 'NONE', ( -0.6087613186456907188, -0.7730177010543248795, -0.1784749023741044327 ) ) ; +#7492 = EDGE_CURVE ( 'NONE', #23221, #6123, #27431, .T. ) ; +#7493 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #23189, #27083, #39514, #13779, #38913, #29521, #26266 ), + ( #35419, #11315, #38703, #32784, #20720, #23796, #13985 ), + ( #11527, #23590, #7429, #19890, #32396, #26462, #39118 ), + ( #4363, #10929, #17227, #36252, #23393, #35830, #7840 ), + ( #4764, #29731, #8256, #1717, #14200, #11122, #20502 ), + ( #32974, #4973, #24421, #60, #36666, #31149, #3121 ), + ( #37074, #15594, #12331, #11939, #30947, #37271, #33588 ), + ( #5381, #28094, #2327, #15400, #27900, #24002, #36872 ), + ( #21552, #40126, #11734, #36459, #18440, #9070, #8466 ), + ( #21349, #2915, #6188, #8674, #39717, #40326, #21750 ), + ( #24217, #24827, #2528, #5991, #27502, #20928, #12139 ), + ( #33792, #33384, #14998, #24625, #21135, #17833, #5581 ), + ( #18042, #8876, #9272, #34192, #30332, #14806, #27289 ), + ( #30543, #18641, #39929, #15205, #5791, #18245, #30744 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 3, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 3, 4 ), + ( -0.009999999139057998490, -4.027722043288000136E-12, 3.385156030728000000E-06, 0.08333638693828999966, 0.1666693887204999946, 0.3333354752625000139, 0.5000015618047000121, 0.6666676483468999548, 0.8333337348888999463, 0.9999999134989999705 ), + ( 0.1539537836571530649, 0.1754433755481999979, 0.8245457737757000416 ), + .UNSPECIFIED. ) ; +#7494 = CARTESIAN_POINT ( 'NONE', ( -13.50000077688951450, 188.3420892684051751, 103.1432776901117307 ) ) ; +#7495 = CARTESIAN_POINT ( 'NONE', ( -35.69616828627999894, 201.9934155195000187, 90.49994975821999788 ) ) ; +#7496 = EDGE_LOOP ( 'NONE', ( #15446, #10627, #27722, #4438 ) ) ; +#7497 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #40447, #22068 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7498 = CARTESIAN_POINT ( 'NONE', ( 20.48231950984458649, 205.5677633305384120, 76.28703242847967658 ) ) ; +#7499 = EDGE_CURVE ( 'NONE', #22046, #28881, #19469, .T. ) ; +#7500 = EDGE_CURVE ( 'NONE', #39778, #25997, #16401, .T. ) ; +#7501 = VECTOR ( 'NONE', #15262, 1000.000000000000227 ) ; +#7502 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999898748, 179.7376864902705904, 101.1595092802000835 ) ) ; +#7503 = CARTESIAN_POINT ( 'NONE', ( -43.95866919468323886, 185.6592565981171390, 107.3047072462908460 ) ) ; +#7504 = CONICAL_SURFACE ( 'NONE', #30381, 2.500000720456969194, 0.7853981633184845546 ) ; +#7505 = ORIENTED_EDGE ( 'NONE', *, *, #20087, .T. ) ; +#7506 = CARTESIAN_POINT ( 'NONE', ( 16.56199388762211200, 121.7260791789329062, 178.0423311718324157 ) ) ; +#7507 = CARTESIAN_POINT ( 'NONE', ( 46.20652635966656163, 124.8532258200277454, 91.35751384932866870 ) ) ; +#7508 = ADVANCED_FACE ( 'NONE', ( #37887 ), #15796, .T. ) ; +#7509 = CARTESIAN_POINT ( 'NONE', ( 38.02566647473999950, 191.1265785857000026, 106.1815786465000002 ) ) ; +#7510 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#7511 = AXIS2_PLACEMENT_3D ( 'NONE', #9204, #40252, #27626 ) ; +#7512 = CARTESIAN_POINT ( 'NONE', ( -17.26247767858138005, 152.5342161776122225, 182.4800534808789791 ) ) ; +#7513 = CARTESIAN_POINT ( 'NONE', ( 35.94569070589000148, 192.8022039118000066, 106.4463298239000153 ) ) ; +#7514 = ORIENTED_EDGE ( 'NONE', *, *, #11121, .T. ) ; +#7515 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 82.27946979429634666, 315.0857197240630967 ) ) ; +#7516 = CARTESIAN_POINT ( 'NONE', ( 20.16596632773250874, 196.4252918348997525, 103.7971211491498167 ) ) ; +#7517 = CARTESIAN_POINT ( 'NONE', ( 25.51044001015309703, 191.4790671403759745, 106.3785283636754855 ) ) ; +#7518 = ORIENTED_EDGE ( 'NONE', *, *, #32564, .F. ) ; +#7519 = CARTESIAN_POINT ( 'NONE', ( -29.42789445533455961, 116.9990604785378423, 176.9382643005241107 ) ) ; +#7520 = CARTESIAN_POINT ( 'NONE', ( -20.49588002752788185, 118.8155058231674701, 94.28014998164199767 ) ) ; +#7521 = ORIENTED_EDGE ( 'NONE', *, *, #29397, .F. ) ; +#7522 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#7523 = ORIENTED_EDGE ( 'NONE', *, *, #4139, .F. ) ; +#7524 = CARTESIAN_POINT ( 'NONE', ( 36.47845471365634751, 191.6031860892433087, 106.3715631444863448 ) ) ; +#7525 = DIRECTION ( 'NONE', ( -0.0005884931264925925961, 0.2249510545839476794, -0.9743698870128375544 ) ) ; +#7526 = FACE_OUTER_BOUND ( 'NONE', #16659, .T. ) ; +#7527 = CARTESIAN_POINT ( 'NONE', ( 21.68400888405614779, 177.1994660713384349, 100.5495466695472544 ) ) ; +#7528 = CARTESIAN_POINT ( 'NONE', ( 3.668109984895000508, 187.1823278903000016, 105.9440663766999933 ) ) ; +#7529 = ORIENTED_EDGE ( 'NONE', *, *, #39391, .T. ) ; +#7530 = EDGE_LOOP ( 'NONE', ( #19431, #18918, #25330, #11893 ) ) ; +#7531 = CARTESIAN_POINT ( 'NONE', ( -2.937261516931815919, 196.5784392894775010, 103.8768773714908775 ) ) ; +#7532 = CARTESIAN_POINT ( 'NONE', ( 30.06995732875381577, 177.2926437816356042, 100.9961439531841165 ) ) ; +#7533 = AXIS2_PLACEMENT_3D ( 'NONE', #9633, #7152, #37635 ) ; +#7534 = CIRCLE ( 'NONE', #15380, 2.249999999967385644 ) ; +#7535 = CARTESIAN_POINT ( 'NONE', ( 4.502832686075696422, 177.3080769709184210, 100.5849984759426405 ) ) ; +#7536 = VECTOR ( 'NONE', #13214, 999.9999999999998863 ) ; +#7537 = CARTESIAN_POINT ( 'NONE', ( -20.51791727788598152, 205.7357679558956534, 75.91561672826185259 ) ) ; +#7538 = VERTEX_POINT ( 'NONE', #26032 ) ; +#7539 = AXIS2_PLACEMENT_3D ( 'NONE', #20979, #23233, #20348 ) ; +#7540 = ORIENTED_EDGE ( 'NONE', *, *, #24549, .T. ) ; +#7541 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989908600, -0.1373964268091705798 ) ) ; +#7542 = ADVANCED_FACE ( 'NONE', ( #23765 ), #9130, .T. ) ; +#7543 = CARTESIAN_POINT ( 'NONE', ( 37.25545905135366098, 116.8164260177301799, 89.68586038215327960 ) ) ; +#7544 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265225566, -0.1368326740407719844 ) ) ; +#7545 = EDGE_CURVE ( 'NONE', #4372, #37091, #1888, .T. ) ; +#7546 = LINE ( 'NONE', #7746, #22212 ) ; +#7547 = EDGE_CURVE ( 'NONE', #8481, #23937, #35433, .T. ) ; +#7548 = CARTESIAN_POINT ( 'NONE', ( -75.99035305782904004, 156.3451282303881555, 95.79393540400390350 ) ) ; +#7549 = ADVANCED_FACE ( 'NONE', ( #13547 ), #36008, .T. ) ; +#7550 = CARTESIAN_POINT ( 'NONE', ( 0.5441253984803264832, 208.9999999999999716, 73.05817544431644706 ) ) ; +#7551 = CARTESIAN_POINT ( 'NONE', ( 38.16277029721000247, 118.9305731983999976, 90.39763992500999734 ) ) ; +#7552 = VERTEX_POINT ( 'NONE', #11283 ) ; +#7553 = CARTESIAN_POINT ( 'NONE', ( 14.14634404124179134, 124.4291101105236095, 88.37110038241654308 ) ) ; +#7554 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#7555 = CONICAL_SURFACE ( 'NONE', #30438, 5.999999999954156671, 0.7853981634347416696 ) ; +#7556 = FACE_OUTER_BOUND ( 'NONE', #6671, .T. ) ; +#7557 = CARTESIAN_POINT ( 'NONE', ( -34.95638760651606702, 220.4002260771005695, 73.57961695570443794 ) ) ; +#7558 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #13130, #22338, #6769 ), + ( #31745, #29877, #1240 ), + ( #1859, #39056, #38646 ), + ( #23529, #19830, #22740 ) ), + .UNSPECIFIED., .F., .F., .F. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), + ( 3, 3 ), + ( 0.5323285496897337543, 0.5323359952438722065 ), + ( 0.3705134913875697822, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 0.8839414210850555786, 0.8433814400653724119, 1.000000000000000000), + ( 0.8839429408946146705, 0.8433834910157350651, 1.000000000000000000), + ( 0.8839444606899004020, 0.8433855419468362369, 1.000000000000000000), + ( 0.8839459804709337565, 0.8433875928587041271, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#7559 = AXIS2_PLACEMENT_3D ( 'NONE', #23774, #11500, #8648 ) ; +#7560 = CARTESIAN_POINT ( 'NONE', ( -39.68966504267002193, 159.7604226669166110, 205.3090077686758832 ) ) ; +#7561 = AXIS2_PLACEMENT_3D ( 'NONE', #7700, #3823, #765 ) ; +#7562 = ORIENTED_EDGE ( 'NONE', *, *, #39994, .F. ) ; +#7563 = VERTEX_POINT ( 'NONE', #4940 ) ; +#7564 = ORIENTED_EDGE ( 'NONE', *, *, #12494, .F. ) ; +#7565 = LINE ( 'NONE', #13711, #24225 ) ; +#7566 = VECTOR ( 'NONE', #26691, 1000.000000000000227 ) ; +#7567 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#7568 = CARTESIAN_POINT ( 'NONE', ( -6.031620047117566052, 177.7903949882438042, 100.7027583919079063 ) ) ; +#7569 = VECTOR ( 'NONE', #21944, 999.9999999999998863 ) ; +#7570 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12193, #12379, #30391, #15258 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.002377699347871517228 ), + .UNSPECIFIED. ) ; +#7571 = ORIENTED_EDGE ( 'NONE', *, *, #33080, .T. ) ; +#7572 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#7573 = EDGE_CURVE ( 'NONE', #33368, #27991, #37435, .T. ) ; +#7574 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#7575 = CARTESIAN_POINT ( 'NONE', ( -39.25194077172999840, 120.2741315228000047, 87.44405325520000360 ) ) ; +#7576 = CARTESIAN_POINT ( 'NONE', ( -35.30228731257000163, 112.8193765062000011, 87.14170685835999564 ) ) ; +#7577 = ORIENTED_EDGE ( 'NONE', *, *, #24220, .F. ) ; +#7578 = CARTESIAN_POINT ( 'NONE', ( 19.41633238111709758, 148.7715877831155069, 183.2842058909355387 ) ) ; +#7579 = ORIENTED_EDGE ( 'NONE', *, *, #8352, .F. ) ; +#7580 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#7581 = CARTESIAN_POINT ( 'NONE', ( -20.51745969899640087, 207.4083551867479116, 77.09396086730279762 ) ) ; +#7582 = CARTESIAN_POINT ( 'NONE', ( -38.93740081958814159, 183.0561992808241882, 105.0172067937131999 ) ) ; +#7583 = CARTESIAN_POINT ( 'NONE', ( -39.73451189162042141, 125.2083021951255262, 106.5273060498917488 ) ) ; +#7584 = DIRECTION ( 'NONE', ( 0.0005884949961206773243, -0.2249510543439054433, 0.9743698870671265722 ) ) ; +#7585 = ORIENTED_EDGE ( 'NONE', *, *, #19775, .F. ) ; +#7586 = CARTESIAN_POINT ( 'NONE', ( -1.024403596856999998, 188.7904093113999977, 103.3726356948999978 ) ) ; +#7587 = CARTESIAN_POINT ( 'NONE', ( 3.666638755385807080, 126.6906504152049706, 89.41269982467663624 ) ) ; +#7588 = CARTESIAN_POINT ( 'NONE', ( -42.84985459258451357, 114.0190886146663587, 121.9014590159802509 ) ) ; +#7589 = DIRECTION ( 'NONE', ( 0.0005884949961239980187, -0.2249510543439088572, 0.9743698870671256840 ) ) ; +#7590 = ADVANCED_FACE ( 'NONE', ( #23552 ), #32164, .F. ) ; +#7591 = AXIS2_PLACEMENT_3D ( 'NONE', #12770, #18880, #33629 ) ; +#7592 = VERTEX_POINT ( 'NONE', #13953 ) ; +#7593 = CARTESIAN_POINT ( 'NONE', ( -6.273363704495623416, 148.4283476285271774, 95.46355138143680108 ) ) ; +#7594 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#7595 = AXIS2_PLACEMENT_3D ( 'NONE', #37994, #10000, #13464 ) ; +#7596 = ORIENTED_EDGE ( 'NONE', *, *, #9028, .F. ) ; +#7597 = AXIS2_PLACEMENT_3D ( 'NONE', #40189, #34248, #28543 ) ; +#7598 = ADVANCED_FACE ( 'NONE', ( #17197 ), #40424, .T. ) ; +#7599 = CIRCLE ( 'NONE', #8945, 6.000000000000001776 ) ; +#7600 = EDGE_CURVE ( 'NONE', #15042, #14325, #18867, .T. ) ; +#7601 = ORIENTED_EDGE ( 'NONE', *, *, #25524, .F. ) ; +#7602 = ORIENTED_EDGE ( 'NONE', *, *, #28574, .T. ) ; +#7603 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000092726, 177.0629346109330982, 100.5202509414855712 ) ) ; +#7604 = DIRECTION ( 'NONE', ( 0.0005884949961244984864, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#7605 = ADVANCED_FACE ( 'NONE', ( #4526 ), #24136, .T. ) ; +#7606 = ORIENTED_EDGE ( 'NONE', *, *, #7125, .T. ) ; +#7607 = CARTESIAN_POINT ( 'NONE', ( 25.99876818124551292, 118.1164810761916470, 87.25208046938912787 ) ) ; +#7608 = VERTEX_POINT ( 'NONE', #1064 ) ; +#7609 = CARTESIAN_POINT ( 'NONE', ( 25.99935010583338268, 120.0781821002242111, 90.41881030976217914 ) ) ; +#7610 = CARTESIAN_POINT ( 'NONE', ( -16.11981483123442871, 151.5072451358702210, 180.2250316836006050 ) ) ; +#7612 = LINE ( 'NONE', #32562, #33802 ) ; +#7611 = CARTESIAN_POINT ( 'NONE', ( -53.43553862205013871, 4.776739081468993398, 161.2530495364081560 ) ) ; +#7613 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4617, #26515, #10975, #35885, #32831, #4812, #17278, #29787, #17484, #17885, #34233, #39769, #2779, #3162, #21796, #39979 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 1, 2, 2, 1, 2, 4 ), + ( 0.000000000000000000, 0.2080649981249293456, 0.2600812476561621955, 0.3120974971873950454, 0.4161299962498555827, 0.5201624953123160644, 0.6241949943747765461, 0.7282274934372370279, 0.8322599924996976206 ), + .UNSPECIFIED. ) ; +#7614 = LINE ( 'NONE', #26245, #7250 ) ; +#7615 = ORIENTED_EDGE ( 'NONE', *, *, #24892, .F. ) ; +#7616 = AXIS2_PLACEMENT_3D ( 'NONE', #35014, #10714, #7022 ) ; +#7617 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 82.27946979429611929, 297.5967072516833127 ) ) ; +#7618 = AXIS2_PLACEMENT_3D ( 'NONE', #20127, #1327, #7869 ) ; +#7619 = AXIS2_PLACEMENT_3D ( 'NONE', #7149, #9435, #22515 ) ; +#7620 = ORIENTED_EDGE ( 'NONE', *, *, #12234, .T. ) ; +#7621 = CARTESIAN_POINT ( 'NONE', ( 38.70841052475000055, 119.0653296949000151, 90.11979583391000403 ) ) ; +#7622 = CARTESIAN_POINT ( 'NONE', ( -35.95198627950571790, 115.8887714456496383, 87.28949839086233453 ) ) ; +#7623 = CARTESIAN_POINT ( 'NONE', ( -45.57969790969411861, 124.0544719173705772, 91.68157259218224908 ) ) ; +#7624 = CARTESIAN_POINT ( 'NONE', ( 37.65057158750833821, 122.6594394773597969, 91.02725657039249541 ) ) ; +#7625 = CONICAL_SURFACE ( 'NONE', #29191, 2.499997363466079037, 0.7853981633710050980 ) ; +#7626 = ORIENTED_EDGE ( 'NONE', *, *, #5244, .T. ) ; +#7627 = ORIENTED_EDGE ( 'NONE', *, *, #38022, .F. ) ; +#7628 = DIRECTION ( 'NONE', ( 0.0005884949961245230978, -0.2249510543439041388, 0.9743698870671267942 ) ) ; +#7629 = VERTEX_POINT ( 'NONE', #17402 ) ; +#7630 = CARTESIAN_POINT ( 'NONE', ( -35.42916843553630457, 192.6084977412129717, 106.9123174018029943 ) ) ; +#7632 = EDGE_CURVE ( 'NONE', #27492, #11405, #20189, .T. ) ; +#7631 = CARTESIAN_POINT ( 'NONE', ( -38.03218355952305529, 118.0144299118464630, 89.71435174365882403 ) ) ; +#7633 = ADVANCED_FACE ( 'NONE', ( #20066 ), #35797, .T. ) ; +#7634 = EDGE_CURVE ( 'NONE', #27521, #9326, #24819, .T. ) ; +#7635 = ADVANCED_FACE ( 'NONE', ( #7805 ), #18873, .F. ) ; +#7636 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#7637 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4367, #30135, #26879, #5171 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7638 = ORIENTED_EDGE ( 'NONE', *, *, #24110, .F. ) ; +#7639 = CARTESIAN_POINT ( 'NONE', ( -43.13843726988963567, 112.6550928102931834, 129.5909698073101595 ) ) ; +#7640 = FACE_OUTER_BOUND ( 'NONE', #2939, .T. ) ; +#7641 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#7642 = CARTESIAN_POINT ( 'NONE', ( -3.668404234652287155, 128.0226348370951541, 91.77725148381138354 ) ) ; +#7643 = ADVANCED_FACE ( 'NONE', ( #32554 ), #29699, .F. ) ; +#7644 = AXIS2_PLACEMENT_3D ( 'NONE', #27684, #3304, #18431 ) ; +#7645 = ORIENTED_EDGE ( 'NONE', *, *, #2452, .F. ) ; +#7646 = LINE ( 'NONE', #38921, #8192 ) ; +#7647 = CARTESIAN_POINT ( 'NONE', ( -22.49970497326182439, 151.8550686446309896, 95.23816841905139086 ) ) ; +#7648 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5219, #34387, #25419, #6575 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7649 = AXIS2_PLACEMENT_3D ( 'NONE', #15220, #21767, #31565 ) ; +#7650 = CARTESIAN_POINT ( 'NONE', ( 30.31510154549722458, 127.1681252649556626, 89.16473717014450528 ) ) ; +#7651 = EDGE_CURVE ( 'NONE', #32876, #9290, #9630, .T. ) ; +#7652 = VERTEX_POINT ( 'NONE', #2096 ) ; +#7653 = DIRECTION ( 'NONE', ( 0.0001408404346094399215, -0.2255194953558362636, 0.9742386449830560124 ) ) ; +#7655 = CARTESIAN_POINT ( 'NONE', ( -36.08362193231000248, 112.3719106449999998, 89.65513700520000384 ) ) ; +#7654 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7826081015363517412, 0.6225147061794341630 ) ) ; +#7656 = ORIENTED_EDGE ( 'NONE', *, *, #38076, .T. ) ; +#7657 = ORIENTED_EDGE ( 'NONE', *, *, #35527, .F. ) ; +#7658 = CARTESIAN_POINT ( 'NONE', ( -13.49852954174844299, 137.6306192790454475, 94.00136703131360605 ) ) ; +#7659 = DIRECTION ( 'NONE', ( -0.6087614115774629964, -0.7729348350621531027, -0.1788331191967996447 ) ) ; +#7660 = CARTESIAN_POINT ( 'NONE', ( 15.05621097247296980, 125.1021127306558043, 171.3704188677303648 ) ) ; +#7661 = DIRECTION ( 'NONE', ( 0.7855032201832807814, -0.6188575693014479739, 0.000000000000000000 ) ) ; +#7662 = LINE ( 'NONE', #25904, #14264 ) ; +#7663 = ORIENTED_EDGE ( 'NONE', *, *, #15145, .F. ) ; +#7664 = VERTEX_POINT ( 'NONE', #2498 ) ; +#7665 = PLANE ( 'NONE', #38929 ) ; +#7666 = VERTEX_POINT ( 'NONE', #17603 ) ; +#7667 = ORIENTED_EDGE ( 'NONE', *, *, #37429, .T. ) ; +#7668 = ORIENTED_EDGE ( 'NONE', *, *, #2345, .F. ) ; +#7669 = DIRECTION ( 'NONE', ( 0.7933532970003738249, 0.5930762008556724751, 0.1372995488602876402 ) ) ; +#7670 = CYLINDRICAL_SURFACE ( 'NONE', #21109, 2.000000000000014655 ) ; +#7671 = CARTESIAN_POINT ( 'NONE', ( 30.44722896069117724, 127.1067747388918434, 88.97944275832713856 ) ) ; +#7672 = VECTOR ( 'NONE', #11265, 1000.000000000000114 ) ; +#7673 = VERTEX_POINT ( 'NONE', #37236 ) ; +#7674 = DIRECTION ( 'NONE', ( -0.0005884949961227338390, 0.2249510543439056653, -0.9743698870671265722 ) ) ; +#7675 = CARTESIAN_POINT ( 'NONE', ( 38.08087559214000350, 118.5847423712999955, 87.56841820341999494 ) ) ; +#7676 = CARTESIAN_POINT ( 'NONE', ( 25.66664312785736968, 120.1441062793254417, 90.08149356691757248 ) ) ; +#7677 = CARTESIAN_POINT ( 'NONE', ( -43.56994142101562062, 121.4012961811330626, 90.41976514615660676 ) ) ; +#7678 = CONICAL_SURFACE ( 'NONE', #27946, 9.999999999987785770, 0.7853981633973015075 ) ; +#7679 = ORIENTED_EDGE ( 'NONE', *, *, #38160, .T. ) ; +#7680 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#7681 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921572969, -0.2249510932971622301 ) ) ; +#7682 = DIRECTION ( 'NONE', ( 0.0006039748319371906473, -0.000000000000000000, 0.9999998176071844824 ) ) ; +#7683 = VERTEX_POINT ( 'NONE', #5954 ) ; +#7684 = CARTESIAN_POINT ( 'NONE', ( 0.5796509708708875719, 188.6024196665420050, 103.1948729230731061 ) ) ; +#7685 = LINE ( 'NONE', #38558, #27995 ) ; +#7686 = EDGE_CURVE ( 'NONE', #31634, #22903, #12102, .T. ) ; +#7687 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7010, #1483, #19483, #13760 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7688 = EDGE_CURVE ( 'NONE', #6603, #39904, #3873, .T. ) ; +#7689 = CARTESIAN_POINT ( 'NONE', ( -6.168135754641124180, 163.2166086438842001, 100.0749825304044265 ) ) ; +#7690 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971582333 ) ) ; +#7691 = ORIENTED_EDGE ( 'NONE', *, *, #40085, .F. ) ; +#7692 = LINE ( 'NONE', #16687, #4996 ) ; +#7693 = CARTESIAN_POINT ( 'NONE', ( 2.230626752277192537, 189.8962178526613798, 103.9420327300870213 ) ) ; +#7694 = CYLINDRICAL_SURFACE ( 'NONE', #20182, 5.000000000000007994 ) ; +#7695 = LINE ( 'NONE', #7486, #19043 ) ; +#7696 = ORIENTED_EDGE ( 'NONE', *, *, #29821, .T. ) ; +#7697 = CARTESIAN_POINT ( 'NONE', ( -25.67549068909692522, 191.4258646064230902, 104.2046749456761603 ) ) ; +#7698 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971553745 ) ) ; +#7699 = CARTESIAN_POINT ( 'NONE', ( 38.02735593688370130, 118.5964293117260695, 87.52753786365937572 ) ) ; +#7700 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364692610378, 136.5649596138845538, 181.4686487119390961 ) ) ; +#7701 = EDGE_LOOP ( 'NONE', ( #32677, #26430, #24395, #34821 ) ) ; +#7702 = VECTOR ( 'NONE', #34187, 1000.000000000000227 ) ; +#7703 = CIRCLE ( 'NONE', #39696, 6.000000000000007994 ) ; +#7704 = PLANE ( 'NONE', #29185 ) ; +#7705 = EDGE_CURVE ( 'NONE', #14883, #25194, #30909, .T. ) ; +#7706 = DIRECTION ( 'NONE', ( -0.6087611434179115433, 0.7728348325624405657, 0.1792657018023848803 ) ) ; +#7707 = FACE_OUTER_BOUND ( 'NONE', #16882, .T. ) ; +#7708 = FACE_OUTER_BOUND ( 'NONE', #8852, .T. ) ; +#7709 = CARTESIAN_POINT ( 'NONE', ( 36.48199150421999803, 190.6222350763999884, 106.8659481697000047 ) ) ; +#7710 = CARTESIAN_POINT ( 'NONE', ( 18.27501454559784122, 126.3924864382006632, 174.4075621399051101 ) ) ; +#7711 = CARTESIAN_POINT ( 'NONE', ( -25.50804057823069471, 190.9260211217805363, 106.3128357153982648 ) ) ; +#7712 = CARTESIAN_POINT ( 'NONE', ( 25.99332206926874278, 209.7096538831000032, 78.04280567916214295 ) ) ; +#7713 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178587041921E-05, 0.0002331579774917524482 ) ) ; +#7714 = VERTEX_POINT ( 'NONE', #21310 ) ; +#7715 = CARTESIAN_POINT ( 'NONE', ( 42.10159726138748226, 77.14301703112127484, 276.8136732519894849 ) ) ; +#7716 = CARTESIAN_POINT ( 'NONE', ( 37.17804754624985719, 145.4524169400428946, 280.9300640675564864 ) ) ; +#7717 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#7718 = VERTEX_POINT ( 'NONE', #8437 ) ; +#7719 = FACE_OUTER_BOUND ( 'NONE', #2208, .T. ) ; +#7720 = ORIENTED_EDGE ( 'NONE', *, *, #32167, .T. ) ; +#7721 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25917, #22244, #10173, #22837 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.570060973614779032, 2.960051731740213743 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8453711073098807427, 0.8453711073098807427, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#7722 = AXIS2_PLACEMENT_3D ( 'NONE', #25606, #3697, #32330 ) ; +#7723 = DIRECTION ( 'NONE', ( -1.447458112927613770E-19, -1.000000000000000000, 1.271205603797056623E-14 ) ) ; +#7724 = DIRECTION ( 'NONE', ( -0.0005734119072328723934, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#7725 = ORIENTED_EDGE ( 'NONE', *, *, #28897, .T. ) ; +#7726 = CARTESIAN_POINT ( 'NONE', ( 36.56395785382211727, 191.5078140368809727, 106.3610736895479789 ) ) ; +#7727 = AXIS2_PLACEMENT_3D ( 'NONE', #24113, #1610, #4674 ) ; +#7728 = CARTESIAN_POINT ( 'NONE', ( 3.544766722543614357, 167.8297556397829453, 101.4672138571396687 ) ) ; +#7729 = CIRCLE ( 'NONE', #10441, 2.000000000000011546 ) ; +#7730 = CARTESIAN_POINT ( 'NONE', ( 25.99876818124551292, 118.1164810761916470, 87.25208046938912787 ) ) ; +#7731 = CARTESIAN_POINT ( 'NONE', ( -13.50000254103607134, 126.8013067660671567, 88.93239042800610150 ) ) ; +#7732 = EDGE_CURVE ( 'NONE', #38732, #24067, #15365, .T. ) ; +#7733 = EDGE_CURVE ( 'NONE', #1631, #10082, #12356, .T. ) ; +#7734 = DIRECTION ( 'NONE', ( 0.6087614109020721420, 0.7729348355671186166, 0.1788331193133692876 ) ) ; +#7735 = LINE ( 'NONE', #4461, #33436 ) ; +#7736 = ORIENTED_EDGE ( 'NONE', *, *, #20732, .F. ) ; +#7737 = CARTESIAN_POINT ( 'NONE', ( 15.50029468041106817, 151.8594625358016401, 95.21623178145287625 ) ) ; +#7738 = PLANE ( 'NONE', #16226 ) ; +#7739 = ADVANCED_FACE ( 'NONE', ( #24787 ), #39890, .T. ) ; +#7740 = FACE_OUTER_BOUND ( 'NONE', #16224, .T. ) ; +#7741 = VERTEX_POINT ( 'NONE', #40291 ) ; +#7742 = CARTESIAN_POINT ( 'NONE', ( 23.35827205255252892, 181.8168341326200448, 101.7856298503688492 ) ) ; +#7743 = FACE_OUTER_BOUND ( 'NONE', #16795, .T. ) ; +#7744 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.387778780778639066E-14 ) ) ; +#7745 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250105753, 132.8554482850478848, 90.84904174526991483 ) ) ; +#7746 = CARTESIAN_POINT ( 'NONE', ( 5.704625823861016798, 115.9590670288128393, 152.9217693071938982 ) ) ; +#7747 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971555410 ) ) ; +#7748 = VECTOR ( 'NONE', #13627, 1000.000000000000114 ) ; +#7749 = DIRECTION ( 'NONE', ( 0.0005884949961239352434, -0.2249510543439079413, 0.9743698870671259060 ) ) ; +#7750 = CARTESIAN_POINT ( 'NONE', ( 38.78370429339999959, 119.1138702176999971, 90.11952439853000385 ) ) ; +#7751 = EDGE_LOOP ( 'NONE', ( #21564, #32349, #3691, #30380 ) ) ; +#7752 = CARTESIAN_POINT ( 'NONE', ( 15.03079896862295861, 124.8517197123057088, 88.46813332591423773 ) ) ; +#7753 = DIRECTION ( 'NONE', ( -0.0005884949961181157882, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#7754 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552357 ) ) ; +#7755 = CONICAL_SURFACE ( 'NONE', #34530, 4.999999999914826354, 0.7853981634347277918 ) ; +#7756 = CARTESIAN_POINT ( 'NONE', ( -27.08876248542915377, 119.4912842839333535, 171.3567424277059956 ) ) ; +#7757 = CARTESIAN_POINT ( 'NONE', ( -28.46728868142984226, 182.0597503807817645, 102.2150741964074143 ) ) ; +#7758 = AXIS2_PLACEMENT_3D ( 'NONE', #26282, #23602, #7653 ) ; +#7759 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #6282, #19148 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7760 = VECTOR ( 'NONE', #34199, 1000.000000000000000 ) ; +#7761 = CARTESIAN_POINT ( 'NONE', ( -14.78422084203157461, 175.4439834284964945, 102.7320481277236013 ) ) ; +#7762 = VERTEX_POINT ( 'NONE', #5545 ) ; +#7763 = ORIENTED_EDGE ( 'NONE', *, *, #1455, .T. ) ; +#7764 = ORIENTED_EDGE ( 'NONE', *, *, #35081, .T. ) ; +#7765 = CARTESIAN_POINT ( 'NONE', ( -13.50102315917679974, 124.6787954048031679, 88.87557530041469533 ) ) ; +#7766 = EDGE_CURVE ( 'NONE', #39651, #34711, #30100, .T. ) ; +#7767 = CARTESIAN_POINT ( 'NONE', ( 15.83475876442500940, 160.0983460365729059, 99.51258769526648962 ) ) ; +#7768 = ORIENTED_EDGE ( 'NONE', *, *, #36654, .T. ) ; +#7769 = CARTESIAN_POINT ( 'NONE', ( 16.16445611541705674, 122.9245094293323888, 174.2137880000448718 ) ) ; +#7770 = EDGE_CURVE ( 'NONE', #32422, #31750, #2704, .T. ) ; +#7771 = CARTESIAN_POINT ( 'NONE', ( -29.78153364950144422, 126.4887807563219440, 91.43890500524419451 ) ) ; +#7772 = CARTESIAN_POINT ( 'NONE', ( -38.00362794936000199, 118.6130157638999947, 87.61697703909000268 ) ) ; +#7773 = ORIENTED_EDGE ( 'NONE', *, *, #39907, .F. ) ; +#7774 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18, #18794, #412, #6738 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7775 = CARTESIAN_POINT ( 'NONE', ( 17.00047812746359810, 137.4649845012766889, 177.5753949225429551 ) ) ; +#7776 = VERTEX_POINT ( 'NONE', #21100 ) ; +#7777 = CARTESIAN_POINT ( 'NONE', ( 5.664848030825724301, 124.6188265068983441, 88.76455461985773354 ) ) ; +#7778 = CARTESIAN_POINT ( 'NONE', ( -32.82620923289504589, 141.9145509277669532, 282.5750060058261965 ) ) ; +#7779 = ADVANCED_FACE ( 'NONE', ( #27654 ), #27049, .T. ) ; +#7780 = EDGE_CURVE ( 'NONE', #23353, #39699, #16939, .T. ) ; +#7781 = CYLINDRICAL_SURFACE ( 'NONE', #32628, 2.000000000000014655 ) ; +#7782 = LINE ( 'NONE', #7583, #28817 ) ; +#7783 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#7784 = ADVANCED_FACE ( 'NONE', ( #37041 ), #647, .F. ) ; +#7785 = ORIENTED_EDGE ( 'NONE', *, *, #4941, .T. ) ; +#7786 = AXIS2_PLACEMENT_3D ( 'NONE', #33740, #32925, #39264 ) ; +#7787 = CARTESIAN_POINT ( 'NONE', ( -19.99999816303952471, 191.5261162992163690, 103.8822987450886046 ) ) ; +#7788 = EDGE_CURVE ( 'NONE', #26229, #37821, #31066, .T. ) ; +#7789 = CARTESIAN_POINT ( 'NONE', ( 37.43095215650283336, 132.6072067203139966, 336.9709689194860402 ) ) ; +#7790 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#7791 = CARTESIAN_POINT ( 'NONE', ( -35.63072100744419402, 191.7838021594926659, 106.9393198751362064 ) ) ; +#7792 = CIRCLE ( 'NONE', #39103, 5.999999999973051779 ) ; +#7793 = AXIS2_PLACEMENT_3D ( 'NONE', #12258, #37200, #15321 ) ; +#7794 = ORIENTED_EDGE ( 'NONE', *, *, #27298, .F. ) ; +#7795 = CARTESIAN_POINT ( 'NONE', ( 17.30417074659255761, 152.9391053872499526, 180.9092052391793004 ) ) ; +#7796 = CARTESIAN_POINT ( 'NONE', ( -25.50006458888940131, 118.8155663869242886, 89.78318340809063614 ) ) ; +#7797 = ORIENTED_EDGE ( 'NONE', *, *, #1013, .T. ) ; +#7798 = ORIENTED_EDGE ( 'NONE', *, *, #3716, .T. ) ; +#7799 = VECTOR ( 'NONE', #34983, 1000.000000000000114 ) ; +#7800 = ORIENTED_EDGE ( 'NONE', *, *, #4537, .F. ) ; +#7801 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1439, #10664, #38256, #16769 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7802 = CARTESIAN_POINT ( 'NONE', ( -21.87345861519190038, 193.2440397361608859, 28.36825712722428605 ) ) ; +#7803 = ORIENTED_EDGE ( 'NONE', *, *, #5449, .F. ) ; +#7804 = CARTESIAN_POINT ( 'NONE', ( -27.86528758660999827, 186.6966694207999922, 105.3378367195000038 ) ) ; +#7805 = FACE_OUTER_BOUND ( 'NONE', #30030, .T. ) ; +#7806 = EDGE_CURVE ( 'NONE', #12963, #32994, #27259, .T. ) ; +#7807 = CARTESIAN_POINT ( 'NONE', ( 5.666470275070000895, 124.7419549469727542, 88.96160009636332688 ) ) ; +#7808 = ORIENTED_EDGE ( 'NONE', *, *, #1352, .T. ) ; +#7809 = CARTESIAN_POINT ( 'NONE', ( 26.00355954743800879, 120.0650824375095453, 90.41110813385893152 ) ) ; +#7810 = CARTESIAN_POINT ( 'NONE', ( -5.669876885668252875, 128.5855644063385057, 89.33958911438577388 ) ) ; +#7811 = DIRECTION ( 'NONE', ( 0.0005884949961199882054, -0.2249510543439090515, 0.9743698870671257950 ) ) ; +#7812 = ORIENTED_EDGE ( 'NONE', *, *, #25040, .F. ) ; +#7813 = AXIS2_PLACEMENT_3D ( 'NONE', #31231, #12423, #37563 ) ; +#7814 = CONICAL_SURFACE ( 'NONE', #18929, 2.499987184277071339, 0.7853981634084753471 ) ; +#7815 = ORIENTED_EDGE ( 'NONE', *, *, #24566, .F. ) ; +#7816 = EDGE_CURVE ( 'NONE', #23591, #19822, #6709, .T. ) ; +#7817 = AXIS2_PLACEMENT_3D ( 'NONE', #27294, #8883, #24224 ) ; +#7818 = AXIS2_PLACEMENT_3D ( 'NONE', #18444, #36876, #27903 ) ; +#7819 = CONICAL_SURFACE ( 'NONE', #30708, 30.49999999998559730, 0.7853981633973063925 ) ; +#7820 = ORIENTED_EDGE ( 'NONE', *, *, #15900, .T. ) ; +#7821 = CARTESIAN_POINT ( 'NONE', ( -3.168113297478124313, 183.4473166593645033, 105.0858980959790188 ) ) ; +#7822 = EDGE_CURVE ( 'NONE', #2849, #18222, #31914, .T. ) ; +#7823 = CARTESIAN_POINT ( 'NONE', ( 5.669143597388600853, 187.3556546440009356, 105.5526921997536078 ) ) ; +#7824 = CARTESIAN_POINT ( 'NONE', ( 30.07038983360635243, 134.2444639735435317, 93.70962392686422504 ) ) ; +#7825 = EDGE_CURVE ( 'NONE', #15218, #30145, #4755, .T. ) ; +#7826 = VERTEX_POINT ( 'NONE', #22312 ) ; +#7827 = VERTEX_POINT ( 'NONE', #21909 ) ; +#7828 = DIRECTION ( 'NONE', ( 0.0005734119072318730843, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#7829 = EDGE_CURVE ( 'NONE', #18693, #8704, #13102, .T. ) ; +#7830 = EDGE_CURVE ( 'NONE', #36424, #22426, #22514, .T. ) ; +#7831 = ORIENTED_EDGE ( 'NONE', *, *, #29687, .T. ) ; +#7832 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #34102, #9383, #11851, #18551 ), + ( #3026, #15512, #36777, #15119 ), + ( #12636, #30657, #9581, #28002 ), + ( #2655, #12438, #21854, #34298 ), + ( #17875, #14642, #20545, #1964 ), + ( #18081, #21174, #20757, #39759 ), + ( #14432, #4802, #14232, #24464 ), + ( #24261, #36703, #11978, #33631 ), + ( #11351, #20971, #36913, #39154 ), + ( #11775, #5629, #26708, #15041 ), + ( #27545, #5009, #8085, #8716 ), + ( #11163, #30372, #8920, #30172 ), + ( #17263, #29966, #2168, #2573 ), + ( #5206, #39970, #27125, #32821 ), + ( #36296, #17677, #39561, #26916 ), + ( #11570, #23837, #24042, #8295 ), + ( #33214, #36500, #33426, #33018 ), + ( #29774, #23634, #36083, #8506 ), + ( #2372, #5419, #17471, #1753 ), + ( #39348, #14846, #27330, #30584 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -7.662039796166000266E-06, 0.001947477951146999895, 0.003902617942089999913, 0.007809034349275999903, 0.01562186716364999915, 0.02343469997802000160, 0.03124753279240000126, 0.04687319842115000162, 0.06249886404991000094, 0.09375019530740000273, 0.1250015265648999896, 0.1875041890797999877, 0.2500068515948999925, 0.3750091000290999843, 0.5000113484632999761, 0.7500158453317999907, 1.000000000000000000, 1.192566656214000043 ), + ( 6.650148147435999969E-07, 1.000000500385000102 ), + .UNSPECIFIED. ) ; +#7833 = CARTESIAN_POINT ( 'NONE', ( 30.06878009202964463, 135.2977368468020813, 91.38385643107594092 ) ) ; +#7834 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1803, #17922, #20599, #36549, #5053, #7929, #39605, #32864, #17311, #11617, #14278 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000902611, 0.3750000000001291744, 0.4375000000001486034, 0.4687500000001207923, 0.5000000000000929257, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7835 = CARTESIAN_POINT ( 'NONE', ( -38.26543874032973491, 118.2653806693816136, 89.71123565515037512 ) ) ; +#7836 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36457, #33586, #18036, #30542 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7837 = ORIENTED_EDGE ( 'NONE', *, *, #15273, .T. ) ; +#7838 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#7839 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27571, #20582, #21419, #36731 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0003943868672497987098, 0.0003970494017626595581 ), + .UNSPECIFIED. ) ; +#7840 = CARTESIAN_POINT ( 'NONE', ( 2.563981084831000068, 190.9709217690999878, 106.3045548138999976 ) ) ; +#7841 = VERTEX_POINT ( 'NONE', #25784 ) ; +#7842 = CARTESIAN_POINT ( 'NONE', ( 37.28562273015844397, 178.8217641854361091, 136.8524436601264540 ) ) ; +#7843 = AXIS2_PLACEMENT_3D ( 'NONE', #19503, #13584, #35228 ) ; +#7844 = LINE ( 'NONE', #20101, #8193 ) ; +#7845 = CARTESIAN_POINT ( 'NONE', ( 20.30299311939850071, 153.1411371379373918, 94.99607687304013837 ) ) ; +#7846 = CARTESIAN_POINT ( 'NONE', ( 32.43759465430078137, 141.7182063835813324, 280.9329271823174281 ) ) ; +#7847 = CONICAL_SURFACE ( 'NONE', #11102, 5.999999999898423475, 0.7853981633778843729 ) ; +#7848 = ORIENTED_EDGE ( 'NONE', *, *, #15721, .F. ) ; +#7849 = CIRCLE ( 'NONE', #10472, 4.499999999986576960 ) ; +#7850 = CARTESIAN_POINT ( 'NONE', ( 4.034499241909815126, 137.2431130921461886, 91.84870606007839910 ) ) ; +#7851 = LINE ( 'NONE', #1725, #4489 ) ; +#7852 = VERTEX_POINT ( 'NONE', #34536 ) ; +#7853 = CARTESIAN_POINT ( 'NONE', ( -30.04055490880000079, 165.2216646563843199, 152.9217693939943388 ) ) ; +#7855 = CARTESIAN_POINT ( 'NONE', ( -36.18897578704999773, 114.9859802024000004, 89.88506924981000168 ) ) ; +#7854 = DIRECTION ( 'NONE', ( 0.6087614109020721420, 0.7729348355671186166, 0.1788331193133692876 ) ) ; +#7856 = VERTEX_POINT ( 'NONE', #15748 ) ; +#7857 = FACE_OUTER_BOUND ( 'NONE', #4539, .T. ) ; +#7858 = EDGE_LOOP ( 'NONE', ( #36397, #16271, #4409, #24044 ) ) ; +#7859 = ADVANCED_FACE ( 'NONE', ( #34348 ), #20215, .F. ) ; +#7860 = CARTESIAN_POINT ( 'NONE', ( 16.16550992384005170, 152.4595644213394223, 178.9888250856261607 ) ) ; +#7861 = EDGE_CURVE ( 'NONE', #19286, #7358, #1281, .T. ) ; +#7862 = DIRECTION ( 'NONE', ( -0.0005884949961216158097, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#7863 = CARTESIAN_POINT ( 'NONE', ( 0.04578642046451000119, 211.2500000000000000, 75.80847693012999855 ) ) ; +#7864 = ADVANCED_FACE ( 'NONE', ( #16158 ), #28052, .F. ) ; +#7865 = CARTESIAN_POINT ( 'NONE', ( 36.40558664052492333, 191.8188463803718093, 104.3612499972096117 ) ) ; +#7866 = ORIENTED_EDGE ( 'NONE', *, *, #28623, .F. ) ; +#7867 = EDGE_CURVE ( 'NONE', #23412, #36516, #34155, .T. ) ; +#7868 = ORIENTED_EDGE ( 'NONE', *, *, #21132, .F. ) ; +#7869 = DIRECTION ( 'NONE', ( -1.063726576468305383E-07, 0.9743700557780770044, 0.2249510933581244931 ) ) ; +#7870 = ORIENTED_EDGE ( 'NONE', *, *, #18914, .F. ) ; +#7871 = ORIENTED_EDGE ( 'NONE', *, *, #29264, .F. ) ; +#7873 = CONICAL_SURFACE ( 'NONE', #13087, 17.00000000000406430, 0.7853981633972577647 ) ; +#7872 = CARTESIAN_POINT ( 'NONE', ( 3.064236136099508290, 190.8512031035150471, 106.7914583158460573 ) ) ; +#7874 = CARTESIAN_POINT ( 'NONE', ( 2.544444642231999953, 209.0637104426000121, 73.60054458572000158 ) ) ; +#7875 = EDGE_CURVE ( 'NONE', #10320, #479, #28440, .T. ) ; +#7876 = VECTOR ( 'NONE', #18269, 1000.000000000000000 ) ; +#7877 = VERTEX_POINT ( 'NONE', #31109 ) ; +#7878 = PLANE ( 'NONE', #29179 ) ; +#7879 = VECTOR ( 'NONE', #4085, 1000.000000000000114 ) ; +#7880 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; +#7881 = CARTESIAN_POINT ( 'NONE', ( 38.02815534111000062, 191.5231178303000092, 104.5088530676000147 ) ) ; +#7882 = CARTESIAN_POINT ( 'NONE', ( -25.83548129009000149, 120.8342218634000034, 87.73633095686001582 ) ) ; +#7883 = ADVANCED_FACE ( 'NONE', ( #3874 ), #9712, .F. ) ; +#7884 = ORIENTED_EDGE ( 'NONE', *, *, #32790, .F. ) ; +#7885 = LINE ( 'NONE', #29973, #1029 ) ; +#7886 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391912172 ) ) ; +#7887 = VERTEX_POINT ( 'NONE', #19614 ) ; +#7888 = CARTESIAN_POINT ( 'NONE', ( 0.5820739880337706396, 188.6030464522529826, 103.1950161645411725 ) ) ; +#7889 = CARTESIAN_POINT ( 'NONE', ( -37.23494651666909050, 103.9956957637453598, 184.2025836917128174 ) ) ; +#7890 = CARTESIAN_POINT ( 'NONE', ( 3.168113141152071321, 127.9133523189982498, 92.26104312719712652 ) ) ; +#7891 = CARTESIAN_POINT ( 'NONE', ( 45.91741224157529189, 185.4616417385437046, 105.5241924283433548 ) ) ; +#7892 = VERTEX_POINT ( 'NONE', #32898 ) ; +#7893 = EDGE_CURVE ( 'NONE', #22776, #25168, #37864, .T. ) ; +#7894 = CARTESIAN_POINT ( 'NONE', ( -25.99978576141418429, 118.1122949349609286, 90.28348809642494643 ) ) ; +#7895 = CARTESIAN_POINT ( 'NONE', ( 1.723508806196166532, 189.3712161428316563, 103.7908781100297659 ) ) ; +#7896 = DIRECTION ( 'NONE', ( -0.0004161288024459554248, 0.8480480898107214394, -0.5299191110020532447 ) ) ; +#7897 = VERTEX_POINT ( 'NONE', #16940 ) ; +#7898 = DIRECTION ( 'NONE', ( -0.0005884949961210389057, 0.2249510543439053878, -0.9743698870671265722 ) ) ; +#7899 = ORIENTED_EDGE ( 'NONE', *, *, #10155, .T. ) ; +#7900 = ORIENTED_EDGE ( 'NONE', *, *, #39029, .T. ) ; +#7901 = CARTESIAN_POINT ( 'NONE', ( -25.50922756583905837, 191.3757872987501969, 104.3640622938216183 ) ) ; +#7902 = DIRECTION ( 'NONE', ( -0.0006039748319373067654, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#7903 = CARTESIAN_POINT ( 'NONE', ( 25.64356753708000269, 191.4983924930999990, 104.2449497898000033 ) ) ; +#7904 = VECTOR ( 'NONE', #7838, 1000.000000000000114 ) ; +#7905 = AXIS2_PLACEMENT_3D ( 'NONE', #22223, #3184, #34651 ) ; +#7906 = CARTESIAN_POINT ( 'NONE', ( -5.668571547460837579, 124.2905521247553366, 90.91684019452070231 ) ) ; +#7907 = ORIENTED_EDGE ( 'NONE', *, *, #35124, .T. ) ; +#7908 = VECTOR ( 'NONE', #8757, 1000.000000000000227 ) ; +#7909 = CARTESIAN_POINT ( 'NONE', ( -14.78424365577531141, 182.9075039701052958, 104.4551379424934083 ) ) ; +#7910 = AXIS2_PLACEMENT_3D ( 'NONE', #24153, #24361, #9214 ) ; +#7911 = DIRECTION ( 'NONE', ( -0.9999998176072601996, 5.311345650496605610E-11, 0.0006039747068119591823 ) ) ; +#7912 = CARTESIAN_POINT ( 'NONE', ( -25.40406319347369646, 116.2731550828873139, 87.28312770962722311 ) ) ; +#7913 = CARTESIAN_POINT ( 'NONE', ( 39.71797952931839149, 110.6587743677033586, 169.3312915083336918 ) ) ; +#7914 = EDGE_CURVE ( 'NONE', #14055, #23221, #32639, .T. ) ; +#7915 = CARTESIAN_POINT ( 'NONE', ( 36.62411393520999781, 190.8924316886999861, 106.6482428512000098 ) ) ; +#7916 = CARTESIAN_POINT ( 'NONE', ( 32.56862158914320560, 175.5141961308963801, 100.1538973425462444 ) ) ; +#7917 = EDGE_CURVE ( 'NONE', #40452, #39678, #15016, .T. ) ; +#7918 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #25048, #35207 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#7919 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 3.427539337001264681E-16, -0.0006039748319384838837 ) ) ; +#7920 = EDGE_CURVE ( 'NONE', #23190, #1172, #13696, .T. ) ; +#7921 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989940797, 0.1373964268091562024 ) ) ; +#7922 = CARTESIAN_POINT ( 'NONE', ( 3.044162730076025447, 208.9211496123335507, 73.11923083669719858 ) ) ; +#7923 = ORIENTED_EDGE ( 'NONE', *, *, #8732, .T. ) ; +#7924 = CARTESIAN_POINT ( 'NONE', ( -37.65053461645775457, 212.3970732061722231, 28.08152331534148161 ) ) ; +#7925 = DIRECTION ( 'NONE', ( -8.673617379883984985E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#7926 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173914670, 126.6881577898831495, 89.42249239926104565 ) ) ; +#7927 = ADVANCED_FACE ( 'NONE', ( #38425 ), #29242, .T. ) ; +#7928 = ORIENTED_EDGE ( 'NONE', *, *, #19856, .F. ) ; +#7929 = CARTESIAN_POINT ( 'NONE', ( 5.665198925310773070, 181.8644090848704025, 101.8756595240227654 ) ) ; +#7930 = ORIENTED_EDGE ( 'NONE', *, *, #38231, .F. ) ; +#7931 = EDGE_CURVE ( 'NONE', #34936, #27937, #13032, .T. ) ; +#7932 = DIRECTION ( 'NONE', ( 0.0004161288024527328268, -0.8480480898032328740, 0.5299191110140372141 ) ) ; +#7933 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; +#7934 = CARTESIAN_POINT ( 'NONE', ( 25.40105660042022251, 116.2731026557913765, 87.25244269034133993 ) ) ; +#7935 = VERTEX_POINT ( 'NONE', #1418 ) ; +#7936 = CARTESIAN_POINT ( 'NONE', ( 36.37336898559946974, 191.7343303945321225, 106.3837163451585752 ) ) ; +#7937 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10340, #28542, #6437, #506 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 1.042368180638002949E-06, 0.0007115812285030307088 ), + .UNSPECIFIED. ) ; +#7938 = LINE ( 'NONE', #20821, #13975 ) ; +#7939 = CARTESIAN_POINT ( 'NONE', ( -25.83464932577865270, 120.7303327882271873, 87.71236904360661413 ) ) ; +#7940 = FACE_OUTER_BOUND ( 'NONE', #11797, .T. ) ; +#7941 = CARTESIAN_POINT ( 'NONE', ( -22.49970497326940588, 160.6243991471941968, 97.26272825661190780 ) ) ; +#7942 = ORIENTED_EDGE ( 'NONE', *, *, #40460, .T. ) ; +#7943 = ORIENTED_EDGE ( 'NONE', *, *, #34270, .F. ) ; +#7944 = ADVANCED_FACE ( 'NONE', ( #26378 ), #14110, .F. ) ; +#7945 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498902562, 132.2978364234161290, 93.26432363106762580 ) ) ; +#7946 = DIRECTION ( 'NONE', ( 0.5987319960703996191, 0.8009494346596138792, 0.000000000000000000 ) ) ; +#7947 = CARTESIAN_POINT ( 'NONE', ( 15.83500835682426633, 127.1069917442591617, 91.89618787420208434 ) ) ; +#7948 = CARTESIAN_POINT ( 'NONE', ( -45.59680607712631684, 124.5521801936699262, 92.16782543916392001 ) ) ; +#7949 = ORIENTED_EDGE ( 'NONE', *, *, #29872, .T. ) ; +#7950 = FACE_OUTER_BOUND ( 'NONE', #3900, .T. ) ; +#7951 = LINE ( 'NONE', #14504, #5906 ) ; +#7952 = CARTESIAN_POINT ( 'NONE', ( -28.41397273838000359, 125.0533781296000200, 91.23143372289999320 ) ) ; +#7953 = CARTESIAN_POINT ( 'NONE', ( -82.81915783535940534, 72.22391443751210716, 166.5742336941279973 ) ) ; +#7954 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825873969720803, 0.0005734119034471432848 ) ) ; +#7955 = PLANE ( 'NONE', #5985 ) ; +#7956 = VECTOR ( 'NONE', #29016, 1000.000000000000000 ) ; +#7957 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749385498, 179.6299767372515817, 101.6260513915996739 ) ) ; +#7958 = VECTOR ( 'NONE', #5280, 1000.000000000000114 ) ; +#7959 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971581501 ) ) ; +#7960 = CIRCLE ( 'NONE', #31498, 6.000000000000007994 ) ; +#7961 = CARTESIAN_POINT ( 'NONE', ( 37.43201049002699676, 166.9755643439367816, 188.5080295440252200 ) ) ; +#7962 = CARTESIAN_POINT ( 'NONE', ( 38.87085646289000351, 118.8888690499999967, 89.81811197227000321 ) ) ; +#7963 = ORIENTED_EDGE ( 'NONE', *, *, #19593, .F. ) ; +#7964 = CARTESIAN_POINT ( 'NONE', ( -21.44693681792356443, 182.5559435529752363, 101.8122371725110611 ) ) ; +#7965 = CARTESIAN_POINT ( 'NONE', ( -21.44517132691637329, 129.4739009503746558, 92.63619159901811884 ) ) ; +#7966 = CARTESIAN_POINT ( 'NONE', ( -36.14192390877251171, 191.8989000296091092, 106.4365041918967592 ) ) ; +#7967 = CARTESIAN_POINT ( 'NONE', ( 44.94235576104665597, 66.48397716096599197, 321.1673902962083957 ) ) ; +#7968 = EDGE_CURVE ( 'NONE', #1951, #22363, #25720, .T. ) ; +#7969 = ADVANCED_FACE ( 'NONE', ( #13499 ), #11104, .T. ) ; +#7971 = VERTEX_POINT ( 'NONE', #10842 ) ; +#7970 = DIRECTION ( 'NONE', ( 0.1843855715116846650, 0.08049128682204491347, -0.9795525068948782721 ) ) ; +#7972 = ORIENTED_EDGE ( 'NONE', *, *, #26674, .T. ) ; +#7973 = ORIENTED_EDGE ( 'NONE', *, *, #19543, .T. ) ; +#7974 = ORIENTED_EDGE ( 'NONE', *, *, #31011, .T. ) ; +#7975 = FACE_OUTER_BOUND ( 'NONE', #7991, .T. ) ; +#7976 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319484430396 ) ) ; +#7977 = ORIENTED_EDGE ( 'NONE', *, *, #17697, .T. ) ; +#7978 = FACE_OUTER_BOUND ( 'NONE', #20459, .T. ) ; +#7979 = CARTESIAN_POINT ( 'NONE', ( -34.62136824934677293, 159.8657254837204391, 187.5296924617526599 ) ) ; +#7980 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; +#7981 = CARTESIAN_POINT ( 'NONE', ( 14.16683332331358613, 129.7278030047937705, 90.10754002185558420 ) ) ; +#7982 = CARTESIAN_POINT ( 'NONE', ( -19.46367937371129742, 126.2449231135791052, 175.9963188856066267 ) ) ; +#7983 = ORIENTED_EDGE ( 'NONE', *, *, #17795, .T. ) ; +#7984 = DIRECTION ( 'NONE', ( 0.0006039748319391906751, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#7985 = ORIENTED_EDGE ( 'NONE', *, *, #32973, .T. ) ; +#7986 = DIRECTION ( 'NONE', ( 0.7933533416835718555, -0.5930537051408170113, -0.1373964266575322390 ) ) ; +#7987 = CONICAL_SURFACE ( 'NONE', #7337, 2.502997276898424772, 0.7853981634249621591 ) ; +#7988 = CARTESIAN_POINT ( 'NONE', ( -2.685652211178042759, 190.9457805259862369, 106.5600337294049638 ) ) ; +#7989 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#7990 = CONICAL_SURFACE ( 'NONE', #22373, 3.499999999950321516, 0.7853981633778843729 ) ; +#7991 = EDGE_LOOP ( 'NONE', ( #17317, #31001, #33412, #2271 ) ) ; +#7992 = ADVANCED_FACE ( 'NONE', ( #22712 ), #14936, .F. ) ; +#7993 = CARTESIAN_POINT ( 'NONE', ( -26.13683318140000011, 191.6581722882000065, 103.7775482495000006 ) ) ; +#7994 = AXIS2_PLACEMENT_3D ( 'NONE', #40237, #28004, #18964 ) ; +#7995 = CARTESIAN_POINT ( 'NONE', ( 1.510991691235000101, 188.7915705609999861, 103.2373913670000007 ) ) ; +#7996 = CARTESIAN_POINT ( 'NONE', ( 16.56895240876187003, 123.0679515848563454, 172.2907917757468681 ) ) ; +#7997 = ORIENTED_EDGE ( 'NONE', *, *, #8494, .F. ) ; +#7998 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#7999 = EDGE_LOOP ( 'NONE', ( #24304, #34522, #22303, #24378 ) ) ; +#8000 = EDGE_LOOP ( 'NONE', ( #7018, #6061, #18030, #34031 ) ) ; +#8001 = EDGE_CURVE ( 'NONE', #6720, #26044, #27681, .T. ) ; +#8002 = EDGE_LOOP ( 'NONE', ( #39685, #6253, #28469, #8922, #26057, #39648 ) ) ; +#8003 = CARTESIAN_POINT ( 'NONE', ( -38.50399426135000169, 118.5032430122000022, 89.70860371832000624 ) ) ; +#8004 = ORIENTED_EDGE ( 'NONE', *, *, #31061, .F. ) ; +#8005 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#8006 = DIRECTION ( 'NONE', ( 0.0006039748319388569577, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#8007 = EDGE_CURVE ( 'NONE', #30603, #16409, #7546, .T. ) ; +#8008 = ORIENTED_EDGE ( 'NONE', *, *, #34246, .T. ) ; +#8009 = CARTESIAN_POINT ( 'NONE', ( 25.01935866475762182, 130.6173723549316605, 89.79320596012071576 ) ) ; +#8010 = DIRECTION ( 'NONE', ( 0.7933535320750288999, 0.5930759023596230417, 0.1372994799130531074 ) ) ; +#8011 = AXIS2_PLACEMENT_3D ( 'NONE', #10551, #32999, #2151 ) ; +#8012 = ORIENTED_EDGE ( 'NONE', *, *, #35641, .F. ) ; +#8013 = CARTESIAN_POINT ( 'NONE', ( 26.13011340010889683, 121.2564972074009830, 90.71553933329148833 ) ) ; +#8014 = CARTESIAN_POINT ( 'NONE', ( -15.49852918602411300, 173.9514291674110780, 102.3878961845165776 ) ) ; +#8015 = EDGE_CURVE ( 'NONE', #35793, #16546, #7729, .T. ) ; +#8016 = AXIS2_PLACEMENT_3D ( 'NONE', #1330, #17467, #33418 ) ; +#8017 = EDGE_CURVE ( 'NONE', #6960, #9305, #23752, .T. ) ; +#8019 = CARTESIAN_POINT ( 'NONE', ( -30.45075997731206030, 185.6036007986156449, 102.5212824999076986 ) ) ; +#8018 = CARTESIAN_POINT ( 'NONE', ( -25.50991579498579398, 209.7152486954105086, 73.57374465072240355 ) ) ; +#8020 = EDGE_CURVE ( 'NONE', #604, #36902, #33950, .T. ) ; +#8021 = EDGE_LOOP ( 'NONE', ( #13141, #34261, #20864, #24192 ) ) ; +#8022 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552635 ) ) ; +#8023 = CONICAL_SURFACE ( 'NONE', #33467, 2.503061174963238766, 0.7853981634355203800 ) ; +#8024 = ORIENTED_EDGE ( 'NONE', *, *, #16923, .T. ) ; +#8025 = ORIENTED_EDGE ( 'NONE', *, *, #29196, .T. ) ; +#8026 = CARTESIAN_POINT ( 'NONE', ( -36.13188863639395976, 116.3632294363277424, 87.28960704737795595 ) ) ; +#8027 = CARTESIAN_POINT ( 'NONE', ( -26.69629712813124556, 110.6131156702000027, 90.28390873370305769 ) ) ; +#8028 = CARTESIAN_POINT ( 'NONE', ( -45.17721186414367907, 180.6407286098181544, 103.9501681112560192 ) ) ; +#8029 = CARTESIAN_POINT ( 'NONE', ( -22.78187663633837801, 153.7285825244628086, 98.23663543168041201 ) ) ; +#8030 = ORIENTED_EDGE ( 'NONE', *, *, #33864, .T. ) ; +#8031 = ORIENTED_EDGE ( 'NONE', *, *, #4413, .F. ) ; +#8032 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #4452, #16910 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8033 = CARTESIAN_POINT ( 'NONE', ( 38.54411846755796489, 218.5902260770999987, 73.03522440067472132 ) ) ; +#8034 = CARTESIAN_POINT ( 'NONE', ( 25.83181227377999889, 121.1031950916000000, 87.76725331590999701 ) ) ; +#8035 = ORIENTED_EDGE ( 'NONE', *, *, #35626, .T. ) ; +#8036 = VERTEX_POINT ( 'NONE', #20421 ) ; +#8037 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 77.27946979429643193, 322.5967026918629585 ) ) ; +#8038 = ORIENTED_EDGE ( 'NONE', *, *, #23611, .F. ) ; +#8039 = CIRCLE ( 'NONE', #9372, 2.000000000000011546 ) ; +#8040 = CARTESIAN_POINT ( 'NONE', ( -38.21353522366803901, 118.2110904979577128, 89.71187766670830399 ) ) ; +#8041 = VERTEX_POINT ( 'NONE', #29850 ) ; +#8042 = AXIS2_PLACEMENT_3D ( 'NONE', #20912, #24806, #33370 ) ; +#8043 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, 2.333520449303964061E-14, 0.9999998176071844824 ) ) ; +#8044 = VERTEX_POINT ( 'NONE', #17340 ) ; +#8045 = CARTESIAN_POINT ( 'NONE', ( 22.50835269910143666, 151.3303562393625441, 183.1450669823467194 ) ) ; +#8046 = CONICAL_SURFACE ( 'NONE', #14578, 40.50000000002031442, 0.7853981633973055043 ) ; +#8047 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971563737 ) ) ; +#8048 = LINE ( 'NONE', #20314, #1278 ) ; +#8049 = CARTESIAN_POINT ( 'NONE', ( 21.21457926054944920, 175.8986325760867828, 100.7626612099922454 ) ) ; +#8050 = EDGE_CURVE ( 'NONE', #22666, #33783, #29036, .T. ) ; +#8051 = VERTEX_POINT ( 'NONE', #36992 ) ; +#8052 = CARTESIAN_POINT ( 'NONE', ( 25.99214295446221357, 205.1071317750680123, 76.08915132579089402 ) ) ; +#8053 = DIRECTION ( 'NONE', ( 0.6087614115774527823, 0.7729348350621607633, 0.1788331191968013378 ) ) ; +#8054 = CARTESIAN_POINT ( 'NONE', ( -2.851221542150457200, 209.7096659646922774, 76.06022685436926167 ) ) ; +#8055 = EDGE_CURVE ( 'NONE', #16596, #14862, #11649, .T. ) ; +#8056 = ORIENTED_EDGE ( 'NONE', *, *, #37016, .T. ) ; +#8057 = CARTESIAN_POINT ( 'NONE', ( 6.042308921164076807, 177.7921139377573638, 100.6958234779730645 ) ) ; +#8058 = EDGE_CURVE ( 'NONE', #36343, #24826, #11504, .T. ) ; +#8059 = EDGE_CURVE ( 'NONE', #40259, #5402, #8095, .T. ) ; +#8061 = CYLINDRICAL_SURFACE ( 'NONE', #16781, 2.250000000000011102 ) ; +#8060 = LINE ( 'NONE', #32801, #35669 ) ; +#8062 = EDGE_CURVE ( 'NONE', #25237, #13011, #13695, .T. ) ; +#8063 = VERTEX_POINT ( 'NONE', #8584 ) ; +#8064 = CYLINDRICAL_SURFACE ( 'NONE', #34080, 2.000000000000011546 ) ; +#8065 = EDGE_CURVE ( 'NONE', #18716, #38112, #31492, .T. ) ; +#8066 = VECTOR ( 'NONE', #18842, 999.9999999999998863 ) ; +#8067 = AXIS2_PLACEMENT_3D ( 'NONE', #36996, #31256, #3233 ) ; +#8068 = ORIENTED_EDGE ( 'NONE', *, *, #26651, .F. ) ; +#8069 = CARTESIAN_POINT ( 'NONE', ( 62.95950931629634795, 92.27946979429611929, 297.5205190635954295 ) ) ; +#8070 = CARTESIAN_POINT ( 'NONE', ( 0.04563542675669964022, 271.9029643395999187, 75.55847697571874733 ) ) ; +#8071 = CARTESIAN_POINT ( 'NONE', ( 15.50147166925602527, 127.1825504195482353, 91.57172455528431954 ) ) ; +#8072 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#8073 = CARTESIAN_POINT ( 'NONE', ( 12.63937458780924494, 177.5948492622155186, 100.8158580061204219 ) ) ; +#8075 = ORIENTED_EDGE ( 'NONE', *, *, #39539, .F. ) ; +#8074 = AXIS2_PLACEMENT_3D ( 'NONE', #4484, #29448, #34743 ) ; +#8076 = ORIENTED_EDGE ( 'NONE', *, *, #26316, .F. ) ; +#8077 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772234801672, 136.6775772631780796, 180.9814965275865575 ) ) ; +#8078 = ORIENTED_EDGE ( 'NONE', *, *, #19775, .T. ) ; +#8079 = VERTEX_POINT ( 'NONE', #18156 ) ; +#8080 = DIRECTION ( 'NONE', ( 0.6087611434179115433, -0.7728348325624404547, -0.1792657018023851023 ) ) ; +#8081 = CARTESIAN_POINT ( 'NONE', ( 2.870476498559999978, 209.1880350332000091, 73.24767605647001290 ) ) ; +#8082 = ORIENTED_EDGE ( 'NONE', *, *, #26651, .T. ) ; +#8083 = CARTESIAN_POINT ( 'NONE', ( 13.01264957174517356, 177.7922272993784816, 100.6916336907332408 ) ) ; +#8084 = FACE_OUTER_BOUND ( 'NONE', #30094, .T. ) ; +#8085 = CARTESIAN_POINT ( 'NONE', ( -36.14064454963000372, 191.7996476902000040, 104.2912827661999984 ) ) ; +#8086 = CARTESIAN_POINT ( 'NONE', ( 37.45139837402000182, 191.5507549815000061, 104.5084902340000070 ) ) ; +#8087 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38373, #10382, #26125, #34881 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999997749458457985 ), + .UNSPECIFIED. ) ; +#8088 = ORIENTED_EDGE ( 'NONE', *, *, #8400, .F. ) ; +#8089 = CARTESIAN_POINT ( 'NONE', ( 41.51603850386035788, 135.1693297037100194, 25.18785158773614796 ) ) ; +#8090 = ORIENTED_EDGE ( 'NONE', *, *, #14635, .T. ) ; +#8091 = DIRECTION ( 'NONE', ( 0.7933535320750287889, -0.5931614265262138419, -0.1369295264925107780 ) ) ; +#8092 = DIRECTION ( 'NONE', ( -0.6088160902985568779, 0.7729595817128234181, 0.1785397805306046526 ) ) ; +#8093 = DIRECTION ( 'NONE', ( 0.0005884949961155384228, -0.2249510543439099397, 0.9743698870671255730 ) ) ; +#8094 = EDGE_LOOP ( 'NONE', ( #35642, #32031, #26069, #5798 ) ) ; +#8095 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #36583, #12055 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 5.382452939443789803E-08, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8096 = CARTESIAN_POINT ( 'NONE', ( 0.6328254411848658334, 188.6147578804658451, 103.1976893086753506 ) ) ; +#8097 = CARTESIAN_POINT ( 'NONE', ( 22.99918985293999540, 115.6131156702015801, 87.75369723384940812 ) ) ; +#8098 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; +#8099 = CARTESIAN_POINT ( 'NONE', ( -35.43925701251282590, 191.9759150222000130, 101.9428517634907507 ) ) ; +#8100 = VERTEX_POINT ( 'NONE', #39837 ) ; +#8101 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9380918495502710286, -0.3463866074307025977 ) ) ; +#8102 = CARTESIAN_POINT ( 'NONE', ( 15.12415969602515986, 146.0659008074709106, 180.8278994957862551 ) ) ; +#8103 = AXIS2_PLACEMENT_3D ( 'NONE', #31495, #31712, #21903 ) ; +#8104 = CIRCLE ( 'NONE', #32278, 2.499999999990780264 ) ; +#8105 = CARTESIAN_POINT ( 'NONE', ( -20.01829689993581596, 209.7096928646539880, 76.07061354826153377 ) ) ; +#8106 = EDGE_CURVE ( 'NONE', #17839, #18192, #36383, .T. ) ; +#8107 = ORIENTED_EDGE ( 'NONE', *, *, #22711, .F. ) ; +#8108 = FACE_OUTER_BOUND ( 'NONE', #31697, .T. ) ; +#8109 = ORIENTED_EDGE ( 'NONE', *, *, #12790, .F. ) ; +#8110 = VERTEX_POINT ( 'NONE', #24334 ) ; +#8111 = EDGE_CURVE ( 'NONE', #24320, #24828, #26146, .T. ) ; +#8112 = AXIS2_PLACEMENT_3D ( 'NONE', #16961, #4908, #29461 ) ; +#8113 = CARTESIAN_POINT ( 'NONE', ( -25.64570212326999865, 191.2554111844000033, 104.2075963127000051 ) ) ; +#8114 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540931966, 151.8558896893983103, 95.23413014777732144 ) ) ; +#8115 = CARTESIAN_POINT ( 'NONE', ( -25.20476889543461851, 212.3494275232980044, 73.57346788151119199 ) ) ; +#8116 = CARTESIAN_POINT ( 'NONE', ( 3.045964837637491485, 205.1071438019466484, 76.10297588903854660 ) ) ; +#8117 = ADVANCED_FACE ( 'NONE', ( #20840 ), #34567, .F. ) ; +#8118 = CARTESIAN_POINT ( 'NONE', ( 16.88368854683466935, 152.4476604039728898, 182.0571496254905242 ) ) ; +#8119 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 82.27946979429611929, 297.5967072516833127 ) ) ; +#8120 = VERTEX_POINT ( 'NONE', #17548 ) ; +#8121 = EDGE_CURVE ( 'NONE', #12044, #39862, #8172, .T. ) ; +#8122 = LINE ( 'NONE', #11194, #22038 ) ; +#8123 = ADVANCED_FACE ( 'NONE', ( #40042 ), #12386, .F. ) ; +#8124 = CARTESIAN_POINT ( 'NONE', ( 42.42192200091505327, 180.1607944338011862, 148.5017479457221441 ) ) ; +#8125 = LINE ( 'NONE', #20585, #36208 ) ; +#8126 = CARTESIAN_POINT ( 'NONE', ( 21.61913182270516742, 154.2531527860821541, 95.25201104625905657 ) ) ; +#8127 = DIRECTION ( 'NONE', ( 0.7066905234170505201, 0.1590644458417531104, -0.6894106223301111891 ) ) ; +#8128 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066962549, 129.9712533186751102, 92.22833354197516087 ) ) ; +#8129 = CARTESIAN_POINT ( 'NONE', ( -38.98625979382970996, 119.3757451136368672, 87.77085995517417416 ) ) ; +#8130 = ORIENTED_EDGE ( 'NONE', *, *, #7875, .F. ) ; +#8131 = AXIS2_PLACEMENT_3D ( 'NONE', #29390, #29194, #1358 ) ; +#8132 = CARTESIAN_POINT ( 'NONE', ( -5.671312717824411820, 181.1260227605253021, 104.4549565478647253 ) ) ; +#8133 = CARTESIAN_POINT ( 'NONE', ( -19.70055405364098533, 149.1723619494412389, 182.9474843209757751 ) ) ; +#8134 = AXIS2_PLACEMENT_3D ( 'NONE', #19611, #19006, #22706 ) ; +#8135 = CARTESIAN_POINT ( 'NONE', ( -31.07623358299026251, 135.1199993735448572, 90.86660040197580201 ) ) ; +#8136 = VECTOR ( 'NONE', #11637, 1000.000000000000114 ) ; +#8137 = ORIENTED_EDGE ( 'NONE', *, *, #3030, .F. ) ; +#8138 = CARTESIAN_POINT ( 'NONE', ( 39.71672226492471935, 182.4826294143295797, 106.8893320580963007 ) ) ; +#8139 = AXIS2_PLACEMENT_3D ( 'NONE', #22319, #6747, #28642 ) ; +#8140 = ORIENTED_EDGE ( 'NONE', *, *, #32533, .F. ) ; +#8141 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250900025, 132.4055461762744983, 92.79778151959283150 ) ) ; +#8142 = EDGE_LOOP ( 'NONE', ( #18826, #6914, #15665, #7848 ) ) ; +#8143 = CARTESIAN_POINT ( 'NONE', ( 36.13089926330142276, 192.2307435129849296, 106.3898830433148248 ) ) ; +#8144 = LINE ( 'NONE', #35927, #23786 ) ; +#8145 = CARTESIAN_POINT ( 'NONE', ( -12.63532165819085940, 130.1640888693136731, 92.54240592023801071 ) ) ; +#8146 = CARTESIAN_POINT ( 'NONE', ( -14.55132762993606477, 129.4747796237930118, 92.63223137880015656 ) ) ; +#8147 = CARTESIAN_POINT ( 'NONE', ( -22.68873265250381976, 154.4034425878945171, 95.31346902715758063 ) ) ; +#8148 = ORIENTED_EDGE ( 'NONE', *, *, #19320, .T. ) ; +#8149 = DIRECTION ( 'NONE', ( -0.7691761624280200049, -0.6302414090841089722, 0.1056588729268925636 ) ) ; +#8150 = CARTESIAN_POINT ( 'NONE', ( -20.00006126831510400, 120.3902141372887087, 87.45929000627990035 ) ) ; +#8151 = CARTESIAN_POINT ( 'NONE', ( 13.67163921588000086, 134.7331883168999980, 93.82918430779000118 ) ) ; +#8152 = ADVANCED_FACE ( 'NONE', ( #17955 ), #7819, .F. ) ; +#8153 = ADVANCED_FACE ( 'NONE', ( #717 ), #35886, .F. ) ; +#8154 = DIRECTION ( 'NONE', ( 0.6087611434179120984, -0.7728348325624403437, -0.1792657018023839366 ) ) ; +#8155 = EDGE_CURVE ( 'NONE', #17879, #1388, #39293, .T. ) ; +#8156 = ORIENTED_EDGE ( 'NONE', *, *, #34149, .T. ) ; +#8157 = LINE ( 'NONE', #35333, #23143 ) ; +#8158 = EDGE_CURVE ( 'NONE', #2940, #629, #5180, .T. ) ; +#8159 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26467, #29933, #4769, #10932 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8160 = CARTESIAN_POINT ( 'NONE', ( -43.53198541835717350, 120.4444449957113648, 91.66393424540790136 ) ) ; +#8161 = AXIS2_PLACEMENT_3D ( 'NONE', #17840, #17649, #33181 ) ; +#8162 = CARTESIAN_POINT ( 'NONE', ( -13.55543936442099096, 147.3963946565219203, 96.76916085569253312 ) ) ; +#8163 = PLANE ( 'NONE', #12380 ) ; +#8164 = CARTESIAN_POINT ( 'NONE', ( 21.26009108512010570, 128.3999477444776574, 91.84930485354649932 ) ) ; +#8165 = VECTOR ( 'NONE', #25526, 1000.000000000000000 ) ; +#8166 = AXIS2_PLACEMENT_3D ( 'NONE', #37522, #15453, #27947 ) ; +#8167 = CARTESIAN_POINT ( 'NONE', ( 22.49964039506790670, 136.6763645039129074, 180.9867425820801259 ) ) ; +#8168 = ADVANCED_FACE ( 'NONE', ( #38145 ), #16315, .F. ) ; +#8169 = CARTESIAN_POINT ( 'NONE', ( 28.70581487919770680, 163.6075652324868486, 97.92051968927451355 ) ) ; +#8170 = AXIS2_PLACEMENT_3D ( 'NONE', #4386, #32606, #32807 ) ; +#8171 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #543, #15880, #28770, #22248 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8172 = LINE ( 'NONE', #30052, #35792 ) ; +#8173 = CARTESIAN_POINT ( 'NONE', ( 28.46606743108605642, 130.6255393001868299, 90.13513050975397789 ) ) ; +#8174 = LINE ( 'NONE', #14517, #3672 ) ; +#8175 = EDGE_LOOP ( 'NONE', ( #20363, #4295, #39090, #13610 ) ) ; +#8176 = CARTESIAN_POINT ( 'NONE', ( -22.82366484708005672, 169.1007803578971220, 29.42961924709861066 ) ) ; +#8177 = CARTESIAN_POINT ( 'NONE', ( 33.41957710359000089, 226.1502260771000010, 73.28831954084999722 ) ) ; +#8178 = CARTESIAN_POINT ( 'NONE', ( -36.28616296343275138, 191.6774367654532796, 106.4232239427282707 ) ) ; +#8179 = CARTESIAN_POINT ( 'NONE', ( -21.48366051631042239, 115.4955022973411900, 87.28075988464726720 ) ) ; +#8180 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#8181 = ORIENTED_EDGE ( 'NONE', *, *, #11299, .T. ) ; +#8182 = ORIENTED_EDGE ( 'NONE', *, *, #16146, .F. ) ; +#8183 = CARTESIAN_POINT ( 'NONE', ( -39.79500347691000428, 182.5468005769366187, 106.5836252739005658 ) ) ; +#8184 = EDGE_LOOP ( 'NONE', ( #2785, #5227, #36798, #28911 ) ) ; +#8185 = LINE ( 'NONE', #20653, #38 ) ; +#8186 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17497, #28098, #14460, #36325 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8187 = CARTESIAN_POINT ( 'NONE', ( 39.79702541312468611, 141.5973318770025173, 284.1405295046018864 ) ) ; +#8188 = VERTEX_POINT ( 'NONE', #1117 ) ; +#8189 = CONICAL_SURFACE ( 'NONE', #23192, 59.40509898896483065, 0.7853981633972950682 ) ; +#8190 = CARTESIAN_POINT ( 'NONE', ( -15.99988210103421871, 186.2297624492397858, 102.6571153657711051 ) ) ; +#8191 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.523234146902447552E-15, 0.0006039748319393680506 ) ) ; +#8192 = VECTOR ( 'NONE', #237, 999.9999999999998863 ) ; +#8193 = VECTOR ( 'NONE', #29331, 999.9999999999998863 ) ; +#8194 = CARTESIAN_POINT ( 'NONE', ( -36.81041944407999722, 117.5332847971999968, 87.39354551883999989 ) ) ; +#8195 = ORIENTED_EDGE ( 'NONE', *, *, #39588, .T. ) ; +#8196 = VECTOR ( 'NONE', #8091, 999.9999999999998863 ) ; +#8197 = CARTESIAN_POINT ( 'NONE', ( -21.82963563099358950, 129.7230376101904881, 90.12818080884812844 ) ) ; +#8198 = EDGE_LOOP ( 'NONE', ( #39345, #15625, #25269, #5832 ) ) ; +#8199 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418800025, 218.5902260770999987, 73.08022052563953253 ) ) ; +#8200 = AXIS2_PLACEMENT_3D ( 'NONE', #22277, #37408, #9005 ) ; +#8201 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971538202 ) ) ; +#8202 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#8203 = ORIENTED_EDGE ( 'NONE', *, *, #37380, .F. ) ; +#8204 = ORIENTED_EDGE ( 'NONE', *, *, #16487, .T. ) ; +#8205 = CARTESIAN_POINT ( 'NONE', ( -0.9403621044584999922, 189.0418273829999976, 103.6974160350000034 ) ) ; +#8206 = CARTESIAN_POINT ( 'NONE', ( 0.7117835834011440044, 189.0161218224870083, 103.6960389501960123 ) ) ; +#8207 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; +#8208 = CARTESIAN_POINT ( 'NONE', ( -35.65705446583450566, 191.7229687839729593, 106.9366313765358854 ) ) ; +#8209 = VERTEX_POINT ( 'NONE', #34647 ) ; +#8210 = ADVANCED_FACE ( 'NONE', ( #19114 ), #10543, .F. ) ; +#8211 = ORIENTED_EDGE ( 'NONE', *, *, #22432, .T. ) ; +#8212 = CARTESIAN_POINT ( 'NONE', ( -26.74382575616715130, 120.3580507813137075, 171.5572023280520000 ) ) ; +#8213 = EDGE_CURVE ( 'NONE', #20812, #18841, #8433, .T. ) ; +#8214 = ORIENTED_EDGE ( 'NONE', *, *, #6248, .F. ) ; +#8215 = EDGE_LOOP ( 'NONE', ( #3667, #12752, #18094, #37851 ) ) ; +#8216 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18137, #27598, #34088, #36974 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8217 = ORIENTED_EDGE ( 'NONE', *, *, #33316, .T. ) ; +#8218 = CARTESIAN_POINT ( 'NONE', ( -27.41957310755384114, 125.0505560954758835, 89.05282576069730283 ) ) ; +#8219 = AXIS2_PLACEMENT_3D ( 'NONE', #9605, #18378, #22080 ) ; +#8220 = VERTEX_POINT ( 'NONE', #32410 ) ; +#8221 = CARTESIAN_POINT ( 'NONE', ( 3.058447091124538719, 190.6904732739033648, 106.7543539244942394 ) ) ; +#8222 = CONICAL_SURFACE ( 'NONE', #40193, 5.000000000424002167, 0.7853981633778847060 ) ; +#8223 = FACE_OUTER_BOUND ( 'NONE', #1643, .T. ) ; +#8224 = CARTESIAN_POINT ( 'NONE', ( -12.67632453871999942, 151.9652147204000130, 28.07991271570000080 ) ) ; +#8225 = DIRECTION ( 'NONE', ( -0.0004963947332026163962, -0.5299192641669762116, -0.8480479509184604137 ) ) ; +#8226 = ORIENTED_EDGE ( 'NONE', *, *, #13010, .T. ) ; +#8227 = DIRECTION ( 'NONE', ( 0.9999998268368047727, 0.0001323825927353974201, -0.0005734119020230789678 ) ) ; +#8228 = ORIENTED_EDGE ( 'NONE', *, *, #38023, .F. ) ; +#8229 = CIRCLE ( 'NONE', #31089, 3.500000000007123635 ) ; +#8230 = CARTESIAN_POINT ( 'NONE', ( 28.02681684991999944, 124.7590000943000064, 91.17562171158999718 ) ) ; +#8231 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568455 ) ) ; +#8232 = VECTOR ( 'NONE', #14239, 1000.000000000000227 ) ; +#8234 = CARTESIAN_POINT ( 'NONE', ( -42.47220679908992480, 189.9442792002049316, 106.2657712603332385 ) ) ; +#8233 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265228896, 0.1368326740407718456 ) ) ; +#8235 = EDGE_LOOP ( 'NONE', ( #2947, #29041, #4521, #24380, #33218, #2727, #38496, #34829, #27788, #29556, #34220, #21983, #11346, #24237, #18238, #36042 ) ) ; +#8236 = EDGE_CURVE ( 'NONE', #39798, #796, #39745, .T. ) ; +#8237 = ORIENTED_EDGE ( 'NONE', *, *, #40010, .F. ) ; +#8238 = CARTESIAN_POINT ( 'NONE', ( -35.98930003077260409, 192.1481011322285610, 104.4284500425794562 ) ) ; +#8239 = EDGE_LOOP ( 'NONE', ( #18196, #36213, #18213, #5409 ) ) ; +#8240 = CARTESIAN_POINT ( 'NONE', ( -36.72119652792175515, 117.5199652785488524, 87.28996297457759113 ) ) ; +#8241 = DIRECTION ( 'NONE', ( -0.5988681445390194868, 0.8008476418498040594, 0.000000000000000000 ) ) ; +#8242 = FACE_OUTER_BOUND ( 'NONE', #1847, .T. ) ; +#8243 = CARTESIAN_POINT ( 'NONE', ( -37.26309767763914493, 111.8941053232203160, 150.0343454695379819 ) ) ; +#8244 = ORIENTED_EDGE ( 'NONE', *, *, #34696, .T. ) ; +#8245 = ORIENTED_EDGE ( 'NONE', *, *, #30559, .F. ) ; +#8246 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927744103482, -0.0005734119022083112227 ) ) ; +#8247 = CARTESIAN_POINT ( 'NONE', ( 20.33494057836571045, 190.9269296371502378, 106.4564606968243510 ) ) ; +#8248 = AXIS2_PLACEMENT_3D ( 'NONE', #325, #31628, #16263 ) ; +#8249 = CARTESIAN_POINT ( 'NONE', ( 27.47889980971000057, 124.6377240942999975, 88.58226852807001706 ) ) ; +#8250 = ORIENTED_EDGE ( 'NONE', *, *, #12641, .T. ) ; +#8251 = ORIENTED_EDGE ( 'NONE', *, *, #3760, .F. ) ; +#8252 = CARTESIAN_POINT ( 'NONE', ( 30.06842554564726910, 135.2666963995015408, 91.33418159856985596 ) ) ; +#8253 = AXIS2_PLACEMENT_3D ( 'NONE', #12876, #785, #15916 ) ; +#8254 = AXIS2_PLACEMENT_3D ( 'NONE', #26065, #34820, #6826 ) ; +#8255 = EDGE_CURVE ( 'NONE', #28384, #17683, #38526, .T. ) ; +#8256 = CARTESIAN_POINT ( 'NONE', ( 3.069762710617847556, 190.8498451990714955, 106.7968295637148799 ) ) ; +#8257 = EDGE_CURVE ( 'NONE', #23280, #6308, #33944, .T. ) ; +#8258 = EDGE_LOOP ( 'NONE', ( #27305, #17635, #19442, #35866 ) ) ; +#8259 = CARTESIAN_POINT ( 'NONE', ( 5.667964583423158231, 129.9727540529065948, 92.22183313054385678 ) ) ; +#8260 = CARTESIAN_POINT ( 'NONE', ( 76.10601358362096391, 156.3575724116909669, 95.70494597592171715 ) ) ; +#8261 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098504, 179.0628333271180850, 104.0826189413490539 ) ) ; +#8262 = CARTESIAN_POINT ( 'NONE', ( -35.95366953697975987, 209.7096538831000032, 78.08022010983776795 ) ) ; +#8263 = EDGE_CURVE ( 'NONE', #367, #14957, #25488, .T. ) ; +#8264 = VERTEX_POINT ( 'NONE', #25288 ) ; +#8265 = DIRECTION ( 'NONE', ( -0.7933533411653073131, 0.5930537057989907490, 0.1373964268091705798 ) ) ; +#8266 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.110223024625155594E-14, -1.000000000000000000 ) ) ; +#8267 = ORIENTED_EDGE ( 'NONE', *, *, #27232, .F. ) ; +#8268 = AXIS2_PLACEMENT_3D ( 'NONE', #21172, #40362, #12366 ) ; +#8269 = CARTESIAN_POINT ( 'NONE', ( 10.44426510892352589, 177.7926467814048124, 100.6933375042854095 ) ) ; +#8270 = CIRCLE ( 'NONE', #14157, 2.000000000000000444 ) ; +#8271 = AXIS2_PLACEMENT_3D ( 'NONE', #35742, #16749, #23503 ) ; +#8273 = CARTESIAN_POINT ( 'NONE', ( 14.12167057796713010, 158.3605014131640303, 96.20479564579193266 ) ) ; +#8272 = CARTESIAN_POINT ( 'NONE', ( 14.15993356491004640, 135.7023639446290417, 90.97372837016631308 ) ) ; +#8274 = ORIENTED_EDGE ( 'NONE', *, *, #30050, .T. ) ; +#8275 = VERTEX_POINT ( 'NONE', #22218 ) ; +#8276 = EDGE_CURVE ( 'NONE', #26011, #23779, #33434, .T. ) ; +#8277 = EDGE_LOOP ( 'NONE', ( #2378, #37293, #3927, #39568 ) ) ; +#8279 = AXIS2_PLACEMENT_3D ( 'NONE', #36656, #8661, #30533 ) ; +#8278 = LINE ( 'NONE', #8069, #34242 ) ; +#8280 = CARTESIAN_POINT ( 'NONE', ( 20.50029381458971400, 151.8610500385970852, 95.21357840886264512 ) ) ; +#8281 = CARTESIAN_POINT ( 'NONE', ( 19.35706105504437602, 157.8277727518531037, 166.6153729214301507 ) ) ; +#8282 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38371, #14044, #26518, #7283 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8283 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#8284 = ORIENTED_EDGE ( 'NONE', *, *, #24612, .T. ) ; +#8285 = ORIENTED_EDGE ( 'NONE', *, *, #13872, .F. ) ; +#8286 = CARTESIAN_POINT ( 'NONE', ( -42.63673691994630843, 120.8556943064256473, 91.02934306460012692 ) ) ; +#8287 = ORIENTED_EDGE ( 'NONE', *, *, #17137, .F. ) ; +#8288 = ORIENTED_EDGE ( 'NONE', *, *, #35404, .F. ) ; +#8289 = FACE_OUTER_BOUND ( 'NONE', #33072, .T. ) ; +#8290 = CARTESIAN_POINT ( 'NONE', ( 2.674747366820000138, 209.4039250993000110, 73.39437287834999779 ) ) ; +#8291 = ORIENTED_EDGE ( 'NONE', *, *, #3942, .T. ) ; +#8292 = EDGE_CURVE ( 'NONE', #21765, #7552, #15417, .T. ) ; +#8293 = VERTEX_POINT ( 'NONE', #7246 ) ; +#8294 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 5.991633438574710639E-15, -0.0006039748319372744562 ) ) ; +#8295 = CARTESIAN_POINT ( 'NONE', ( -36.12682697814000221, 192.1857872781000083, 104.5704194111000191 ) ) ; +#8296 = CARTESIAN_POINT ( 'NONE', ( 38.03732978805999920, 191.1273048889999870, 103.8765410749000040 ) ) ; +#8297 = ORIENTED_EDGE ( 'NONE', *, *, #31610, .F. ) ; +#8298 = CARTESIAN_POINT ( 'NONE', ( -25.66813934661154661, 120.6730681322564465, 87.86559688811576052 ) ) ; +#8299 = EDGE_CURVE ( 'NONE', #29253, #38732, #22236, .T. ) ; +#8300 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#8301 = ORIENTED_EDGE ( 'NONE', *, *, #21663, .T. ) ; +#8302 = DIRECTION ( 'NONE', ( -0.0004161288024450390572, 0.8480480898092163100, -0.5299191110044617625 ) ) ; +#8303 = CARTESIAN_POINT ( 'NONE', ( -3.334889541086432985, 126.1639861300818097, 91.69003341170677857 ) ) ; +#8304 = CARTESIAN_POINT ( 'NONE', ( 16.00176583132817498, 118.9451395335793649, 90.18281804087268938 ) ) ; +#8305 = ORIENTED_EDGE ( 'NONE', *, *, #9133, .F. ) ; +#8306 = CONICAL_SURFACE ( 'NONE', #10909, 6.499999999766678194, 0.7853981634251984145 ) ; +#8307 = CARTESIAN_POINT ( 'NONE', ( -12.60649365401999944, 163.2729245447999915, 152.4718672074000381 ) ) ; +#8308 = EDGE_CURVE ( 'NONE', #18764, #19078, #30146, .T. ) ; +#8309 = CARTESIAN_POINT ( 'NONE', ( -16.55494438683570735, 127.1017686116984180, 154.7943589889946168 ) ) ; +#8310 = EDGE_CURVE ( 'NONE', #32791, #21410, #20942, .T. ) ; +#8311 = DIRECTION ( 'NONE', ( -0.0004161288024540093665, -0.5299192578742120130, -0.8480479980348188951 ) ) ; +#8312 = ADVANCED_FACE ( 'NONE', ( #4984 ), #2143, .F. ) ; +#8313 = ORIENTED_EDGE ( 'NONE', *, *, #29773, .T. ) ; +#8314 = PLANE ( 'NONE', #12655 ) ; +#8315 = ADVANCED_FACE ( 'NONE', ( #39530 ), #18839, .F. ) ; +#8316 = FACE_OUTER_BOUND ( 'NONE', #18262, .T. ) ; +#8317 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#8318 = ORIENTED_EDGE ( 'NONE', *, *, #11868, .T. ) ; +#8319 = CARTESIAN_POINT ( 'NONE', ( -22.49860963037942341, 158.0258723631266378, 98.88646763493585468 ) ) ; +#8320 = ORIENTED_EDGE ( 'NONE', *, *, #34309, .F. ) ; +#8321 = ORIENTED_EDGE ( 'NONE', *, *, #36289, .T. ) ; +#8322 = CARTESIAN_POINT ( 'NONE', ( -6.045835231059395021, 134.9182589738620095, 90.80491324842614631 ) ) ; +#8323 = CARTESIAN_POINT ( 'NONE', ( -45.14168110797990607, 115.6906603679936154, 128.0405359920818853 ) ) ; +#8324 = DIRECTION ( 'NONE', ( 0.0005559617641677616195, -0.3907311284691155073, 0.9205046855675251827 ) ) ; +#8325 = CARTESIAN_POINT ( 'NONE', ( -20.58392306733278332, 211.7448544280097451, 75.57086740851539730 ) ) ; +#8326 = LINE ( 'NONE', #20787, #40032 ) ; +#8327 = CARTESIAN_POINT ( 'NONE', ( 39.06385346265498981, 191.4135374074515994, 104.3337792663689072 ) ) ; +#8328 = ORIENTED_EDGE ( 'NONE', *, *, #37793, .F. ) ; +#8329 = CARTESIAN_POINT ( 'NONE', ( -14.89128842545527576, 182.7456056360065020, 104.5888761284686694 ) ) ; +#8330 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20082, #22781, #26255, #7216, #3747, #32376, #35813, #17010, #1085, #7823, #35215 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999997887246, 0.3749999999997143396, 0.4374999999997122857, 0.4687499999996813105, 0.4999999999996502797, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8331 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#8332 = ADVANCED_FACE ( 'NONE', ( #1728 ), #9739, .T. ) ; +#8333 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#8334 = CARTESIAN_POINT ( 'NONE', ( 2.519724450483999956, 209.0000002173999860, 32.65697486330000032 ) ) ; +#8335 = CARTESIAN_POINT ( 'NONE', ( 15.59057381605467896, 127.7851801377404826, 174.7303348607053692 ) ) ; +#8336 = CIRCLE ( 'NONE', #29878, 59.40509898823096790 ) ; +#8337 = CARTESIAN_POINT ( 'NONE', ( 19.01986883121886862, 124.9296800124309925, 178.2906471469820247 ) ) ; +#8338 = CARTESIAN_POINT ( 'NONE', ( 19.31194489278902537, 124.3312024124945339, 178.3888998772247305 ) ) ; +#8339 = FACE_OUTER_BOUND ( 'NONE', #25179, .T. ) ; +#8340 = CARTESIAN_POINT ( 'NONE', ( -35.77119973190495017, 192.3543298451174053, 104.2454963614574126 ) ) ; +#8341 = AXIS2_PLACEMENT_3D ( 'NONE', #11200, #14066, #1791 ) ; +#8342 = ORIENTED_EDGE ( 'NONE', *, *, #39532, .T. ) ; +#8343 = EDGE_LOOP ( 'NONE', ( #37131, #7063, #32785, #24255 ) ) ; +#8344 = CARTESIAN_POINT ( 'NONE', ( 25.99199080364422443, 211.0901596425212574, 76.04279652306830428 ) ) ; +#8345 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11221, #30229, #33278, #17325 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8346 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#8347 = ADVANCED_FACE ( 'NONE', ( #36056 ), #20321, .F. ) ; +#8348 = ORIENTED_EDGE ( 'NONE', *, *, #32715, .F. ) ; +#8349 = CARTESIAN_POINT ( 'NONE', ( 33.37602094669033193, 84.06324503389978986, 284.1448219155665242 ) ) ; +#8350 = ORIENTED_EDGE ( 'NONE', *, *, #31018, .F. ) ; +#8351 = CARTESIAN_POINT ( 'NONE', ( -38.24019460149000338, 119.1859645161000003, 87.44767029253000601 ) ) ; +#8352 = EDGE_CURVE ( 'NONE', #8293, #18457, #26682, .T. ) ; +#8353 = CARTESIAN_POINT ( 'NONE', ( -5.675054657474391639, 124.3656264979204167, 88.36836997283377571 ) ) ; +#8354 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2255194953558363191, 0.9742386449830560124 ) ) ; +#8355 = EDGE_LOOP ( 'NONE', ( #25291, #5321, #39152, #23356 ) ) ; +#8356 = CARTESIAN_POINT ( 'NONE', ( 36.26293756970083138, 191.9133757257809805, 106.3931895791960329 ) ) ; +#8357 = EDGE_CURVE ( 'NONE', #1132, #12650, #16834, .T. ) ; +#8358 = CYLINDRICAL_SURFACE ( 'NONE', #31608, 2.000000000000014655 ) ; +#8359 = CARTESIAN_POINT ( 'NONE', ( -36.37433508471929855, 115.1473213475028103, 89.75326492886478036 ) ) ; +#8360 = DIRECTION ( 'NONE', ( -0.0005884949961189803310, 0.2249510543439054433, -0.9743698870671265722 ) ) ; +#8361 = DIRECTION ( 'NONE', ( -0.5668486650917774483, -0.8238218701100766816, 0.0003423623896884662554 ) ) ; +#8362 = CARTESIAN_POINT ( 'NONE', ( 15.50029466864684835, 174.4049028184354881, 100.4212577462347866 ) ) ; +#8363 = EDGE_LOOP ( 'NONE', ( #3717, #21156, #12072, #34836 ) ) ; +#8364 = ADVANCED_FACE ( 'NONE', ( #10735 ), #25421, .T. ) ; +#8365 = ORIENTED_EDGE ( 'NONE', *, *, #31892, .F. ) ; +#8366 = CARTESIAN_POINT ( 'NONE', ( -39.79500347691000428, 182.5468005769366187, 106.5836252739005658 ) ) ; +#8367 = CARTESIAN_POINT ( 'NONE', ( -25.60482130047309823, 148.7605380546862079, 204.9143772511571910 ) ) ; +#8368 = CARTESIAN_POINT ( 'NONE', ( 40.49581267819608854, 84.18892247206676416, 282.5307213418886931 ) ) ; +#8369 = ORIENTED_EDGE ( 'NONE', *, *, #21373, .T. ) ; +#8370 = VECTOR ( 'NONE', #33077, 1000.000000000000227 ) ; +#8371 = CARTESIAN_POINT ( 'NONE', ( -13.46869826275617754, 154.0042694268834111, 95.55785016883520200 ) ) ; +#8372 = VERTEX_POINT ( 'NONE', #26887 ) ; +#8373 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#8374 = CARTESIAN_POINT ( 'NONE', ( -42.14140742790571181, 120.7945795707638297, 90.64491201421904520 ) ) ; +#8375 = CIRCLE ( 'NONE', #36439, 7.499999999987333688 ) ; +#8376 = LINE ( 'NONE', #23298, #24842 ) ; +#8377 = DIRECTION ( 'NONE', ( -0.0005884949961131590327, 0.2249510543438973387, -0.9743698870671282375 ) ) ; +#8378 = CARTESIAN_POINT ( 'NONE', ( -23.41217839213117813, 214.0714960154889468, 73.07264445148327070 ) ) ; +#8379 = CARTESIAN_POINT ( 'NONE', ( 13.88517613221250713, 135.5848694388539002, 93.51252930518586481 ) ) ; +#8380 = CARTESIAN_POINT ( 'NONE', ( 3.666638755409086681, 184.0129645450027738, 102.6466012127862371 ) ) ; +#8381 = CARTESIAN_POINT ( 'NONE', ( -25.80849207073569218, 209.7108689636089025, 73.27563589262052801 ) ) ; +#8382 = CARTESIAN_POINT ( 'NONE', ( 37.59407280179000566, 112.0479120775361821, 151.0714151308390854 ) ) ; +#8383 = CARTESIAN_POINT ( 'NONE', ( 38.65917831171999808, 118.7960982540000003, 87.80084228631000087 ) ) ; +#8384 = CARTESIAN_POINT ( 'NONE', ( 20.48051720016978550, 208.3330510408972884, 73.76180694069462618 ) ) ; +#8385 = CARTESIAN_POINT ( 'NONE', ( 38.30233299830000959, 119.0433665966999968, 90.39987451477999514 ) ) ; +#8386 = EDGE_LOOP ( 'NONE', ( #616, #18197, #32293, #38608 ) ) ; +#8387 = CARTESIAN_POINT ( 'NONE', ( 15.50176591790000025, 174.8481220399000335, 103.0893428321000016 ) ) ; +#8388 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12273, #27235, #39660, #18383 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999975533700791175 ), + .UNSPECIFIED. ) ; +#8389 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971546529 ) ) ; +#8390 = CARTESIAN_POINT ( 'NONE', ( -23.36170564740040234, 182.0604262685139361, 102.2121465934016129 ) ) ; +#8391 = CARTESIAN_POINT ( 'NONE', ( 26.01897932439291239, 191.0393230234643340, 106.8210248016044375 ) ) ; +#8393 = ORIENTED_EDGE ( 'NONE', *, *, #36551, .F. ) ; +#8392 = FACE_OUTER_BOUND ( 'NONE', #25050, .T. ) ; +#8394 = ORIENTED_EDGE ( 'NONE', *, *, #24220, .T. ) ; +#8395 = VERTEX_POINT ( 'NONE', #14404 ) ; +#8396 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#8397 = EDGE_LOOP ( 'NONE', ( #18494, #2082, #35153, #35028 ) ) ; +#8398 = DIRECTION ( 'NONE', ( 0.0006039748319392653766, 3.841674172953530792E-18, 0.9999998176071845934 ) ) ; +#8399 = EDGE_CURVE ( 'NONE', #34665, #33491, #29542, .T. ) ; +#8400 = EDGE_CURVE ( 'NONE', #39173, #7664, #25210, .T. ) ; +#8401 = VECTOR ( 'NONE', #23850, 1000.000000000000114 ) ; +#8402 = CARTESIAN_POINT ( 'NONE', ( -94.40216589637994105, 221.9412051121879301, 195.0241205818432491 ) ) ; +#8403 = ORIENTED_EDGE ( 'NONE', *, *, #24984, .F. ) ; +#8404 = CARTESIAN_POINT ( 'NONE', ( -20.16489867514991730, 151.3249859477512018, 97.50919180760990912 ) ) ; +#8405 = EDGE_CURVE ( 'NONE', #32868, #189, #27395, .T. ) ; +#8406 = EDGE_CURVE ( 'NONE', #26291, #14524, #13006, .T. ) ; +#8407 = ORIENTED_EDGE ( 'NONE', *, *, #27949, .T. ) ; +#8408 = CARTESIAN_POINT ( 'NONE', ( -39.71020355217999764, 119.5364205527000081, 89.96485858007000047 ) ) ; +#8409 = DIRECTION ( 'NONE', ( -0.0005884949961259457879, 0.2249510543439049437, -0.9743698870671266832 ) ) ; +#8410 = CARTESIAN_POINT ( 'NONE', ( -31.19810823188564797, 110.6131156702000027, 87.28662716757878570 ) ) ; +#8411 = CARTESIAN_POINT ( 'NONE', ( -35.85197975471000120, 116.1896316198000108, 87.15460714735000636 ) ) ; +#8412 = EDGE_LOOP ( 'NONE', ( #11520, #19501, #22417, #37945 ) ) ; +#8413 = ADVANCED_FACE ( 'NONE', ( #20523 ), #11326, .T. ) ; +#8414 = PLANE ( 'NONE', #22563 ) ; +#8415 = CARTESIAN_POINT ( 'NONE', ( 4.404252103613135461, 188.0359524915844815, 103.0617836839577421 ) ) ; +#8416 = CARTESIAN_POINT ( 'NONE', ( 20.50146814542411278, 184.4050074329408915, 104.7795556516932436 ) ) ; +#8417 = LINE ( 'NONE', #29676, #19542 ) ; +#8418 = CARTESIAN_POINT ( 'NONE', ( -12.63730865053593000, 181.2845053770731738, 104.3593437533184556 ) ) ; +#8419 = EDGE_LOOP ( 'NONE', ( #866, #26047, #6716, #22645 ) ) ; +#8420 = EDGE_CURVE ( 'NONE', #22426, #29452, #12508, .T. ) ; +#8421 = EDGE_LOOP ( 'NONE', ( #39712, #12937, #12869, #13540 ) ) ; +#8422 = CARTESIAN_POINT ( 'NONE', ( 20.50029254611199292, 184.8549113859068029, 102.8308091169877798 ) ) ; +#8423 = CARTESIAN_POINT ( 'NONE', ( 0.5945401647096061337, 189.0170313296219717, 103.6953509331899852 ) ) ; +#8424 = CARTESIAN_POINT ( 'NONE', ( 26.78494046123167394, 122.8681522354715838, 91.08200428504154900 ) ) ; +#8425 = ORIENTED_EDGE ( 'NONE', *, *, #9028, .T. ) ; +#8426 = CARTESIAN_POINT ( 'NONE', ( -0.4015627557743999820, 191.0000000000000000, 162.9824824849000322 ) ) ; +#8427 = ORIENTED_EDGE ( 'NONE', *, *, #13113, .T. ) ; +#8428 = EDGE_CURVE ( 'NONE', #29659, #12341, #13967, .T. ) ; +#8429 = CIRCLE ( 'NONE', #24754, 2.000000000183163262 ) ; +#8430 = CIRCLE ( 'NONE', #31270, 2.500000000049116711 ) ; +#8431 = ORIENTED_EDGE ( 'NONE', *, *, #31405, .F. ) ; +#8432 = DIRECTION ( 'NONE', ( -0.7066905234111825473, -0.1590644036919597049, 0.6894106320611468330 ) ) ; +#8433 = CIRCLE ( 'NONE', #37803, 8.000000000000007105 ) ; +#8434 = ORIENTED_EDGE ( 'NONE', *, *, #17107, .T. ) ; +#8435 = CARTESIAN_POINT ( 'NONE', ( 22.66333107552271287, 213.5901743958560814, 73.54467151608274378 ) ) ; +#8436 = AXIS2_PLACEMENT_3D ( 'NONE', #7745, #26183, #14109 ) ; +#8437 = CARTESIAN_POINT ( 'NONE', ( 17.25783335673383689, 152.2632692426403196, 183.6728012514050477 ) ) ; +#8438 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173983415, 185.7936928887390025, 103.0680828614480760 ) ) ; +#8439 = ORIENTED_EDGE ( 'NONE', *, *, #7545, .T. ) ; +#8440 = CARTESIAN_POINT ( 'NONE', ( 28.66350241469961446, 179.7814215269904139, 27.86386413335047507 ) ) ; +#8441 = VERTEX_POINT ( 'NONE', #2927 ) ; +#8442 = CARTESIAN_POINT ( 'NONE', ( 26.06074785331999877, 120.9057430171999954, 90.62944187114999295 ) ) ; +#8443 = FACE_OUTER_BOUND ( 'NONE', #35805, .T. ) ; +#8445 = CARTESIAN_POINT ( 'NONE', ( -42.82182963578055990, 189.4469289804731602, 106.3937290658157622 ) ) ; +#8444 = CARTESIAN_POINT ( 'NONE', ( 15.59065710782552650, 147.2783093505951229, 179.8436489131068186 ) ) ; +#8446 = EDGE_LOOP ( 'NONE', ( #34323, #15046, #18007, #25023 ) ) ; +#8447 = ORIENTED_EDGE ( 'NONE', *, *, #37980, .T. ) ; +#8448 = CARTESIAN_POINT ( 'NONE', ( 36.04645032798080706, 209.7096537570166390, 75.53673338561257822 ) ) ; +#8449 = ADVANCED_FACE ( 'NONE', ( #21359 ), #27912, .T. ) ; +#8450 = EDGE_CURVE ( 'NONE', #34762, #22424, #8625, .T. ) ; +#8451 = ORIENTED_EDGE ( 'NONE', *, *, #18573, .F. ) ; +#8452 = LINE ( 'NONE', #23990, #21133 ) ; +#8453 = AXIS2_PLACEMENT_3D ( 'NONE', #22884, #7522, #13080 ) ; +#8454 = DIRECTION ( 'NONE', ( -0.6087614109020677011, -0.7729348355671219473, -0.1788331193133700647 ) ) ; +#8455 = CARTESIAN_POINT ( 'NONE', ( -35.93925701852640486, 191.9759150222000130, 101.9431537509654220 ) ) ; +#8456 = ORIENTED_EDGE ( 'NONE', *, *, #20814, .T. ) ; +#8457 = AXIS2_PLACEMENT_3D ( 'NONE', #25882, #12792, #501 ) ; +#8458 = AXIS2_PLACEMENT_3D ( 'NONE', #36014, #5139, #4533 ) ; +#8459 = DIRECTION ( 'NONE', ( -0.0008702530711002103318, 0.2253087760482092305, -0.9742870203873447155 ) ) ; +#8460 = AXIS2_PLACEMENT_3D ( 'NONE', #25036, #34788, #71 ) ; +#8461 = CARTESIAN_POINT ( 'NONE', ( -30.07180902684082469, 134.5538535379703262, 93.54580703498288585 ) ) ; +#8462 = CARTESIAN_POINT ( 'NONE', ( 13.50718655633492382, 188.3455032986072979, 103.1278069412195748 ) ) ; +#8463 = EDGE_CURVE ( 'NONE', #37032, #25663, #21566, .T. ) ; +#8464 = ORIENTED_EDGE ( 'NONE', *, *, #3901, .T. ) ; +#8465 = LINE ( 'NONE', #37071, #11499 ) ; +#8466 = CARTESIAN_POINT ( 'NONE', ( 2.297205121341999945, 189.9561994427999991, 106.0117969655000110 ) ) ; +#8467 = EDGE_LOOP ( 'NONE', ( #4144, #19241, #3798, #32744, #18962, #3996, #25994, #30086, #3782, #17288, #23610, #9626 ) ) ; +#8468 = CARTESIAN_POINT ( 'NONE', ( 39.04675176836854433, 209.7096538831000316, 76.03492163576670748 ) ) ; +#8469 = ADVANCED_FACE ( 'NONE', ( #37087 ), #40337, .F. ) ; +#8470 = FACE_OUTER_BOUND ( 'NONE', #27960, .T. ) ; +#8471 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; +#8472 = CARTESIAN_POINT ( 'NONE', ( 5.217102900732569104, 135.0871424630537945, 181.2784941562133270 ) ) ; +#8473 = ORIENTED_EDGE ( 'NONE', *, *, #23307, .F. ) ; +#8474 = CARTESIAN_POINT ( 'NONE', ( 25.99186909154838787, 205.2975165461204483, 75.64064060287584823 ) ) ; +#8475 = DIRECTION ( 'NONE', ( -2.355754480376490302E-12, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#8476 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; +#8477 = ORIENTED_EDGE ( 'NONE', *, *, #38625, .F. ) ; +#8478 = CONICAL_SURFACE ( 'NONE', #18293, 2.503080759942041489, 0.7853981634198553552 ) ; +#8479 = VECTOR ( 'NONE', #2203, 1000.000000000000000 ) ; +#8480 = CARTESIAN_POINT ( 'NONE', ( 39.79988895049328335, 119.8651423291884726, 87.81508310122019623 ) ) ; +#8481 = VERTEX_POINT ( 'NONE', #24436 ) ; +#8482 = AXIS2_PLACEMENT_3D ( 'NONE', #33300, #17751, #27203 ) ; +#8484 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921578520, -0.2249510932971593991 ) ) ; +#8483 = CARTESIAN_POINT ( 'NONE', ( -15.99823277108970743, 185.2321969574450975, 105.5057198903149782 ) ) ; +#8485 = ORIENTED_EDGE ( 'NONE', *, *, #33500, .F. ) ; +#8486 = VERTEX_POINT ( 'NONE', #24843 ) ; +#8487 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971560961 ) ) ; +#8488 = ORIENTED_EDGE ( 'NONE', *, *, #3523, .T. ) ; +#8489 = CARTESIAN_POINT ( 'NONE', ( 2.926120382530000175, 209.1401824993000389, 76.01042625537000674 ) ) ; +#8490 = CARTESIAN_POINT ( 'NONE', ( 37.17435508146867562, 191.1177037234376428, 106.3028558592205002 ) ) ; +#8491 = CARTESIAN_POINT ( 'NONE', ( 12.63930000360815775, 177.2888256666688562, 101.0070828283669471 ) ) ; +#8492 = ADVANCED_FACE ( 'NONE', ( #30556 ), #10386, .F. ) ; +#8493 = ORIENTED_EDGE ( 'NONE', *, *, #21424, .F. ) ; +#8494 = EDGE_CURVE ( 'NONE', #16249, #1239, #30555, .T. ) ; +#8495 = EDGE_LOOP ( 'NONE', ( #21630, #26153 ) ) ; +#8496 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#8497 = ORIENTED_EDGE ( 'NONE', *, *, #14007, .F. ) ; +#8498 = ORIENTED_EDGE ( 'NONE', *, *, #21233, .F. ) ; +#8499 = CYLINDRICAL_SURFACE ( 'NONE', #28294, 2.000000000000014655 ) ; +#8500 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971557076 ) ) ; +#8501 = CARTESIAN_POINT ( 'NONE', ( -20.49970532888763941, 191.4139234226054498, 104.3698659823340478 ) ) ; +#8502 = CARTESIAN_POINT ( 'NONE', ( 12.63943526405010154, 181.6152899300451509, 104.1402435546899170 ) ) ; +#8503 = VERTEX_POINT ( 'NONE', #18053 ) ; +#8504 = EDGE_LOOP ( 'NONE', ( #16462, #39338, #32922, #6245, #34889, #39965, #24208, #23027, #13012 ) ) ; +#8505 = DIRECTION ( 'NONE', ( 0.7933535325932939974, -0.5931614258681802143, -0.1369295263402624252 ) ) ; +#8506 = CARTESIAN_POINT ( 'NONE', ( -36.08104566930000345, 192.3950126661999889, 104.5573297432000004 ) ) ; +#8507 = CARTESIAN_POINT ( 'NONE', ( 36.22716640846000047, 191.3195042085999944, 103.6679230210999947 ) ) ; +#8508 = CARTESIAN_POINT ( 'NONE', ( -25.50305200493978219, 120.5913031158892750, 88.01798731102564943 ) ) ; +#8509 = VECTOR ( 'NONE', #28374, 1000.000000000000227 ) ; +#8510 = ORIENTED_EDGE ( 'NONE', *, *, #10341, .T. ) ; +#8511 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; +#8512 = FACE_OUTER_BOUND ( 'NONE', #31279, .T. ) ; +#8513 = ORIENTED_EDGE ( 'NONE', *, *, #21704, .T. ) ; +#8514 = AXIS2_PLACEMENT_3D ( 'NONE', #30818, #27764, #12214 ) ; +#8515 = CARTESIAN_POINT ( 'NONE', ( 0.7483071947399341228, 188.6199125398798628, 103.1988096077017616 ) ) ; +#8516 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562904 ) ) ; +#8517 = CARTESIAN_POINT ( 'NONE', ( -14.56364043194524882, 124.5953383809047779, 88.42681732072288980 ) ) ; +#8518 = ORIENTED_EDGE ( 'NONE', *, *, #13441, .F. ) ; +#8519 = CARTESIAN_POINT ( 'NONE', ( -21.44693681792356443, 182.5559435529752363, 101.8122371725110611 ) ) ; +#8520 = EDGE_CURVE ( 'NONE', #40259, #14084, #36483, .T. ) ; +#8521 = CARTESIAN_POINT ( 'NONE', ( 1.677769475863515547, 189.3391757884121773, 103.7816631172656088 ) ) ; +#8522 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#8523 = EDGE_LOOP ( 'NONE', ( #4040, #5882, #34548 ) ) ; +#8524 = CARTESIAN_POINT ( 'NONE', ( -25.50901378188272872, 210.6290357530666597, 75.57427749355011315 ) ) ; +#8525 = ORIENTED_EDGE ( 'NONE', *, *, #20187, .F. ) ; +#8526 = ORIENTED_EDGE ( 'NONE', *, *, #21800, .T. ) ; +#8527 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568178 ) ) ; +#8528 = PLANE ( 'NONE', #15967 ) ; +#8529 = CARTESIAN_POINT ( 'NONE', ( 35.67769589643999950, 112.3628679466000051, 90.12501460967999378 ) ) ; +#8530 = CARTESIAN_POINT ( 'NONE', ( 39.06373257172650426, 191.2886342178498751, 104.1338925413297432 ) ) ; +#8531 = VERTEX_POINT ( 'NONE', #34202 ) ; +#8532 = ADVANCED_FACE ( 'NONE', ( #3133 ), #28646, .F. ) ; +#8533 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15838, #19307, #37719, #22606 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8534 = CARTESIAN_POINT ( 'NONE', ( -45.98534017754115411, 187.3083424662111725, 103.4373877126195680 ) ) ; +#8535 = AXIS2_PLACEMENT_3D ( 'NONE', #31190, #18088, #5843 ) ; +#8536 = EDGE_CURVE ( 'NONE', #39629, #37162, #21488, .T. ) ; +#8537 = VECTOR ( 'NONE', #33877, 1000.000000000000000 ) ; +#8538 = CARTESIAN_POINT ( 'NONE', ( -14.13194399373848142, 115.2628856887303073, 152.7619685138874104 ) ) ; +#8539 = CARTESIAN_POINT ( 'NONE', ( -3.776848093818052199, 137.2994165897591188, 91.59881672241711215 ) ) ; +#8540 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25989, #4486, #20643, #1425 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8541 = AXIS2_PLACEMENT_3D ( 'NONE', #22724, #38839, #4703 ) ; +#8542 = CARTESIAN_POINT ( 'NONE', ( 19.01953534574752069, 125.4129100880593057, 176.1943672198347883 ) ) ; +#8543 = CARTESIAN_POINT ( 'NONE', ( 32.40151345882750888, 176.2355478910340310, 100.3205354780729692 ) ) ; +#8544 = AXIS2_PLACEMENT_3D ( 'NONE', #26203, #35969, #7567 ) ; +#8545 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#8546 = EDGE_CURVE ( 'NONE', #39814, #21071, #19308, .T. ) ; +#8547 = ADVANCED_FACE ( 'NONE', ( #28690 ), #24105, .T. ) ; +#8548 = CARTESIAN_POINT ( 'NONE', ( 15.10714335843527145, 176.3834766976846993, 100.3651329064352922 ) ) ; +#8549 = ORIENTED_EDGE ( 'NONE', *, *, #32169, .T. ) ; +#8550 = VERTEX_POINT ( 'NONE', #10090 ) ; +#8551 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099476, 182.4219699177349128, 101.7574819547242697 ) ) ; +#8552 = DIRECTION ( 'NONE', ( 0.7075227875440994740, -0.1589708073325998561, 0.6885780910846993619 ) ) ; +#8553 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#8554 = EDGE_LOOP ( 'NONE', ( #18096, #20893 ) ) ; +#8555 = CARTESIAN_POINT ( 'NONE', ( 77.74752315181704887, 192.2565373609087089, 194.3622733290381461 ) ) ; +#8556 = EDGE_LOOP ( 'NONE', ( #38056, #18468, #35809, #14660 ) ) ; +#8557 = CARTESIAN_POINT ( 'NONE', ( -17.26180060959741525, 121.6800750551767578, 175.7628748181817855 ) ) ; +#8558 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251390299, 179.1753088543660510, 103.5954339978240029 ) ) ; +#8559 = CARTESIAN_POINT ( 'NONE', ( 30.03524845263000032, 185.6785554479999973, 102.7586311877000185 ) ) ; +#8560 = EDGE_LOOP ( 'NONE', ( #25147, #2906, #24691, #4620 ) ) ; +#8561 = DIRECTION ( 'NONE', ( 0.7855817641270325113, 0.6187578620680785901, 0.000000000000000000 ) ) ; +#8562 = CARTESIAN_POINT ( 'NONE', ( -37.31440426593247395, 172.2715631620466468, 165.0215178663606252 ) ) ; +#8563 = DIRECTION ( 'NONE', ( -6.938893903762204978E-15, 0.9743700557921589622, 0.2249510932971546529 ) ) ; +#8564 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971549582 ) ) ; +#8565 = DIRECTION ( 'NONE', ( 0.9914448404770122014, 0.1271187482266248059, 0.02963025718429710201 ) ) ; +#8566 = EDGE_LOOP ( 'NONE', ( #20303, #15071, #22485, #12550 ) ) ; +#8567 = AXIS2_PLACEMENT_3D ( 'NONE', #11791, #9119, #36714 ) ; +#8568 = CARTESIAN_POINT ( 'NONE', ( -41.13832148997259708, 182.7434276679351797, 104.9463272867566133 ) ) ; +#8569 = ADVANCED_FACE ( 'NONE', ( #10298 ), #14287, .F. ) ; +#8570 = CARTESIAN_POINT ( 'NONE', ( -44.12429222051905242, 188.3338783572263253, 106.2387882118758995 ) ) ; +#8571 = DIRECTION ( 'NONE', ( 0.7857167650892390443, -0.6185862428610306996, -0.0004745532376930882020 ) ) ; +#8572 = CONICAL_SURFACE ( 'NONE', #33359, 5.000000000095701225, 0.7853981634197699790 ) ; +#8573 = CARTESIAN_POINT ( 'NONE', ( 16.79405117887437271, 152.3217338832941721, 181.8411719429184075 ) ) ; +#8574 = ORIENTED_EDGE ( 'NONE', *, *, #37287, .T. ) ; +#8575 = EDGE_LOOP ( 'NONE', ( #8228, #12816, #22601, #22747 ) ) ; +#8576 = DIRECTION ( 'NONE', ( 0.7856637144487861324, -0.6186538028643616682, 0.000000000000000000 ) ) ; +#8577 = CARTESIAN_POINT ( 'NONE', ( -40.97271368781576228, 120.4617346393614525, 90.56736283153441036 ) ) ; +#8578 = DIRECTION ( 'NONE', ( 0.0005734119072325851883, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#8579 = CARTESIAN_POINT ( 'NONE', ( 35.04645051037203984, 217.7719116314000019, 75.53733736051518122 ) ) ; +#8580 = CARTESIAN_POINT ( 'NONE', ( 12.63462730242783572, 181.0589446024862639, 104.4878890928621615 ) ) ; +#8581 = CARTESIAN_POINT ( 'NONE', ( 36.04737028554169598, 207.4083918097923629, 77.05990514452676621 ) ) ; +#8582 = ADVANCED_FACE ( 'NONE', ( #3331 ), #29955, .F. ) ; +#8583 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971550969 ) ) ; +#8584 = CARTESIAN_POINT ( 'NONE', ( -43.65360665174738841, 185.3905100451317765, 107.6115822775834374 ) ) ; +#8585 = CARTESIAN_POINT ( 'NONE', ( 20.48136443024816344, 209.7093559074854454, 75.54613107284740181 ) ) ; +#8586 = ADVANCED_FACE ( 'NONE', ( #13164 ), #33194, .T. ) ; +#8587 = DATE_AND_TIME ( #5494, #5527 ) ; +#8588 = CARTESIAN_POINT ( 'NONE', ( 26.89533298033946096, 123.7171680322964562, 88.19903550279475724 ) ) ; +#8589 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#8590 = EDGE_CURVE ( 'NONE', #12877, #30394, #13553, .T. ) ; +#8591 = CARTESIAN_POINT ( 'NONE', ( 17.27144951970729991, 122.5453306081213043, 172.0736587966182469 ) ) ; +#8592 = DIRECTION ( 'NONE', ( -0.0004270746993301994870, 0.7071067811864992780, -0.7071066522153991452 ) ) ; +#8593 = FACE_OUTER_BOUND ( 'NONE', #12767, .T. ) ; +#8594 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971550969 ) ) ; +#8595 = VECTOR ( 'NONE', #35320, 1000.000000000000227 ) ; +#8596 = EDGE_CURVE ( 'NONE', #35367, #36684, #19064, .T. ) ; +#8597 = EDGE_LOOP ( 'NONE', ( #22798, #820, #24849, #8434 ) ) ; +#8598 = CARTESIAN_POINT ( 'NONE', ( -20.50006521734148990, 193.1656132470480429, 104.1466103976766107 ) ) ; +#8599 = ORIENTED_EDGE ( 'NONE', *, *, #30832, .T. ) ; +#8600 = ORIENTED_EDGE ( 'NONE', *, *, #37377, .F. ) ; +#8601 = EDGE_CURVE ( 'NONE', #4106, #4933, #22741, .T. ) ; +#8602 = ORIENTED_EDGE ( 'NONE', *, *, #29815, .T. ) ; +#8603 = CONICAL_SURFACE ( 'NONE', #16393, 5.999999999898478542, 0.7853981633778843729 ) ; +#8604 = CARTESIAN_POINT ( 'NONE', ( -25.50112048447915569, 120.6553735626000048, 88.03695903724376137 ) ) ; +#8605 = ADVANCED_FACE ( 'NONE', ( #34401 ), #6444, .F. ) ; +#8606 = EDGE_LOOP ( 'NONE', ( #19912, #2683, #22465, #18068 ) ) ; +#8607 = DIRECTION ( 'NONE', ( 0.1779895592101686796, 0.3532431349384635433, -0.9184437949221587738 ) ) ; +#8608 = DIRECTION ( 'NONE', ( -0.7069397808361403968, 0.6508952239913371463, 0.2767156548817158446 ) ) ; +#8609 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#8610 = ORIENTED_EDGE ( 'NONE', *, *, #14635, .F. ) ; +#8611 = LINE ( 'NONE', #27442, #10074 ) ; +#8612 = CARTESIAN_POINT ( 'NONE', ( -77.80691370946981067, 191.9356020547612900, 194.2498739115223145 ) ) ; +#8613 = DIRECTION ( 'NONE', ( 0.0005884949961204579902, -0.2249510543439042221, 0.9743698870671267942 ) ) ; +#8614 = PLANE ( 'NONE', #7339 ) ; +#8615 = ORIENTED_EDGE ( 'NONE', *, *, #40085, .T. ) ; +#8616 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319377338326 ) ) ; +#8617 = FACE_OUTER_BOUND ( 'NONE', #4059, .T. ) ; +#8618 = FACE_OUTER_BOUND ( 'NONE', #1219, .T. ) ; +#8619 = CARTESIAN_POINT ( 'NONE', ( 36.19813064229271049, 115.7978980914772364, 90.24592207534902855 ) ) ; +#8620 = CARTESIAN_POINT ( 'NONE', ( 36.05382442431439216, 109.6131156806000035, 87.74600877644128616 ) ) ; +#8621 = EDGE_LOOP ( 'NONE', ( #1130, #33920, #15739, #19058 ) ) ; +#8622 = CARTESIAN_POINT ( 'NONE', ( -40.95638651213572956, 220.4002260740000168, 73.58324080466404382 ) ) ; +#8623 = CARTESIAN_POINT ( 'NONE', ( 0.9444534192402208594, 189.0472900984059663, 103.7089565807309981 ) ) ; +#8624 = CARTESIAN_POINT ( 'NONE', ( 28.14966852377056483, 124.3573228059849498, 91.42498220208800319 ) ) ; +#8625 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30958, #27704, #37285, #5395, #27516, #40141, #12153, #6200, #33604, #33806, #15418 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000685563, 0.3750000000001185163, 0.4375000000001610378, 0.4687500000001221800, 0.5000000000000832667, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8626 = ORIENTED_EDGE ( 'NONE', *, *, #12535, .F. ) ; +#8627 = EDGE_LOOP ( 'NONE', ( #15570, #38780, #2212, #20657 ) ) ; +#8628 = CONICAL_SURFACE ( 'NONE', #13827, 5.000000000037475800, 0.7853981634506773668 ) ; +#8629 = CARTESIAN_POINT ( 'NONE', ( 20.25161797161999999, 187.6280213585999945, 105.7803707432999971 ) ) ; +#8630 = ORIENTED_EDGE ( 'NONE', *, *, #16146, .T. ) ; +#8631 = AXIS2_PLACEMENT_3D ( 'NONE', #9375, #12625, #12042 ) ; +#8632 = VECTOR ( 'NONE', #3425, 1000.000000000000114 ) ; +#8633 = EDGE_CURVE ( 'NONE', #7007, #26180, #4126, .T. ) ; +#8634 = ADVANCED_FACE ( 'NONE', ( #18857 ), #7203, .T. ) ; +#8635 = ORIENTED_EDGE ( 'NONE', *, *, #28305, .T. ) ; +#8636 = EDGE_CURVE ( 'NONE', #28271, #13439, #16598, .T. ) ; +#8637 = ORIENTED_EDGE ( 'NONE', *, *, #4065, .T. ) ; +#8638 = CARTESIAN_POINT ( 'NONE', ( -37.05605030574000125, 191.0258856046000062, 106.5406989459000044 ) ) ; +#8639 = DIRECTION ( 'NONE', ( 0.9999998268367130683, 0.0001323824760006246388, -0.0005734120890906795271 ) ) ; +#8640 = CARTESIAN_POINT ( 'NONE', ( 38.59086485963890567, 79.69179921679354095, 285.2955982571226059 ) ) ; +#8641 = EDGE_CURVE ( 'NONE', #8771, #29915, #1069, .T. ) ; +#8642 = ORIENTED_EDGE ( 'NONE', *, *, #24712, .T. ) ; +#8643 = LINE ( 'NONE', #5549, #19836 ) ; +#8644 = ORIENTED_EDGE ( 'NONE', *, *, #23925, .T. ) ; +#8645 = EDGE_CURVE ( 'NONE', #662, #16108, #20161, .T. ) ; +#8646 = CARTESIAN_POINT ( 'NONE', ( 26.02775071507020499, 120.6384143230500143, 90.56953989852389952 ) ) ; +#8647 = CARTESIAN_POINT ( 'NONE', ( -26.01003256183229695, 210.6300345901000242, 76.07590184482684492 ) ) ; +#8649 = CARTESIAN_POINT ( 'NONE', ( 40.49581267819608854, 84.18892247206676416, 282.5307213418886931 ) ) ; +#8648 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825959531803938, 0.0005734119014747785219 ) ) ; +#8650 = EDGE_LOOP ( 'NONE', ( #17019, #26307, #5725, #38933, #21921, #39958, #9306, #4101, #26925, #25906 ) ) ; +#8651 = EDGE_CURVE ( 'NONE', #1667, #5335, #37685, .T. ) ; +#8652 = VERTEX_POINT ( 'NONE', #34596 ) ; +#8653 = CARTESIAN_POINT ( 'NONE', ( 20.02704401006072743, 117.6316107474358432, 87.25568845928445683 ) ) ; +#8654 = VECTOR ( 'NONE', #29626, 1000.000000000000114 ) ; +#8655 = ORIENTED_EDGE ( 'NONE', *, *, #10107, .F. ) ; +#8657 = AXIS2_PLACEMENT_3D ( 'NONE', #22004, #36858, #33782 ) ; +#8656 = FACE_OUTER_BOUND ( 'NONE', #32622, .T. ) ; +#8658 = EDGE_CURVE ( 'NONE', #10328, #38615, #6594, .T. ) ; +#8659 = CONICAL_SURFACE ( 'NONE', #6012, 2.249999999984611421, 0.7853981634347277918 ) ; +#8660 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5220, #14244, #35673, #29576 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8661 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#8662 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#8663 = CARTESIAN_POINT ( 'NONE', ( 12.63659917731993865, 130.8565322054421927, 89.99855747202538225 ) ) ; +#8664 = CARTESIAN_POINT ( 'NONE', ( -12.64352839772552173, 134.9564157408762242, 90.87116896037730385 ) ) ; +#8665 = VERTEX_POINT ( 'NONE', #25436 ) ; +#8666 = ORIENTED_EDGE ( 'NONE', *, *, #3401, .F. ) ; +#8667 = CARTESIAN_POINT ( 'NONE', ( -1.429316825074233188, 189.2366094587022474, 103.7538750078491034 ) ) ; +#8668 = CARTESIAN_POINT ( 'NONE', ( 20.50147137495634198, 190.9646546281344683, 106.2940065278771016 ) ) ; +#8669 = CYLINDRICAL_SURFACE ( 'NONE', #34658, 40.00000000000000000 ) ; +#8670 = CARTESIAN_POINT ( 'NONE', ( 25.66514228811999843, 121.0763891642999965, 87.93230023964001418 ) ) ; +#8671 = VERTEX_POINT ( 'NONE', #9897 ) ; +#8672 = ORIENTED_EDGE ( 'NONE', *, *, #32541, .F. ) ; +#8673 = CARTESIAN_POINT ( 'NONE', ( 35.54675198585685791, 209.7096512551739238, 76.03703539298859937 ) ) ; +#8674 = CARTESIAN_POINT ( 'NONE', ( 2.321157821276000455, 189.0697464220000086, 106.3805944500000038 ) ) ; +#8675 = ORIENTED_EDGE ( 'NONE', *, *, #38836, .F. ) ; +#8676 = CARTESIAN_POINT ( 'NONE', ( 5.669776689925148716, 130.9358280359080595, 89.95242648389140072 ) ) ; +#8677 = LINE ( 'NONE', #40329, #2622 ) ; +#8678 = LINE ( 'NONE', #21140, #13062 ) ; +#8679 = CIRCLE ( 'NONE', #25672, 16.50000000000000000 ) ; +#8680 = ADVANCED_FACE ( 'NONE', ( #22368 ), #34791, .F. ) ; +#8681 = VERTEX_POINT ( 'NONE', #1689 ) ; +#8682 = ADVANCED_FACE ( 'NONE', ( #10501 ), #29990, .F. ) ; +#8683 = AXIS2_PLACEMENT_3D ( 'NONE', #18735, #36564, #5692 ) ; +#8684 = ADVANCED_FACE ( 'NONE', ( #30110 ), #19518, .T. ) ; +#8685 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14038, #35882, #29785, #7684, #7888, #1344, #26312, #4615, #20351, #14242, #26716, #39164, #8096, #20558, #33027, #29977, #14441, #39361, #11361, #11788, #28472, #2379, #22143, #8515, #36711, #31146, #25020, #6380, #37465, #25218, #24053, #12939, #31752, #3500, #20982, #21945, #34774, #33435, #21745, #18834, #6775, #31342, #3713, #15587, #243, #39767, #3313, #12725, #25418, #34572, #9467, #15985, #19245, #17884, #37668, #9668, #34184, #36513, #16189, #453, #5426, #27340, #15782, #6184, #37869, #28277, #9874, #30382, #18637, #6574, #19048, #22351, #24268, #12516, #31541, #28672 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 1, 1, 1, 2, 2, 1, 1, 2, 2, 1, 1, 2, 2, 1, 1, 1, 1, 2, 2, 1, 1, 1, 1, 1, 1, 1, 2, 2, 1, 1, 1, 1, 1, 1, 2, 2, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.03124999999947112445, 0.04687499999920669014, 0.06249999999894224889, 0.09374999999841299170, 0.1093749999981470239, 0.1249999999978810561, 0.1562499999973329667, 0.1874999999967849051, 0.2187499999962368158, 0.2343749999959629238, 0.2421874999958204266, 0.2460937499957437380, 0.2499999999956670493, 0.2812499999958106844, 0.2968749999958828489, 0.3046874999959189312, 0.3124999999959550134, 0.3437499999960999530, 0.3593749999961756147, 0.3671874999962137509, 0.3749999999962518871, 0.4374999999965747954, 0.4687499999967366660, 0.4843749999968176567, 0.4921874999968535169, 0.4960937499968759434, 0.4999999999968983699, 0.6249999999975812681, 0.6874999999979228837, 0.7187499999980997423, 0.7343749999981823429, 0.7421874999982177590, 0.7460937499982416288, 0.7480468749982472909, 0.7490234374982557286, 0.7499999999982641663, 0.8124999999985818011, 0.8437499999987405630, 0.8593749999988243848, 0.8671874999988656851, 0.8710937499988817834, 0.8730468749988948840, 0.8740234374989059862, 0.8749999999989169774, 0.9062499999992081889, 0.9218749999993504085, 0.9296874999994176880, 0.9335937499994479971, 0.9355468749994635402, 0.9374999999994790834, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8686 = CARTESIAN_POINT ( 'NONE', ( 15.58035690247840144, 137.1114215606455389, 91.29817711239832079 ) ) ; +#8687 = LINE ( 'NONE', #21144, #20851 ) ; +#8688 = VECTOR ( 'NONE', #15361, 1000.000000000000000 ) ; +#8689 = ORIENTED_EDGE ( 'NONE', *, *, #14697, .F. ) ; +#8690 = ADVANCED_FACE ( 'NONE', ( #32365 ), #18870, .F. ) ; +#8691 = CARTESIAN_POINT ( 'NONE', ( -13.82977187757395221, 154.4043701110990128, 95.30833257247996926 ) ) ; +#8692 = VERTEX_POINT ( 'NONE', #38677 ) ; +#8694 = CARTESIAN_POINT ( 'NONE', ( -41.95974523811950263, 77.14301703112136011, 284.1899085454229521 ) ) ; +#8693 = DIRECTION ( 'NONE', ( 0.0005884949961229014566, -0.2249510543439049715, 0.9743698870671266832 ) ) ; +#8695 = VERTEX_POINT ( 'NONE', #36224 ) ; +#8696 = ADVANCED_FACE ( 'NONE', ( #2102 ), #25449, .T. ) ; +#8697 = ORIENTED_EDGE ( 'NONE', *, *, #19800, .F. ) ; +#8698 = DIRECTION ( 'NONE', ( -4.163336342485308837E-15, 0.9743700557921587402, 0.2249510932971551525 ) ) ; +#8699 = VERTEX_POINT ( 'NONE', #13961 ) ; +#8700 = CARTESIAN_POINT ( 'NONE', ( 2.842207948177999821, 209.6286538536000137, 75.93572464195000293 ) ) ; +#8701 = CARTESIAN_POINT ( 'NONE', ( -2.952854090120908381, 209.7096538831000032, 78.06028844424199065 ) ) ; +#8702 = LINE ( 'NONE', #36280, #7034 ) ; +#8703 = ORIENTED_EDGE ( 'NONE', *, *, #15195, .T. ) ; +#8704 = VERTEX_POINT ( 'NONE', #4334 ) ; +#8705 = DIRECTION ( 'NONE', ( -0.0002393071182782277790, -0.2252352986010052460, 0.9743043687658488050 ) ) ; +#8706 = VERTEX_POINT ( 'NONE', #38886 ) ; +#8707 = VERTEX_POINT ( 'NONE', #14573 ) ; +#8708 = FACE_OUTER_BOUND ( 'NONE', #15779, .T. ) ; +#8709 = CYLINDRICAL_SURFACE ( 'NONE', #27664, 6.000000000000008882 ) ; +#8710 = DIRECTION ( 'NONE', ( 0.0004161288024354952049, -0.8480480898215656538, 0.5299191109846985714 ) ) ; +#8711 = CARTESIAN_POINT ( 'NONE', ( 23.31161622905471731, 134.9426957410666716, 90.79281772715843601 ) ) ; +#8712 = CIRCLE ( 'NONE', #31552, 40.50000000002204104 ) ; +#8713 = ORIENTED_EDGE ( 'NONE', *, *, #15088, .F. ) ; +#8714 = ORIENTED_EDGE ( 'NONE', *, *, #5315, .F. ) ; +#8715 = CYLINDRICAL_SURFACE ( 'NONE', #7591, 1.000000000000001554 ) ; +#8716 = CARTESIAN_POINT ( 'NONE', ( -36.30859555223000257, 191.9504843571999970, 104.5588447405000068 ) ) ; +#8717 = AXIS2_PLACEMENT_3D ( 'NONE', #5827, #18470, #12358 ) ; +#8718 = ORIENTED_EDGE ( 'NONE', *, *, #16763, .F. ) ; +#8719 = CARTESIAN_POINT ( 'NONE', ( -25.83465801582000054, 120.7303359361000048, 87.71237979401999496 ) ) ; +#8720 = ORIENTED_EDGE ( 'NONE', *, *, #18518, .F. ) ; +#8721 = CARTESIAN_POINT ( 'NONE', ( -21.21281380558005125, 182.9066539643694966, 104.4588199671594850 ) ) ; +#8722 = CARTESIAN_POINT ( 'NONE', ( 39.91788020334763587, 190.3182931183406481, 106.6461671755548508 ) ) ; +#8723 = VERTEX_POINT ( 'NONE', #10902 ) ; +#8724 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901141, 132.2978364233219963, 93.26432363102219369 ) ) ; +#8725 = CARTESIAN_POINT ( 'NONE', ( -15.14908912525229567, 124.9619667792663051, 88.51181376764675690 ) ) ; +#8726 = CARTESIAN_POINT ( 'NONE', ( 19.99933118494021755, 196.5785306413737601, 103.8628508136982731 ) ) ; +#8727 = CARTESIAN_POINT ( 'NONE', ( 23.36209697621471193, 182.0666116869439861, 102.1853546028109321 ) ) ; +#8728 = CARTESIAN_POINT ( 'NONE', ( -15.83177648456734943, 137.5598563050514258, 94.32865390342180945 ) ) ; +#8729 = ORIENTED_EDGE ( 'NONE', *, *, #8276, .T. ) ; +#8730 = CARTESIAN_POINT ( 'NONE', ( -0.4558744191268589985, 208.9999999999999716, 73.05877941917057683 ) ) ; +#8731 = ORIENTED_EDGE ( 'NONE', *, *, #16458, .T. ) ; +#8732 = EDGE_CURVE ( 'NONE', #21532, #39497, #11290, .T. ) ; +#8733 = LINE ( 'NONE', #15066, #21860 ) ; +#8734 = EDGE_CURVE ( 'NONE', #17312, #39158, #7480, .T. ) ; +#8735 = CARTESIAN_POINT ( 'NONE', ( 16.00200912906086614, 173.8361395730204322, 102.8554915256801650 ) ) ; +#8736 = CARTESIAN_POINT ( 'NONE', ( -25.50053198731683324, 120.4304220968047474, 89.01133250720081946 ) ) ; +#8737 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31093, #5, #3257, #28423 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8738 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; +#8739 = VECTOR ( 'NONE', #2048, 1000.000000000000114 ) ; +#8740 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971546251 ) ) ; +#8741 = ORIENTED_EDGE ( 'NONE', *, *, #39531, .T. ) ; +#8742 = EDGE_CURVE ( 'NONE', #10555, #33981, #11095, .T. ) ; +#8743 = VECTOR ( 'NONE', #32130, 1000.000000000000000 ) ; +#8744 = CARTESIAN_POINT ( 'NONE', ( -6.038835622038210005, 135.1607352200812215, 91.19296211258786400 ) ) ; +#8745 = VECTOR ( 'NONE', #5520, 1000.000000000000000 ) ; +#8746 = ORIENTED_EDGE ( 'NONE', *, *, #36386, .F. ) ; +#8747 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567345 ) ) ; +#8748 = CARTESIAN_POINT ( 'NONE', ( -20.49854722029782295, 184.1159485384492314, 104.7375718384251542 ) ) ; +#8749 = CARTESIAN_POINT ( 'NONE', ( 21.33595229338290622, 124.0143879427035642, 174.3475635039766587 ) ) ; +#8750 = DIRECTION ( 'NONE', ( 0.0005884949961244146776, -0.2249510543439057209, 0.9743698870671265722 ) ) ; +#8751 = CARTESIAN_POINT ( 'NONE', ( -17.26213291099019997, 152.2612616225560771, 183.6636115490260863 ) ) ; +#8752 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21075, #15147, #36401, #12078 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8753 = CARTESIAN_POINT ( 'NONE', ( -36.84324029226966957, 117.2651960508476634, 90.29003723313010710 ) ) ; +#8754 = VERTEX_POINT ( 'NONE', #8014 ) ; +#8755 = DIRECTION ( 'NONE', ( 0.0006039748319378514686, 1.190362635753271326E-14, 0.9999998176071847045 ) ) ; +#8756 = EDGE_CURVE ( 'NONE', #35118, #3175, #20696, .T. ) ; +#8757 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363196006660E-14, -0.9999998176071844824 ) ) ; +#8758 = ORIENTED_EDGE ( 'NONE', *, *, #33565, .T. ) ; +#8759 = CARTESIAN_POINT ( 'NONE', ( -20.33313815255117163, 174.4356457342066165, 100.2789485125420583 ) ) ; +#8760 = ORIENTED_EDGE ( 'NONE', *, *, #33318, .T. ) ; +#8761 = CARTESIAN_POINT ( 'NONE', ( -38.28386786901999983, 119.2293362182000038, 87.45079503396999598 ) ) ; +#8762 = CARTESIAN_POINT ( 'NONE', ( -5.668458121731908328, 130.7278572272551571, 90.08794464196098772 ) ) ; +#8763 = CARTESIAN_POINT ( 'NONE', ( 36.08489528552837555, 191.2182783123578247, 106.8419584201553079 ) ) ; +#8764 = AXIS2_PLACEMENT_3D ( 'NONE', #8629, #15164, #14958 ) ; +#8765 = CONICAL_SURFACE ( 'NONE', #40084, 2.502986836105446145, 0.7853981633574639298 ) ; +#8766 = EDGE_CURVE ( 'NONE', #16835, #24779, #27058, .T. ) ; +#8767 = DIRECTION ( 'NONE', ( -3.549981615672110651E-11, -0.9743700557841834531, -0.2249510933316997141 ) ) ; +#8768 = CARTESIAN_POINT ( 'NONE', ( 23.72254622402000024, 114.0103269029000188, 152.4718672074000381 ) ) ; +#8769 = CARTESIAN_POINT ( 'NONE', ( 41.37407482599210340, 109.2646873992651422, 170.0357904634387580 ) ) ; +#8770 = CARTESIAN_POINT ( 'NONE', ( -32.65040898612480191, 153.0051697192221241, 291.5764532040477093 ) ) ; +#8771 = VERTEX_POINT ( 'NONE', #29297 ) ; +#8772 = VERTEX_POINT ( 'NONE', #35391 ) ; +#8773 = CARTESIAN_POINT ( 'NONE', ( 38.50022159043000158, 118.6460062394999966, 87.79248012469000173 ) ) ; +#8774 = AXIS2_PLACEMENT_3D ( 'NONE', #27690, #5986, #15396 ) ; +#8775 = CARTESIAN_POINT ( 'NONE', ( 20.24064596600999977, 199.6921864814999878, 89.48934496540999817 ) ) ; +#8776 = CARTESIAN_POINT ( 'NONE', ( 37.31163124181149016, 191.4712155356178300, 104.3367040115298607 ) ) ; +#8777 = FACE_OUTER_BOUND ( 'NONE', #39339, .T. ) ; +#8778 = VERTEX_POINT ( 'NONE', #7398 ) ; +#8779 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; +#8780 = EDGE_CURVE ( 'NONE', #34131, #2174, #13383, .T. ) ; +#8781 = CARTESIAN_POINT ( 'NONE', ( -43.84816494817811616, 120.4493680208014723, 90.56624447257551935 ) ) ; +#8782 = CARTESIAN_POINT ( 'NONE', ( 15.66686322801795406, 127.6698194824295882, 89.46046031359570350 ) ) ; +#8783 = CARTESIAN_POINT ( 'NONE', ( -5.669412827410644340, 187.7434695915656562, 103.5134950631828588 ) ) ; +#8784 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265227786, -0.1368326740407709297 ) ) ; +#8785 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#8786 = ADVANCED_FACE ( 'NONE', ( #4743 ), #17203, .T. ) ; +#8787 = CARTESIAN_POINT ( 'NONE', ( -25.76318952320184152, 209.7106752283213780, 73.32088370617481132 ) ) ; +#8788 = VECTOR ( 'NONE', #27639, 1000.000000000000114 ) ; +#8789 = LINE ( 'NONE', #36785, #16091 ) ; +#8790 = PERSON_AND_ORGANIZATION_ROLE ( 'classification_officer' ) ; +#8791 = PLANE ( 'NONE', #15455 ) ; +#8792 = CIRCLE ( 'NONE', #26420, 8.000000000000007105 ) ; +#8793 = CIRCLE ( 'NONE', #10072, 2.000000000000011546 ) ; +#8794 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#8795 = DIRECTION ( 'NONE', ( 0.0005884949671858177161, -0.2249510543353067382, 0.9743698870691291924 ) ) ; +#8796 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319389714494 ) ) ; +#8797 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#8798 = ORIENTED_EDGE ( 'NONE', *, *, #13168, .T. ) ; +#8799 = CARTESIAN_POINT ( 'NONE', ( 28.70581487418796129, 148.8854600315911796, 94.52165327196804867 ) ) ; +#8800 = ORIENTED_EDGE ( 'NONE', *, *, #25214, .T. ) ; +#8801 = ORIENTED_EDGE ( 'NONE', *, *, #25950, .F. ) ; +#8802 = VERTEX_POINT ( 'NONE', #14366 ) ; +#8803 = DIRECTION ( 'NONE', ( 0.9999998268366048215, 0.0001323826692270894153, -0.0005734122332635458808 ) ) ; +#8804 = ORIENTED_EDGE ( 'NONE', *, *, #32973, .F. ) ; +#8805 = CARTESIAN_POINT ( 'NONE', ( 20.32589321757966516, 126.8344400321431920, 91.66874526613595719 ) ) ; +#8806 = CARTESIAN_POINT ( 'NONE', ( 18.87587832947231092, 125.0050401149588879, 178.4556788297441585 ) ) ; +#8807 = CARTESIAN_POINT ( 'NONE', ( -42.86870032173014522, 121.2410338499262537, 90.70283413665809746 ) ) ; +#8808 = VERTEX_POINT ( 'NONE', #37047 ) ; +#8809 = CARTESIAN_POINT ( 'NONE', ( 15.50107933875540667, 127.3325056150999899, 90.92214182049345084 ) ) ; +#8810 = DIRECTION ( 'NONE', ( -0.6087613186456907188, -0.7730177010543248795, -0.1784749023741044327 ) ) ; +#8811 = DIRECTION ( 'NONE', ( 0.5986917825334797660, 0.8009794122048706777, -0.0003615948347012658639 ) ) ; +#8812 = CARTESIAN_POINT ( 'NONE', ( -12.63809828823728232, 131.0198806733800438, 89.90888323108799796 ) ) ; +#8813 = ORIENTED_EDGE ( 'NONE', *, *, #3386, .T. ) ; +#8814 = CARTESIAN_POINT ( 'NONE', ( -35.95473150036615806, 205.5673820438667292, 76.32193034923589892 ) ) ; +#8815 = EDGE_CURVE ( 'NONE', #206, #2569, #15343, .T. ) ; +#8816 = CARTESIAN_POINT ( 'NONE', ( -15.38775925502634756, 176.1499588361438384, 100.3296392074066006 ) ) ; +#8817 = FACE_OUTER_BOUND ( 'NONE', #23576, .T. ) ; +#8818 = CARTESIAN_POINT ( 'NONE', ( 23.08502856561264593, 148.5869484094654354, 197.0326829874275347 ) ) ; +#8819 = CARTESIAN_POINT ( 'NONE', ( -6.679083190205946056E-14, 155.6803346354327289, 98.67347229705578115 ) ) ; +#8820 = CIRCLE ( 'NONE', #14029, 1.749999999939591433 ) ; +#8821 = ORIENTED_EDGE ( 'NONE', *, *, #17512, .F. ) ; +#8822 = EDGE_CURVE ( 'NONE', #12107, #11953, #4602, .T. ) ; +#8823 = CARTESIAN_POINT ( 'NONE', ( -31.19810823188564797, 110.6131156702000027, 87.28662716757878570 ) ) ; +#8824 = CARTESIAN_POINT ( 'NONE', ( 0.5740959785458999987, 188.8577272846999904, 103.5276859817000030 ) ) ; +#8825 = CONICAL_SURFACE ( 'NONE', #20555, 6.499999999947934981, 0.7853981633829972830 ) ; +#8826 = AXIS2_PLACEMENT_3D ( 'NONE', #30032, #35936, #17329 ) ; +#8827 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971555410 ) ) ; +#8828 = PLANE ( 'NONE', #20820 ) ; +#8829 = AXIS2_PLACEMENT_3D ( 'NONE', #16846, #26483, #4585 ) ; +#8830 = EDGE_CURVE ( 'NONE', #32100, #11480, #33560, .T. ) ; +#8831 = ORIENTED_EDGE ( 'NONE', *, *, #8111, .T. ) ; +#8832 = CARTESIAN_POINT ( 'NONE', ( -39.17187909013465230, 120.2212968650121496, 87.43185284211611474 ) ) ; +#8833 = EDGE_LOOP ( 'NONE', ( #21079, #12411, #14440, #2708, #31783 ) ) ; +#8834 = ADVANCED_FACE ( 'NONE', ( #30302 ), #24597, .F. ) ; +#8835 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25424, #28282, #12732, #3509 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.579035019922823579, 6.150665660457575790 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8045411634788331989, 0.8045411634788331989, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#8836 = EDGE_CURVE ( 'NONE', #5617, #18856, #10497, .T. ) ; +#8837 = EDGE_CURVE ( 'NONE', #2295, #10713, #28527, .T. ) ; +#8838 = VERTEX_POINT ( 'NONE', #12109 ) ; +#8839 = DIRECTION ( 'NONE', ( 0.0005884949961243997156, -0.2249510543439061094, 0.9743698870671263501 ) ) ; +#8840 = CARTESIAN_POINT ( 'NONE', ( -36.23778119402999920, 191.7113188957999910, 106.6305335173999964 ) ) ; +#8841 = CARTESIAN_POINT ( 'NONE', ( -20.01989362473241130, 208.7351702940684675, 73.14224971100274786 ) ) ; +#8842 = CARTESIAN_POINT ( 'NONE', ( -36.75858231525709385, 191.2532611179763649, 106.3676456459981665 ) ) ; +#8843 = ORIENTED_EDGE ( 'NONE', *, *, #23916, .T. ) ; +#8844 = CARTESIAN_POINT ( 'NONE', ( -12.64022723116406510, 134.3423969131311821, 93.66938630730395232 ) ) ; +#8845 = VERTEX_POINT ( 'NONE', #37243 ) ; +#8846 = CARTESIAN_POINT ( 'NONE', ( 26.94166893793940076, 123.1531157623659851, 91.15290741612201941 ) ) ; +#8847 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8501, #10809, #24252, #33420 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8848 = CARTESIAN_POINT ( 'NONE', ( 13.53487526333000091, 138.6412561347999883, 152.4718672074000381 ) ) ; +#8850 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673502968, 185.7972672194256063, 103.0526007371361175 ) ) ; +#8849 = CARTESIAN_POINT ( 'NONE', ( 44.30515803278058229, 188.2843354219114929, 106.1739411498338939 ) ) ; +#8851 = AXIS2_PLACEMENT_3D ( 'NONE', #30099, #29896, #2095 ) ; +#8852 = EDGE_LOOP ( 'NONE', ( #7800, #16513, #26325 ) ) ; +#8853 = ADVANCED_FACE ( 'NONE', ( #8443 ), #21319, .F. ) ; +#8854 = AXIS2_PLACEMENT_3D ( 'NONE', #26009, #1655, #7984 ) ; +#8855 = AXIS2_PLACEMENT_3D ( 'NONE', #40177, #37125, #25072 ) ; +#8856 = ORIENTED_EDGE ( 'NONE', *, *, #29168, .T. ) ; +#8857 = AXIS2_PLACEMENT_3D ( 'NONE', #39218, #16736, #32492 ) ; +#8858 = CARTESIAN_POINT ( 'NONE', ( 15.94054669826102177, 152.1475402096681080, 184.5616883112009816 ) ) ; +#8859 = VECTOR ( 'NONE', #10407, 1000.000000000000114 ) ; +#8860 = EDGE_LOOP ( 'NONE', ( #6201, #2870, #31185, #37497 ) ) ; +#8861 = CARTESIAN_POINT ( 'NONE', ( 38.87094024417000071, 119.1787111753999966, 90.12667056598999693 ) ) ; +#8862 = CARTESIAN_POINT ( 'NONE', ( -30.05378917699556141, 127.2828694753868319, 89.56979070794703546 ) ) ; +#8863 = CARTESIAN_POINT ( 'NONE', ( -40.45487666627001033, 206.4002260771000010, 76.08293836136373045 ) ) ; +#8864 = CARTESIAN_POINT ( 'NONE', ( 30.79668133981403599, 129.4657338577335395, 89.52384042189491709 ) ) ; +#8865 = CARTESIAN_POINT ( 'NONE', ( 37.33113517456880714, 106.2740459041111478, 174.4753009534431669 ) ) ; +#8866 = ORIENTED_EDGE ( 'NONE', *, *, #24900, .T. ) ; +#8867 = ADVANCED_FACE ( 'NONE', ( #5962 ), #24783, .T. ) ; +#8868 = VERTEX_POINT ( 'NONE', #15373 ) ; +#8869 = DIRECTION ( 'NONE', ( -0.0006039748319384964604, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#8870 = CARTESIAN_POINT ( 'NONE', ( -14.55129768904543930, 135.1122403316443581, 93.93374132341575944 ) ) ; +#8871 = ORIENTED_EDGE ( 'NONE', *, *, #22806, .F. ) ; +#8872 = EDGE_CURVE ( 'NONE', #25826, #8188, #29529, .T. ) ; +#8873 = CARTESIAN_POINT ( 'NONE', ( -36.31535205723999837, 190.8511612753999884, 106.8152324706999963 ) ) ; +#8874 = DIRECTION ( 'NONE', ( 9.251858538525972270E-15, -1.000000000000000000, 1.387778780778895919E-14 ) ) ; +#8875 = EDGE_CURVE ( 'NONE', #31409, #9446, #6558, .T. ) ; +#8876 = CARTESIAN_POINT ( 'NONE', ( 0.7701782471999670809, 188.3723031557926788, 106.2344282965262465 ) ) ; +#8877 = CARTESIAN_POINT ( 'NONE', ( -20.51953037942761782, 208.4917401325288324, 73.73871995449873396 ) ) ; +#8878 = ADVANCED_FACE ( 'NONE', ( #18215 ), #2298, .T. ) ; +#8879 = CARTESIAN_POINT ( 'NONE', ( -36.31535185967262436, 190.8511613781771530, 106.8152324789805903 ) ) ; +#8880 = AXIS2_PLACEMENT_3D ( 'NONE', #17342, #20842, #30057 ) ; +#8881 = VECTOR ( 'NONE', #38275, 1000.000000000000114 ) ; +#8882 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971567623 ) ) ; +#8883 = DIRECTION ( 'NONE', ( 0.0006039748319386881474, 1.110222822128452674E-14, 0.9999998176071845934 ) ) ; +#8884 = AXIS2_PLACEMENT_3D ( 'NONE', #1446, #29274, #13727 ) ; +#8885 = ORIENTED_EDGE ( 'NONE', *, *, #18337, .F. ) ; +#8886 = AXIS2_PLACEMENT_3D ( 'NONE', #6033, #30590, #3156 ) ; +#8887 = DIRECTION ( 'NONE', ( 0.0006039748319391408018, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#8888 = CARTESIAN_POINT ( 'NONE', ( -1.762796035792233207, 151.6652447683722471, 130.5904578368917441 ) ) ; +#8889 = ORIENTED_EDGE ( 'NONE', *, *, #21396, .F. ) ; +#8890 = CARTESIAN_POINT ( 'NONE', ( 15.95546908501697558, 121.2205045768968432, 177.4121190822531560 ) ) ; +#8891 = VERTEX_POINT ( 'NONE', #25792 ) ; +#8893 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569566 ) ) ; +#8892 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559019 ) ) ; +#8894 = ORIENTED_EDGE ( 'NONE', *, *, #23439, .F. ) ; +#8895 = VERTEX_POINT ( 'NONE', #37838 ) ; +#8896 = ORIENTED_EDGE ( 'NONE', *, *, #22582, .T. ) ; +#8897 = CARTESIAN_POINT ( 'NONE', ( 2.639085314459999942, 209.3675475706999976, 75.69331483121000304 ) ) ; +#8898 = VECTOR ( 'NONE', #32040, 1000.000000000000000 ) ; +#8899 = CARTESIAN_POINT ( 'NONE', ( -4.037441715711839407, 168.3837378232002209, 99.04296232379908815 ) ) ; +#8900 = DIRECTION ( 'NONE', ( 0.0005884949961203239828, -0.2249510543439058874, 0.9743698870671263501 ) ) ; +#8901 = ORIENTED_EDGE ( 'NONE', *, *, #17974, .F. ) ; +#8902 = AXIS2_PLACEMENT_3D ( 'NONE', #1131, #16855, #31831 ) ; +#8903 = ORIENTED_EDGE ( 'NONE', *, *, #20606, .T. ) ; +#8904 = CARTESIAN_POINT ( 'NONE', ( -22.50000097825470746, 184.9622399467538685, 102.3653456266050483 ) ) ; +#8905 = ORIENTED_EDGE ( 'NONE', *, *, #13071, .F. ) ; +#8906 = AXIS2_PLACEMENT_3D ( 'NONE', #19112, #25888, #16646 ) ; +#8907 = ORIENTED_EDGE ( 'NONE', *, *, #12101, .F. ) ; +#8908 = CARTESIAN_POINT ( 'NONE', ( 20.46346868659919238, 151.7331366245661286, 196.7148367672695883 ) ) ; +#8909 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927766006264, 0.0005734119022010027242 ) ) ; +#8910 = CARTESIAN_POINT ( 'NONE', ( -45.26777240408874547, 110.5472149921316571, 150.9714395293199232 ) ) ; +#8911 = CARTESIAN_POINT ( 'NONE', ( 2.779653847929548949, 209.6693628105339826, 73.22349325451288848 ) ) ; +#8912 = EDGE_LOOP ( 'NONE', ( #28451, #39786, #2319, #28304 ) ) ; +#8913 = EDGE_CURVE ( 'NONE', #8188, #35446, #12958, .T. ) ; +#8914 = AXIS2_PLACEMENT_3D ( 'NONE', #11454, #27013, #20860 ) ; +#8915 = VERTEX_POINT ( 'NONE', #22116 ) ; +#8916 = EDGE_CURVE ( 'NONE', #20686, #32437, #29, .T. ) ; +#8917 = ORIENTED_EDGE ( 'NONE', *, *, #13812, .F. ) ; +#8918 = CARTESIAN_POINT ( 'NONE', ( -5.669681737655269060, 123.9839218370772187, 91.10844462476967465 ) ) ; +#8919 = ADVANCED_FACE ( 'NONE', ( #25386 ), #34744, .T. ) ; +#8920 = CARTESIAN_POINT ( 'NONE', ( -36.11135576184000229, 191.8228972718000307, 104.2943896964000032 ) ) ; +#8921 = CARTESIAN_POINT ( 'NONE', ( -25.94032117352999833, 122.9550272655999947, 88.56828463643999783 ) ) ; +#8922 = ORIENTED_EDGE ( 'NONE', *, *, #28081, .T. ) ; +#8923 = DIRECTION ( 'NONE', ( -0.0006039748319368648446, -1.157494911401840404E-14, -0.9999998176071845934 ) ) ; +#8924 = DIRECTION ( 'NONE', ( 0.0005884949961239144267, -0.2249510543439066923, 0.9743698870671261281 ) ) ; +#8925 = CARTESIAN_POINT ( 'NONE', ( 40.07504156640001014, 190.2887409542544788, 106.6480229763039063 ) ) ; +#8926 = ORIENTED_EDGE ( 'NONE', *, *, #30510, .T. ) ; +#8927 = EDGE_CURVE ( 'NONE', #26246, #8652, #29022, .T. ) ; +#8928 = CARTESIAN_POINT ( 'NONE', ( -0.1043368103128384378, 188.6124742552540283, 103.1976073196855026 ) ) ; +#8929 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178587041921E-05, -0.0002331579774917524482 ) ) ; +#8930 = EDGE_CURVE ( 'NONE', #22954, #17036, #34531, .T. ) ; +#8931 = CARTESIAN_POINT ( 'NONE', ( 36.04562886062198857, 218.5902260770999987, 75.53673388173362468 ) ) ; +#8932 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364818587623, 136.5649596138779884, 181.4686487119677167 ) ) ; +#8933 = ORIENTED_EDGE ( 'NONE', *, *, #33990, .T. ) ; +#8934 = LINE ( 'NONE', #20990, #13232 ) ; +#8935 = ORIENTED_EDGE ( 'NONE', *, *, #4551, .T. ) ; +#8936 = EDGE_LOOP ( 'NONE', ( #25796, #16078, #32976, #3398 ) ) ; +#8937 = CARTESIAN_POINT ( 'NONE', ( 2.941278393888057341, 209.7096877029368613, 73.05672770647804271 ) ) ; +#8938 = AXIS2_PLACEMENT_3D ( 'NONE', #27319, #36901, #3483 ) ; +#8939 = DIRECTION ( 'NONE', ( -0.7700768272164115746, -0.6290960810766029754, 0.1059235618659280648 ) ) ; +#8940 = AXIS2_PLACEMENT_3D ( 'NONE', #2044, #21055, #33908 ) ; +#8941 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023851578 ) ) ; +#8942 = ORIENTED_EDGE ( 'NONE', *, *, #38023, .T. ) ; +#8943 = FACE_OUTER_BOUND ( 'NONE', #2492, .T. ) ; +#8944 = ORIENTED_EDGE ( 'NONE', *, *, #35864, .F. ) ; +#8945 = AXIS2_PLACEMENT_3D ( 'NONE', #4729, #26023, #4318 ) ; +#8946 = CARTESIAN_POINT ( 'NONE', ( 14.17036435349962353, 176.4975660804189488, 100.9051904591885886 ) ) ; +#8947 = CONICAL_SURFACE ( 'NONE', #28518, 2.249999999906822978, 0.7853981633778703841 ) ; +#8948 = CARTESIAN_POINT ( 'NONE', ( -6.038589899303025810, 135.0345199613422551, 90.99097522609406496 ) ) ; +#8949 = ORIENTED_EDGE ( 'NONE', *, *, #25034, .F. ) ; +#8950 = CARTESIAN_POINT ( 'NONE', ( -20.99834812677269369, 175.6169579277373032, 103.1178387243066510 ) ) ; +#8951 = CARTESIAN_POINT ( 'NONE', ( -15.66640061118684812, 151.8962593205783946, 95.07257227604921468 ) ) ; +#8952 = CARTESIAN_POINT ( 'NONE', ( -37.24442942593478278, 164.8639741617558059, 196.9343803322838369 ) ) ; +#8953 = CARTESIAN_POINT ( 'NONE', ( 20.50176505208000322, 157.9337197842999956, 99.18132479289999992 ) ) ; +#8954 = CARTESIAN_POINT ( 'NONE', ( 5.704476631508000217, 114.0103269029000188, 152.4718672074000381 ) ) ; +#8955 = EDGE_LOOP ( 'NONE', ( #22217, #3988, #8518, #25010 ) ) ; +#8956 = DIRECTION ( 'NONE', ( -0.0005884949961208347504, 0.2249510543439081633, -0.9743698870671259060 ) ) ; +#8957 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#8958 = CARTESIAN_POINT ( 'NONE', ( -40.55546040088514559, 184.3694242608361265, 104.8082136547167096 ) ) ; +#8959 = VERTEX_POINT ( 'NONE', #6955 ) ; +#8960 = CARTESIAN_POINT ( 'NONE', ( 30.06604060545006973, 134.3090764877889569, 93.66925167689640830 ) ) ; +#8961 = EDGE_CURVE ( 'NONE', #26268, #1952, #11945, .T. ) ; +#8962 = CARTESIAN_POINT ( 'NONE', ( -28.46737701145232791, 128.5818728664343951, 89.35557892710436079 ) ) ; +#8963 = ADVANCED_FACE ( 'NONE', ( #38240 ), #33888, .T. ) ; +#8964 = VERTEX_POINT ( 'NONE', #31723 ) ; +#8965 = CARTESIAN_POINT ( 'NONE', ( 22.53365398946230158, 145.9296226677156767, 152.0219650208057089 ) ) ; +#8966 = AXIS2_PLACEMENT_3D ( 'NONE', #25289, #19326, #31824 ) ; +#8967 = FACE_OUTER_BOUND ( 'NONE', #4342, .T. ) ; +#8968 = CARTESIAN_POINT ( 'NONE', ( 35.72955092202045080, 193.9703422006220705, 102.7464518626500904 ) ) ; +#8969 = DIRECTION ( 'NONE', ( -0.5614015438086682463, -0.2604365532041851283, -0.7854941809869552261 ) ) ; +#8970 = ORIENTED_EDGE ( 'NONE', *, *, #22325, .T. ) ; +#8971 = CARTESIAN_POINT ( 'NONE', ( -20.89133279417689337, 135.6510826495900517, 94.06197212497137627 ) ) ; +#8972 = DIRECTION ( 'NONE', ( 0.5987319967475925875, 0.8009494341533932582, 0.000000000000000000 ) ) ; +#8973 = CARTESIAN_POINT ( 'NONE', ( -6.035970131896196911, 174.6797516720102976, 103.0634797155744167 ) ) ; +#8974 = CARTESIAN_POINT ( 'NONE', ( -23.79008126526258593, 115.2160427521631334, 90.28215345216254661 ) ) ; +#8975 = CARTESIAN_POINT ( 'NONE', ( 3.188020543578640176, 126.4217074165510439, 88.83774635480644122 ) ) ; +#8976 = ORIENTED_EDGE ( 'NONE', *, *, #37096, .T. ) ; +#8977 = VERTEX_POINT ( 'NONE', #3684 ) ; +#8978 = CARTESIAN_POINT ( 'NONE', ( 39.39884470921000315, 119.4108113951999997, 87.86449634650999485 ) ) ; +#8979 = PLANE ( 'NONE', #16003 ) ; +#8980 = CARTESIAN_POINT ( 'NONE', ( 36.75369171218457609, 191.6321295115402563, 104.3442627534098506 ) ) ; +#8981 = CARTESIAN_POINT ( 'NONE', ( -17.26244873158546511, 152.5112902433045861, 182.5794626460271957 ) ) ; +#8982 = EDGE_LOOP ( 'NONE', ( #21849, #15992, #9779, #33763 ) ) ; +#8983 = DIRECTION ( 'NONE', ( -0.0005884949961221956410, 0.2249510543439041110, -0.9743698870671267942 ) ) ; +#8984 = DIRECTION ( 'NONE', ( -0.7933533411653341805, 0.5930537057989598848, 0.1373964268091485141 ) ) ; +#8985 = CARTESIAN_POINT ( 'NONE', ( 24.14312846718948435, 213.8597117594435701, 73.04392223777644233 ) ) ; +#8986 = CARTESIAN_POINT ( 'NONE', ( 12.63828875764826343, 181.2191498300309149, 104.3877799491323657 ) ) ; +#8987 = ADVANCED_FACE ( 'NONE', ( #10251 ), #4075, .F. ) ; +#8988 = CARTESIAN_POINT ( 'NONE', ( 15.05323202847136876, 135.9260618574729165, 94.10374647281754790 ) ) ; +#8989 = AXIS2_PLACEMENT_3D ( 'NONE', #16569, #22544, #28467 ) ; +#8990 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048993906, 177.1117171981997558, 103.6430084149375688 ) ) ; +#8991 = CONICAL_SURFACE ( 'NONE', #31192, 3.002819725383311322, 0.7853589219486486472 ) ; +#8992 = DIRECTION ( 'NONE', ( -0.0005884949961216158097, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#8993 = COORDINATED_UNIVERSAL_TIME_OFFSET ( 8, 0, .AHEAD. ) ; +#8994 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; +#8995 = CARTESIAN_POINT ( 'NONE', ( 36.74499328828947142, 191.3591568088928909, 106.3388620510278457 ) ) ; +#8996 = DIRECTION ( 'NONE', ( -8.006416042957766484E-15, 0.9743700557921585181, 0.2249510932971565125 ) ) ; +#8997 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #27500, #36665 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#8998 = DIRECTION ( 'NONE', ( 0.7942820423213362568, 0.5918950211223029667, 0.1370267171630251968 ) ) ; +#8999 = CARTESIAN_POINT ( 'NONE', ( 37.96499713718259983, 190.9621088645640157, 106.2897951478049947 ) ) ; +#9000 = ORIENTED_EDGE ( 'NONE', *, *, #23613, .F. ) ; +#9002 = EDGE_LOOP ( 'NONE', ( #27435, #916 ) ) ; +#9001 = CARTESIAN_POINT ( 'NONE', ( 36.62814241374000090, 191.2703535884000132, 106.4498546874999931 ) ) ; +#9003 = EDGE_LOOP ( 'NONE', ( #23769, #37028, #4048, #4094 ) ) ; +#9004 = ORIENTED_EDGE ( 'NONE', *, *, #2020, .F. ) ; +#9005 = DIRECTION ( 'NONE', ( 1.110223024561561099E-14, 0.9743700557921592953, 0.2249510932971529042 ) ) ; +#9006 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#9007 = CARTESIAN_POINT ( 'NONE', ( -31.60569785394651277, 177.3017686088606126, 100.6053507231819566 ) ) ; +#9008 = EDGE_CURVE ( 'NONE', #39273, #14135, #822, .T. ) ; +#9009 = VERTEX_POINT ( 'NONE', #6547 ) ; +#9010 = CARTESIAN_POINT ( 'NONE', ( -39.19212960309999971, 119.4692301673999992, 90.21497160778000080 ) ) ; +#9011 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825968184599486, 0.0005734119012737704749 ) ) ; +#9012 = LINE ( 'NONE', #5517, #17039 ) ; +#9013 = VERTEX_POINT ( 'NONE', #3882 ) ; +#9014 = CARTESIAN_POINT ( 'NONE', ( 15.50029468041064362, 174.4049028184014105, 100.4212577462938327 ) ) ; +#9015 = VECTOR ( 'NONE', #29425, 1000.000000000000114 ) ; +#9016 = DIRECTION ( 'NONE', ( 0.7066903926851649809, 0.000000000000000000, -0.7075229246367126246 ) ) ; +#9017 = CARTESIAN_POINT ( 'NONE', ( 36.94455153219831089, 117.2454428897012519, 90.24547125583531226 ) ) ; +#9018 = AXIS2_PLACEMENT_3D ( 'NONE', #7712, #7919, #29207 ) ; +#9019 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563182 ) ) ; +#9020 = ORIENTED_EDGE ( 'NONE', *, *, #17828, .F. ) ; +#9021 = CARTESIAN_POINT ( 'NONE', ( -26.85016591629000260, 189.2575623740999902, 103.2237545534000134 ) ) ; +#9022 = DIRECTION ( 'NONE', ( -0.0005884949961270922233, 0.2249510543439054433, -0.9743698870671265722 ) ) ; +#9023 = CARTESIAN_POINT ( 'NONE', ( -37.31403596624686969, 185.5641699427571893, 107.6478458894942065 ) ) ; +#9024 = ORIENTED_EDGE ( 'NONE', *, *, #13376, .F. ) ; +#9025 = ORIENTED_EDGE ( 'NONE', *, *, #23583, .T. ) ; +#9026 = CARTESIAN_POINT ( 'NONE', ( 38.29411851311186865, 218.5902260770999987, 73.03537539441880710 ) ) ; +#9027 = ORIENTED_EDGE ( 'NONE', *, *, #18205, .T. ) ; +#9028 = EDGE_CURVE ( 'NONE', #9881, #18343, #1766, .T. ) ; +#9029 = CARTESIAN_POINT ( 'NONE', ( -36.55029116362000252, 191.5651398178999898, 104.9986570192999977 ) ) ; +#9030 = CARTESIAN_POINT ( 'NONE', ( 14.89441505909820762, 175.5348048312332025, 102.9061423033102756 ) ) ; +#9031 = CARTESIAN_POINT ( 'NONE', ( -25.50945386513487989, 211.0902258593999932, 74.23939878291034233 ) ) ; +#9032 = CARTESIAN_POINT ( 'NONE', ( 44.87027855527305320, 186.7831729946450992, 105.8418005208418435 ) ) ; +#9033 = CARTESIAN_POINT ( 'NONE', ( -5.670672681055139108, 181.8783021462742227, 101.9067947796755931 ) ) ; +#9034 = CARTESIAN_POINT ( 'NONE', ( -0.6722830789079499159, 188.9999999857274418, 105.7361035176449349 ) ) ; +#9035 = ORIENTED_EDGE ( 'NONE', *, *, #33176, .F. ) ; +#9036 = EDGE_CURVE ( 'NONE', #9304, #29634, #39105, .T. ) ; +#9037 = CARTESIAN_POINT ( 'NONE', ( -22.49823188806079344, 127.0672912568829247, 92.08444022695447018 ) ) ; +#9038 = AXIS2_PLACEMENT_3D ( 'NONE', #31147, #245, #18836 ) ; +#9039 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#9040 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#9041 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6237, #18691, #33648, #24064, #31194, #15645 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9042 = VECTOR ( 'NONE', #9145, 1000.000000000000000 ) ; +#9044 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 67.27946979429627561, 310.0857197240632104 ) ) ; +#9043 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971574007 ) ) ; +#9045 = EDGE_CURVE ( 'NONE', #2967, #19190, #34367, .T. ) ; +#9046 = ORIENTED_EDGE ( 'NONE', *, *, #7350, .F. ) ; +#9047 = EDGE_CURVE ( 'NONE', #5617, #4266, #21514, .T. ) ; +#9048 = EDGE_CURVE ( 'NONE', #7852, #36789, #9988, .T. ) ; +#9049 = ORIENTED_EDGE ( 'NONE', *, *, #28884, .F. ) ; +#9051 = ADVANCED_FACE ( 'NONE', ( #32509 ), #11049, .F. ) ; +#9050 = CARTESIAN_POINT ( 'NONE', ( 30.17614581013264186, 126.7625099995479445, 88.90012669361888697 ) ) ; +#9052 = CARTESIAN_POINT ( 'NONE', ( 13.50176809758824703, 126.1286536816045327, 91.84597050332364176 ) ) ; +#9053 = EDGE_CURVE ( 'NONE', #20341, #30736, #29449, .T. ) ; +#9054 = CARTESIAN_POINT ( 'NONE', ( 39.63353669152581915, 119.7633698288389184, 87.79166280016082169 ) ) ; +#9055 = CARTESIAN_POINT ( 'NONE', ( -25.49128147572124092, 192.8634534852218110, 104.3291085408993411 ) ) ; +#9056 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250095806, 177.4328783376051888, 101.1405542638008939 ) ) ; +#9057 = VERTEX_POINT ( 'NONE', #1222 ) ; +#9058 = VERTEX_POINT ( 'NONE', #26193 ) ; +#9059 = CARTESIAN_POINT ( 'NONE', ( -20.01813817220386937, 208.9308472833029953, 76.18768590624890180 ) ) ; +#9060 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.271205363196006660E-14, -0.9999998176071844824 ) ) ; +#9061 = DIRECTION ( 'NONE', ( 0.0005884949961243157984, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#9062 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25350, #29215, #34710, #6919 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 2.725652208953761146, 4.544051345060554858 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7429183312171805387, 0.7429183312171805387, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#9063 = FACE_OUTER_BOUND ( 'NONE', #12761, .T. ) ; +#9064 = ORIENTED_EDGE ( 'NONE', *, *, #8590, .F. ) ; +#9065 = ORIENTED_EDGE ( 'NONE', *, *, #14466, .F. ) ; +#9066 = AXIS2_PLACEMENT_3D ( 'NONE', #21933, #18424, #5779 ) ; +#9067 = CARTESIAN_POINT ( 'NONE', ( 35.79920382921711308, 209.7096538412770030, 75.78427872630588524 ) ) ; +#9068 = CARTESIAN_POINT ( 'NONE', ( -14.20829634260898544, 150.7122502792225873, 27.79156830144150092 ) ) ; +#9069 = VECTOR ( 'NONE', #34478, 1000.000000000000114 ) ; +#9070 = CARTESIAN_POINT ( 'NONE', ( 2.441738457499000425, 189.8317159618999881, 106.1741859263999999 ) ) ; +#9071 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825928200210802, -0.0005734119021977812343 ) ) ; +#9072 = ADVANCED_FACE ( 'NONE', ( #7556 ), #38631, .T. ) ; +#9073 = DIRECTION ( 'NONE', ( -0.7933532970003751572, -0.5930762008556708098, -0.1372995488602872238 ) ) ; +#9074 = CARTESIAN_POINT ( 'NONE', ( 20.16822828554578706, 137.8789466221655857, 94.38057372190250760 ) ) ; +#9075 = FACE_OUTER_BOUND ( 'NONE', #20728, .T. ) ; +#9076 = ORIENTED_EDGE ( 'NONE', *, *, #19316, .F. ) ; +#9077 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620729128, 0.0004744508866335443741 ) ) ; +#9078 = CARTESIAN_POINT ( 'NONE', ( -20.24273581848683889, 127.1220280533010225, 91.84170706686390417 ) ) ; +#9079 = EDGE_LOOP ( 'NONE', ( #3192, #105, #8008, #28507 ) ) ; +#9080 = CARTESIAN_POINT ( 'NONE', ( 29.17518171049927034, 209.7097231784644009, 73.04088300409637213 ) ) ; +#9081 = ORIENTED_EDGE ( 'NONE', *, *, #26780, .T. ) ; +#9083 = CARTESIAN_POINT ( 'NONE', ( 35.56396753058658078, 192.2313336904389871, 103.8839717972468719 ) ) ; +#9082 = CARTESIAN_POINT ( 'NONE', ( 16.28891463742873569, 151.6603294600179765, 160.4527445207948801 ) ) ; +#9084 = EDGE_LOOP ( 'NONE', ( #17796, #31488, #40241, #5543 ) ) ; +#9086 = EDGE_LOOP ( 'NONE', ( #11510, #15328, #18428, #5179 ) ) ; +#9085 = EDGE_CURVE ( 'NONE', #11474, #11331, #23114, .T. ) ; +#9087 = ORIENTED_EDGE ( 'NONE', *, *, #26316, .T. ) ; +#9088 = CARTESIAN_POINT ( 'NONE', ( 3.180503606262000016, 209.1196423350000089, 76.28617253618000404 ) ) ; +#9089 = EDGE_CURVE ( 'NONE', #27242, #4266, #8540, .T. ) ; +#9090 = CIRCLE ( 'NONE', #37827, 2.000000000000011546 ) ; +#9091 = CARTESIAN_POINT ( 'NONE', ( -25.83320125070846274, 118.1125350644666696, 90.11672424654607028 ) ) ; +#9092 = LINE ( 'NONE', #21580, #9339 ) ; +#9093 = CONICAL_SURFACE ( 'NONE', #12352, 3.005897397098168167, 0.7853589132598342015 ) ; +#9094 = CARTESIAN_POINT ( 'NONE', ( 44.30339254327586218, 188.9591885891941558, 103.2508314896253552 ) ) ; +#9095 = ORIENTED_EDGE ( 'NONE', *, *, #38380, .F. ) ; +#9096 = VERTEX_POINT ( 'NONE', #38830 ) ; +#9097 = ADVANCED_FACE ( 'NONE', ( #13907 ), #9093, .F. ) ; +#9098 = CIRCLE ( 'NONE', #19520, 51.90509898892980090 ) ; +#9099 = ORIENTED_EDGE ( 'NONE', *, *, #29264, .T. ) ; +#9100 = ORIENTED_EDGE ( 'NONE', *, *, #10938, .F. ) ; +#9102 = EDGE_CURVE ( 'NONE', #8778, #11332, #13887, .T. ) ; +#9101 = PLANE ( 'NONE', #4768 ) ; +#9103 = CARTESIAN_POINT ( 'NONE', ( -19.37816306946693956, 125.5365691439678244, 178.4012088705679560 ) ) ; +#9104 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640315690, 0.2252353050503788645 ) ) ; +#9105 = LINE ( 'NONE', #27537, #32002 ) ; +#9106 = VERTEX_POINT ( 'NONE', #35956 ) ; +#9107 = VERTEX_POINT ( 'NONE', #33105 ) ; +#9108 = CARTESIAN_POINT ( 'NONE', ( 25.99018610745488900, 211.0908525021142168, 73.04280463953621449 ) ) ; +#9109 = DIRECTION ( 'NONE', ( -0.0006039748319343064527, 0.000000000000000000, -0.9999998176071845934 ) ) ; +#9110 = CARTESIAN_POINT ( 'NONE', ( -28.46687738437000093, 130.4181374611307263, 90.29266601293539907 ) ) ; +#9111 = EDGE_LOOP ( 'NONE', ( #10314, #152, #3315, #7523 ) ) ; +#9112 = CARTESIAN_POINT ( 'NONE', ( 15.99998378901094576, 184.9656665294078266, 102.3459542884652365 ) ) ; +#9113 = ORIENTED_EDGE ( 'NONE', *, *, #16273, .F. ) ; +#9114 = CARTESIAN_POINT ( 'NONE', ( -22.49970497326689767, 174.4001378592136575, 100.4431087167393031 ) ) ; +#9115 = CARTESIAN_POINT ( 'NONE', ( -23.36013443277664692, 183.4461002756636674, 105.1009555742510031 ) ) ; +#9116 = CARTESIAN_POINT ( 'NONE', ( -40.39772054252907907, 190.1557916721299932, 106.7158979401700947 ) ) ; +#9117 = ORIENTED_EDGE ( 'NONE', *, *, #1032, .T. ) ; +#9118 = LINE ( 'NONE', #30794, #36605 ) ; +#9119 = DIRECTION ( 'NONE', ( 0.0005884949961248443469, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#9120 = VECTOR ( 'NONE', #14649, 1000.000000000000000 ) ; +#9121 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049007406, 177.1117171981941851, 103.6430084149362898 ) ) ; +#9122 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480527206264441, 0.5299193337450082142 ) ) ; +#9123 = CIRCLE ( 'NONE', #32634, 2.500000000047894133 ) ; +#9124 = ORIENTED_EDGE ( 'NONE', *, *, #26536, .F. ) ; +#9125 = CARTESIAN_POINT ( 'NONE', ( 25.40348470219815624, 116.2738580246023474, 90.25244177100570653 ) ) ; +#9126 = ORIENTED_EDGE ( 'NONE', *, *, #23820, .T. ) ; +#9127 = CIRCLE ( 'NONE', #36550, 2.749999999927935423 ) ; +#9128 = CARTESIAN_POINT ( 'NONE', ( 36.61849814939751724, 77.14301703113001452, 291.5364272799121750 ) ) ; +#9129 = FACE_OUTER_BOUND ( 'NONE', #13265, .T. ) ; +#9130 = CONICAL_SURFACE ( 'NONE', #13038, 5.003486694794308853, 0.7853981633880587898 ) ; +#9131 = CARTESIAN_POINT ( 'NONE', ( 25.49182901039327831, 209.7089661076149127, 75.54314178666862745 ) ) ; +#9132 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; +#9133 = EDGE_CURVE ( 'NONE', #372, #20220, #35405, .T. ) ; +#9134 = ORIENTED_EDGE ( 'NONE', *, *, #7825, .T. ) ; +#9135 = EDGE_CURVE ( 'NONE', #29784, #36964, #14308, .T. ) ; +#9136 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16796, #24385, #11693, #27044, #8218, #36425 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9137 = CARTESIAN_POINT ( 'NONE', ( -38.20245686653000661, 118.7297676069999994, 90.14874192493999772 ) ) ; +#9138 = CARTESIAN_POINT ( 'NONE', ( 15.66823977521199218, 185.3098073501215026, 105.1624151300140397 ) ) ; +#9139 = ORIENTED_EDGE ( 'NONE', *, *, #5136, .F. ) ; +#9140 = DIRECTION ( 'NONE', ( -0.1305262373691798983, 0.9659583596717404852, 0.2233547598295697878 ) ) ; +#9141 = EDGE_CURVE ( 'NONE', #7741, #1667, #35748, .T. ) ; +#9142 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524656274, 149.3470289647502511, 130.0514119197545142 ) ) ; +#9143 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22673, #35298, #19575, #10399, #22869, #36338, #2202, #1577, #4643, #20793 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000001860734, 0.3750000000002791101, 0.4375000000002600697, 0.5000000000002410294, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9144 = CARTESIAN_POINT ( 'NONE', ( -15.49970617573983311, 151.8558896894846839, 95.23413014739874427 ) ) ; +#9145 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#9146 = CARTESIAN_POINT ( 'NONE', ( -37.15756392146106890, 117.7187502869175688, 90.29022707672584147 ) ) ; +#9147 = VERTEX_POINT ( 'NONE', #1840 ) ; +#9148 = EDGE_CURVE ( 'NONE', #4337, #18000, #3659, .T. ) ; +#9150 = AXIS2_PLACEMENT_3D ( 'NONE', #29833, #17733, #11632 ) ; +#9149 = DIRECTION ( 'NONE', ( -0.0005884949961228161299, 0.2249510543439076360, -0.9743698870671260170 ) ) ; +#9151 = AXIS2_PLACEMENT_3D ( 'NONE', #28313, #5622, #18077 ) ; +#9152 = CARTESIAN_POINT ( 'NONE', ( 15.83329133259355892, 160.6986494121390763, 96.91476092110876550 ) ) ; +#9153 = VECTOR ( 'NONE', #27967, 1000.000000000000000 ) ; +#9154 = ORIENTED_EDGE ( 'NONE', *, *, #6038, .T. ) ; +#9155 = DIRECTION ( 'NONE', ( 0.9999998176071458467, 6.423608955952692560E-11, -0.0006039748961739839408 ) ) ; +#9156 = CIRCLE ( 'NONE', #30728, 2.000000000040583092 ) ; +#9157 = CARTESIAN_POINT ( 'NONE', ( 15.99974815555098218, 138.5019114137554936, 91.61902897505088106 ) ) ; +#9158 = EDGE_LOOP ( 'NONE', ( #36011, #18686, #35781, #17721 ) ) ; +#9159 = DIRECTION ( 'NONE', ( -0.1843855713908465477, -0.08049128666858569592, 0.9795525069302342125 ) ) ; +#9160 = EDGE_CURVE ( 'NONE', #4109, #1948, #30467, .T. ) ; +#9161 = LINE ( 'NONE', #27981, #20586 ) ; +#9162 = CARTESIAN_POINT ( 'NONE', ( -43.34074992346683786, 121.9127549832748514, 88.07565497363744100 ) ) ; +#9163 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39819, #5476, #29625, #14492 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0009046650482442253728, 0.0009710577665168405566 ), + .UNSPECIFIED. ) ; +#9164 = ORIENTED_EDGE ( 'NONE', *, *, #15911, .F. ) ; +#9165 = CARTESIAN_POINT ( 'NONE', ( 36.10151592346490190, 191.1961136956948906, 106.8385014937324655 ) ) ; +#9166 = CARTESIAN_POINT ( 'NONE', ( -2.464592264399565469, 152.1442425547639630, 99.91119810786710786 ) ) ; +#9167 = CARTESIAN_POINT ( 'NONE', ( -37.24083814574551354, 106.2470826507470889, 174.4507514582041381 ) ) ; +#9168 = CARTESIAN_POINT ( 'NONE', ( 13.47462245814947934, 158.2310456470601423, 98.74105996008697161 ) ) ; +#9169 = CARTESIAN_POINT ( 'NONE', ( -22.49823197028072030, 137.5162774524455358, 94.49663580420342157 ) ) ; +#9170 = ORIENTED_EDGE ( 'NONE', *, *, #32238, .F. ) ; +#9171 = VERTEX_POINT ( 'NONE', #8390 ) ; +#9172 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#9173 = DIRECTION ( 'NONE', ( 0.0005884949961181604574, -0.2249510543439091625, 0.9743698870671256840 ) ) ; +#9174 = LINE ( 'NONE', #2829, #9069 ) ; +#9175 = CYLINDRICAL_SURFACE ( 'NONE', #39278, 48.00000000000002132 ) ; +#9176 = ORIENTED_EDGE ( 'NONE', *, *, #35, .F. ) ; +#9177 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971596766 ) ) ; +#9178 = CARTESIAN_POINT ( 'NONE', ( -28.47263367539243717, 181.2100821311606467, 104.4136188016237412 ) ) ; +#9179 = CARTESIAN_POINT ( 'NONE', ( 15.83343177718414552, 127.7072229588672485, 89.29794427536299395 ) ) ; +#9180 = CONICAL_SURFACE ( 'NONE', #35905, 2.503000015132546885, 0.7853981633220994407 ) ; +#9181 = CONICAL_SURFACE ( 'NONE', #15699, 2.502999999838765088, 0.7853981634080003937 ) ; +#9182 = CARTESIAN_POINT ( 'NONE', ( -20.49957889925088139, 194.9089184157244574, 105.3865625666390713 ) ) ; +#9183 = CARTESIAN_POINT ( 'NONE', ( -25.83759314228409210, 190.9097546720246896, 106.6513809942738931 ) ) ; +#9184 = AXIS2_PLACEMENT_3D ( 'NONE', #23615, #4588, #5404 ) ; +#9185 = CARTESIAN_POINT ( 'NONE', ( -30.11575774535129923, 182.2816626742635435, 101.7541501812646487 ) ) ; +#9186 = ADVANCED_FACE ( 'NONE', ( #30062 ), #33711, .F. ) ; +#9187 = AXIS2_PLACEMENT_3D ( 'NONE', #29166, #12819, #6658 ) ; +#9188 = EDGE_CURVE ( 'NONE', #35508, #26180, #14991, .T. ) ; +#9189 = EDGE_CURVE ( 'NONE', #9773, #13129, #24487, .T. ) ; +#9190 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7587, #10878, #29281, #29075 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9191 = PERSON_AND_ORGANIZATION_ROLE ( 'creator' ) ; +#9192 = CARTESIAN_POINT ( 'NONE', ( 4.701270843627139762, 181.8782530787316318, 101.6399871078483415 ) ) ; +#9193 = CARTESIAN_POINT ( 'NONE', ( -37.13575228356130253, 117.3340227016620787, 87.73004207770956953 ) ) ; +#9194 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; +#9195 = EDGE_CURVE ( 'NONE', #12564, #2594, #11000, .T. ) ; +#9196 = CARTESIAN_POINT ( 'NONE', ( 77.66020299980834807, 192.0465887426067866, 194.3137169050042701 ) ) ; +#9197 = CARTESIAN_POINT ( 'NONE', ( 36.36655296585029618, 191.7208402573679962, 106.4157350352320037 ) ) ; +#9198 = VERTEX_POINT ( 'NONE', #27819 ) ; +#9199 = CARTESIAN_POINT ( 'NONE', ( 36.66573766188999883, 191.2416103959000111, 106.4445292027000107 ) ) ; +#9200 = ORIENTED_EDGE ( 'NONE', *, *, #1697, .F. ) ; +#9201 = ORIENTED_EDGE ( 'NONE', *, *, #7198, .F. ) ; +#9202 = ORIENTED_EDGE ( 'NONE', *, *, #3031, .T. ) ; +#9203 = EDGE_CURVE ( 'NONE', #12706, #16466, #2252, .T. ) ; +#9204 = CARTESIAN_POINT ( 'NONE', ( -0.03375341898833555260, -31.76863880746333280, 137.4221703796379188 ) ) ; +#9205 = CARTESIAN_POINT ( 'NONE', ( -20.21994974020127955, 184.9112019368533026, 102.5811191251855661 ) ) ; +#9206 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35840, #20108, #36051, #10942 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9207 = CARTESIAN_POINT ( 'NONE', ( 31.79177573931936962, 115.2378407561303391, 176.5461501322318725 ) ) ; +#9208 = CARTESIAN_POINT ( 'NONE', ( -38.90532417260193654, 169.1823092633644023, 183.8675584944714387 ) ) ; +#9209 = VERTEX_POINT ( 'NONE', #17760 ) ; +#9210 = CARTESIAN_POINT ( 'NONE', ( -39.21221060463999919, 118.9500855288000025, 89.58294657444000109 ) ) ; +#9211 = EDGE_CURVE ( 'NONE', #10701, #21872, #34860, .T. ) ; +#9212 = AXIS2_PLACEMENT_3D ( 'NONE', #12912, #37839, #35345 ) ; +#9213 = CARTESIAN_POINT ( 'NONE', ( -15.38986229257041849, 129.3784849134285935, 89.53159292728777530 ) ) ; +#9214 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971577337 ) ) ; +#9215 = CARTESIAN_POINT ( 'NONE', ( 0.05270753573795999847, 0.000000000000000000, 87.26775245800000391 ) ) ; +#9216 = ORIENTED_EDGE ( 'NONE', *, *, #16815, .F. ) ; +#9217 = CARTESIAN_POINT ( 'NONE', ( 20.50176505208000322, 136.5173134723999908, 94.23695690543999604 ) ) ; +#9218 = VECTOR ( 'NONE', #33786, 1000.000000000000114 ) ; +#9219 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567345 ) ) ; +#9220 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971560406 ) ) ; +#9221 = DIRECTION ( 'NONE', ( 0.0005884949961235717104, -0.2249510543439064147, 0.9743698870671262391 ) ) ; +#9222 = CARTESIAN_POINT ( 'NONE', ( -5.345045829023177042, 188.3421103602547078, 103.1383541418427825 ) ) ; +#9223 = DIRECTION ( 'NONE', ( -0.9914447795421099663, -0.1272537940605282525, -0.02904687618140097335 ) ) ; +#9224 = ORIENTED_EDGE ( 'NONE', *, *, #13298, .F. ) ; +#9225 = CARTESIAN_POINT ( 'NONE', ( -25.62364350484000042, 191.5126371725000070, 104.2709893052000183 ) ) ; +#9226 = CARTESIAN_POINT ( 'NONE', ( 2.551106744431880013, 190.8269631700860032, 104.2238537024139902 ) ) ; +#9227 = LINE ( 'NONE', #28041, #11019 ) ; +#9228 = ORIENTED_EDGE ( 'NONE', *, *, #15816, .F. ) ; +#9229 = ORIENTED_EDGE ( 'NONE', *, *, #39073, .F. ) ; +#9230 = CARTESIAN_POINT ( 'NONE', ( 42.85442617173308832, 113.6598254356972149, 123.5406245648973993 ) ) ; +#9231 = ORIENTED_EDGE ( 'NONE', *, *, #10483, .F. ) ; +#9232 = CARTESIAN_POINT ( 'NONE', ( 20.00174584374092035, 192.4630694782412093, 106.9093782835173272 ) ) ; +#9233 = CARTESIAN_POINT ( 'NONE', ( -38.45586748819795986, 218.5902260770999987, 73.08173046273984141 ) ) ; +#9234 = ADVANCED_FACE ( 'NONE', ( #8593 ), #15131, .F. ) ; +#9235 = EDGE_CURVE ( 'NONE', #10196, #22508, #18291, .T. ) ; +#9236 = CARTESIAN_POINT ( 'NONE', ( -35.93177844966999857, 192.5575653067000133, 105.7869005091999952 ) ) ; +#9237 = CARTESIAN_POINT ( 'NONE', ( -12.63302500439942477, 177.0349334693919729, 103.5018215138099293 ) ) ; +#9238 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#9239 = AXIS2_PLACEMENT_3D ( 'NONE', #3080, #37038, #36428 ) ; +#9240 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9514, #35369, #35168, #23342 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9241 = CARTESIAN_POINT ( 'NONE', ( 25.80813857899862640, 134.9224874684686597, 90.78667747519583031 ) ) ; +#9242 = FACE_OUTER_BOUND ( 'NONE', #27910, .T. ) ; +#9243 = ORIENTED_EDGE ( 'NONE', *, *, #30308, .T. ) ; +#9244 = CARTESIAN_POINT ( 'NONE', ( 22.73844078587000084, 180.7017300104000128, 28.07991271570000080 ) ) ; +#9245 = CARTESIAN_POINT ( 'NONE', ( -35.97272584480918312, 191.5347990022295050, 103.8939579469935524 ) ) ; +#9246 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971549582 ) ) ; +#9247 = ADVANCED_FACE ( 'NONE', ( #17559 ), #2050, .F. ) ; +#9249 = CARTESIAN_POINT ( 'NONE', ( 22.50034184233011914, 153.8097659799650501, 95.66226703669086362 ) ) ; +#9248 = CARTESIAN_POINT ( 'NONE', ( -28.46561152636741809, 183.4461128628643962, 105.1009010528843390 ) ) ; +#9250 = VERTEX_POINT ( 'NONE', #36391 ) ; +#9251 = CARTESIAN_POINT ( 'NONE', ( -36.27941088227176181, 191.8189068658341796, 104.4052308140100820 ) ) ; +#9252 = ORIENTED_EDGE ( 'NONE', *, *, #39725, .F. ) ; +#9253 = VERTEX_POINT ( 'NONE', #27003 ) ; +#9254 = CARTESIAN_POINT ( 'NONE', ( -5.669730063980141566, 182.0627683792234848, 102.2020018026141486 ) ) ; +#9255 = EDGE_CURVE ( 'NONE', #32868, #275, #28050, .T. ) ; +#9256 = CARTESIAN_POINT ( 'NONE', ( -6.037582702418865743, 135.2929569925057365, 91.40456025213514124 ) ) ; +#9257 = CARTESIAN_POINT ( 'NONE', ( -25.49160734743147927, 193.7303623055392165, 103.7895634579492139 ) ) ; +#9258 = CARTESIAN_POINT ( 'NONE', ( -12.63910804469136018, 135.1699220826425005, 91.21284715633554185 ) ) ; +#9259 = ORIENTED_EDGE ( 'NONE', *, *, #4039, .T. ) ; +#9260 = EDGE_LOOP ( 'NONE', ( #29024, #30174, #29760, #3819 ) ) ; +#9261 = CARTESIAN_POINT ( 'NONE', ( -8.050307609250221930, 161.2716461841048101, 96.89027781497259184 ) ) ; +#9262 = CIRCLE ( 'NONE', #26888, 7.999999999999992895 ) ; +#9263 = DIRECTION ( 'NONE', ( -0.6087613505917195411, 0.7729391288371411095, 0.1788147676737769087 ) ) ; +#9264 = VECTOR ( 'NONE', #22255, 1000.000000000000114 ) ; +#9265 = ORIENTED_EDGE ( 'NONE', *, *, #17828, .T. ) ; +#9266 = CARTESIAN_POINT ( 'NONE', ( -35.93343814688130067, 191.2052343210330321, 106.8950642838330083 ) ) ; +#9267 = AXIS2_PLACEMENT_3D ( 'NONE', #8009, #28545, #1683 ) ; +#9268 = DIRECTION ( 'NONE', ( -0.0005884949961203652909, 0.2249510543439047217, -0.9743698870671267942 ) ) ; +#9269 = CARTESIAN_POINT ( 'NONE', ( 2.685831580372000094, 190.9740651400000218, 106.4314954190000009 ) ) ; +#9270 = EDGE_CURVE ( 'NONE', #37805, #26191, #28407, .T. ) ; +#9271 = ORIENTED_EDGE ( 'NONE', *, *, #12203, .F. ) ; +#9272 = CARTESIAN_POINT ( 'NONE', ( 0.7697222838020335578, 188.3790661465463359, 106.2290520075631264 ) ) ; +#9273 = ORIENTED_EDGE ( 'NONE', *, *, #39440, .T. ) ; +#9274 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#9275 = CARTESIAN_POINT ( 'NONE', ( 37.42082352723856076, 132.6200669550715929, 336.9739440566017379 ) ) ; +#9276 = CARTESIAN_POINT ( 'NONE', ( 22.73844078587000084, 174.8555096756470562, 26.73020615591706317 ) ) ; +#9277 = VERTEX_POINT ( 'NONE', #11860 ) ; +#9278 = CARTESIAN_POINT ( 'NONE', ( -20.02002437005085511, 209.7095682957761085, 73.07054393135327075 ) ) ; +#9279 = EDGE_CURVE ( 'NONE', #18386, #7608, #21473, .T. ) ; +#9280 = FACE_OUTER_BOUND ( 'NONE', #8575, .T. ) ; +#9281 = EDGE_CURVE ( 'NONE', #20336, #29879, #31334, .T. ) ; +#9282 = CARTESIAN_POINT ( 'NONE', ( 20.00171108015191024, 119.7153632178993377, 90.35824133875276232 ) ) ; +#9283 = DIRECTION ( 'NONE', ( -0.7933533411653075351, 0.5930537057989938576, 0.1373964268091553698 ) ) ; +#9284 = ADVANCED_FACE ( 'NONE', ( #775 ), #18973, .F. ) ; +#9285 = VERTEX_POINT ( 'NONE', #6701 ) ; +#9286 = DIRECTION ( 'NONE', ( -0.0005884949961206773243, 0.2249510543439054433, -0.9743698870671265722 ) ) ; +#9287 = ORIENTED_EDGE ( 'NONE', *, *, #22386, .F. ) ; +#9289 = CARTESIAN_POINT ( 'NONE', ( 35.56220589193565473, 192.2733171777023244, 103.8779218060368663 ) ) ; +#9288 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971558741 ) ) ; +#9290 = VERTEX_POINT ( 'NONE', #37991 ) ; +#9291 = ORIENTED_EDGE ( 'NONE', *, *, #18405, .F. ) ; +#9292 = CARTESIAN_POINT ( 'NONE', ( 25.49066424179351387, 208.8330507578011179, 73.60756374810169689 ) ) ; +#9293 = AXIS2_PLACEMENT_3D ( 'NONE', #33564, #5557, #14979 ) ; +#9294 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923337649, 151.9719590600774097, 94.73025963079751932 ) ) ; +#9295 = ORIENTED_EDGE ( 'NONE', *, *, #13010, .F. ) ; +#9296 = CARTESIAN_POINT ( 'NONE', ( 2.409583324830999906, 208.9008541284999865, 75.55482340362000571 ) ) ; +#9297 = FACE_OUTER_BOUND ( 'NONE', #34906, .T. ) ; +#9298 = ORIENTED_EDGE ( 'NONE', *, *, #8658, .T. ) ; +#9299 = ORIENTED_EDGE ( 'NONE', *, *, #18020, .T. ) ; +#9300 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -7.450515246535590627E-18, -0.0006039748319384396482 ) ) ; +#9301 = FACE_OUTER_BOUND ( 'NONE', #38349, .T. ) ; +#9302 = CARTESIAN_POINT ( 'NONE', ( 13.50310082153462687, 187.4283568871894659, 105.6628883825429313 ) ) ; +#9303 = CARTESIAN_POINT ( 'NONE', ( 22.94777843336958512, 135.0298113340575981, 90.81314969911097990 ) ) ; +#9304 = VERTEX_POINT ( 'NONE', #25341 ) ; +#9305 = VERTEX_POINT ( 'NONE', #12647 ) ; +#9306 = ORIENTED_EDGE ( 'NONE', *, *, #7732, .T. ) ; +#9307 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; +#9308 = CARTESIAN_POINT ( 'NONE', ( -23.35464359634993770, 177.7881151143831744, 100.7126876897662697 ) ) ; +#9309 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28498, #21965, #37898, #40340 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9310 = CARTESIAN_POINT ( 'NONE', ( -26.24957250174999857, 122.9022317860000015, 88.21403771043999598 ) ) ; +#9311 = VERTEX_POINT ( 'NONE', #31258 ) ; +#9312 = CARTESIAN_POINT ( 'NONE', ( 37.19332676480694744, 118.8604558151628794, 122.9910815359380507 ) ) ; +#9313 = CARTESIAN_POINT ( 'NONE', ( 41.01618596887276880, 189.1080813873311399, 107.1984901808192916 ) ) ; +#9314 = ORIENTED_EDGE ( 'NONE', *, *, #36322, .T. ) ; +#9315 = EDGE_CURVE ( 'NONE', #25669, #39751, #19731, .T. ) ; +#9316 = AXIS2_PLACEMENT_3D ( 'NONE', #6069, #36743, #139 ) ; +#9317 = CARTESIAN_POINT ( 'NONE', ( 25.99899579567569319, 120.3902236067009710, 87.43149108635580546 ) ) ; +#9318 = CARTESIAN_POINT ( 'NONE', ( 38.79583243979153195, 119.2582491005199188, 90.26888869832909279 ) ) ; +#9319 = AXIS2_PLACEMENT_3D ( 'NONE', #12883, #4050, #25356 ) ; +#9320 = ADVANCED_FACE ( 'NONE', ( #37589 ), #30702, .F. ) ; +#9321 = CIRCLE ( 'NONE', #20417, 2.500000000030116354 ) ; +#9322 = CARTESIAN_POINT ( 'NONE', ( -39.69261857620511336, 119.4152473592345842, 89.81183687744525912 ) ) ; +#9323 = CARTESIAN_POINT ( 'NONE', ( 20.49980344970378354, 118.1127835573565221, 87.75514417896067698 ) ) ; +#9324 = VERTEX_POINT ( 'NONE', #28795 ) ; +#9325 = CARTESIAN_POINT ( 'NONE', ( -38.14644832516935224, 118.6015573411539350, 87.71343857591170945 ) ) ; +#9326 = VERTEX_POINT ( 'NONE', #31678 ) ; +#9328 = EDGE_CURVE ( 'NONE', #37550, #3470, #27089, .T. ) ; +#9327 = CARTESIAN_POINT ( 'NONE', ( 32.97800373234639437, 77.14301703112774078, 291.5386260473334801 ) ) ; +#9329 = ADVANCED_FACE ( 'NONE', ( #28402 ), #31875, .F. ) ; +#9330 = CARTESIAN_POINT ( 'NONE', ( -37.87234534139999909, 118.4650738466999940, 87.61639254823001011 ) ) ; +#9331 = CARTESIAN_POINT ( 'NONE', ( 38.15918854550000106, 118.9362607739000026, 90.40236251288000346 ) ) ; +#9332 = ADVANCED_FACE ( 'NONE', ( #375 ), #33917, .F. ) ; +#9333 = ADVANCED_FACE ( 'NONE', ( #16311 ), #28010, .F. ) ; +#9334 = ORIENTED_EDGE ( 'NONE', *, *, #5392, .F. ) ; +#9335 = PLANE ( 'NONE', #34349 ) ; +#9336 = ORIENTED_EDGE ( 'NONE', *, *, #2531, .T. ) ; +#9337 = DIRECTION ( 'NONE', ( 0.0006039748319385305044, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#9338 = CARTESIAN_POINT ( 'NONE', ( -38.55330989715999834, 118.3701213246999941, 89.55576858278001851 ) ) ; +#9339 = VECTOR ( 'NONE', #34017, 1000.000000000000114 ) ; +#9340 = CARTESIAN_POINT ( 'NONE', ( -30.69780633562609751, 110.6131156702000027, 87.78632508902590814 ) ) ; +#9341 = EDGE_LOOP ( 'NONE', ( #21820, #6556 ) ) ; +#9342 = CARTESIAN_POINT ( 'NONE', ( -20.89111388057672158, 175.7038788979348283, 103.3088927995675590 ) ) ; +#9343 = CARTESIAN_POINT ( 'NONE', ( 22.50071842841086678, 154.4094130781474803, 95.28756121982962668 ) ) ; +#9344 = CARTESIAN_POINT ( 'NONE', ( -3.756824743301873770, 174.7284091586126920, 102.8468063176449903 ) ) ; +#9345 = VECTOR ( 'NONE', #15234, 1000.000000000000114 ) ; +#9346 = CARTESIAN_POINT ( 'NONE', ( -5.668109638569103659, 126.1268167267171378, 91.85392722789381992 ) ) ; +#9347 = DIRECTION ( 'NONE', ( -0.0006039748319292908250, -1.314021223879979801E-14, -0.9999998176071847045 ) ) ; +#9348 = ORIENTED_EDGE ( 'NONE', *, *, #17357, .T. ) ; +#9349 = CARTESIAN_POINT ( 'NONE', ( -19.70066204944312815, 149.3538291754968554, 182.1602101174578365 ) ) ; +#9350 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971575672 ) ) ; +#9351 = EDGE_CURVE ( 'NONE', #31797, #26863, #22273, .T. ) ; +#9352 = LINE ( 'NONE', #28362, #14426 ) ; +#9353 = ORIENTED_EDGE ( 'NONE', *, *, #21989, .T. ) ; +#9354 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501099925, 176.3833156737908041, 103.4640034347438160 ) ) ; +#9355 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058470054, 185.7947294611689983, 103.0635929737944565 ) ) ; +#9356 = EDGE_LOOP ( 'NONE', ( #31074, #37756, #10506, #37472 ) ) ; +#9357 = DIRECTION ( 'NONE', ( -0.0004161288024547937867, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#9358 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37664, #37865, #13328, #28865 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9359 = CARTESIAN_POINT ( 'NONE', ( 14.20467396702673746, 115.2632914020303048, 152.7602116350681456 ) ) ; +#9360 = DIRECTION ( 'NONE', ( -2.258754526012903512E-19, -1.000000000000000000, -4.625929269274426393E-16 ) ) ; +#9361 = ORIENTED_EDGE ( 'NONE', *, *, #24602, .T. ) ; +#9362 = CARTESIAN_POINT ( 'NONE', ( 28.43929873840000155, 125.3863105753000013, 88.75451872105999485 ) ) ; +#9363 = EDGE_CURVE ( 'NONE', #8695, #31711, #7497, .T. ) ; +#9364 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923093933, 174.5173791610974376, 99.93528093888356523 ) ) ; +#9365 = CARTESIAN_POINT ( 'NONE', ( -25.61448796683999873, 191.5574138185000095, 106.5411355717999982 ) ) ; +#9366 = CARTESIAN_POINT ( 'NONE', ( -5.674480817841737412, 181.6879534348617824, 101.6022789869470131 ) ) ; +#9367 = CARTESIAN_POINT ( 'NONE', ( -17.26183737405610330, 121.4975388230068916, 176.5517749385022057 ) ) ; +#9368 = ORIENTED_EDGE ( 'NONE', *, *, #35218, .T. ) ; +#9369 = DIRECTION ( 'NONE', ( -0.0005884949961241829836, 0.2249510543439074139, -0.9743698870671260170 ) ) ; +#9370 = ADVANCED_FACE ( 'NONE', ( #6303 ), #12448, .F. ) ; +#9371 = FACE_OUTER_BOUND ( 'NONE', #4604, .T. ) ; +#9372 = AXIS2_PLACEMENT_3D ( 'NONE', #28893, #16806, #13353 ) ; +#9373 = CARTESIAN_POINT ( 'NONE', ( 36.78043872729679720, 191.6213203184406382, 104.3437258726304151 ) ) ; +#9374 = ADVANCED_FACE ( 'NONE', ( #19381 ), #13261, .T. ) ; +#9375 = CARTESIAN_POINT ( 'NONE', ( 76.10630783111386677, 156.2450968845475359, 96.19213091945711369 ) ) ; +#9376 = ORIENTED_EDGE ( 'NONE', *, *, #29488, .T. ) ; +#9377 = ORIENTED_EDGE ( 'NONE', *, *, #34878, .F. ) ; +#9378 = AXIS2_PLACEMENT_3D ( 'NONE', #7013, #28906, #13367 ) ; +#9379 = FACE_OUTER_BOUND ( 'NONE', #38639, .T. ) ; +#9380 = CARTESIAN_POINT ( 'NONE', ( 30.06862252804696212, 175.3593846892260046, 100.1196662353369362 ) ) ; +#9381 = CARTESIAN_POINT ( 'NONE', ( 16.00000031304551129, 127.7446264382961232, 89.13542822417404921 ) ) ; +#9382 = ADVANCED_FACE ( 'NONE', ( #31067 ), #289, .F. ) ; +#9383 = CARTESIAN_POINT ( 'NONE', ( -36.05702791021000309, 191.5952182986000309, 104.0132102184000047 ) ) ; +#9384 = CARTESIAN_POINT ( 'NONE', ( -26.00248196372567477, 190.9001546227889037, 106.8203149384555815 ) ) ; +#9385 = CARTESIAN_POINT ( 'NONE', ( -30.48035046349547628, 182.6378642661185552, 101.8366060183172550 ) ) ; +#9386 = CARTESIAN_POINT ( 'NONE', ( -19.70056751610980683, 149.1949662753088433, 182.8494181478328358 ) ) ; +#9387 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#9388 = COORDINATED_UNIVERSAL_TIME_OFFSET ( 8, 0, .AHEAD. ) ; +#9389 = CARTESIAN_POINT ( 'NONE', ( -12.62895464393706924, 177.1149013944556145, 103.6296996846185152 ) ) ; +#9390 = CARTESIAN_POINT ( 'NONE', ( 31.79421365039000591, 226.4002260770902808, 73.53930126517946064 ) ) ; +#9391 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557941447071, -0.2249510932885531445 ) ) ; +#9392 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#9393 = CARTESIAN_POINT ( 'NONE', ( 36.67762507159000052, 191.4660682097999995, 105.6908988317999984 ) ) ; +#9394 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #7660, #29953 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9395 = ORIENTED_EDGE ( 'NONE', *, *, #24382, .F. ) ; +#9396 = CARTESIAN_POINT ( 'NONE', ( 36.51773902275000694, 190.9747009333999870, 106.6659721184000063 ) ) ; +#9397 = ORIENTED_EDGE ( 'NONE', *, *, #8520, .F. ) ; +#9398 = ORIENTED_EDGE ( 'NONE', *, *, #12278, .F. ) ; +#9399 = EDGE_LOOP ( 'NONE', ( #11712, #38319 ) ) ; +#9400 = CARTESIAN_POINT ( 'NONE', ( -5.162153182269309859, 135.0725709097216622, 90.83999922111836156 ) ) ; +#9401 = AXIS2_PLACEMENT_3D ( 'NONE', #13143, #38271, #16390 ) ; +#9402 = CARTESIAN_POINT ( 'NONE', ( 20.48555995111231809, 211.0898943587194481, 73.54694346759191603 ) ) ; +#9403 = CONICAL_SURFACE ( 'NONE', #32250, 2.499999999874955137, 0.7853981634107377596 ) ; +#9404 = FACE_OUTER_BOUND ( 'NONE', #26959, .T. ) ; +#9405 = AXIS2_PLACEMENT_3D ( 'NONE', #9244, #21318, #12910 ) ; +#9406 = ORIENTED_EDGE ( 'NONE', *, *, #4113, .F. ) ; +#9407 = CARTESIAN_POINT ( 'NONE', ( -38.85031400081999919, 118.9564915689000060, 89.86658617362999735 ) ) ; +#9408 = LINE ( 'NONE', #31276, #33851 ) ; +#9409 = CARTESIAN_POINT ( 'NONE', ( 36.05539628075284497, 119.7153703235578774, 90.34852797225485688 ) ) ; +#9410 = EDGE_CURVE ( 'NONE', #28125, #38430, #13849, .T. ) ; +#9411 = VERTEX_POINT ( 'NONE', #26341 ) ; +#9412 = CARTESIAN_POINT ( 'NONE', ( 25.49032535677042688, 209.7096538831000032, 78.04310947658244402 ) ) ; +#9413 = EDGE_CURVE ( 'NONE', #25693, #3248, #33358, .T. ) ; +#9414 = EDGE_CURVE ( 'NONE', #17381, #19871, #38774, .T. ) ; +#9415 = CARTESIAN_POINT ( 'NONE', ( 25.99193850452332910, 211.4827920245210748, 76.04285411136869755 ) ) ; +#9416 = EDGE_CURVE ( 'NONE', #36005, #31399, #3238, .T. ) ; +#9417 = CARTESIAN_POINT ( 'NONE', ( -32.78648776892129035, 141.8832786522445133, 282.0370463350590740 ) ) ; +#9418 = CARTESIAN_POINT ( 'NONE', ( -3.537744142989006857, 173.0598683674986376, 99.60908667913541592 ) ) ; +#9419 = CARTESIAN_POINT ( 'NONE', ( 36.05503237434692210, 111.0397749124999933, 89.74600841160673781 ) ) ; +#9420 = ORIENTED_EDGE ( 'NONE', *, *, #18611, .T. ) ; +#9421 = CARTESIAN_POINT ( 'NONE', ( 12.63969765807997625, 176.7434396814577440, 103.0154879366982641 ) ) ; +#9422 = CARTESIAN_POINT ( 'NONE', ( 2.551442792066930032, 190.9974047891880105, 104.2715986393109944 ) ) ; +#9423 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#9424 = ADVANCED_FACE ( 'NONE', ( #14269 ), #3872, .T. ) ; +#9425 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12758, #4132, #37694, #37902 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9426 = ORIENTED_EDGE ( 'NONE', *, *, #34273, .F. ) ; +#9427 = ORIENTED_EDGE ( 'NONE', *, *, #36357, .F. ) ; +#9428 = DIRECTION ( 'NONE', ( -0.6087904839324249640, 0.7729173423006456822, 0.1788097554503956799 ) ) ; +#9429 = EDGE_LOOP ( 'NONE', ( #21268, #24611, #38970 ) ) ; +#9430 = ADVANCED_FACE ( 'NONE', ( #23261 ), #16503, .F. ) ; +#9431 = CARTESIAN_POINT ( 'NONE', ( -15.94435305949166626, 121.6629303779242406, 175.4476447897932019 ) ) ; +#9432 = VECTOR ( 'NONE', #27653, 1000.000000000000114 ) ; +#9433 = DIRECTION ( 'NONE', ( -0.7947985590179719173, 0.5913221741348984040, 0.1365039814779489546 ) ) ; +#9434 = CARTESIAN_POINT ( 'NONE', ( -12.63563752004072782, 176.9377883658784754, 103.3463588580742964 ) ) ; +#9435 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -0.000000000000000000, 0.0006039748319387908213 ) ) ; +#9436 = CARTESIAN_POINT ( 'NONE', ( 30.05382551891246834, 103.6131156702177094, 87.74963262556697430 ) ) ; +#9437 = CARTESIAN_POINT ( 'NONE', ( -2.242517155490072689, 190.1395195109974452, 106.0676264810896612 ) ) ; +#9438 = VERTEX_POINT ( 'NONE', #1788 ) ; +#9439 = FACE_OUTER_BOUND ( 'NONE', #21154, .T. ) ; +#9440 = CARTESIAN_POINT ( 'NONE', ( 37.66308823783763415, 78.96001237643454829, 291.8950395725842100 ) ) ; +#9441 = DIRECTION ( 'NONE', ( 0.0002331579778304189888, 0.000000000000000000, -0.9999999728186783621 ) ) ; +#9443 = CARTESIAN_POINT ( 'NONE', ( -15.94501330445751996, 152.5955922385961969, 182.6046949465412865 ) ) ; +#9442 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#9444 = VERTEX_POINT ( 'NONE', #35096 ) ; +#9445 = EDGE_LOOP ( 'NONE', ( #33187, #37183, #15177, #39625 ) ) ; +#9446 = VERTEX_POINT ( 'NONE', #4033 ) ; +#9448 = ORIENTED_EDGE ( 'NONE', *, *, #8742, .T. ) ; +#9447 = LOCAL_TIME ( 14, 25, 27.00000000000000000, #8993 ) ; +#9449 = CIRCLE ( 'NONE', #14686, 6.499999999869228162 ) ; +#9450 = DIRECTION ( 'NONE', ( 0.6087602524243990176, 0.7731011285869124894, 0.1781168157300828114 ) ) ; +#9451 = CARTESIAN_POINT ( 'NONE', ( 43.53526136507346678, 121.9496774062499043, 88.05073105187337035 ) ) ; +#9452 = FACE_OUTER_BOUND ( 'NONE', #24402, .T. ) ; +#9453 = FACE_OUTER_BOUND ( 'NONE', #37867, .T. ) ; +#9454 = FACE_OUTER_BOUND ( 'NONE', #33831, .T. ) ; +#9455 = CIRCLE ( 'NONE', #32957, 4.500000000016830093 ) ; +#9456 = AXIS2_PLACEMENT_3D ( 'NONE', #3912, #32542, #1051 ) ; +#9457 = FACE_OUTER_BOUND ( 'NONE', #35816, .T. ) ; +#9458 = ORIENTED_EDGE ( 'NONE', *, *, #15955, .F. ) ; +#9459 = FACE_OUTER_BOUND ( 'NONE', #29134, .T. ) ; +#9460 = ORIENTED_EDGE ( 'NONE', *, *, #16537, .T. ) ; +#9461 = EDGE_CURVE ( 'NONE', #4210, #36212, #28992, .T. ) ; +#9462 = AXIS2_PLACEMENT_3D ( 'NONE', #21623, #30816, #21423 ) ; +#9463 = ADVANCED_FACE ( 'NONE', ( #10597 ), #7147, .T. ) ; +#9464 = DIRECTION ( 'NONE', ( 0.1632030863883311977, -0.3417424275059330885, 0.9255143790539803739 ) ) ; +#9465 = ORIENTED_EDGE ( 'NONE', *, *, #14784, .T. ) ; +#9466 = CARTESIAN_POINT ( 'NONE', ( 19.98210856654580780, 205.1070970766282358, 76.09272704596726555 ) ) ; +#9467 = CARTESIAN_POINT ( 'NONE', ( 1.981463868355714641, 189.0541665519779713, 103.2983202685192055 ) ) ; +#9468 = LINE ( 'NONE', #9068, #516 ) ; +#9469 = ORIENTED_EDGE ( 'NONE', *, *, #9188, .F. ) ; +#9470 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921592953, -0.2249510932971527932 ) ) ; +#9471 = PLANE ( 'NONE', #29829 ) ; +#9472 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501099925, 181.7423509806621951, 104.7012344478815322 ) ) ; +#9473 = CARTESIAN_POINT ( 'NONE', ( -39.61054748937312553, 129.5177821288435780, 336.3042500576304974 ) ) ; +#9474 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927756174176, 0.0005734119022080326911 ) ) ; +#9475 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3920, #28096, #10080, #28877 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9476 = ORIENTED_EDGE ( 'NONE', *, *, #27899, .T. ) ; +#9477 = CARTESIAN_POINT ( 'NONE', ( -15.56570128701472377, 147.2799833431736545, 179.8363833230590103 ) ) ; +#9478 = DIRECTION ( 'NONE', ( 0.6188015000093128881, -0.7855473910504855439, 0.000000000000000000 ) ) ; +#9479 = CARTESIAN_POINT ( 'NONE', ( 17.99823451500899907, 132.2978359559240289, 93.26432565570340216 ) ) ; +#9480 = EDGE_CURVE ( 'NONE', #17741, #38457, #26148, .T. ) ; +#9481 = CIRCLE ( 'NONE', #24530, 2.000000000309440917 ) ; +#9482 = CONICAL_SURFACE ( 'NONE', #38851, 2.502997798619384540, 0.7853981633682427521 ) ; +#9483 = VERTEX_POINT ( 'NONE', #11198 ) ; +#9484 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597599 ) ) ; +#9485 = CARTESIAN_POINT ( 'NONE', ( 25.99285328132379291, 207.8686442202288447, 77.26134345908226919 ) ) ; +#9487 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825911284117981, 0.0005734119025914883282 ) ) ; +#9486 = CARTESIAN_POINT ( 'NONE', ( 37.19332676483216460, 178.1386719297145476, 136.6947527228966521 ) ) ; +#9488 = VERTEX_POINT ( 'NONE', #23877 ) ; +#9489 = CARTESIAN_POINT ( 'NONE', ( 25.49062502244311190, 209.7098837966309475, 73.54308088453358039 ) ) ; +#9490 = EDGE_LOOP ( 'NONE', ( #14977, #13346, #34161, #30959 ) ) ; +#9491 = CARTESIAN_POINT ( 'NONE', ( -37.30573013310910113, 122.1249136379386613, 105.8120874930726671 ) ) ; +#9492 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971580390 ) ) ; +#9493 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #27683, #20920 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9494 = CARTESIAN_POINT ( 'NONE', ( 5.667815391071755471, 185.3463280707672141, 105.0058324240259822 ) ) ; +#9495 = CARTESIAN_POINT ( 'NONE', ( -44.76913686494872735, 108.4408363393548882, 169.8241779223887136 ) ) ; +#9496 = ORIENTED_EDGE ( 'NONE', *, *, #40182, .T. ) ; +#9497 = ORIENTED_EDGE ( 'NONE', *, *, #27391, .F. ) ; +#9498 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 1.540743955509789367E-33, -0.0006039748319385908944 ) ) ; +#9499 = CARTESIAN_POINT ( 'NONE', ( -16.53785153513707584, 123.0772470471530085, 172.1883206570706477 ) ) ; +#9500 = CARTESIAN_POINT ( 'NONE', ( -25.02288790531975593, 130.6107453957711471, 89.82190044176225285 ) ) ; +#9501 = CARTESIAN_POINT ( 'NONE', ( 2.780295052165365988, 209.6670236940893233, 73.22349242878858888 ) ) ; +#9502 = LINE ( 'NONE', #28122, #2003 ) ; +#9503 = VERTEX_POINT ( 'NONE', #39387 ) ; +#9504 = ORIENTED_EDGE ( 'NONE', *, *, #9480, .T. ) ; +#9505 = CARTESIAN_POINT ( 'NONE', ( 24.53348384879784305, 109.6131156702000027, 87.75296677373469834 ) ) ; +#9506 = EDGE_CURVE ( 'NONE', #37463, #13780, #19663, .T. ) ; +#9507 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; +#9508 = EDGE_CURVE ( 'NONE', #8441, #8041, #24293, .T. ) ; +#9509 = CARTESIAN_POINT ( 'NONE', ( -25.67151722820999993, 122.1102479606999935, 88.37309007614000222 ) ) ; +#9510 = CIRCLE ( 'NONE', #33635, 2.000000000000011546 ) ; +#9511 = ORIENTED_EDGE ( 'NONE', *, *, #30842, .F. ) ; +#9512 = DIRECTION ( 'NONE', ( -2.081668171172156523E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#9513 = LINE ( 'NONE', #5423, #16670 ) ; +#9514 = CARTESIAN_POINT ( 'NONE', ( -26.00624846271685442, 190.8511609718977127, 106.8090059743847178 ) ) ; +#9515 = ORIENTED_EDGE ( 'NONE', *, *, #13298, .T. ) ; +#9516 = AXIS2_PLACEMENT_3D ( 'NONE', #5737, #36192, #27446 ) ; +#9517 = CONICAL_SURFACE ( 'NONE', #25197, 2.249999999963673503, 0.7853981633778843729 ) ; +#9518 = CARTESIAN_POINT ( 'NONE', ( -36.94477238337578484, 116.4506421962486797, 89.73586812368668575 ) ) ; +#9519 = AXIS2_PLACEMENT_3D ( 'NONE', #40400, #40001, #5454 ) ; +#9520 = EDGE_CURVE ( 'NONE', #28131, #36832, #9127, .T. ) ; +#9521 = CIRCLE ( 'NONE', #40201, 5.500000000022822633 ) ; +#9522 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058320840, 128.4724153155870567, 89.82969158201160553 ) ) ; +#9523 = DIRECTION ( 'NONE', ( 0.0005884949961156549746, -0.2249510543439098842, 0.9743698870671255730 ) ) ; +#9524 = CARTESIAN_POINT ( 'NONE', ( -19.33075647067465397, 149.2722955532668436, 181.2498491173590764 ) ) ; +#9525 = ORIENTED_EDGE ( 'NONE', *, *, #3356, .T. ) ; +#9526 = CARTESIAN_POINT ( 'NONE', ( 40.54675149456901551, 220.4002261244750116, 76.03401540774370915 ) ) ; +#9527 = ORIENTED_EDGE ( 'NONE', *, *, #27758, .F. ) ; +#9528 = CARTESIAN_POINT ( 'NONE', ( 30.80442935676257221, 110.6131156702000027, 88.74917946218410236 ) ) ; +#9529 = CARTESIAN_POINT ( 'NONE', ( 25.99030219703914568, 209.7096538831000032, 73.04280978677728342 ) ) ; +#9530 = ADVANCED_FACE ( 'NONE', ( #2609 ), #5182, .F. ) ; +#9531 = CARTESIAN_POINT ( 'NONE', ( -29.09726181183376781, 181.7433723500874976, 101.6292608991324897 ) ) ; +#9532 = EDGE_LOOP ( 'NONE', ( #27145, #3543, #7449, #32430, #329 ) ) ; +#9533 = FACE_OUTER_BOUND ( 'NONE', #37357, .T. ) ; +#9534 = ORIENTED_EDGE ( 'NONE', *, *, #22527, .F. ) ; +#9535 = VECTOR ( 'NONE', #34267, 1000.000000000000227 ) ; +#9536 = AXIS2_PLACEMENT_3D ( 'NONE', #32716, #35540, #35346 ) ; +#9537 = CARTESIAN_POINT ( 'NONE', ( -25.86880953606799949, 189.5976987908379954, 103.9537772934139923 ) ) ; +#9538 = LINE ( 'NONE', #19911, #17109 ) ; +#9539 = VERTEX_POINT ( 'NONE', #24081 ) ; +#9540 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#9541 = ADVANCED_FACE ( 'NONE', ( #5453 ), #39610, .F. ) ; +#9542 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048787848, 153.7268358529419743, 98.24418217436381440 ) ) ; +#9543 = DIRECTION ( 'NONE', ( 0.9999998268370344778, 0.0001323825049342479854, -0.0005734115218532780545 ) ) ; +#9544 = AXIS2_PLACEMENT_3D ( 'NONE', #13774, #7427, #17432 ) ; +#9545 = CARTESIAN_POINT ( 'NONE', ( -21.26225680614087921, 158.5941992317567895, 96.28012005377419769 ) ) ; +#9546 = CYLINDRICAL_SURFACE ( 'NONE', #30470, 2.000000000000001332 ) ; +#9547 = ORIENTED_EDGE ( 'NONE', *, *, #13716, .F. ) ; +#9548 = ORIENTED_EDGE ( 'NONE', *, *, #10181, .T. ) ; +#9549 = DIRECTION ( 'NONE', ( 0.5986917825334768795, 0.8009794122048727871, -0.0003615948347011540827 ) ) ; +#9550 = EDGE_CURVE ( 'NONE', #38290, #14324, #34784, .T. ) ; +#9551 = CARTESIAN_POINT ( 'NONE', ( -38.98458235476000056, 142.5847786539000026, 26.89884147244999824 ) ) ; +#9552 = VERTEX_POINT ( 'NONE', #14676 ) ; +#9553 = CARTESIAN_POINT ( 'NONE', ( -23.36243050683136957, 135.2128115065362124, 91.28990528929200821 ) ) ; +#9555 = ADVANCED_FACE ( 'NONE', ( #36737 ), #33662, .T. ) ; +#9554 = DIRECTION ( 'NONE', ( -0.7066795775423952986, -4.274442269987938000E-15, 0.7075337268883383768 ) ) ; +#9556 = EDGE_CURVE ( 'NONE', #19444, #6128, #18214, .T. ) ; +#9557 = ORIENTED_EDGE ( 'NONE', *, *, #35352, .T. ) ; +#9558 = DIRECTION ( 'NONE', ( 0.0005734119072325851883, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#9559 = ADVANCED_FACE ( 'NONE', ( #26672 ), #29378, .F. ) ; +#9560 = EDGE_CURVE ( 'NONE', #34014, #7336, #22207, .T. ) ; +#9561 = DIRECTION ( 'NONE', ( -0.7856637698373362122, -0.6186537325232790430, 0.000000000000000000 ) ) ; +#9562 = DIRECTION ( 'NONE', ( -0.0006039748319381367221, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#9563 = EDGE_LOOP ( 'NONE', ( #19849, #38381, #25995, #5600 ) ) ; +#9564 = CARTESIAN_POINT ( 'NONE', ( 28.52923972082999882, 125.2870818839000009, 88.56041932755000801 ) ) ; +#9565 = CARTESIAN_POINT ( 'NONE', ( 25.65932787654801572, 211.0906275801376637, 73.37418414931370592 ) ) ; +#9566 = DIRECTION ( 'NONE', ( -0.0005884949961224280940, 0.2249510543439061094, -0.9743698870671263501 ) ) ; +#9567 = DIRECTION ( 'NONE', ( 0.7933533175743878729, 0.5930761747309519771, 0.1372995428259456974 ) ) ; +#9568 = DIRECTION ( 'NONE', ( -3.469446951882167451E-15, 0.9743700557921584071, 0.2249510932971570953 ) ) ; +#9569 = AXIS2_PLACEMENT_3D ( 'NONE', #4168, #16447, #28937 ) ; +#9570 = ORIENTED_EDGE ( 'NONE', *, *, #11155, .T. ) ; +#9571 = CARTESIAN_POINT ( 'NONE', ( 2.561557522426483491, 191.9759150222000130, 101.9199002238076162 ) ) ; +#9572 = CARTESIAN_POINT ( 'NONE', ( 5.667647268250993520, 124.2920528419670632, 90.91033987003989125 ) ) ; +#9573 = CARTESIAN_POINT ( 'NONE', ( 36.04502488578000197, 218.5902260770999987, 74.53673406417000535 ) ) ; +#9574 = CIRCLE ( 'NONE', #21984, 2.499999999952864371 ) ; +#9575 = CARTESIAN_POINT ( 'NONE', ( -45.98849231353116096, 125.1674804258049392, 91.77005729733592432 ) ) ; +#9576 = VERTEX_POINT ( 'NONE', #10933 ) ; +#9577 = ORIENTED_EDGE ( 'NONE', *, *, #27459, .T. ) ; +#9578 = CARTESIAN_POINT ( 'NONE', ( 38.49288589009113792, 119.0337946565482667, 90.25041038663783866 ) ) ; +#9579 = CARTESIAN_POINT ( 'NONE', ( 19.30946322470169108, 148.8544289525886768, 180.8759745330408748 ) ) ; +#9580 = CARTESIAN_POINT ( 'NONE', ( 24.19055539170138047, 213.8395337131380813, 73.04389359310243890 ) ) ; +#9581 = CARTESIAN_POINT ( 'NONE', ( -36.20902675056999698, 191.7497827512000015, 104.2839535104999982 ) ) ; +#9582 = EDGE_LOOP ( 'NONE', ( #30036, #16361, #20302, #2948, #15951, #20967 ) ) ; +#9583 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391913256 ) ) ; +#9584 = CARTESIAN_POINT ( 'NONE', ( -23.35287815472955941, 177.1132788188974132, 103.6357243926429135 ) ) ; +#9585 = CARTESIAN_POINT ( 'NONE', ( 20.50146814542411278, 184.4050074329408915, 104.7795556516932436 ) ) ; +#9586 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#9587 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265227786, 0.1368326740407719844 ) ) ; +#9588 = EDGE_CURVE ( 'NONE', #33439, #520, #8048, .T. ) ; +#9589 = CONICAL_SURFACE ( 'NONE', #6337, 2.502999999975751066, 0.7853981634562235969 ) ; +#9590 = CARTESIAN_POINT ( 'NONE', ( 20.16458336689871089, 127.3986389566010899, 89.22184904988743881 ) ) ; +#9591 = CARTESIAN_POINT ( 'NONE', ( 37.18343761575999906, 191.4768738335000080, 104.3136478636999982 ) ) ; +#9592 = AXIS2_PLACEMENT_3D ( 'NONE', #32725, #16959, #13916 ) ; +#9593 = CARTESIAN_POINT ( 'NONE', ( 36.55216596207999658, 191.7401717577000397, 106.2476387699000071 ) ) ; +#9594 = AXIS2_PLACEMENT_3D ( 'NONE', #24741, #37192, #15314 ) ; +#9595 = VERTEX_POINT ( 'NONE', #11129 ) ; +#9596 = ORIENTED_EDGE ( 'NONE', *, *, #24623, .F. ) ; +#9597 = ORIENTED_EDGE ( 'NONE', *, *, #12026, .F. ) ; +#9598 = FACE_OUTER_BOUND ( 'NONE', #3664, .T. ) ; +#9599 = EDGE_CURVE ( 'NONE', #2544, #11548, #30014, .T. ) ; +#9600 = CARTESIAN_POINT ( 'NONE', ( 20.14652253711376773, 126.7948032831537404, 91.84390006618201596 ) ) ; +#9601 = CONICAL_SURFACE ( 'NONE', #23970, 3.003184325552035627, 0.7853589132226472813 ) ; +#9602 = ADVANCED_FACE ( 'NONE', ( #29934 ), #29332, .T. ) ; +#9603 = DIRECTION ( 'NONE', ( 0.0006039748319378610095, 9.939046677758948188E-15, 0.9999998176071845934 ) ) ; +#9604 = PLANE ( 'NONE', #22657 ) ; +#9605 = CARTESIAN_POINT ( 'NONE', ( 12.31588672122218320, 137.2441267807453471, 91.84393833925072670 ) ) ; +#9606 = ORIENTED_EDGE ( 'NONE', *, *, #13694, .T. ) ; +#9607 = CARTESIAN_POINT ( 'NONE', ( 37.88562005261000110, 118.7629374576000174, 87.34018596161999426 ) ) ; +#9608 = EDGE_CURVE ( 'NONE', #26876, #14927, #32788, .T. ) ; +#9609 = CARTESIAN_POINT ( 'NONE', ( 37.48938149088855454, 212.8449748121827838, 73.03586143537702924 ) ) ; +#9610 = CARTESIAN_POINT ( 'NONE', ( -29.41585490894198784, 161.0327472628627561, 187.1177767716451399 ) ) ; +#9611 = FACE_OUTER_BOUND ( 'NONE', #6267, .T. ) ; +#9612 = ORIENTED_EDGE ( 'NONE', *, *, #12689, .F. ) ; +#9613 = FACE_OUTER_BOUND ( 'NONE', #8560, .T. ) ; +#9614 = CARTESIAN_POINT ( 'NONE', ( 5.666787591738080110, 130.4226561615404023, 90.27309335817682268 ) ) ; +#9615 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29837, #32692, #4673, #39621, #17126, #23699, #36568, #14293, #11029, #26573 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999807931, 0.3749999999999774070, 0.4374999999999818479, 0.4999999999999863443, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9616 = FACE_OUTER_BOUND ( 'NONE', #25556, .T. ) ; +#9617 = PLANE ( 'NONE', #12536 ) ; +#9618 = ORIENTED_EDGE ( 'NONE', *, *, #24793, .F. ) ; +#9619 = ORIENTED_EDGE ( 'NONE', *, *, #15969, .F. ) ; +#9620 = CARTESIAN_POINT ( 'NONE', ( 12.64366213596533406, 177.0557396825045373, 103.5152694373627895 ) ) ; +#9621 = CARTESIAN_POINT ( 'NONE', ( 1.317609656703000010, 189.1505943148000028, 103.7349513905000009 ) ) ; +#9622 = DIRECTION ( 'NONE', ( 0.7066795775021792458, -8.644699693605865341E-15, -0.7075337269285059127 ) ) ; +#9623 = VECTOR ( 'NONE', #6770, 1000.000000000000000 ) ; +#9624 = EDGE_LOOP ( 'NONE', ( #26096, #20483, #31135, #633 ) ) ; +#9625 = CARTESIAN_POINT ( 'NONE', ( -12.59997215317999952, 114.0103269030000064, 152.4718672074000381 ) ) ; +#9626 = ORIENTED_EDGE ( 'NONE', *, *, #6554, .F. ) ; +#9627 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37870, #15987, #12134, #15589 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9628 = VECTOR ( 'NONE', #16255, 1000.000000000000227 ) ; +#9629 = DIRECTION ( 'NONE', ( -0.0005884949961222158072, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#9630 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39081, #21517, #8841, #12295, #33144, #20689, #30514, #15171, #33955, #36836 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9631 = CARTESIAN_POINT ( 'NONE', ( -39.39972888957502306, 182.9666818760945830, 104.9968195249913236 ) ) ; +#9632 = CARTESIAN_POINT ( 'NONE', ( 13.46162264378999929, 153.1807780540000294, 28.07991271570000080 ) ) ; +#9633 = CARTESIAN_POINT ( 'NONE', ( 35.98188939040999657, 134.7361418062000098, 93.81639134258000468 ) ) ; +#9634 = CARTESIAN_POINT ( 'NONE', ( -2.214908976321755318, 190.0835411280691574, 106.0514516821102120 ) ) ; +#9635 = ORIENTED_EDGE ( 'NONE', *, *, #32122, .T. ) ; +#9636 = EDGE_CURVE ( 'NONE', #30285, #37352, #35209, .T. ) ; +#9637 = ADVANCED_FACE ( 'NONE', ( #13589 ), #26880, .F. ) ; +#9638 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8380, #5290, #21666, #2243 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9639 = CARTESIAN_POINT ( 'NONE', ( 24.94568828298271157, 117.2261764025736568, 170.8458856035829569 ) ) ; +#9640 = CARTESIAN_POINT ( 'NONE', ( 39.71644058364383056, 182.4824187750803333, 106.8892835983133693 ) ) ; +#9641 = EDGE_CURVE ( 'NONE', #37303, #12627, #1106, .T. ) ; +#9642 = EDGE_CURVE ( 'NONE', #906, #21267, #31416, .T. ) ; +#9643 = FACE_OUTER_BOUND ( 'NONE', #30130, .T. ) ; +#9644 = ORIENTED_EDGE ( 'NONE', *, *, #24296, .F. ) ; +#9645 = ORIENTED_EDGE ( 'NONE', *, *, #21529, .T. ) ; +#9646 = DIRECTION ( 'NONE', ( -0.7730662169443226484, -0.5272861007345266415, -0.3526159273084134571 ) ) ; +#9647 = CIRCLE ( 'NONE', #21401, 4.749999999995090150 ) ; +#9648 = CARTESIAN_POINT ( 'NONE', ( -29.94780647572998333, 103.6131156703220597, 87.78587210778204053 ) ) ; +#9649 = CIRCLE ( 'NONE', #11611, 6.000000000333073125 ) ; +#9650 = EDGE_LOOP ( 'NONE', ( #9695, #14802, #10810, #23964 ) ) ; +#9651 = DIRECTION ( 'NONE', ( -0.6087613502019255662, 0.7729389820454566351, 0.1788154035167601463 ) ) ; +#9652 = LINE ( 'NONE', #12925, #8743 ) ; +#9653 = EDGE_CURVE ( 'NONE', #36851, #3943, #16637, .T. ) ; +#9654 = CARTESIAN_POINT ( 'NONE', ( -38.65167172564999731, 119.0452778641000009, 90.11067139839001072 ) ) ; +#9655 = CARTESIAN_POINT ( 'NONE', ( -38.25200071130999646, 118.9539271141999990, 87.58069048670999734 ) ) ; +#9656 = LINE ( 'NONE', #19034, #15189 ) ; +#9657 = VERTEX_POINT ( 'NONE', #29138 ) ; +#9658 = CARTESIAN_POINT ( 'NONE', ( 17.27193878522344406, 122.1565749163837182, 173.7593392666709917 ) ) ; +#9659 = ORIENTED_EDGE ( 'NONE', *, *, #38423, .F. ) ; +#9660 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251391720, 179.1753088543719343, 103.5954339977985796 ) ) ; +#9661 = LINE ( 'NONE', #34380, #1140 ) ; +#9662 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28164, #31017, #24905, #10156, #37350, #9952, #31830, #38153, #18514, #19125, #34659, #730, #35051, #21818 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000997535, 0.3750000000000997535, 0.5000000000000998090, 0.6250000000000998090, 0.6875000000000498490, 0.7499999999999997780, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9663 = FACE_OUTER_BOUND ( 'NONE', #281, .T. ) ; +#9664 = EDGE_LOOP ( 'NONE', ( #34549, #17245, #10847, #37241 ) ) ; +#9665 = VERTEX_POINT ( 'NONE', #38513 ) ; +#9666 = CARTESIAN_POINT ( 'NONE', ( 20.94993391244204872, 135.9271259092254240, 94.10042936185872975 ) ) ; +#9667 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28619, #25968, #19187, #23091 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.0001384919294626354644 ), + .UNSPECIFIED. ) ; +#9668 = CARTESIAN_POINT ( 'NONE', ( 2.119762003991769284, 189.1507938075172888, 103.3205449036793766 ) ) ; +#9669 = CARTESIAN_POINT ( 'NONE', ( -30.07200330635000185, 135.2897752494975521, 91.41834187731066663 ) ) ; +#9670 = ORIENTED_EDGE ( 'NONE', *, *, #7788, .T. ) ; +#9671 = CARTESIAN_POINT ( 'NONE', ( -13.49823529423287560, 173.8389516671386161, 102.8738727251156462 ) ) ; +#9672 = CYLINDRICAL_SURFACE ( 'NONE', #33721, 2.000000000000011546 ) ; +#9673 = ORIENTED_EDGE ( 'NONE', *, *, #27501, .T. ) ; +#9674 = CARTESIAN_POINT ( 'NONE', ( 21.00135297806761514, 116.5765964922940725, 89.75535705397723518 ) ) ; +#9675 = CYLINDRICAL_SURFACE ( 'NONE', #18294, 1.750000000000001998 ) ; +#9676 = CARTESIAN_POINT ( 'NONE', ( -25.44744374708999857, 121.4359792056000060, 90.13081907286000671 ) ) ; +#9677 = AXIS2_PLACEMENT_3D ( 'NONE', #29470, #17374, #1862 ) ; +#9678 = ORIENTED_EDGE ( 'NONE', *, *, #23817, .T. ) ; +#9679 = CARTESIAN_POINT ( 'NONE', ( 2.729058208330169322, 189.6265354008074269, 106.5089234100929332 ) ) ; +#9680 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; +#9681 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11655, #4896, #17558, #20846 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9682 = AXIS2_PLACEMENT_3D ( 'NONE', #27374, #39795, #18118 ) ; +#9683 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#9684 = ORIENTED_EDGE ( 'NONE', *, *, #16099, .T. ) ; +#9685 = EDGE_CURVE ( 'NONE', #26196, #25299, #16090, .T. ) ; +#9686 = CARTESIAN_POINT ( 'NONE', ( -15.56569021289253740, 127.6492525721004654, 175.3175532804469015 ) ) ; +#9687 = CARTESIAN_POINT ( 'NONE', ( 3.166377416628577190, 128.5876387387983186, 89.33781556475464924 ) ) ; +#9688 = EDGE_CURVE ( 'NONE', #2849, #3073, #24234, .T. ) ; +#9689 = EDGE_CURVE ( 'NONE', #23147, #5203, #4368, .T. ) ; +#9691 = CARTESIAN_POINT ( 'NONE', ( -16.78015712463011866, 121.5863303463596452, 177.0789580759722810 ) ) ; +#9690 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265228896, 0.1368326740407718733 ) ) ; +#9692 = EDGE_LOOP ( 'NONE', ( #39069, #485, #7930, #13504 ) ) ; +#9693 = CARTESIAN_POINT ( 'NONE', ( -14.08011580147661235, 129.1601492223334446, 176.8499123979196099 ) ) ; +#9694 = DIRECTION ( 'NONE', ( 0.6087616187692346248, -0.7730003051580285334, -0.1785492081725818803 ) ) ; +#9695 = ORIENTED_EDGE ( 'NONE', *, *, #12729, .F. ) ; +#9696 = LINE ( 'NONE', #22175, #23880 ) ; +#9697 = EDGE_CURVE ( 'NONE', #17622, #20919, #32636, .T. ) ; +#9698 = DIRECTION ( 'NONE', ( -0.0004161288024526093362, -0.5299192578742120130, -0.8480479980348188951 ) ) ; +#9699 = ORIENTED_EDGE ( 'NONE', *, *, #18453, .F. ) ; +#9700 = ORIENTED_EDGE ( 'NONE', *, *, #8734, .T. ) ; +#9701 = PLANE ( 'NONE', #19126 ) ; +#9702 = EDGE_CURVE ( 'NONE', #11066, #22581, #33389, .T. ) ; +#9703 = CIRCLE ( 'NONE', #14929, 2.000000003389833303 ) ; +#9704 = DIRECTION ( 'NONE', ( -0.0006039748319386757875, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#9705 = CARTESIAN_POINT ( 'NONE', ( -2.813786152616000180, 190.8797540774000083, 106.6764626145999983 ) ) ; +#9706 = CARTESIAN_POINT ( 'NONE', ( 36.11091198150000281, 191.5180279879000125, 103.8372736401999958 ) ) ; +#9707 = EDGE_LOOP ( 'NONE', ( #38399, #11105, #2669, #40190 ) ) ; +#9708 = ORIENTED_EDGE ( 'NONE', *, *, #19650, .T. ) ; +#9709 = CIRCLE ( 'NONE', #22757, 2.500000000052250204 ) ; +#9710 = ORIENTED_EDGE ( 'NONE', *, *, #3626, .F. ) ; +#9711 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#9712 = CONICAL_SURFACE ( 'NONE', #30613, 6.500001099657994885, 0.7853982150629152947 ) ; +#9713 = LINE ( 'NONE', #22591, #10042 ) ; +#9714 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, -1.271205595054999941E-14 ) ) ; +#9715 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#9716 = AXIS2_PLACEMENT_3D ( 'NONE', #6942, #24981, #19008 ) ; +#9717 = ORIENTED_EDGE ( 'NONE', *, *, #36251, .T. ) ; +#9718 = EDGE_CURVE ( 'NONE', #35915, #6019, #8677, .T. ) ; +#9719 = EDGE_LOOP ( 'NONE', ( #29211, #10236, #27680, #17843 ) ) ; +#9720 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, -1.298960938811000068E-14 ) ) ; +#9721 = DIRECTION ( 'NONE', ( -0.0005884949961261904923, 0.2255194585872569157, -0.9742384859325513569 ) ) ; +#9722 = EDGE_LOOP ( 'NONE', ( #22191, #24248, #29802, #383, #35603, #28973, #24646, #30975, #26660, #29309, #3548 ) ) ; +#9723 = CARTESIAN_POINT ( 'NONE', ( -13.50000076883903510, 154.4042507776735818, 95.30811371979322644 ) ) ; +#9724 = ORIENTED_EDGE ( 'NONE', *, *, #28033, .F. ) ; +#9725 = CARTESIAN_POINT ( 'NONE', ( -5.667652426752654904, 187.3243678606383753, 105.5115252951561189 ) ) ; +#9726 = CARTESIAN_POINT ( 'NONE', ( -1.108382502455999896, 188.2795632126000100, 106.3695074111000025 ) ) ; +#9727 = FACE_OUTER_BOUND ( 'NONE', #2235, .T. ) ; +#9728 = VERTEX_POINT ( 'NONE', #33592 ) ; +#9729 = FACE_OUTER_BOUND ( 'NONE', #10558, .T. ) ; +#9730 = ORIENTED_EDGE ( 'NONE', *, *, #3756, .T. ) ; +#9731 = CARTESIAN_POINT ( 'NONE', ( 34.37515011644319429, 83.27714336192299527, 284.1420403139794644 ) ) ; +#9732 = CARTESIAN_POINT ( 'NONE', ( -25.83474554800833189, 118.1159992059333206, 87.45011729634273934 ) ) ; +#9733 = LINE ( 'NONE', #29143, #19608 ) ; +#9734 = CIRCLE ( 'NONE', #38427, 1.750000000000001998 ) ; +#9735 = ORIENTED_EDGE ( 'NONE', *, *, #22358, .T. ) ; +#9736 = CARTESIAN_POINT ( 'NONE', ( -22.49823197369664385, 157.6225053518252821, 99.13851915872771770 ) ) ; +#9737 = ORIENTED_EDGE ( 'NONE', *, *, #9195, .T. ) ; +#9738 = AXIS2_PLACEMENT_3D ( 'NONE', #19843, #20458, #33537 ) ; +#9739 = CONICAL_SURFACE ( 'NONE', #23415, 4.999999999912411397, 0.7853981633778838178 ) ; +#9740 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319364896022 ) ) ; +#9741 = EDGE_CURVE ( 'NONE', #22525, #28860, #25479, .T. ) ; +#9742 = EDGE_CURVE ( 'NONE', #7259, #8, #11942, .T. ) ; +#9743 = AXIS2_PLACEMENT_3D ( 'NONE', #23806, #36267, #2744 ) ; +#9744 = CARTESIAN_POINT ( 'NONE', ( -38.55367922949000103, 118.3586223536000119, 89.54641048761999400 ) ) ; +#9745 = ORIENTED_EDGE ( 'NONE', *, *, #20612, .T. ) ; +#9746 = ORIENTED_EDGE ( 'NONE', *, *, #23032, .T. ) ; +#9747 = CARTESIAN_POINT ( 'NONE', ( 37.40799538047578920, 111.9543163460056121, 150.4009621148262283 ) ) ; +#9748 = CARTESIAN_POINT ( 'NONE', ( -26.00142186005520983, 120.7678123865047297, 87.55007858260474052 ) ) ; +#9749 = CARTESIAN_POINT ( 'NONE', ( -20.06090143618003907, 160.1206884207606151, 96.63181232735072967 ) ) ; +#9750 = FACE_BOUND ( 'NONE', #35223, .T. ) ; +#9751 = ORIENTED_EDGE ( 'NONE', *, *, #3660, .T. ) ; +#9752 = EDGE_LOOP ( 'NONE', ( #14650, #34927, #20435, #32090 ) ) ; +#9753 = CYLINDRICAL_SURFACE ( 'NONE', #15245, 2.000000000000014655 ) ; +#9754 = PLANE ( 'NONE', #32068 ) ; +#9755 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #36088, #29567 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9756 = ORIENTED_EDGE ( 'NONE', *, *, #18051, .T. ) ; +#9757 = CARTESIAN_POINT ( 'NONE', ( -15.10513900131456388, 175.7048190624925610, 103.3056127689209376 ) ) ; +#9758 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30312, #27486, #18023, #17817 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9759 = ORIENTED_EDGE ( 'NONE', *, *, #25675, .T. ) ; +#9760 = DIRECTION ( 'NONE', ( -0.0005884949961233675551, 0.2249510543439052490, -0.9743698870671265722 ) ) ; +#9761 = AXIS2_PLACEMENT_3D ( 'NONE', #23279, #20603, #14485 ) ; +#9762 = ADVANCED_FACE ( 'NONE', ( #5587 ), #12334, .F. ) ; +#9763 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#9764 = CARTESIAN_POINT ( 'NONE', ( -22.49859347127474152, 158.2257569248202458, 98.76156587771905038 ) ) ; +#9765 = ORIENTED_EDGE ( 'NONE', *, *, #33879, .F. ) ; +#9766 = CARTESIAN_POINT ( 'NONE', ( 28.39476059464999835, 125.2008286205000047, 88.54061883459999649 ) ) ; +#9767 = VECTOR ( 'NONE', #36047, 1000.000000000000114 ) ; +#9768 = DIRECTION ( 'NONE', ( -2.081668171257503147E-15, 0.9743700557921587402, 0.2249510932971554300 ) ) ; +#9769 = VECTOR ( 'NONE', #8998, 999.9999999999998863 ) ; +#9770 = CARTESIAN_POINT ( 'NONE', ( 41.20534109643615039, 166.2329448439782027, 182.1790434216227084 ) ) ; +#9771 = CARTESIAN_POINT ( 'NONE', ( 3.868560647465115299, 175.2822330077133017, 100.4606273346248457 ) ) ; +#9772 = FACE_OUTER_BOUND ( 'NONE', #11016, .T. ) ; +#9773 = VERTEX_POINT ( 'NONE', #24223 ) ; +#9774 = CARTESIAN_POINT ( 'NONE', ( 6.035817316620117445, 176.7425654412684537, 103.0192746809948403 ) ) ; +#9775 = CARTESIAN_POINT ( 'NONE', ( 0.6241150675635340761, 189.0009256389474217, 103.6843667366763810 ) ) ; +#9776 = CARTESIAN_POINT ( 'NONE', ( 36.44740353825743995, 191.7901934835035149, 104.3576882541939312 ) ) ; +#9777 = EDGE_CURVE ( 'NONE', #40162, #30287, #7849, .T. ) ; +#9778 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799607651, 137.3509909075849009, 91.38105903666725283 ) ) ; +#9779 = ORIENTED_EDGE ( 'NONE', *, *, #34410, .F. ) ; +#9780 = ORIENTED_EDGE ( 'NONE', *, *, #33014, .F. ) ; +#9781 = CARTESIAN_POINT ( 'NONE', ( 38.50707698816808744, 119.0448651478242681, 90.25104051021725127 ) ) ; +#9782 = CARTESIAN_POINT ( 'NONE', ( 19.45332703025135146, 148.3679948532157482, 180.6096929009134158 ) ) ; +#9783 = CARTESIAN_POINT ( 'NONE', ( -3.779454719330632262, 168.4408027603464291, 98.79105186909471570 ) ) ; +#9784 = EDGE_CURVE ( 'NONE', #654, #29169, #37894, .T. ) ; +#9785 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #23073, #19171, #7111, #19584 ), + ( #35103, #7310, #22685, #19774 ), + ( #22479, #32081, #1380, #34902 ), + ( #16508, #25955, #4237, #35306 ), + ( #10002, #32275, #29415, #6916 ), + ( #13859, #19389, #31882, #28999 ), + ( #16714, #29212, #32472, #3836 ), + ( #26348, #4042, #28803, #38781 ), + ( #1184, #979, #13266, #13072 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 3, 4 ), + ( 4, 4 ), + ( 1.184794198244000012E-11, 0.3333321166536000191, 0.6666659962015000218, 0.9999984199999000234, 1.009998404199780486 ), + ( 0.1756414547379999969, 0.8243585473361000338 ), + .UNSPECIFIED. ) ; +#9786 = CARTESIAN_POINT ( 'NONE', ( -23.36043048140919609, 183.5592642829485328, 104.6107884962622876 ) ) ; +#9787 = ORIENTED_EDGE ( 'NONE', *, *, #13790, .T. ) ; +#9788 = ADVANCED_FACE ( 'NONE', ( #20725 ), #21139, .F. ) ; +#9789 = EDGE_CURVE ( 'NONE', #35367, #18185, #27698, .T. ) ; +#9790 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.261220487827980678E-14, 0.9999998176071847045 ) ) ; +#9791 = CIRCLE ( 'NONE', #4536, 7.500000216081117443 ) ; +#9792 = PLANE ( 'NONE', #21025 ) ; +#9793 = VECTOR ( 'NONE', #35607, 1000.000000000000000 ) ; +#9794 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971550692 ) ) ; +#9795 = ORIENTED_EDGE ( 'NONE', *, *, #31523, .T. ) ; +#9796 = CARTESIAN_POINT ( 'NONE', ( 28.35076616234001179, 124.9606007872231004, 91.22203692840190570 ) ) ; +#9797 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319379635751 ) ) ; +#9798 = CIRCLE ( 'NONE', #35844, 2.250000000000011102 ) ; +#9799 = CARTESIAN_POINT ( 'NONE', ( 20.11399216128939571, 127.4110302031022712, 89.17284890815865595 ) ) ; +#9800 = CARTESIAN_POINT ( 'NONE', ( 37.96459381866999649, 191.1162765711000020, 105.6220215677000027 ) ) ; +#9801 = VECTOR ( 'NONE', #36260, 1000.000000000000000 ) ; +#9802 = AXIS2_PLACEMENT_3D ( 'NONE', #22106, #21712, #3464 ) ; +#9803 = CARTESIAN_POINT ( 'NONE', ( 36.35497006709000090, 190.7198586766999995, 106.8900521645000055 ) ) ; +#9804 = ORIENTED_EDGE ( 'NONE', *, *, #18242, .T. ) ; +#9805 = ORIENTED_EDGE ( 'NONE', *, *, #24102, .F. ) ; +#9806 = FACE_OUTER_BOUND ( 'NONE', #2489, .T. ) ; +#9807 = CARTESIAN_POINT ( 'NONE', ( 15.99999439207489615, 185.9093013714976053, 102.5638074086867846 ) ) ; +#9808 = LINE ( 'NONE', #31689, #19331 ) ; +#9809 = DIRECTION ( 'NONE', ( 0.6087613186456907188, -0.7729176985478710682, -0.1789074850089337476 ) ) ; +#9810 = ORIENTED_EDGE ( 'NONE', *, *, #631, .T. ) ; +#9811 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971543198 ) ) ; +#9812 = VERTEX_POINT ( 'NONE', #5795 ) ; +#9813 = CARTESIAN_POINT ( 'NONE', ( -4.606609670189222960, 130.7903696091986490, 89.85103943815249750 ) ) ; +#9814 = CARTESIAN_POINT ( 'NONE', ( -36.27950425524976907, 191.8188495074159334, 104.4051415298545180 ) ) ; +#9815 = ORIENTED_EDGE ( 'NONE', *, *, #4920, .T. ) ; +#9816 = CARTESIAN_POINT ( 'NONE', ( 36.06588537441000142, 194.9391275604999976, 107.7152975676000040 ) ) ; +#9817 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#9818 = CARTESIAN_POINT ( 'NONE', ( -44.88970483650875565, 186.0423651227323205, 106.4552165319083628 ) ) ; +#9819 = DIRECTION ( 'NONE', ( 0.7933533411653070910, -0.5930537057989907490, -0.1373964268091706076 ) ) ; +#9820 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; +#9821 = CARTESIAN_POINT ( 'NONE', ( 22.11658946403013815, 136.0358612623089982, 91.55906883338052182 ) ) ; +#9822 = ORIENTED_EDGE ( 'NONE', *, *, #3611, .T. ) ; +#9823 = VERTEX_POINT ( 'NONE', #5172 ) ; +#9824 = CIRCLE ( 'NONE', #29400, 4.500000000062149397 ) ; +#9825 = CARTESIAN_POINT ( 'NONE', ( 12.64052830712477515, 176.9480430948374021, 103.3429212818187324 ) ) ; +#9826 = VECTOR ( 'NONE', #4407, 999.9999999999998863 ) ; +#9827 = FACE_OUTER_BOUND ( 'NONE', #21165, .T. ) ; +#9828 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921569638, -0.2249510932971626187 ) ) ; +#9829 = EDGE_CURVE ( 'NONE', #31713, #31820, #22873, .T. ) ; +#9830 = CONICAL_SURFACE ( 'NONE', #13092, 4.999999999982041032, 0.7853981634219900920 ) ; +#9831 = VECTOR ( 'NONE', #18249, 1000.000000000000114 ) ; +#9832 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; +#9833 = ORIENTED_EDGE ( 'NONE', *, *, #21232, .F. ) ; +#9834 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319364147923 ) ) ; +#9835 = EDGE_LOOP ( 'NONE', ( #1328, #11087, #19299, #1110, #39245, #21671, #23662, #13944, #39732, #14381, #9570 ) ) ; +#9836 = EDGE_CURVE ( 'NONE', #14883, #10112, #9156, .T. ) ; +#9838 = ADVANCED_FACE ( 'NONE', ( #12145 ), #38516, .F. ) ; +#9837 = CARTESIAN_POINT ( 'NONE', ( -20.49970530398912771, 127.6304983571866813, 89.64427666219336288 ) ) ; +#9839 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21734, #24609, #39916, #30535, #33978, #18426, #18626, #30316, #8663, #27277, #27489, #24204, #11927, #24408, #16564, #15770, #22737 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000008273937, 0.1875000000012067292, 0.2187500000014120094, 0.2343750000014990786, 0.2500000000015861201, 0.3750000000012484458, 0.4375000000010796364, 0.4687500000009522383, 0.5000000000008247847, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9840 = EDGE_CURVE ( 'NONE', #16668, #36222, #14604, .T. ) ; +#9841 = CARTESIAN_POINT ( 'NONE', ( -12.63532509571790108, 176.8621834306625260, 103.2253653902710511 ) ) ; +#9842 = EDGE_CURVE ( 'NONE', #30285, #2544, #12364, .T. ) ; +#9843 = CARTESIAN_POINT ( 'NONE', ( 15.50107933576640029, 185.4974642970334173, 104.3505830678656849 ) ) ; +#9844 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552156487, 3.781093664149108639E-12, 291.5584375788758393 ) ) ; +#9845 = FACE_OUTER_BOUND ( 'NONE', #35264, .T. ) ; +#9846 = EDGE_LOOP ( 'NONE', ( #19005, #1036, #11760, #1668 ) ) ; +#9847 = FACE_OUTER_BOUND ( 'NONE', #36842, .T. ) ; +#9848 = CARTESIAN_POINT ( 'NONE', ( 24.33241291692780806, 117.2920445016514748, 170.8609620625155117 ) ) ; +#9849 = CARTESIAN_POINT ( 'NONE', ( 43.14456005852381537, 112.6780295318855565, 129.4537069268840526 ) ) ; +#9850 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; +#9851 = ORIENTED_EDGE ( 'NONE', *, *, #35576, .T. ) ; +#9852 = ORIENTED_EDGE ( 'NONE', *, *, #30889, .T. ) ; +#9853 = VECTOR ( 'NONE', #18688, 1000.000000000000114 ) ; +#9854 = AXIS2_PLACEMENT_3D ( 'NONE', #37916, #4150, #9920 ) ; +#9855 = ORIENTED_EDGE ( 'NONE', *, *, #29115, .T. ) ; +#9856 = CARTESIAN_POINT ( 'NONE', ( 23.68305125547955470, 135.1720086282025477, 91.18766367950343010 ) ) ; +#9857 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927783543234, -0.0005734119022076374994 ) ) ; +#9858 = AXIS2_PLACEMENT_3D ( 'NONE', #38054, #19033, #18824 ) ; +#9859 = PLANE ( 'NONE', #18697 ) ; +#9860 = VERTEX_POINT ( 'NONE', #11532 ) ; +#9861 = LINE ( 'NONE', #433, #11314 ) ; +#9862 = CARTESIAN_POINT ( 'NONE', ( -38.59197811685999824, 118.5863865315999988, 89.70884965135999778 ) ) ; +#9863 = CARTESIAN_POINT ( 'NONE', ( -38.14759201839999747, 119.0917469409999967, 87.44184615819000328 ) ) ; +#9864 = LINE ( 'NONE', #7171, #34627 ) ; +#9865 = CARTESIAN_POINT ( 'NONE', ( 6.026693642215255053, 134.9199437178238838, 90.79804054718465522 ) ) ; +#9866 = ORIENTED_EDGE ( 'NONE', *, *, #40007, .F. ) ; +#9867 = EDGE_LOOP ( 'NONE', ( #27272, #10620, #12127, #17463 ) ) ; +#9868 = LINE ( 'NONE', #22342, #20474 ) ; +#9869 = CARTESIAN_POINT ( 'NONE', ( 31.86660797104250875, 191.2310028312767258, 27.90332390889487257 ) ) ; +#9870 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971571509 ) ) ; +#9871 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282902982, 164.6343173020860320, 97.67551052990278038 ) ) ; +#9872 = ORIENTED_EDGE ( 'NONE', *, *, #3964, .F. ) ; +#9873 = CARTESIAN_POINT ( 'NONE', ( -2.938990254353359699, 191.1128505916019833, 103.7748658681480123 ) ) ; +#9874 = CARTESIAN_POINT ( 'NONE', ( 2.774572678350095689, 189.9381179826846449, 103.5019175557437734 ) ) ; +#9876 = EDGE_CURVE ( 'NONE', #33925, #3470, #33971, .T. ) ; +#9875 = CARTESIAN_POINT ( 'NONE', ( -26.01077944034773282, 209.7097224531575534, 73.07398733611859143 ) ) ; +#9877 = CARTESIAN_POINT ( 'NONE', ( 0.04503145192460000085, 226.4002260771000010, 74.55847715811999876 ) ) ; +#9878 = EDGE_CURVE ( 'NONE', #15288, #34118, #29457, .T. ) ; +#9879 = EDGE_CURVE ( 'NONE', #10049, #22996, #9475, .T. ) ; +#9880 = ORIENTED_EDGE ( 'NONE', *, *, #11733, .T. ) ; +#9881 = VERTEX_POINT ( 'NONE', #3723 ) ; +#9882 = CARTESIAN_POINT ( 'NONE', ( 20.49980344970378354, 118.1127835573565221, 87.75514417896067698 ) ) ; +#9883 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825996983, 153.3598638654817989, 97.61100683840648173 ) ) ; +#9884 = VERTEX_POINT ( 'NONE', #37274 ) ; +#9885 = ADVANCED_FACE ( 'NONE', ( #38080 ), #9675, .F. ) ; +#9886 = CARTESIAN_POINT ( 'NONE', ( 2.729597314120624674, 191.4510214948855946, 104.1933275101542762 ) ) ; +#9887 = CARTESIAN_POINT ( 'NONE', ( 0.5638618802117814077, 189.0000000030334490, 105.7369977366696219 ) ) ; +#9888 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#9889 = CIRCLE ( 'NONE', #1972, 5.999999999999998224 ) ; +#9890 = ORIENTED_EDGE ( 'NONE', *, *, #21442, .T. ) ; +#9891 = AXIS2_PLACEMENT_3D ( 'NONE', #26210, #8613, #33929 ) ; +#9892 = CARTESIAN_POINT ( 'NONE', ( -19.99827189493212387, 119.1180982749954609, 90.27979767742741046 ) ) ; +#9893 = CARTESIAN_POINT ( 'NONE', ( -5.343454222961205424, 124.3650038869850079, 88.36807164162695472 ) ) ; +#9894 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#9895 = ADVANCED_FACE ( 'NONE', ( #6586 ), #13093, .F. ) ; +#9896 = ORIENTED_EDGE ( 'NONE', *, *, #4917, .F. ) ; +#9897 = CARTESIAN_POINT ( 'NONE', ( 3.166377416628577190, 128.5876387387983186, 89.33781556475464924 ) ) ; +#9898 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#9900 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709481474, 77.27946979429643193, 322.5205145037752459 ) ) ; +#9899 = CARTESIAN_POINT ( 'NONE', ( -21.82963555936113309, 135.9868450106493185, 91.57429495730107760 ) ) ; +#9901 = ADVANCED_FACE ( 'NONE', ( #34584 ), #856, .F. ) ; +#9902 = LINE ( 'NONE', #34795, #16394 ) ; +#9903 = ORIENTED_EDGE ( 'NONE', *, *, #8059, .F. ) ; +#9904 = LINE ( 'NONE', #9491, #36263 ) ; +#9905 = CARTESIAN_POINT ( 'NONE', ( 3.166361157742045407, 185.3154562800214649, 102.4344721822745328 ) ) ; +#9906 = ORIENTED_EDGE ( 'NONE', *, *, #6486, .F. ) ; +#9907 = CIRCLE ( 'NONE', #5980, 6.500000000016243895 ) ; +#9908 = EDGE_LOOP ( 'NONE', ( #36895, #19490, #6706, #6341 ) ) ; +#9910 = VECTOR ( 'NONE', #39120, 1000.000000000000000 ) ; +#9909 = CARTESIAN_POINT ( 'NONE', ( -25.99225322733968113, 193.8169247290872761, 102.7186084094945926 ) ) ; +#9911 = AXIS2_PLACEMENT_3D ( 'NONE', #32319, #26194, #10852 ) ; +#9912 = CARTESIAN_POINT ( 'NONE', ( 13.50308961628300430, 187.4748527437822645, 105.7372973370598004 ) ) ; +#9913 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597321 ) ) ; +#9914 = CARTESIAN_POINT ( 'NONE', ( 36.31286245014000258, 191.7213987641999893, 104.1933407292000027 ) ) ; +#9915 = VERTEX_POINT ( 'NONE', #9887 ) ; +#9916 = ORIENTED_EDGE ( 'NONE', *, *, #34850, .F. ) ; +#9917 = CARTESIAN_POINT ( 'NONE', ( -29.94780647242213689, 109.6131156702000027, 87.78587210770182025 ) ) ; +#9918 = CYLINDRICAL_SURFACE ( 'NONE', #25064, 2.000000000000014655 ) ; +#9919 = CARTESIAN_POINT ( 'NONE', ( -30.77616838766000029, 184.0515098276000003, 103.7026069805999953 ) ) ; +#9920 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; +#9921 = ORIENTED_EDGE ( 'NONE', *, *, #22451, .F. ) ; +#9922 = CARTESIAN_POINT ( 'NONE', ( 31.79391125766024118, 112.9712782986316171, 186.3766760902708199 ) ) ; +#9923 = ORIENTED_EDGE ( 'NONE', *, *, #20804, .F. ) ; +#9925 = EDGE_CURVE ( 'NONE', #19846, #13511, #660, .T. ) ; +#9924 = CARTESIAN_POINT ( 'NONE', ( -37.00271443861222309, 116.5564442434732371, 89.73446267232999674 ) ) ; +#9926 = ADVANCED_FACE ( 'NONE', ( #34782 ), #3512, .F. ) ; +#9927 = EDGE_CURVE ( 'NONE', #10716, #40452, #36250, .T. ) ; +#9928 = PLANE ( 'NONE', #11804 ) ; +#9929 = ORIENTED_EDGE ( 'NONE', *, *, #26552, .T. ) ; +#9930 = CARTESIAN_POINT ( 'NONE', ( 40.54493956969010071, 206.4002260771000010, 73.03401595486556630 ) ) ; +#9931 = CARTESIAN_POINT ( 'NONE', ( -46.53618338323362735, 143.6732897604458685, 289.8004740256295690 ) ) ; +#9932 = CARTESIAN_POINT ( 'NONE', ( 22.11776639833565028, 135.5859592220768945, 93.50780862338704935 ) ) ; +#9933 = EDGE_CURVE ( 'NONE', #5155, #24392, #23587, .T. ) ; +#9934 = ORIENTED_EDGE ( 'NONE', *, *, #35500, .F. ) ; +#9935 = FACE_OUTER_BOUND ( 'NONE', #24719, .T. ) ; +#9936 = ORIENTED_EDGE ( 'NONE', *, *, #37629, .T. ) ; +#9937 = ORIENTED_EDGE ( 'NONE', *, *, #7733, .F. ) ; +#9938 = FACE_OUTER_BOUND ( 'NONE', #14898, .T. ) ; +#9939 = AXIS2_PLACEMENT_3D ( 'NONE', #19188, #31901, #32291 ) ; +#9940 = CARTESIAN_POINT ( 'NONE', ( -37.29435884442529670, 164.6092402323636463, 198.2106787237848948 ) ) ; +#9941 = LINE ( 'NONE', #7045, #18965 ) ; +#9942 = CONICAL_SURFACE ( 'NONE', #32772, 2.502997546632800940, 0.7853981634134501455 ) ; +#9943 = EDGE_CURVE ( 'NONE', #36211, #27638, #671, .T. ) ; +#9944 = AXIS2_PLACEMENT_3D ( 'NONE', #12003, #40191, #37537 ) ; +#9945 = DIRECTION ( 'NONE', ( 0.0005884949961175196939, -0.2249510543439042221, 0.9743698870671267942 ) ) ; +#9946 = ORIENTED_EDGE ( 'NONE', *, *, #3219, .T. ) ; +#9947 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#9948 = CARTESIAN_POINT ( 'NONE', ( 16.00000031304551129, 127.7446264382961232, 89.13542822417404921 ) ) ; +#9949 = ORIENTED_EDGE ( 'NONE', *, *, #32184, .T. ) ; +#9950 = CARTESIAN_POINT ( 'NONE', ( 8.188663998450230963, 161.0533193647609949, 96.83006515600399666 ) ) ; +#9951 = CARTESIAN_POINT ( 'NONE', ( 25.49919833444198858, 118.8155663768459505, 87.75236248755290092 ) ) ; +#9952 = CARTESIAN_POINT ( 'NONE', ( 23.36304559730844232, 177.4675757536537617, 100.8901253294131237 ) ) ; +#9953 = DIRECTION ( 'NONE', ( 0.0005884949950583391728, -0.2249510543447034716, 0.9743698870669428302 ) ) ; +#9954 = EDGE_LOOP ( 'NONE', ( #29504, #35960, #27331, #37545 ) ) ; +#9955 = ORIENTED_EDGE ( 'NONE', *, *, #33115, .T. ) ; +#9956 = EDGE_LOOP ( 'NONE', ( #11216, #30512, #34415, #37312 ) ) ; +#9957 = CARTESIAN_POINT ( 'NONE', ( 37.40434350968867250, 145.4460227941551409, 282.5393146728916918 ) ) ; +#9958 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971548471 ) ) ; +#9959 = EDGE_LOOP ( 'NONE', ( #19073, #34780, #23859, #13830 ) ) ; +#9960 = VERTEX_POINT ( 'NONE', #10289 ) ; +#9961 = DIRECTION ( 'NONE', ( -0.6087611434178765712, -0.7731004625452565504, -0.1781166614241066204 ) ) ; +#9962 = CARTESIAN_POINT ( 'NONE', ( 19.98271301993268523, 207.8686081833218111, 77.26500776042075813 ) ) ; +#9963 = VECTOR ( 'NONE', #15666, 1000.000000000000227 ) ; +#9964 = ORIENTED_EDGE ( 'NONE', *, *, #23682, .T. ) ; +#9965 = FACE_OUTER_BOUND ( 'NONE', #40009, .T. ) ; +#9966 = CONICAL_SURFACE ( 'NONE', #32795, 2.503158050477443552, 0.7853981633930871009 ) ; +#9967 = AXIS2_PLACEMENT_3D ( 'NONE', #36336, #17096, #8333 ) ; +#9968 = LINE ( 'NONE', #28766, #7748 ) ; +#9969 = ORIENTED_EDGE ( 'NONE', *, *, #12535, .T. ) ; +#9970 = CARTESIAN_POINT ( 'NONE', ( 28.40947388104000382, 125.3678125673000068, 88.75007089381999492 ) ) ; +#9971 = FACE_OUTER_BOUND ( 'NONE', #16704, .T. ) ; +#9972 = CARTESIAN_POINT ( 'NONE', ( -31.70415073521903082, 226.4002260770974715, 75.57765305100397768 ) ) ; +#9973 = EDGE_CURVE ( 'NONE', #26075, #6177, #8376, .T. ) ; +#9974 = EDGE_CURVE ( 'NONE', #8110, #33342, #30455, .T. ) ; +#9975 = CARTESIAN_POINT ( 'NONE', ( 20.50029382911849041, 160.6303866027595575, 97.23813965018092631 ) ) ; +#9976 = CARTESIAN_POINT ( 'NONE', ( 36.04411892353206781, 218.5902260770999987, 73.03673433784747715 ) ) ; +#9977 = ORIENTED_EDGE ( 'NONE', *, *, #24430, .T. ) ; +#9978 = CARTESIAN_POINT ( 'NONE', ( 0.5444273898015423718, 211.0000000000153761, 73.55817535318051625 ) ) ; +#9979 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 132.9679238121742912, 90.36185680194377312 ) ) ; +#9980 = CARTESIAN_POINT ( 'NONE', ( -1.546702755154200526, 188.6421838410412306, 106.2842503570885810 ) ) ; +#9981 = CARTESIAN_POINT ( 'NONE', ( -26.00138850119475364, 118.1173731751006102, 87.28355378449504087 ) ) ; +#9982 = DIRECTION ( 'NONE', ( 0.0005884949961254435855, -0.2249510543439056098, 0.9743698870671265722 ) ) ; +#9983 = DIRECTION ( 'NONE', ( -0.7856246811335055868, -0.6187033702784217049, 0.000000000000000000 ) ) ; +#9984 = CARTESIAN_POINT ( 'NONE', ( -3.742149463410260335, 168.4491106192983523, 98.75463826265171008 ) ) ; +#9985 = AXIS2_PLACEMENT_3D ( 'NONE', #20765, #6823, #28719 ) ; +#9986 = CARTESIAN_POINT ( 'NONE', ( -25.71583257454510374, 189.5945154360309743, 106.0004275678039960 ) ) ; +#9987 = ORIENTED_EDGE ( 'NONE', *, *, #30388, .T. ) ; +#9988 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28844, #31509, #22522, #34940, #16357, #13307, #7156, #23511, #4282, #20224, #13508, #8178, #39240, #29250, #32318, #7966, #14318, #13705, #16756, #32908, #35538, #20026 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 1, 1, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999997939149, 0.1874999999997047362, 0.2187499999996750932, 0.2343749999996755651, 0.2421874999996899980, 0.2499999999997044031, 0.3749999999997604139, 0.4374999999997855604, 0.4999999999998107070, 0.7499999999999052980, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#9989 = CIRCLE ( 'NONE', #14544, 5.249999999999986677 ) ; +#9990 = CARTESIAN_POINT ( 'NONE', ( -19.00212931565669550, 148.4455407551447195, 183.7151382749372033 ) ) ; +#9991 = ADVANCED_FACE ( 'NONE', ( #23495 ), #20836, .T. ) ; +#9992 = CIRCLE ( 'NONE', #23039, 2.499999999999997335 ) ; +#9993 = CARTESIAN_POINT ( 'NONE', ( 19.98210856654580780, 205.1070970766282358, 76.09272704596726555 ) ) ; +#9994 = EDGE_LOOP ( 'NONE', ( #4626, #13949, #20764, #22397 ) ) ; +#9995 = CARTESIAN_POINT ( 'NONE', ( 20.49918579871235735, 117.7855550408559253, 87.75515918128132853 ) ) ; +#9996 = CARTESIAN_POINT ( 'NONE', ( 23.36030151151609857, 181.4168257864797340, 104.2589971034701222 ) ) ; +#9997 = DIRECTION ( 'NONE', ( 0.9914447795421099663, 0.1272537940605282525, 0.02904687618140097335 ) ) ; +#9998 = CARTESIAN_POINT ( 'NONE', ( -41.39564160242315438, 120.8598907892144609, 87.92272842288021195 ) ) ; +#9999 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#10000 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10001 = ORIENTED_EDGE ( 'NONE', *, *, #36269, .T. ) ; +#10002 = CARTESIAN_POINT ( 'NONE', ( -2.874686192646000116, 209.6463030548999882, 76.06021946686999513 ) ) ; +#10003 = CARTESIAN_POINT ( 'NONE', ( 20.50068614270568190, 184.7049436401913738, 103.4803894424373141 ) ) ; +#10004 = FACE_OUTER_BOUND ( 'NONE', #2698, .T. ) ; +#10005 = ORIENTED_EDGE ( 'NONE', *, *, #20292, .T. ) ; +#10006 = CARTESIAN_POINT ( 'NONE', ( 6.042308921164076807, 177.7921139377573638, 100.6958234779730645 ) ) ; +#10007 = VERTEX_POINT ( 'NONE', #21045 ) ; +#10008 = EDGE_CURVE ( 'NONE', #25177, #2058, #6992, .T. ) ; +#10009 = DIRECTION ( 'NONE', ( 0.6087614883550945821, -0.7730004026499608383, -0.1785492307423601210 ) ) ; +#10010 = LINE ( 'NONE', #4049, #7112 ) ; +#10011 = CARTESIAN_POINT ( 'NONE', ( -37.58602203893437377, 191.4135895612745912, 104.3798639524113270 ) ) ; +#10012 = CARTESIAN_POINT ( 'NONE', ( -42.49459211381155654, 185.0676328030043294, 127.1859204975182251 ) ) ; +#10013 = LINE ( 'NONE', #37812, #21425 ) ; +#10014 = ADVANCED_FACE ( 'NONE', ( #7743 ), #6531, .F. ) ; +#10015 = CIRCLE ( 'NONE', #29595, 4.500000000010447643 ) ; +#10016 = EDGE_CURVE ( 'NONE', #16362, #32161, #28031, .T. ) ; +#10017 = CARTESIAN_POINT ( 'NONE', ( 22.99888613823950578, 118.1131156702000169, 87.25083745503069110 ) ) ; +#10018 = CARTESIAN_POINT ( 'NONE', ( 20.50039165879256942, 118.8156470718432729, 87.75541749211321019 ) ) ; +#10019 = EDGE_LOOP ( 'NONE', ( #33170, #40204, #36069, #22683 ) ) ; +#10020 = CARTESIAN_POINT ( 'NONE', ( 12.64122564679159311, 176.9953992898509227, 103.4187065096068210 ) ) ; +#10021 = CONICAL_SURFACE ( 'NONE', #18454, 6.499999999875097245, 0.7853981634274167511 ) ; +#10022 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10023 = FACE_OUTER_BOUND ( 'NONE', #703, .T. ) ; +#10024 = PLANE ( 'NONE', #39247 ) ; +#10025 = ORIENTED_EDGE ( 'NONE', *, *, #40135, .T. ) ; +#10026 = PLANE ( 'NONE', #8134 ) ; +#10027 = VERTEX_POINT ( 'NONE', #17948 ) ; +#10028 = CARTESIAN_POINT ( 'NONE', ( 20.00178331300101320, 191.9758063960465790, 106.9093738487591736 ) ) ; +#10029 = CARTESIAN_POINT ( 'NONE', ( -12.63378477145710299, 177.0226112301060368, 103.4821023998732272 ) ) ; +#10030 = CARTESIAN_POINT ( 'NONE', ( -15.49852918059724693, 160.1761146120170736, 99.20761365264185372 ) ) ; +#10031 = EDGE_CURVE ( 'NONE', #19312, #25364, #7951, .T. ) ; +#10032 = CARTESIAN_POINT ( 'NONE', ( -3.083129345975000213, 209.1876396531000069, 72.95049128518999737 ) ) ; +#10033 = LINE ( 'NONE', #1421, #37631 ) ; +#10034 = CIRCLE ( 'NONE', #29617, 2.000000000000011546 ) ; +#10035 = EDGE_LOOP ( 'NONE', ( #37263, #18372, #33048, #11371 ) ) ; +#10036 = CARTESIAN_POINT ( 'NONE', ( 15.05621097247296980, 125.1021127306558043, 171.3704188677303648 ) ) ; +#10037 = DIRECTION ( 'NONE', ( 0.0005884949961248781740, -0.2249510543439064425, 0.9743698870671262391 ) ) ; +#10038 = DIRECTION ( 'NONE', ( 4.622231023467483304E-33, -1.000000000000000000, -2.791711714772432647E-36 ) ) ; +#10039 = AXIS2_PLACEMENT_3D ( 'NONE', #15968, #25003, #22535 ) ; +#10040 = CARTESIAN_POINT ( 'NONE', ( -43.94868134759096279, 113.2635659203109242, 86.34157100920022287 ) ) ; +#10041 = ORIENTED_EDGE ( 'NONE', *, *, #14697, .T. ) ; +#10042 = VECTOR ( 'NONE', #34222, 1000.000000000000000 ) ; +#10043 = EDGE_LOOP ( 'NONE', ( #36128, #6187, #5198, #17012, #3155 ) ) ; +#10044 = CARTESIAN_POINT ( 'NONE', ( 23.67998985452990368, 134.9222885997251637, 90.78792508986444432 ) ) ; +#10045 = ADVANCED_FACE ( 'NONE', ( #4680 ), #4880, .F. ) ; +#10046 = CARTESIAN_POINT ( 'NONE', ( 28.46126684983220301, 181.2175652934160723, 104.3810058980785698 ) ) ; +#10047 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10048 = LINE ( 'NONE', #17859, #23276 ) ; +#10049 = VERTEX_POINT ( 'NONE', #1616 ) ; +#10050 = VERTEX_POINT ( 'NONE', #1824 ) ; +#10051 = DIRECTION ( 'NONE', ( 0.0006039748302207421579, 7.542342735779980945E-05, 0.9999998147628383904 ) ) ; +#10052 = EDGE_CURVE ( 'NONE', #31713, #37217, #11421, .T. ) ; +#10053 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#10054 = CARTESIAN_POINT ( 'NONE', ( -38.71072168210999820, 118.8966380287999982, 89.91271735956999578 ) ) ; +#10055 = CARTESIAN_POINT ( 'NONE', ( -38.35938540240999828, 118.8192337114000026, 87.71744047141000067 ) ) ; +#10056 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; +#10057 = CARTESIAN_POINT ( 'NONE', ( 13.76493622865632105, 124.4309290350651622, 178.6669391780345109 ) ) ; +#10058 = ORIENTED_EDGE ( 'NONE', *, *, #10804, .T. ) ; +#10059 = CARTESIAN_POINT ( 'NONE', ( -12.63662705431230293, 128.0215907353206717, 91.78242701837325512 ) ) ; +#10060 = ORIENTED_EDGE ( 'NONE', *, *, #5575, .T. ) ; +#10061 = CARTESIAN_POINT ( 'NONE', ( 10.21688458673440891, 134.9203821546222741, 90.79555158895830402 ) ) ; +#10062 = CARTESIAN_POINT ( 'NONE', ( -23.00006628334871550, 115.6131129681876359, 89.78164257609942922 ) ) ; +#10063 = ADVANCED_FACE ( 'NONE', ( #36159 ), #16313, .F. ) ; +#10064 = ADVANCED_FACE ( 'NONE', ( #17544 ), #39424, .T. ) ; +#10065 = CARTESIAN_POINT ( 'NONE', ( -20.00104315107090258, 184.5969240560925186, 102.2825614518015982 ) ) ; +#10066 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988409597765, 156.3551877982712028, 95.75036263596727792 ) ) ; +#10067 = ORIENTED_EDGE ( 'NONE', *, *, #5442, .F. ) ; +#10068 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; +#10069 = ADVANCED_FACE ( 'NONE', ( #39632, #34294, #33901 ), #31053, .T. ) ; +#10070 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927798816119, -0.0005734119022070481271 ) ) ; +#10071 = AXIS2_PLACEMENT_3D ( 'NONE', #1981, #36929, #9470 ) ; +#10072 = AXIS2_PLACEMENT_3D ( 'NONE', #40421, #21447, #2821 ) ; +#10073 = PLANE ( 'NONE', #19464 ) ; +#10074 = VECTOR ( 'NONE', #33521, 1000.000000000000227 ) ; +#10075 = ORIENTED_EDGE ( 'NONE', *, *, #898, .F. ) ; +#10076 = FACE_OUTER_BOUND ( 'NONE', #33660, .T. ) ; +#10077 = FACE_OUTER_BOUND ( 'NONE', #24461, .T. ) ; +#10078 = EDGE_LOOP ( 'NONE', ( #39926, #33403, #4136, #10463, #36228, #11660, #33716, #22337, #33365, #1072 ) ) ; +#10079 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#10080 = CARTESIAN_POINT ( 'NONE', ( 21.09369789642633108, 176.5485049525730403, 100.3996169591982408 ) ) ; +#10081 = FACE_OUTER_BOUND ( 'NONE', #34043, .T. ) ; +#10082 = VERTEX_POINT ( 'NONE', #18357 ) ; +#10083 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28202, #21254, #37388, #18152, #15121, #24535, #21466, #24739, #21664, #9385, #9185, #21415, #5856, #17903, #6053, #18500, #118, #9531, #2973, #12579 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999517331, 0.1874999999999391875, 0.2187499999999441280, 0.2343749999999461264, 0.2499999999999481526, 0.4999999999999749090, 0.6249999999999944489, 0.6875000000000048850, 0.7187500000000140998, 0.7343750000000180966, 0.7500000000000219824, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10084 = FACE_OUTER_BOUND ( 'NONE', #4081, .T. ) ; +#10085 = CARTESIAN_POINT ( 'NONE', ( -5.675054657474391639, 124.3656264979204167, 88.36836997283377571 ) ) ; +#10086 = EDGE_CURVE ( 'NONE', #15609, #6503, #27608, .T. ) ; +#10087 = VERTEX_POINT ( 'NONE', #34100 ) ; +#10088 = ORIENTED_EDGE ( 'NONE', *, *, #6190, .F. ) ; +#10089 = CARTESIAN_POINT ( 'NONE', ( 26.00433782744423894, 120.0770285022223618, 90.42368137231409264 ) ) ; +#10090 = CARTESIAN_POINT ( 'NONE', ( 32.37049208148693680, 138.3096525682149718, 91.56466976714693828 ) ) ; +#10091 = ORIENTED_EDGE ( 'NONE', *, *, #38187, .F. ) ; +#10093 = LINE ( 'NONE', #29101, #5741 ) ; +#10092 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971566513 ) ) ; +#10094 = AXIS2_PLACEMENT_3D ( 'NONE', #38627, #29853, #23107 ) ; +#10095 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319412346130 ) ) ; +#10096 = AXIS2_PLACEMENT_3D ( 'NONE', #19410, #3866, #11034 ) ; +#10097 = VECTOR ( 'NONE', #747, 1000.000000000000114 ) ; +#10098 = VERTEX_POINT ( 'NONE', #21852 ) ; +#10099 = CARTESIAN_POINT ( 'NONE', ( 13.45852275855000180, 176.5968831303999877, 28.07991271570000080 ) ) ; +#10100 = EDGE_CURVE ( 'NONE', #32767, #13796, #28871, .T. ) ; +#10101 = CARTESIAN_POINT ( 'NONE', ( 39.72066837979766518, 175.7297623423441166, 136.1382466769391897 ) ) ; +#10103 = ORIENTED_EDGE ( 'NONE', *, *, #3811, .T. ) ; +#10102 = CIRCLE ( 'NONE', #32935, 6.500000000009833023 ) ; +#10104 = ORIENTED_EDGE ( 'NONE', *, *, #33281, .T. ) ; +#10105 = CARTESIAN_POINT ( 'NONE', ( 39.02126669689999972, 118.7292573019000059, 89.54553178854999373 ) ) ; +#10106 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; +#10107 = EDGE_CURVE ( 'NONE', #29513, #20244, #20248, .T. ) ; +#10108 = CARTESIAN_POINT ( 'NONE', ( -46.11428651860251904, 125.3901704247413420, 91.70828747460114982 ) ) ; +#10109 = CARTESIAN_POINT ( 'NONE', ( -2.557040332230999802, 190.9413657988000068, 106.4259741240000068 ) ) ; +#10110 = EDGE_CURVE ( 'NONE', #19817, #24492, #29714, .T. ) ; +#10111 = ORIENTED_EDGE ( 'NONE', *, *, #13520, .T. ) ; +#10112 = VERTEX_POINT ( 'NONE', #27799 ) ; +#10113 = CARTESIAN_POINT ( 'NONE', ( -6.035627011758199600, 176.7717547812872283, 103.0754667242794369 ) ) ; +#10114 = CARTESIAN_POINT ( 'NONE', ( -12.63689782195842426, 177.3133338180326461, 101.0041712154207971 ) ) ; +#10115 = CARTESIAN_POINT ( 'NONE', ( -23.36135659116623131, 134.7454096763920575, 93.42281670956344897 ) ) ; +#10116 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394468890994, 77.14301703112153064, 297.5584364845176424 ) ) ; +#10117 = EDGE_CURVE ( 'NONE', #18466, #27631, #33274, .T. ) ; +#10118 = CARTESIAN_POINT ( 'NONE', ( -3.419728389424999904, 184.9596546093000029, 102.6128657888999953 ) ) ; +#10119 = ORIENTED_EDGE ( 'NONE', *, *, #37569, .F. ) ; +#10120 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #25515, #25112, #9362, #9564 ), + ( #22041, #34672, #13237, #16478 ), + ( #34279, #153, #25920, #31228 ), + ( #942, #13031, #12612, #3805 ), + ( #7076, #37559, #9970, #3203 ), + ( #15682, #6672, #19141, #34470 ), + ( #16283, #13433, #18940, #35072 ), + ( #15878, #22443, #25719, #9766 ), + ( #28370, #28968, #21834, #343 ), + ( #28183, #10175, #31643, #12829 ), + ( #25315, #3601, #16083, #6879 ), + ( #19351, #27284, #4202, #30124 ), + ( #14593, #23582, #8249, #23792 ), + ( #5576, #39711, #36246, #17826 ), + ( #11117, #14195, #30328, #36661 ), + ( #39109, #14801, #17429, #20923 ), + ( #38365, #27080, #18034, #11726 ), + ( #30540, #29925, #39511, #26663 ), + ( #36036, #8670, #8034, #11310 ), + ( #21124, #32241, #22840, #29726 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( 4.144611087445999877E-13, 0.001560744696352999979, 0.003123273415232000021, 0.006248330852988999602, 0.009373388290745000850, 0.01249844572850000030, 0.02499867547953000049, 0.04999913498157999847, 0.07499959448364000580, 0.1000000539855999959, 0.1500009729898000022, 0.2000018919939000051, 0.3000016515100000225, 0.4000014110264000222, 0.5000011705425999597, 0.6000009300586000016, 0.8000004490911000188, 0.9999999999993000044 ), + ( 0.1755538993766999900, 0.8244309313148000529 ), + .UNSPECIFIED. ) ; +#10121 = CARTESIAN_POINT ( 'NONE', ( -21.48379418977146216, 213.0894754797338635, 73.57151699824268576 ) ) ; +#10122 = ORIENTED_EDGE ( 'NONE', *, *, #38794, .T. ) ; +#10123 = CARTESIAN_POINT ( 'NONE', ( -36.88617345849917228, 116.3403704899029805, 89.73734838559249738 ) ) ; +#10124 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; +#10125 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37977, #31858, #38181, #7087, #19561, #25929, #25322, #13635, #32449, #4212, #9775, #32059, #35471, #22253, #34880, #4019, #19949, #3608, #16485, #4421, #28975, #549, #954, #13442, #26124, #22851, #35282, #29189, #16878, #19149, #32248, #1158, #19361, #37766, #29385, #38564, #34683, #755, #10584, #3815, #28583, #23050, #1350, #31653, #16292, #13042, #25522, #13244, #14045, #1770, #39370, #8521, #7895, #11586, #10779, #1561, #5433, #10979, #26520, #5224, #38757, #35678, #5028, #13834, #30190, #7693, #39175, #39574, #17691, #35891, #33037, #24063, #1982, #20987, #17891, #36519, #20156, #30390, #36313, #17284, #11177, #11367, #26723 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 2, 1, 2, 2, 2, 2, 1, 1, 1, 2, 2, 2, 2, 1, 1, 1, 2, 2, 2, 2, 1, 1, 1, 1, 1, 2, 2, 2, 2, 2, 1, 1, 1, 1, 1, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.03124999999964665071, 0.04687499999947851437, 0.06249999999931038497, 0.09374999999901274805, 0.1249999999987151111, 0.1562499999984174603, 0.1718749999982719656, 0.1874999999981264431, 0.2187499999978410326, 0.2343749999976944276, 0.2421874999976163789, 0.2499999999975383025, 0.3124999999969176878, 0.3437499999966042719, 0.3593749999964475639, 0.3671874999963690711, 0.3710937499963357644, 0.3730468749963191111, 0.3749999999963024577, 0.4374999999957845387, 0.4687499999955245800, 0.4843749999953838037, 0.4921874999953129159, 0.4960937499952750573, 0.4980468749952560725, 0.4999999999952371432, 0.6249999999941835416, 0.6874999999936627360, 0.7187499999934022776, 0.7343749999932634998, 0.7421874999931941108, 0.7460937499931673544, 0.7480468749931539207, 0.7490234374931551420, 0.7499999999931562522, 0.8124999999930890837, 0.8437499999930507810, 0.8593749999930213601, 0.8671874999930213601, 0.8710937499930025973, 0.8730468749929957140, 0.8740234374929921612, 0.8745117187430150318, 0.8747558593680300199, 0.8749999999930448968, 0.9062499999947836171, 0.9374999999965223374, 0.9687499999982611687, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10126 = CARTESIAN_POINT ( 'NONE', ( -14.44401576354613326, 124.5449641176314799, 88.41511525325832110 ) ) ; +#10127 = AXIS2_PLACEMENT_3D ( 'NONE', #11997, #30807, #28147 ) ; +#10128 = CARTESIAN_POINT ( 'NONE', ( -2.561038461354999907, 190.7963388503999909, 106.3865919585000057 ) ) ; +#10129 = AXIS2_PLACEMENT_3D ( 'NONE', #19705, #32009, #19899 ) ; +#10130 = CONICAL_SURFACE ( 'NONE', #22539, 2.500000720456969194, 0.7853981633184845546 ) ; +#10131 = DIRECTION ( 'NONE', ( 0.0005884949961234677354, -0.2249510543439058596, 0.9743698870671263501 ) ) ; +#10132 = ORIENTED_EDGE ( 'NONE', *, *, #25902, .T. ) ; +#10133 = CARTESIAN_POINT ( 'NONE', ( -35.95405601968200671, 218.5902260770999987, 76.08021997850752882 ) ) ; +#10134 = ORIENTED_EDGE ( 'NONE', *, *, #15852, .F. ) ; +#10135 = CIRCLE ( 'NONE', #29713, 51.40509898898542929 ) ; +#10136 = DIRECTION ( 'NONE', ( -0.0006039748319386088922, 0.000000000000000000, -0.9999998176071845934 ) ) ; +#10137 = CARTESIAN_POINT ( 'NONE', ( 30.05352353131179655, 109.6131156702000027, 87.24963271652086405 ) ) ; +#10138 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #20746, #27114, #26490, #29553 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.570796326794891895, 3.141592653589798889 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8047378541243626060, 0.8047378541243626060, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#10139 = CARTESIAN_POINT ( 'NONE', ( 19.31897996664549311, 125.9032283610015952, 175.4006784427203911 ) ) ; +#10140 = FACE_OUTER_BOUND ( 'NONE', #35350, .T. ) ; +#10141 = FACE_OUTER_BOUND ( 'NONE', #18403, .T. ) ; +#10142 = ORIENTED_EDGE ( 'NONE', *, *, #9973, .F. ) ; +#10143 = CARTESIAN_POINT ( 'NONE', ( 28.46393509008022349, 182.0672870871918576, 102.1824291507762865 ) ) ; +#10144 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7196, #34399, #3517, #28687, #25235 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 4 ), + ( 0.000000000000000000, 0.001674833360455941925, 0.003349666720911883850 ), + .UNSPECIFIED. ) ; +#10145 = CARTESIAN_POINT ( 'NONE', ( -45.12594099392538993, 124.0049325119809254, 93.44049169948378619 ) ) ; +#10146 = CARTESIAN_POINT ( 'NONE', ( -35.90900567064999649, 113.8802525378000041, 89.89618011484999727 ) ) ; +#10147 = ORIENTED_EDGE ( 'NONE', *, *, #9702, .F. ) ; +#10148 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -4.625929269271484533E-15, 0.0006039748319299392864 ) ) ; +#10149 = ORIENTED_EDGE ( 'NONE', *, *, #22113, .F. ) ; +#10150 = ADVANCED_FACE ( 'NONE', ( #18956 ), #36773, .F. ) ; +#10151 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#10152 = ADVANCED_FACE ( 'NONE', ( #21661 ), #28761, .F. ) ; +#10153 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16109, #10198, #29396, #7101 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10154 = CARTESIAN_POINT ( 'NONE', ( 25.49919833792598212, 119.3071684866960567, 87.75237467855311024 ) ) ; +#10155 = EDGE_CURVE ( 'NONE', #38686, #16668, #12433, .T. ) ; +#10156 = CARTESIAN_POINT ( 'NONE', ( 23.36315499107861982, 177.3935024194639425, 100.9364114368636223 ) ) ; +#10157 = ADVANCED_FACE ( 'NONE', ( #40435 ), #32008, .F. ) ; +#10158 = DIRECTION ( 'NONE', ( 0.0005884949961258157921, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10159 = VERTEX_POINT ( 'NONE', #30656 ) ; +#10160 = AXIS2_PLACEMENT_3D ( 'NONE', #4939, #14564, #1886 ) ; +#10161 = ORIENTED_EDGE ( 'NONE', *, *, #29687, .F. ) ; +#10162 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10163 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825944865401622, 0.0005734119018115155621 ) ) ; +#10164 = AXIS2_PLACEMENT_3D ( 'NONE', #11426, #14503, #5283 ) ; +#10165 = CIRCLE ( 'NONE', #40199, 51.90509898902980979 ) ; +#10166 = EDGE_CURVE ( 'NONE', #16493, #34215, #30838, .T. ) ; +#10167 = EDGE_LOOP ( 'NONE', ( #13999, #37058, #29712, #27594 ) ) ; +#10168 = CARTESIAN_POINT ( 'NONE', ( -30.77616838766000029, 127.9758643804000116, 90.75652178872999798 ) ) ; +#10169 = VECTOR ( 'NONE', #34998, 1000.000000000000000 ) ; +#10170 = FACE_OUTER_BOUND ( 'NONE', #5590, .T. ) ; +#10171 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10172 = EDGE_CURVE ( 'NONE', #14325, #5169, #35238, .T. ) ; +#10173 = CARTESIAN_POINT ( 'NONE', ( 37.32093527568547131, 124.9538660553759115, 92.22097858659103053 ) ) ; +#10174 = EDGE_LOOP ( 'NONE', ( #3446, #3544, #17555, #18364, #24725, #31535, #37627, #7602 ) ) ; +#10175 = CARTESIAN_POINT ( 'NONE', ( 27.98864118927000533, 125.2419143087000180, 88.89258992074999810 ) ) ; +#10176 = CARTESIAN_POINT ( 'NONE', ( -14.91027383994646272, 151.7163915728016548, 177.9904694539845025 ) ) ; +#10177 = PLANE ( 'NONE', #29929 ) ; +#10178 = DIRECTION ( 'NONE', ( -0.0005884949961238529524, 0.2249510543439058596, -0.9743698870671263501 ) ) ; +#10179 = CARTESIAN_POINT ( 'NONE', ( 5.659153654835778369, 124.3673852322629187, 88.36203164978959990 ) ) ; +#10180 = EDGE_LOOP ( 'NONE', ( #17599, #5888, #5416, #31224 ) ) ; +#10181 = EDGE_CURVE ( 'NONE', #7714, #33558, #25508, .T. ) ; +#10182 = CARTESIAN_POINT ( 'NONE', ( 18.98511042798971360, 148.3283295584973871, 184.1927148392349807 ) ) ; +#10183 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10184 = CARTESIAN_POINT ( 'NONE', ( 3.166376970775131028, 185.9099593149100542, 102.5717182116986521 ) ) ; +#10185 = VECTOR ( 'NONE', #15484, 1000.000000000000000 ) ; +#10186 = CARTESIAN_POINT ( 'NONE', ( 25.99886678296517672, 118.8155665066540934, 87.25209012101137773 ) ) ; +#10187 = EDGE_LOOP ( 'NONE', ( #30177, #26805, #9815, #27311, #23951, #39119, #20115, #36899, #30169, #4916, #22198, #23486, #18724, #12218, #28629 ) ) ; +#10188 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825909994896701, 0.0005734119026157004058 ) ) ; +#10189 = LINE ( 'NONE', #35686, #37520 ) ; +#10190 = VECTOR ( 'NONE', #39992, 1000.000000000000227 ) ; +#10191 = DIRECTION ( 'NONE', ( 0.7856637149787887298, -0.6186538021912810770, 0.000000000000000000 ) ) ; +#10192 = CARTESIAN_POINT ( 'NONE', ( 25.50046720880995110, 119.8278461341044903, 89.86771791569053391 ) ) ; +#10193 = CARTESIAN_POINT ( 'NONE', ( 35.65259997913155132, 138.3326317399398988, 284.1430326337134602 ) ) ; +#10194 = CONICAL_SURFACE ( 'NONE', #33012, 2.502986300332882497, 0.7853981634574371817 ) ; +#10195 = CARTESIAN_POINT ( 'NONE', ( -15.66504166165583811, 173.9170443170240787, 102.5510515039815971 ) ) ; +#10196 = VERTEX_POINT ( 'NONE', #28782 ) ; +#10197 = AXIS2_PLACEMENT_3D ( 'NONE', #23177, #4347, #29509 ) ; +#10198 = CARTESIAN_POINT ( 'NONE', ( -15.83311930531312939, 174.4825619823285763, 100.1161292540394214 ) ) ; +#10199 = AXIS2_PLACEMENT_3D ( 'NONE', #15047, #8924, #15250 ) ; +#10200 = CARTESIAN_POINT ( 'NONE', ( 39.05471716683091188, 128.1851843108063917, 89.22321456362486458 ) ) ; +#10201 = CARTESIAN_POINT ( 'NONE', ( -15.99998378297181745, 127.7446958148473186, 89.15477705487283799 ) ) ; +#10202 = CARTESIAN_POINT ( 'NONE', ( 20.56429213702289971, 117.4584657514178758, 87.75512422162726978 ) ) ; +#10203 = CARTESIAN_POINT ( 'NONE', ( -31.70535867972207456, 220.4002260770999726, 73.57765341566839368 ) ) ; +#10204 = DIRECTION ( 'NONE', ( 0.0005884949672441799938, -0.2249510543775923299, 0.9743698870593667793 ) ) ; +#10205 = CARTESIAN_POINT ( 'NONE', ( 20.04841488032064234, 118.1066675202736036, 90.20916913282452754 ) ) ; +#10206 = ADVANCED_FACE ( 'NONE', ( #25528 ), #35479, .T. ) ; +#10207 = CARTESIAN_POINT ( 'NONE', ( -8.245636600931119276, 134.9179796086513363, 90.80620474745657589 ) ) ; +#10208 = ADVANCED_FACE ( 'NONE', ( #22857 ), #22461, .F. ) ; +#10209 = CARTESIAN_POINT ( 'NONE', ( -25.75142470483000068, 118.4643410412000009, 87.53333755287000884 ) ) ; +#10210 = CARTESIAN_POINT ( 'NONE', ( 13.50046316317049566, 187.7460073498711495, 103.5025028263219014 ) ) ; +#10211 = ORIENTED_EDGE ( 'NONE', *, *, #35841, .F. ) ; +#10212 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10213 = DIRECTION ( 'NONE', ( 0.0002393071182786170076, 0.2252352986010032476, -0.9743043687658492491 ) ) ; +#10214 = DIRECTION ( 'NONE', ( 0.7856637149787886187, -0.6186538021912811880, 0.000000000000000000 ) ) ; +#10215 = CIRCLE ( 'NONE', #39542, 5.499999999931961092 ) ; +#10216 = ORIENTED_EDGE ( 'NONE', *, *, #28480, .T. ) ; +#10217 = CARTESIAN_POINT ( 'NONE', ( -43.57149722038838036, 121.9974985178074434, 87.84418581487720701 ) ) ; +#10218 = VECTOR ( 'NONE', #21430, 1000.000000000000114 ) ; +#10219 = ORIENTED_EDGE ( 'NONE', *, *, #32353, .F. ) ; +#10220 = CIRCLE ( 'NONE', #8906, 5.999999999996103561 ) ; +#10221 = CARTESIAN_POINT ( 'NONE', ( 1.222756100067673435, 140.3958132876599620, 157.8527939211185753 ) ) ; +#10222 = CARTESIAN_POINT ( 'NONE', ( -36.54959120146399698, 191.6649449992200971, 104.3912839148767233 ) ) ; +#10223 = CIRCLE ( 'NONE', #10197, 2.500000000042679638 ) ; +#10224 = CARTESIAN_POINT ( 'NONE', ( -45.81619705300119705, 185.6006999936632837, 105.6694458431696688 ) ) ; +#10225 = VECTOR ( 'NONE', #33535, 1000.000000000000114 ) ; +#10226 = CARTESIAN_POINT ( 'NONE', ( -12.63766980425072184, 130.4202329703295788, 90.28358935384768813 ) ) ; +#10227 = FACE_OUTER_BOUND ( 'NONE', #11583, .T. ) ; +#10228 = EDGE_LOOP ( 'NONE', ( #9353, #38947 ) ) ; +#10229 = EDGE_CURVE ( 'NONE', #14171, #36248, #556, .T. ) ; +#10230 = CARTESIAN_POINT ( 'NONE', ( 2.545697083959657991, 209.0000005535759158, 75.65980364788404700 ) ) ; +#10231 = CARTESIAN_POINT ( 'NONE', ( -5.093541643503057159, 177.6102236329692232, 100.6605505116180410 ) ) ; +#10232 = CARTESIAN_POINT ( 'NONE', ( 4.034652562532943243, 176.8532558938365753, 100.4802775065020199 ) ) ; +#10233 = CARTESIAN_POINT ( 'NONE', ( -37.91598371520999677, 191.5233122829000081, 104.5546425013999965 ) ) ; +#10234 = VERTEX_POINT ( 'NONE', #361 ) ; +#10235 = DIRECTION ( 'NONE', ( -0.6185863125140933505, -0.7857168535612663041, 0.000000000000000000 ) ) ; +#10236 = ORIENTED_EDGE ( 'NONE', *, *, #24688, .F. ) ; +#10237 = CARTESIAN_POINT ( 'NONE', ( 36.96746166380989251, 116.2895703986138045, 89.69339363532195364 ) ) ; +#10238 = CARTESIAN_POINT ( 'NONE', ( -35.69644648028999967, 112.4664344015000097, 90.03934455280000293 ) ) ; +#10239 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098504, 132.2930706491197554, 93.28496646308185802 ) ) ; +#10240 = CIRCLE ( 'NONE', #18692, 2.000000000000000000 ) ; +#10241 = CARTESIAN_POINT ( 'NONE', ( 39.06502905710053142, 190.9636352783319069, 106.2825191316666888 ) ) ; +#10242 = CIRCLE ( 'NONE', #27889, 4.999999999999990230 ) ; +#10243 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 5.029100215316657124E-18, 0.0006039748319386160479 ) ) ; +#10244 = CIRCLE ( 'NONE', #22652, 2.250000000025644820 ) ; +#10245 = DIRECTION ( 'NONE', ( 0.7933533411653341805, -0.5930537057989598848, -0.1373964268091485141 ) ) ; +#10246 = CARTESIAN_POINT ( 'NONE', ( -2.701082792949999867, 209.7945284301000299, 73.18331558202000053 ) ) ; +#10247 = CARTESIAN_POINT ( 'NONE', ( 38.53322760872000430, 118.5959699799000049, 89.80756470608000086 ) ) ; +#10248 = ORIENTED_EDGE ( 'NONE', *, *, #13662, .T. ) ; +#10249 = CIRCLE ( 'NONE', #17395, 2.499999999981690646 ) ; +#10250 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971564015 ) ) ; +#10251 = FACE_OUTER_BOUND ( 'NONE', #16721, .T. ) ; +#10252 = LINE ( 'NONE', #1223, #37272 ) ; +#10253 = VECTOR ( 'NONE', #33894, 1000.000000000000114 ) ; +#10254 = EDGE_CURVE ( 'NONE', #1631, #2366, #4024, .T. ) ; +#10255 = ADVANCED_FACE ( 'NONE', ( #12850 ), #23560, .T. ) ; +#10257 = ORIENTED_EDGE ( 'NONE', *, *, #23162, .T. ) ; +#10256 = CARTESIAN_POINT ( 'NONE', ( -13.47107783232944378, 153.8044057555319739, 95.68275536702104489 ) ) ; +#10258 = ORIENTED_EDGE ( 'NONE', *, *, #18995, .F. ) ; +#10259 = VERTEX_POINT ( 'NONE', #32064 ) ; +#10260 = CARTESIAN_POINT ( 'NONE', ( -13.50128341151254041, 124.5457894246117405, 88.66272138216928056 ) ) ; +#10261 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775456658 ) ) ; +#10262 = CARTESIAN_POINT ( 'NONE', ( -5.960622339528989677, 163.5635530557085247, 97.41814418763185301 ) ) ; +#10263 = VERTEX_POINT ( 'NONE', #31454 ) ; +#10264 = VERTEX_POINT ( 'NONE', #13450 ) ; +#10265 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#10266 = DIRECTION ( 'NONE', ( 0.0002393071182785534462, 0.2252352986010039970, -0.9743043687658490271 ) ) ; +#10267 = CARTESIAN_POINT ( 'NONE', ( 76.10601358361095947, 156.3729538787885645, 95.70849706805188362 ) ) ; +#10268 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971540422 ) ) ; +#10269 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#10270 = ORIENTED_EDGE ( 'NONE', *, *, #34722, .F. ) ; +#10271 = CARTESIAN_POINT ( 'NONE', ( -35.44629553183553838, 112.4664344014998818, 90.28919351346762312 ) ) ; +#10272 = VECTOR ( 'NONE', #5705, 1000.000000000000000 ) ; +#10273 = ORIENTED_EDGE ( 'NONE', *, *, #36044, .F. ) ; +#10274 = CARTESIAN_POINT ( 'NONE', ( -25.50005268430136951, 117.7857744470418879, 89.78316151549972801 ) ) ; +#10275 = AXIS2_PLACEMENT_3D ( 'NONE', #16324, #7317, #38210 ) ; +#10276 = CARTESIAN_POINT ( 'NONE', ( 22.74075048786999886, 163.2545600168000135, 28.07991271570000080 ) ) ; +#10277 = VECTOR ( 'NONE', #34011, 1000.000000000000114 ) ; +#10278 = CARTESIAN_POINT ( 'NONE', ( -27.39351927441814638, 155.9581902257390880, 179.7869227509170003 ) ) ; +#10279 = EDGE_LOOP ( 'NONE', ( #34581, #15735, #7233, #4765 ) ) ; +#10280 = EDGE_CURVE ( 'NONE', #17189, #22581, #33791, .T. ) ; +#10281 = CARTESIAN_POINT ( 'NONE', ( -2.604892257046000026, 190.8452476264000097, 104.0499095697999934 ) ) ; +#10282 = DIRECTION ( 'NONE', ( -1.387778780823376196E-15, 0.9743700557921586292, 0.2249510932971564570 ) ) ; +#10283 = CARTESIAN_POINT ( 'NONE', ( -35.45366962857106330, 209.7096538831000032, 78.07991812242501339 ) ) ; +#10284 = ORIENTED_EDGE ( 'NONE', *, *, #26126, .T. ) ; +#10285 = CARTESIAN_POINT ( 'NONE', ( 6.034640325019517526, 177.1924675499267892, 101.0705349078851327 ) ) ; +#10286 = CARTESIAN_POINT ( 'NONE', ( 16.22247671335948382, 122.0701589875174164, 174.5870958018068109 ) ) ; +#10287 = EDGE_LOOP ( 'NONE', ( #37822, #3056, #5253, #6807 ) ) ; +#10288 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; +#10289 = CARTESIAN_POINT ( 'NONE', ( -16.53432056516032489, 121.7275407210895679, 178.0345399794734078 ) ) ; +#10290 = ADVANCED_FACE ( 'NONE', ( #22261 ), #25737, .T. ) ; +#10291 = EDGE_LOOP ( 'NONE', ( #8926, #38614, #32514, #30704 ) ) ; +#10292 = LINE ( 'NONE', #4119, #14744 ) ; +#10293 = CARTESIAN_POINT ( 'NONE', ( -3.170187864156448043, 126.4764607245763273, 88.85422735284892326 ) ) ; +#10294 = CARTESIAN_POINT ( 'NONE', ( 23.68970156757699641, 130.2249728062055283, 92.61131571664684259 ) ) ; +#10295 = ADVANCED_FACE ( 'NONE', ( #34691 ), #5248, .F. ) ; +#10296 = EDGE_LOOP ( 'NONE', ( #16238, #34785, #9684, #23803, #13116, #9949 ) ) ; +#10297 = CARTESIAN_POINT ( 'NONE', ( 25.83775114702000053, 120.3471401855999972, 90.32964940587000058 ) ) ; +#10298 = FACE_OUTER_BOUND ( 'NONE', #17993, .T. ) ; +#10299 = EDGE_CURVE ( 'NONE', #18545, #22996, #3505, .T. ) ; +#10300 = ADVANCED_FACE ( 'NONE', ( #6687 ), #34886, .F. ) ; +#10301 = AXIS2_PLACEMENT_3D ( 'NONE', #32468, #38776, #19768 ) ; +#10303 = PLANE ( 'NONE', #10968 ) ; +#10302 = PLANE ( 'NONE', #6719 ) ; +#10304 = EDGE_CURVE ( 'NONE', #11064, #20943, #16104, .T. ) ; +#10305 = ORIENTED_EDGE ( 'NONE', *, *, #22796, .T. ) ; +#10306 = CARTESIAN_POINT ( 'NONE', ( 12.63809651561607517, 175.3577520439124555, 100.1267379975303129 ) ) ; +#10307 = EDGE_CURVE ( 'NONE', #9884, #1120, #14767, .T. ) ; +#10308 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5066, #5269, #32687, #39216 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.002038048205810061037 ), + .UNSPECIFIED. ) ; +#10309 = CARTESIAN_POINT ( 'NONE', ( 12.31023268411626148, 134.2457138696073855, 93.71750156584897695 ) ) ; +#10310 = ORIENTED_EDGE ( 'NONE', *, *, #24383, .T. ) ; +#10311 = CARTESIAN_POINT ( 'NONE', ( -20.51863885680050359, 209.7097602209678939, 75.57089512796630970 ) ) ; +#10312 = CARTESIAN_POINT ( 'NONE', ( -8.050307605157906110, 151.4365984322141117, 94.61967771673485572 ) ) ; +#10313 = ORIENTED_EDGE ( 'NONE', *, *, #40232, .T. ) ; +#10314 = ORIENTED_EDGE ( 'NONE', *, *, #2541, .T. ) ; +#10315 = CARTESIAN_POINT ( 'NONE', ( 39.03663829597000046, 118.7256501412000063, 89.52709215164999534 ) ) ; +#10316 = CARTESIAN_POINT ( 'NONE', ( -35.46521474675949293, 113.6040542059936627, 87.28920439305406376 ) ) ; +#10317 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927783657346, -0.0005734119022073981076 ) ) ; +#10318 = CARTESIAN_POINT ( 'NONE', ( 17.27897118364565898, 126.5703640932063223, 154.6621420009977612 ) ) ; +#10319 = CARTESIAN_POINT ( 'NONE', ( 37.35642412351155173, 166.8680590464960005, 188.4831583878417121 ) ) ; +#10320 = VERTEX_POINT ( 'NONE', #32650 ) ; +#10321 = VERTEX_POINT ( 'NONE', #1569 ) ; +#10322 = FACE_OUTER_BOUND ( 'NONE', #3442, .T. ) ; +#10323 = CARTESIAN_POINT ( 'NONE', ( 19.98059076253610300, 209.7097557544199162, 73.04669817794425057 ) ) ; +#10324 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#10325 = CARTESIAN_POINT ( 'NONE', ( -35.94780537797892350, 109.6131156792400105, 87.78949595639598158 ) ) ; +#10326 = ORIENTED_EDGE ( 'NONE', *, *, #30745, .T. ) ; +#10327 = CARTESIAN_POINT ( 'NONE', ( 45.24519689809859813, 116.5437060779667036, 124.8975000631534158 ) ) ; +#10328 = VERTEX_POINT ( 'NONE', #14051 ) ; +#10329 = CARTESIAN_POINT ( 'NONE', ( -37.84443728459891787, 117.7927406794386371, 89.71739196407644101 ) ) ; +#10330 = VERTEX_POINT ( 'NONE', #13840 ) ; +#10331 = FACE_OUTER_BOUND ( 'NONE', #35149, .T. ) ; +#10332 = EDGE_LOOP ( 'NONE', ( #25058, #26592, #8250, #12521 ) ) ; +#10333 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#10334 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921579630, -0.2249510932971593713 ) ) ; +#10335 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#10336 = EDGE_CURVE ( 'NONE', #35367, #13602, #15705, .T. ) ; +#10337 = ORIENTED_EDGE ( 'NONE', *, *, #816, .F. ) ; +#10338 = CARTESIAN_POINT ( 'NONE', ( 12.63088349563799184, 181.6904995670203391, 101.5918601121804556 ) ) ; +#10339 = CARTESIAN_POINT ( 'NONE', ( -25.50129508846853099, 118.1132512059233335, 87.78307593003776788 ) ) ; +#10340 = CARTESIAN_POINT ( 'NONE', ( 42.43787138009228244, 189.9416574239004376, 106.2771675705110823 ) ) ; +#10341 = EDGE_CURVE ( 'NONE', #36184, #18716, #16690, .T. ) ; +#10342 = CARTESIAN_POINT ( 'NONE', ( -20.01839671862364867, 211.0902260915352429, 76.07059681904712534 ) ) ; +#10343 = ORIENTED_EDGE ( 'NONE', *, *, #10100, .T. ) ; +#10344 = EDGE_CURVE ( 'NONE', #39849, #28841, #36324, .T. ) ; +#10345 = CARTESIAN_POINT ( 'NONE', ( 28.46032611397967571, 181.9423863315211065, 101.9825489435484371 ) ) ; +#10346 = CARTESIAN_POINT ( 'NONE', ( 23.00039803961572460, 115.6131156701970895, 89.75408929892711285 ) ) ; +#10347 = EDGE_CURVE ( 'NONE', #17666, #37266, #6918, .T. ) ; +#10348 = CARTESIAN_POINT ( 'NONE', ( -37.75582100020000098, 118.2672493073999931, 90.15050444096000604 ) ) ; +#10349 = EDGE_CURVE ( 'NONE', #21433, #133, #24551, .T. ) ; +#10350 = ORIENTED_EDGE ( 'NONE', *, *, #29144, .F. ) ; +#10351 = VERTEX_POINT ( 'NONE', #10784 ) ; +#10352 = CARTESIAN_POINT ( 'NONE', ( 6.271009707311050896, 148.6549594042781450, 94.48198805953025214 ) ) ; +#10353 = CIRCLE ( 'NONE', #22115, 2.000000000508086018 ) ; +#10354 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971546251 ) ) ; +#10355 = CARTESIAN_POINT ( 'NONE', ( 45.27824277984586132, 110.5546504301846937, 150.9392683825311394 ) ) ; +#10356 = FACE_OUTER_BOUND ( 'NONE', #12986, .T. ) ; +#10357 = ORIENTED_EDGE ( 'NONE', *, *, #28842, .T. ) ; +#10358 = FACE_BOUND ( 'NONE', #33108, .T. ) ; +#10359 = ORIENTED_EDGE ( 'NONE', *, *, #20517, .T. ) ; +#10360 = ORIENTED_EDGE ( 'NONE', *, *, #13940, .F. ) ; +#10361 = ORIENTED_EDGE ( 'NONE', *, *, #12058, .F. ) ; +#10362 = CARTESIAN_POINT ( 'NONE', ( -6.036367076841044010, 177.5255795168471877, 100.8683065539579076 ) ) ; +#10363 = CARTESIAN_POINT ( 'NONE', ( 39.63114452991690939, 77.60549610642482321, 291.0478473981480647 ) ) ; +#10364 = ORIENTED_EDGE ( 'NONE', *, *, #20042, .T. ) ; +#10365 = CARTESIAN_POINT ( 'NONE', ( 26.00067918362605468, 118.8155664802563791, 90.25207353690788636 ) ) ; +#10366 = CARTESIAN_POINT ( 'NONE', ( 35.66634557559000029, 113.4066539298000009, 87.36246233996999422 ) ) ; +#10367 = CARTESIAN_POINT ( 'NONE', ( 36.03225916190000078, 191.4406869845000188, 103.7002245042999959 ) ) ; +#10368 = CARTESIAN_POINT ( 'NONE', ( 19.99991698292431508, 192.6764903808516749, 103.7970526813206646 ) ) ; +#10369 = CARTESIAN_POINT ( 'NONE', ( 122.4499743256723292, 56.73304889893216796, 171.8750556891886276 ) ) ; +#10370 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10371 = ORIENTED_EDGE ( 'NONE', *, *, #21141, .F. ) ; +#10372 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10373 = PLANE ( 'NONE', #4167 ) ; +#10374 = CARTESIAN_POINT ( 'NONE', ( 28.66581211170679566, 164.1764372810140173, 28.28916630219680073 ) ) ; +#10375 = CARTESIAN_POINT ( 'NONE', ( -32.57214901757254211, 137.3507445002516079, 91.38251427481793598 ) ) ; +#10376 = CARTESIAN_POINT ( 'NONE', ( 15.10714331102995800, 183.1006619385863701, 101.9159176678921312 ) ) ; +#10377 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #22021, #15661, #33865, #31015 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.712388980384688786, 4.732449003942794441 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999664665690304322, 0.9999664665690304322, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#10378 = ORIENTED_EDGE ( 'NONE', *, *, #14491, .F. ) ; +#10379 = CARTESIAN_POINT ( 'NONE', ( 20.00004282447493864, 191.5259056233101091, 103.8580927373495371 ) ) ; +#10380 = AXIS2_PLACEMENT_3D ( 'NONE', #40110, #22130, #25406 ) ; +#10381 = DIRECTION ( 'NONE', ( 0.5398771442070721127, 0.8202413914877526580, 0.1890416061428051298 ) ) ; +#10382 = CARTESIAN_POINT ( 'NONE', ( -29.91502785019211075, 126.8772888668398764, 89.30502066549905749 ) ) ; +#10383 = EDGE_CURVE ( 'NONE', #3644, #10734, #19958, .T. ) ; +#10384 = ADVANCED_FACE ( 'NONE', ( #29391 ), #3549, .F. ) ; +#10385 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971518218 ) ) ; +#10386 = CONICAL_SURFACE ( 'NONE', #582, 6.499999999957590369, 0.7853981633629670833 ) ; +#10387 = ADVANCED_FACE ( 'NONE', ( #17496 ), #29392, .F. ) ; +#10388 = CARTESIAN_POINT ( 'NONE', ( -25.35587684138999975, 191.8276697700999875, 104.5703393706999975 ) ) ; +#10389 = DIRECTION ( 'NONE', ( 0.9914448496661263377, 0.1271951663094869900, 0.02930016617724658101 ) ) ; +#10390 = AXIS2_PLACEMENT_3D ( 'NONE', #19, #606, #3272 ) ; +#10391 = CARTESIAN_POINT ( 'NONE', ( -3.956032534055420324, 168.4008771991734079, 98.96327028634475198 ) ) ; +#10392 = DIRECTION ( 'NONE', ( -0.7933533411653341805, 0.5930537057989598848, 0.1373964268091485141 ) ) ; +#10393 = CARTESIAN_POINT ( 'NONE', ( 27.41878023809479359, 124.6083876202890224, 90.97023811390801029 ) ) ; +#10394 = EDGE_LOOP ( 'NONE', ( #20493, #33862, #5401, #11026 ) ) ; +#10395 = ADVANCED_FACE ( 'NONE', ( #15263 ), #25082, .F. ) ; +#10396 = PLANE ( 'NONE', #31785 ) ; +#10397 = EDGE_CURVE ( 'NONE', #7538, #27242, #20607, .T. ) ; +#10398 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048995327, 130.3419545077157693, 92.84535593379736440 ) ) ; +#10399 = CARTESIAN_POINT ( 'NONE', ( 5.666563139484574130, 181.4015622423786169, 104.2772169685427173 ) ) ; +#10400 = CARTESIAN_POINT ( 'NONE', ( 36.61811095221000301, 191.2758974482999861, 106.4512996302999994 ) ) ; +#10401 = CARTESIAN_POINT ( 'NONE', ( 36.08519291063979750, 192.3728519051840067, 106.4067655339000140 ) ) ; +#10402 = FACE_OUTER_BOUND ( 'NONE', #22081, .T. ) ; +#10403 = FACE_OUTER_BOUND ( 'NONE', #2018, .T. ) ; +#10404 = CARTESIAN_POINT ( 'NONE', ( 36.20259201116000014, 192.7448354070999983, 106.1952316783000043 ) ) ; +#10405 = ORIENTED_EDGE ( 'NONE', *, *, #38604, .F. ) ; +#10406 = EDGE_CURVE ( 'NONE', #17225, #25223, #27752, .T. ) ; +#10408 = VECTOR ( 'NONE', #10618, 1000.000000000000114 ) ; +#10407 = DIRECTION ( 'NONE', ( -0.1305260325596790116, -0.9660514818508153523, -0.2229517643753315681 ) ) ; +#10409 = CARTESIAN_POINT ( 'NONE', ( 8.286289185724438511, 188.3449241355613708, 103.1308165897977887 ) ) ; +#10410 = AXIS2_PLACEMENT_3D ( 'NONE', #904, #10131, #37928 ) ; +#10411 = CARTESIAN_POINT ( 'NONE', ( 40.54493957013273331, 217.7719115632999944, 73.03401595487400755 ) ) ; +#10412 = EDGE_LOOP ( 'NONE', ( #12708, #13236, #36662, #3562 ) ) ; +#10413 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 89.47423874572474745, 291.5876487235610171 ) ) ; +#10414 = AXIS2_PLACEMENT_3D ( 'NONE', #22718, #219, #3280 ) ; +#10415 = CARTESIAN_POINT ( 'NONE', ( 39.79126515168999845, 119.5205125080999977, 89.91298374922000392 ) ) ; +#10416 = VECTOR ( 'NONE', #24389, 1000.000000000000114 ) ; +#10417 = ORIENTED_EDGE ( 'NONE', *, *, #28880, .T. ) ; +#10418 = CYLINDRICAL_SURFACE ( 'NONE', #16903, 9.000000000000003553 ) ; +#10419 = ORIENTED_EDGE ( 'NONE', *, *, #29330, .T. ) ; +#10420 = CARTESIAN_POINT ( 'NONE', ( 16.00151820029350702, 137.8265450205371394, 94.54185288967525480 ) ) ; +#10421 = LINE ( 'NONE', #35322, #40065 ) ; +#10422 = CARTESIAN_POINT ( 'NONE', ( -44.30687190001572162, 185.8858876664870650, 106.9719525047996029 ) ) ; +#10423 = CARTESIAN_POINT ( 'NONE', ( 28.42685679119000142, 142.7284776650000140, 28.07991271570000080 ) ) ; +#10424 = DIRECTION ( 'NONE', ( 0.0006039748319391886151, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#10425 = ORIENTED_EDGE ( 'NONE', *, *, #33859, .T. ) ; +#10426 = PLANE ( 'NONE', #27229 ) ; +#10427 = CARTESIAN_POINT ( 'NONE', ( -10.88124804834476933, 188.3423871091218871, 103.1418072217568493 ) ) ; +#10428 = CARTESIAN_POINT ( 'NONE', ( -22.49823197369664385, 160.0613479605241878, 99.70157044293461013 ) ) ; +#10429 = EDGE_CURVE ( 'NONE', #33081, #9576, #18498, .T. ) ; +#10430 = CARTESIAN_POINT ( 'NONE', ( -36.15032745052999985, 191.7932147525000062, 104.2905027447000066 ) ) ; +#10431 = ORIENTED_EDGE ( 'NONE', *, *, #1065, .F. ) ; +#10432 = EDGE_CURVE ( 'NONE', #20961, #15877, #3290, .T. ) ; +#10433 = EDGE_LOOP ( 'NONE', ( #7430, #3949, #26100, #39973 ) ) ; +#10434 = DIRECTION ( 'NONE', ( 0.6087613505917195411, -0.7729391288371411095, -0.1788147676737769087 ) ) ; +#10435 = EDGE_CURVE ( 'NONE', #39292, #21947, #25487, .T. ) ; +#10436 = VECTOR ( 'NONE', #13728, 1000.000000000000114 ) ; +#10437 = CARTESIAN_POINT ( 'NONE', ( 37.40957686559463014, 117.0607182589398150, 89.68224475837769205 ) ) ; +#10438 = LINE ( 'NONE', #32703, #21516 ) ; +#10439 = ADVANCED_FACE ( 'NONE', ( #11998 ), #24488, .T. ) ; +#10440 = AXIS2_PLACEMENT_3D ( 'NONE', #8579, #20208, #7744 ) ; +#10441 = AXIS2_PLACEMENT_3D ( 'NONE', #23502, #16539, #26186 ) ; +#10442 = CARTESIAN_POINT ( 'NONE', ( 13.49481983871936386, 124.3681642032378534, 88.35737770391504853 ) ) ; +#10443 = CARTESIAN_POINT ( 'NONE', ( 25.64383499035999847, 191.0236203942999964, 106.4328263517000011 ) ) ; +#10444 = ADVANCED_FACE ( 'NONE', ( #28338 ), #27511, .F. ) ; +#10445 = FACE_OUTER_BOUND ( 'NONE', #34178, .T. ) ; +#10446 = CARTESIAN_POINT ( 'NONE', ( -3.093297121992999887, 208.9488293358000419, 72.98050324807999800 ) ) ; +#10447 = CARTESIAN_POINT ( 'NONE', ( 38.69173525550999670, 118.4044799225000020, 89.51251263176000350 ) ) ; +#10448 = ORIENTED_EDGE ( 'NONE', *, *, #31754, .T. ) ; +#10449 = LINE ( 'NONE', #4074, #25091 ) ; +#10450 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363196006660E-14, 0.9999998176071844824 ) ) ; +#10451 = CARTESIAN_POINT ( 'NONE', ( 3.168077837919118345, 126.1295738578562009, 91.84923819592059147 ) ) ; +#10452 = FACE_OUTER_BOUND ( 'NONE', #25911, .T. ) ; +#10453 = ORIENTED_EDGE ( 'NONE', *, *, #19852, .T. ) ; +#10454 = ORIENTED_EDGE ( 'NONE', *, *, #6611, .T. ) ; +#10455 = EDGE_CURVE ( 'NONE', #3485, #16249, #22411, .T. ) ; +#10456 = PRODUCT_DEFINITION_SHAPE ( 'NONE', 'NONE', #14451 ) ; +#10457 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22658, #956, #7091, #32253 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10458 = ORIENTED_EDGE ( 'NONE', *, *, #21006, .T. ) ; +#10459 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319397694222 ) ) ; +#10460 = CARTESIAN_POINT ( 'NONE', ( 5.958856853884591409, 162.8902775912074787, 100.3344200888616200 ) ) ; +#10461 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 137.0112424259995976, 291.5876487235603918 ) ) ; +#10462 = EDGE_LOOP ( 'NONE', ( #18721, #33666, #19341 ) ) ; +#10463 = ORIENTED_EDGE ( 'NONE', *, *, #577, .F. ) ; +#10464 = CARTESIAN_POINT ( 'NONE', ( -35.38988506213597418, 77.14301703112144537, 290.1978808180363671 ) ) ; +#10465 = CARTESIAN_POINT ( 'NONE', ( -38.48030512001000147, 118.7021383040000018, 89.90325869229000944 ) ) ; +#10466 = CARTESIAN_POINT ( 'NONE', ( -38.36245917373000225, 118.8225225366000046, 87.71979598265001243 ) ) ; +#10467 = CARTESIAN_POINT ( 'NONE', ( -28.51213027334999950, 201.2278123622000123, 28.07991271570000080 ) ) ; +#10468 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#10469 = VERTEX_POINT ( 'NONE', #31404 ) ; +#10470 = CARTESIAN_POINT ( 'NONE', ( 5.704725281391000102, 112.1320600213999938, 152.4718672074000381 ) ) ; +#10471 = VECTOR ( 'NONE', #9543, 1000.000000000000227 ) ; +#10472 = AXIS2_PLACEMENT_3D ( 'NONE', #8261, #27293, #8882 ) ; +#10473 = EDGE_LOOP ( 'NONE', ( #9298, #14567, #7075, #39146 ) ) ; +#10474 = DIRECTION ( 'NONE', ( 0.7066905234002724967, 0.1590644375676184552, -0.6894106242563616815 ) ) ; +#10475 = FACE_OUTER_BOUND ( 'NONE', #1969, .T. ) ; +#10476 = CARTESIAN_POINT ( 'NONE', ( 16.83816207964345324, 121.5429834961812645, 177.3963189431576666 ) ) ; +#10477 = DIRECTION ( 'NONE', ( -0.6087611434179117653, 0.7728348325624403437, 0.1792657018023852966 ) ) ; +#10478 = EDGE_LOOP ( 'NONE', ( #11993, #11118, #16265, #37101 ) ) ; +#10479 = CARTESIAN_POINT ( 'NONE', ( -2.208163358325990089, 189.3050797433780019, 103.3573457354410010 ) ) ; +#10480 = CARTESIAN_POINT ( 'NONE', ( 20.50147137495634198, 190.9646546281344683, 106.2940065278771016 ) ) ; +#10481 = CARTESIAN_POINT ( 'NONE', ( 18.99670475096374034, 148.1889770648965623, 184.7135872576050986 ) ) ; +#10482 = VERTEX_POINT ( 'NONE', #19513 ) ; +#10483 = EDGE_CURVE ( 'NONE', #10159, #22555, #25690, .T. ) ; +#10484 = ORIENTED_EDGE ( 'NONE', *, *, #12208, .F. ) ; +#10485 = CARTESIAN_POINT ( 'NONE', ( 20.15797964693969391, 118.1111885588362327, 87.41331544875174586 ) ) ; +#10486 = CARTESIAN_POINT ( 'NONE', ( -23.00006628498088901, 118.1131156702000169, 89.78163987410425761 ) ) ; +#10487 = EDGE_CURVE ( 'NONE', #8706, #27876, #26177, .T. ) ; +#10488 = ORIENTED_EDGE ( 'NONE', *, *, #31106, .T. ) ; +#10489 = CARTESIAN_POINT ( 'NONE', ( -43.83121863444220878, 120.3967290634445249, 90.85147244797772714 ) ) ; +#10490 = EDGE_LOOP ( 'NONE', ( #24952, #22534, #7663, #17651 ) ) ; +#10491 = CARTESIAN_POINT ( 'NONE', ( 22.99181599359000217, 213.5902260771004819, 75.54481431629028521 ) ) ; +#10492 = DIRECTION ( 'NONE', ( 0.7066518061492224057, -1.565012837052518894E-15, -0.7075614636666145429 ) ) ; +#10493 = LINE ( 'NONE', #3516, #13417 ) ; +#10494 = CARTESIAN_POINT ( 'NONE', ( 15.50176591790000025, 153.4317157280000004, 98.14497494459000393 ) ) ; +#10495 = AXIS2_PLACEMENT_3D ( 'NONE', #7467, #38744, #22439 ) ; +#10496 = ORIENTED_EDGE ( 'NONE', *, *, #24003, .T. ) ; +#10497 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36643, #31120, #30917, #36438 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10498 = VECTOR ( 'NONE', #8607, 999.9999999999998863 ) ; +#10499 = CARTESIAN_POINT ( 'NONE', ( 26.00267525357395471, 120.0774130348896591, 90.42205768479676919 ) ) ; +#10500 = AXIS2_PLACEMENT_3D ( 'NONE', #37532, #20233, #1027 ) ; +#10501 = FACE_OUTER_BOUND ( 'NONE', #19795, .T. ) ; +#10503 = DIRECTION ( 'NONE', ( -0.0006039748319387566690, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#10502 = CARTESIAN_POINT ( 'NONE', ( -16.15249828763665363, 151.1189587783885884, 184.8292094970151425 ) ) ; +#10504 = DIRECTION ( 'NONE', ( 0.0005884949961259727845, -0.2249510543439064703, 0.9743698870671262391 ) ) ; +#10505 = LINE ( 'NONE', #22969, #39248 ) ; +#10506 = ORIENTED_EDGE ( 'NONE', *, *, #19811, .T. ) ; +#10507 = LINE ( 'NONE', #3243, #39502 ) ; +#10508 = CARTESIAN_POINT ( 'NONE', ( -36.08484471194226018, 191.9980746492448702, 104.4229788667364716 ) ) ; +#10509 = CARTESIAN_POINT ( 'NONE', ( -22.49962777877401265, 154.4034663070004285, 95.31336199324331915 ) ) ; +#10510 = ORIENTED_EDGE ( 'NONE', *, *, #31664, .F. ) ; +#10511 = ORIENTED_EDGE ( 'NONE', *, *, #62, .T. ) ; +#10512 = LINE ( 'NONE', #22183, #34786 ) ; +#10513 = FACE_OUTER_BOUND ( 'NONE', #37065, .T. ) ; +#10514 = CARTESIAN_POINT ( 'NONE', ( -2.300423297926999844, 191.0118119155000045, 106.1782564142000069 ) ) ; +#10515 = ORIENTED_EDGE ( 'NONE', *, *, #32993, .F. ) ; +#10516 = ORIENTED_EDGE ( 'NONE', *, *, #185, .T. ) ; +#10517 = EDGE_CURVE ( 'NONE', #25046, #5067, #39, .T. ) ; +#10518 = ORIENTED_EDGE ( 'NONE', *, *, #13016, .F. ) ; +#10519 = CARTESIAN_POINT ( 'NONE', ( -23.36142968010071286, 134.4390921883068302, 93.61422517553531009 ) ) ; +#10520 = DIRECTION ( 'NONE', ( 0.9914446895100101909, -0.1270495645017608588, -0.02993051623865213007 ) ) ; +#10521 = ORIENTED_EDGE ( 'NONE', *, *, #30510, .F. ) ; +#10522 = ORIENTED_EDGE ( 'NONE', *, *, #11585, .F. ) ; +#10523 = CARTESIAN_POINT ( 'NONE', ( -21.69818314611236332, 120.0177369536598775, 190.2070442068906573 ) ) ; +#10524 = AXIS2_PLACEMENT_3D ( 'NONE', #37641, #21527, #9246 ) ; +#10525 = CONICAL_SURFACE ( 'NONE', #39898, 2.502999999877876025, 0.7853981634382917187 ) ; +#10526 = CIRCLE ( 'NONE', #5961, 1.750000000000001998 ) ; +#10527 = ORIENTED_EDGE ( 'NONE', *, *, #17925, .T. ) ; +#10528 = EDGE_CURVE ( 'NONE', #34802, #20666, #34443, .T. ) ; +#10529 = CARTESIAN_POINT ( 'NONE', ( 18.98506067126258046, 148.2070439170772431, 184.7168109706149721 ) ) ; +#10530 = EDGE_CURVE ( 'NONE', #6692, #35055, #9733, .T. ) ; +#10531 = CARTESIAN_POINT ( 'NONE', ( -30.07461407415773991, 135.0052377692200025, 90.96298864312910837 ) ) ; +#10532 = EDGE_CURVE ( 'NONE', #18192, #27561, #3930, .T. ) ; +#10533 = CARTESIAN_POINT ( 'NONE', ( -2.293543225787999962, 188.9465872380000064, 106.5163128416999996 ) ) ; +#10534 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#10535 = ADVANCED_FACE ( 'NONE', ( #16246 ), #31393, .F. ) ; +#10536 = ORIENTED_EDGE ( 'NONE', *, *, #35494, .F. ) ; +#10537 = EDGE_LOOP ( 'NONE', ( #11898, #22716, #32397, #17056 ) ) ; +#10538 = CARTESIAN_POINT ( 'NONE', ( 35.56355292868355633, 196.5784392900514206, 103.8536238432368037 ) ) ; +#10539 = CARTESIAN_POINT ( 'NONE', ( 19.98483764167631094, 211.0849390754169974, 73.04592155476974824 ) ) ; +#10540 = CARTESIAN_POINT ( 'NONE', ( -16.27844647470670481, 132.2223051904889246, 155.9713390441192473 ) ) ; +#10541 = CARTESIAN_POINT ( 'NONE', ( -25.82491794804302288, 196.4250218345125631, 103.8255790278501820 ) ) ; +#10542 = ORIENTED_EDGE ( 'NONE', *, *, #30182, .F. ) ; +#10543 = CYLINDRICAL_SURFACE ( 'NONE', #11021, 1.750000000000001998 ) ; +#10544 = VECTOR ( 'NONE', #30078, 1000.000000000000114 ) ; +#10545 = CARTESIAN_POINT ( 'NONE', ( -37.56558860730999783, 118.4361947088000022, 90.44661560864000194 ) ) ; +#10546 = VECTOR ( 'NONE', #26070, 999.9999999999998863 ) ; +#10547 = ORIENTED_EDGE ( 'NONE', *, *, #31813, .T. ) ; +#10548 = ORIENTED_EDGE ( 'NONE', *, *, #5058, .T. ) ; +#10549 = CYLINDRICAL_SURFACE ( 'NONE', #8829, 2.000000000000011546 ) ; +#10550 = CARTESIAN_POINT ( 'NONE', ( 23.68782161451136403, 130.6249251104771645, 90.13785893629349744 ) ) ; +#10551 = CARTESIAN_POINT ( 'NONE', ( -85.24348513260991922, 108.2328939675489039, 25.03902193712222513 ) ) ; +#10552 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319380785005 ) ) ; +#10553 = EDGE_LOOP ( 'NONE', ( #24682, #33272, #13734 ) ) ; +#10554 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7094, #28781, #16103, #13250 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10555 = VERTEX_POINT ( 'NONE', #19111 ) ; +#10556 = FACE_OUTER_BOUND ( 'NONE', #35151, .T. ) ; +#10557 = ORIENTED_EDGE ( 'NONE', *, *, #19376, .T. ) ; +#10558 = EDGE_LOOP ( 'NONE', ( #22245, #14403, #15839, #38587 ) ) ; +#10559 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#10560 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#10561 = ORIENTED_EDGE ( 'NONE', *, *, #17657, .T. ) ; +#10562 = LINE ( 'NONE', #25712, #4281 ) ; +#10563 = CARTESIAN_POINT ( 'NONE', ( 37.93701571562999675, 118.0299904344000055, 87.80017651164999393 ) ) ; +#10564 = CARTESIAN_POINT ( 'NONE', ( 36.18104500945000268, 191.5953453467000145, 103.9690375264000011 ) ) ; +#10565 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35937, #7947, #14294, #20410 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10566 = CARTESIAN_POINT ( 'NONE', ( -25.99151835185281456, 191.8641524188973904, 103.9340199701208292 ) ) ; +#10567 = EDGE_CURVE ( 'NONE', #18222, #3073, #9941, .T. ) ; +#10568 = ORIENTED_EDGE ( 'NONE', *, *, #27759, .T. ) ; +#10569 = DIRECTION ( 'NONE', ( 0.1305262607518133389, -0.9660168937933039102, -0.2231014481353405798 ) ) ; +#10570 = DIRECTION ( 'NONE', ( -0.0002393071182785116774, -0.2252352986010041080, 0.9743043687658491381 ) ) ; +#10571 = VERTEX_POINT ( 'NONE', #28936 ) ; +#10572 = CARTESIAN_POINT ( 'NONE', ( 16.15948502493926853, 156.4779744257297125, 161.5570139484795220 ) ) ; +#10573 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452351231, 0.1781166614240801693 ) ) ; +#10574 = EDGE_CURVE ( 'NONE', #12222, #9881, #618, .T. ) ; +#10575 = AXIS2_PLACEMENT_3D ( 'NONE', #23137, #35564, #28668 ) ; +#10576 = CARTESIAN_POINT ( 'NONE', ( 3.776102309766777410, 175.3027701955228110, 100.3705899655855092 ) ) ; +#10577 = EDGE_CURVE ( 'NONE', #20125, #26354, #7937, .T. ) ; +#10578 = CARTESIAN_POINT ( 'NONE', ( 23.67998985452990368, 134.9222885997251637, 90.78792508986444432 ) ) ; +#10579 = EDGE_CURVE ( 'NONE', #27781, #30934, #15269, .T. ) ; +#10580 = ORIENTED_EDGE ( 'NONE', *, *, #16354, .F. ) ; +#10581 = CARTESIAN_POINT ( 'NONE', ( 21.15670202924908949, 136.2567377786867837, 93.83430039101608600 ) ) ; +#10582 = ADVANCED_FACE ( 'NONE', ( #25887 ), #38331, .F. ) ; +#10583 = VECTOR ( 'NONE', #37394, 1000.000000000000114 ) ; +#10584 = CARTESIAN_POINT ( 'NONE', ( 1.052492825995231751, 189.0609387198332456, 103.7017148797387165 ) ) ; +#10585 = CARTESIAN_POINT ( 'NONE', ( -0.4358427445845766135, 188.3875244028057807, 106.2247867227265630 ) ) ; +#10586 = CARTESIAN_POINT ( 'NONE', ( -4.037441716910447731, 175.2423114651814160, 100.6263891030057778 ) ) ; +#10587 = CARTESIAN_POINT ( 'NONE', ( -25.61313952212999823, 191.8482039261000125, 104.3089394863000052 ) ) ; +#10588 = CARTESIAN_POINT ( 'NONE', ( -13.50000253664885719, 151.9690088118221922, 94.74282098678578734 ) ) ; +#10589 = CARTESIAN_POINT ( 'NONE', ( -3.570188269422462035, 168.4780809577787863, 98.58463426929444040 ) ) ; +#10590 = CARTESIAN_POINT ( 'NONE', ( -2.453916141205511714, 205.5673811410610767, 76.30169882389490965 ) ) ; +#10591 = ORIENTED_EDGE ( 'NONE', *, *, #4080, .T. ) ; +#10592 = DIRECTION ( 'NONE', ( 8.326672684688689830E-15, -0.9743700557921582961, -0.2249510932971575394 ) ) ; +#10593 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#10594 = ORIENTED_EDGE ( 'NONE', *, *, #15764, .T. ) ; +#10595 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10596 = CARTESIAN_POINT ( 'NONE', ( 23.36327396620029262, 181.6167095797193838, 104.1340943760966411 ) ) ; +#10597 = FACE_OUTER_BOUND ( 'NONE', #24603, .T. ) ; +#10598 = CARTESIAN_POINT ( 'NONE', ( 36.06384157275000035, 192.3755910232000019, 104.3313795858999953 ) ) ; +#10599 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33695, #14502, #30237, #39828 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10600 = CARTESIAN_POINT ( 'NONE', ( -25.02288988185319596, 182.0930031294805644, 101.7075183579726456 ) ) ; +#10601 = AXIS2_PLACEMENT_3D ( 'NONE', #7528, #20826, #32875 ) ; +#10602 = CARTESIAN_POINT ( 'NONE', ( 13.76493657109577384, 124.4303889429143624, 178.6692723925305017 ) ) ; +#10603 = ORIENTED_EDGE ( 'NONE', *, *, #39969, .T. ) ; +#10604 = VERTEX_POINT ( 'NONE', #14132 ) ; +#10605 = VECTOR ( 'NONE', #28334, 1000.000000000000114 ) ; +#10606 = CARTESIAN_POINT ( 'NONE', ( -42.55448647980254151, 182.5615766734265719, 104.9051989971102188 ) ) ; +#10607 = CIRCLE ( 'NONE', #23650, 2.499999999915349047 ) ; +#10608 = CARTESIAN_POINT ( 'NONE', ( 18.98511042798971360, 148.3283295584973871, 184.1927148392349807 ) ) ; +#10609 = ADVANCED_FACE ( 'NONE', ( #14328 ), #1850, .T. ) ; +#10610 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#10611 = ORIENTED_EDGE ( 'NONE', *, *, #25948, .T. ) ; +#10612 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; +#10613 = CARTESIAN_POINT ( 'NONE', ( -10.03773492422894620, 168.4955924422535531, 98.55925788101369278 ) ) ; +#10614 = ORIENTED_EDGE ( 'NONE', *, *, #22940, .T. ) ; +#10615 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #960, #26327, #28587, #25736 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 5.793999508258149689, 7.571725326505850617 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7535301471135593676, 0.7535301471135593676, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#10616 = EDGE_CURVE ( 'NONE', #25509, #6189, #31861, .T. ) ; +#10617 = CARTESIAN_POINT ( 'NONE', ( 13.50176625667807428, 157.6312284029801845, 99.11570381321912748 ) ) ; +#10618 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927769878492, -0.0005734119022077161041 ) ) ; +#10619 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10620 = ORIENTED_EDGE ( 'NONE', *, *, #37749, .T. ) ; +#10621 = CARTESIAN_POINT ( 'NONE', ( 23.68575892633012003, 134.8469895808620436, 93.33625697840975022 ) ) ; +#10622 = LINE ( 'NONE', #23089, #38383 ) ; +#10623 = CARTESIAN_POINT ( 'NONE', ( -30.06930367573490059, 176.9314637670682657, 103.3499274907251788 ) ) ; +#10624 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#10625 = ORIENTED_EDGE ( 'NONE', *, *, #36767, .F. ) ; +#10626 = EDGE_CURVE ( 'NONE', #23762, #11575, #26000, .T. ) ; +#10627 = ORIENTED_EDGE ( 'NONE', *, *, #29462, .F. ) ; +#10628 = FACE_OUTER_BOUND ( 'NONE', #26200, .T. ) ; +#10629 = LINE ( 'NONE', #22503, #17238 ) ; +#10630 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#10631 = VERTEX_POINT ( 'NONE', #10460 ) ; +#10632 = CARTESIAN_POINT ( 'NONE', ( -36.12223251268000013, 191.8158961599000349, 104.2940808302000022 ) ) ; +#10633 = ORIENTED_EDGE ( 'NONE', *, *, #38660, .F. ) ; +#10634 = ORIENTED_EDGE ( 'NONE', *, *, #21024, .F. ) ; +#10635 = AXIS2_PLACEMENT_3D ( 'NONE', #2997, #5673, #15480 ) ; +#10636 = DIRECTION ( 'NONE', ( 0.5988683521957647304, -0.8008474865655316188, 0.000000000000000000 ) ) ; +#10637 = DIRECTION ( 'NONE', ( -0.6087611434179115433, 0.7728348325624405657, 0.1792657018023848803 ) ) ; +#10638 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825953469412410, 0.0005734119016186655943 ) ) ; +#10639 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #21545, #34566 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10640 = CARTESIAN_POINT ( 'NONE', ( 18.85494637915880389, 148.3003327196275904, 183.8440936709722848 ) ) ; +#10641 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825829930067965, 0.0005734119044644985386 ) ) ; +#10642 = DIRECTION ( 'NONE', ( -0.7933532970003721596, -0.5930762008556746956, -0.1372995488602881120 ) ) ; +#10643 = CARTESIAN_POINT ( 'NONE', ( -37.93323152093999795, 191.1278711168000086, 106.2274912793999988 ) ) ; +#10644 = ORIENTED_EDGE ( 'NONE', *, *, #36000, .T. ) ; +#10645 = CARTESIAN_POINT ( 'NONE', ( 13.82651559197693913, 124.3675412307241146, 88.35707925228412307 ) ) ; +#10646 = DIRECTION ( 'NONE', ( 0.6087614115774879764, 0.7729348350621345620, 0.1788331191967953704 ) ) ; +#10647 = CARTESIAN_POINT ( 'NONE', ( 24.53348384879791411, 109.6131156702000027, 87.75296677362121045 ) ) ; +#10649 = ORIENTED_EDGE ( 'NONE', *, *, #4582, .F. ) ; +#10648 = CARTESIAN_POINT ( 'NONE', ( 2.879226012311342675, 209.0946219175737610, 75.97922651357153256 ) ) ; +#10650 = ORIENTED_EDGE ( 'NONE', *, *, #5041, .F. ) ; +#10651 = ORIENTED_EDGE ( 'NONE', *, *, #37880, .F. ) ; +#10652 = ORIENTED_EDGE ( 'NONE', *, *, #5378, .T. ) ; +#10653 = CARTESIAN_POINT ( 'NONE', ( -13.50287905500021779, 124.4549746631454497, 88.51738859572765250 ) ) ; +#10654 = AXIS2_PLACEMENT_3D ( 'NONE', #38345, #28553, #13412 ) ; +#10655 = CARTESIAN_POINT ( 'NONE', ( -22.69152947388643682, 213.5901932291387197, 75.57214034997275576 ) ) ; +#10656 = EDGE_CURVE ( 'NONE', #1942, #40336, #2060, .T. ) ; +#10657 = CARTESIAN_POINT ( 'NONE', ( 23.71418063517253216, 115.9567856581436160, 178.7590535630116051 ) ) ; +#10658 = CARTESIAN_POINT ( 'NONE', ( 5.666394801357205857, 124.0804070564130512, 91.04259146090616639 ) ) ; +#10659 = CONICAL_SURFACE ( 'NONE', #33492, 4.999999999857982935, 0.7853981633210400659 ) ; +#10660 = ADVANCED_FACE ( 'NONE', ( #40060 ), #3393, .T. ) ; +#10661 = ORIENTED_EDGE ( 'NONE', *, *, #28849, .T. ) ; +#10662 = CARTESIAN_POINT ( 'NONE', ( -14.29616511099273346, 135.3960512967398984, 93.65700873416508898 ) ) ; +#10663 = AXIS2_PLACEMENT_3D ( 'NONE', #7520, #1804, #11208 ) ; +#10664 = CARTESIAN_POINT ( 'NONE', ( 20.33495252378841656, 118.8155847327597030, 89.92220002530788747 ) ) ; +#10665 = CARTESIAN_POINT ( 'NONE', ( -38.43509036414000235, 118.8935578815000156, 87.72379152730999863 ) ) ; +#10666 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319381707661 ) ) ; +#10667 = ORIENTED_EDGE ( 'NONE', *, *, #28750, .T. ) ; +#10668 = EDGE_CURVE ( 'NONE', #7718, #22341, #34708, .T. ) ; +#10669 = PLANE ( 'NONE', #31706 ) ; +#10670 = CARTESIAN_POINT ( 'NONE', ( 5.665063307604782494, 124.5504061188815683, 88.65505891053771848 ) ) ; +#10671 = CARTESIAN_POINT ( 'NONE', ( -21.79955176292590124, 171.2571027978372342, 152.1817658970814193 ) ) ; +#10672 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#10673 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971565957 ) ) ; +#10674 = EDGE_CURVE ( 'NONE', #25549, #18343, #5988, .T. ) ; +#10675 = VERTEX_POINT ( 'NONE', #37959 ) ; +#10676 = CARTESIAN_POINT ( 'NONE', ( -20.50092100153493746, 194.2771564787859120, 102.9104786413515740 ) ) ; +#10677 = DIRECTION ( 'NONE', ( -7.346163213264980213E-13, -0.9743700555116001638, -0.2249510945123874561 ) ) ; +#10678 = CARTESIAN_POINT ( 'NONE', ( -24.42625685282796510, 109.6131156702000027, 89.78253759511289900 ) ) ; +#10679 = CARTESIAN_POINT ( 'NONE', ( 19.98825758066151081, 204.1052561192695123, 86.13095846269416711 ) ) ; +#10680 = ORIENTED_EDGE ( 'NONE', *, *, #33823, .F. ) ; +#10681 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13413, #16655, #10742, #925 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10682 = PLANE ( 'NONE', #8764 ) ; +#10683 = CARTESIAN_POINT ( 'NONE', ( -26.01597357618275552, 211.4825417517944572, 76.07170175244279164 ) ) ; +#10684 = ORIENTED_EDGE ( 'NONE', *, *, #19261, .F. ) ; +#10685 = VECTOR ( 'NONE', #3669, 1000.000000000000227 ) ; +#10686 = EDGE_LOOP ( 'NONE', ( #36755, #12070, #17354, #38143 ) ) ; +#10687 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#10688 = ORIENTED_EDGE ( 'NONE', *, *, #20147, .T. ) ; +#10689 = CONICAL_SURFACE ( 'NONE', #36806, 55.00273826252905707, 0.7853981633973132759 ) ; +#10690 = CARTESIAN_POINT ( 'NONE', ( 25.49062502244311190, 209.7098837966309475, 73.54308088453358039 ) ) ; +#10691 = DIRECTION ( 'NONE', ( -0.0005884949961217802832, 0.2249510543439081078, -0.9743698870671260170 ) ) ; +#10692 = VECTOR ( 'NONE', #13426, 1000.000000000000114 ) ; +#10693 = VERTEX_POINT ( 'NONE', #34858 ) ; +#10694 = ORIENTED_EDGE ( 'NONE', *, *, #20511, .T. ) ; +#10695 = CARTESIAN_POINT ( 'NONE', ( 26.01380077701120186, 120.4370565852799899, 90.52453431236820336 ) ) ; +#10696 = DIRECTION ( 'NONE', ( -0.6087611434179104331, -0.7731004625452351231, -0.1781166614240846935 ) ) ; +#10697 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5513, #8809, #24559, #30485 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10699 = CARTESIAN_POINT ( 'NONE', ( 30.96384560852109047, 128.5897405105000360, 89.32150042245991983 ) ) ; +#10698 = CARTESIAN_POINT ( 'NONE', ( 20.48202491551230153, 207.9221666367885462, 76.29632206515334758 ) ) ; +#10700 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; +#10701 = VERTEX_POINT ( 'NONE', #28561 ) ; +#10702 = CARTESIAN_POINT ( 'NONE', ( -39.74915155288540092, 182.4989200128275399, 106.8177713122808115 ) ) ; +#10703 = DIRECTION ( 'NONE', ( 0.7933530821293313107, 0.5932640870757662777, 0.1364866662427073052 ) ) ; +#10704 = EDGE_CURVE ( 'NONE', #5512, #33715, #33331, .T. ) ; +#10705 = EDGE_CURVE ( 'NONE', #26211, #7245, #1137, .T. ) ; +#10706 = VERTEX_POINT ( 'NONE', #3995 ) ; +#10707 = CARTESIAN_POINT ( 'NONE', ( 13.46852558400658850, 153.7328115929476269, 98.21571663388800744 ) ) ; +#10708 = CARTESIAN_POINT ( 'NONE', ( -44.75464527753396027, 124.2849483418497414, 93.49415263160652501 ) ) ; +#10709 = FACE_OUTER_BOUND ( 'NONE', #22478, .T. ) ; +#10710 = CIRCLE ( 'NONE', #18502, 2.499999999897516645 ) ; +#10711 = CONICAL_SURFACE ( 'NONE', #8067, 6.502999999995862090, 0.7853981633961898412 ) ; +#10712 = VERTEX_POINT ( 'NONE', #3589 ) ; +#10713 = VERTEX_POINT ( 'NONE', #37748 ) ; +#10714 = DIRECTION ( 'NONE', ( 0.6087611434179120984, -0.7728348325624403437, -0.1792657018023839366 ) ) ; +#10715 = CONICAL_SURFACE ( 'NONE', #31615, 2.503139744998429617, 0.7853981633680950925 ) ; +#10716 = VERTEX_POINT ( 'NONE', #26104 ) ; +#10717 = ORIENTED_EDGE ( 'NONE', *, *, #7366, .F. ) ; +#10718 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; +#10719 = ORIENTED_EDGE ( 'NONE', *, *, #7861, .T. ) ; +#10720 = CARTESIAN_POINT ( 'NONE', ( -22.49852798326972092, 153.3539066485355988, 97.63681037851679889 ) ) ; +#10721 = ORIENTED_EDGE ( 'NONE', *, *, #5566, .T. ) ; +#10722 = LINE ( 'NONE', #35421, #32092 ) ; +#10723 = ADVANCED_FACE ( 'NONE', ( #6867 ), #19340, .T. ) ; +#10724 = CARTESIAN_POINT ( 'NONE', ( -23.36013623391093930, 174.6774582535031186, 103.0734136003139838 ) ) ; +#10725 = CARTESIAN_POINT ( 'NONE', ( 21.10872591445046709, 182.7503592616568824, 104.5682307738507149 ) ) ; +#10726 = ORIENTED_EDGE ( 'NONE', *, *, #33905, .F. ) ; +#10727 = VERTEX_POINT ( 'NONE', #29365 ) ; +#10728 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#10729 = CARTESIAN_POINT ( 'NONE', ( -23.35464359634993770, 177.7881151143831744, 100.7126876897662697 ) ) ; +#10730 = CARTESIAN_POINT ( 'NONE', ( 25.84237761017833535, 191.9398424858814280, 104.0722080153798856 ) ) ; +#10731 = VECTOR ( 'NONE', #30716, 1000.000000000000114 ) ; +#10732 = AXIS2_PLACEMENT_3D ( 'NONE', #27410, #11425, #21043 ) ; +#10733 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.6225145670957882293, 0.7826082121684793114 ) ) ; +#10734 = VERTEX_POINT ( 'NONE', #39556 ) ; +#10735 = FACE_OUTER_BOUND ( 'NONE', #17406, .T. ) ; +#10736 = CIRCLE ( 'NONE', #29688, 4.499999999895906377 ) ; +#10737 = CARTESIAN_POINT ( 'NONE', ( -38.29117464694000006, 118.4625604934000052, 89.85066910585000244 ) ) ; +#10738 = ORIENTED_EDGE ( 'NONE', *, *, #8015, .T. ) ; +#10739 = ORIENTED_EDGE ( 'NONE', *, *, #21094, .T. ) ; +#10740 = DIRECTION ( 'NONE', ( -0.000000000000000000, 1.000000000000000000, -1.110223024625155594E-14 ) ) ; +#10741 = PLANE ( 'NONE', #18319 ) ; +#10742 = CARTESIAN_POINT ( 'NONE', ( 2.897488257060280681, 190.8911024193934054, 106.6291602111235477 ) ) ; +#10743 = EDGE_CURVE ( 'NONE', #18476, #21152, #684, .T. ) ; +#10744 = ORIENTED_EDGE ( 'NONE', *, *, #4304, .F. ) ; +#10745 = EDGE_CURVE ( 'NONE', #7231, #4711, #18134, .T. ) ; +#10746 = ORIENTED_EDGE ( 'NONE', *, *, #22074, .F. ) ; +#10747 = DIRECTION ( 'NONE', ( 0.0005884949961231548347, -0.2249510543439030841, 0.9743698870671270162 ) ) ; +#10748 = ORIENTED_EDGE ( 'NONE', *, *, #27811, .F. ) ; +#10749 = ORIENTED_EDGE ( 'NONE', *, *, #18608, .F. ) ; +#10750 = CARTESIAN_POINT ( 'NONE', ( -12.63780403360086524, 184.0105860366603281, 102.6558995647242227 ) ) ; +#10751 = CARTESIAN_POINT ( 'NONE', ( -31.70535867971752708, 220.4002260770989778, 73.57765341576822493 ) ) ; +#10752 = CARTESIAN_POINT ( 'NONE', ( -12.63780402291296134, 137.2408233462553255, 91.85824708360104296 ) ) ; +#10753 = VERTEX_POINT ( 'NONE', #11565 ) ; +#10754 = ADVANCED_FACE ( 'NONE', ( #23424 ), #36291, .T. ) ; +#10755 = ORIENTED_EDGE ( 'NONE', *, *, #7446, .F. ) ; +#10756 = FACE_OUTER_BOUND ( 'NONE', #39057, .T. ) ; +#10757 = CARTESIAN_POINT ( 'NONE', ( -35.94659742851874284, 109.6131156826799895, 89.78949559170979455 ) ) ; +#10758 = DIRECTION ( 'NONE', ( 0.7857167650892391553, -0.6185862428610305885, -0.0004745532376930816426 ) ) ; +#10759 = CARTESIAN_POINT ( 'NONE', ( -38.40646698065000919, 119.2087085174999999, 90.46070431091000330 ) ) ; +#10760 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455649311516, -31.54510897440487938, 136.4474729010643159 ) ) ; +#10761 = APPROVAL_PERSON_ORGANIZATION ( #36585, #25220, #18362 ) ; +#10762 = AXIS2_PLACEMENT_3D ( 'NONE', #10137, #28736, #7044 ) ; +#10763 = LINE ( 'NONE', #36507, #36733 ) ; +#10764 = ORIENTED_EDGE ( 'NONE', *, *, #34576, .T. ) ; +#10765 = CARTESIAN_POINT ( 'NONE', ( -37.83658563635734851, 190.9636364155839487, 106.3289608523462846 ) ) ; +#10766 = CARTESIAN_POINT ( 'NONE', ( -15.49852919254797179, 185.3436308334966895, 105.0179936564814511 ) ) ; +#10767 = VERTEX_POINT ( 'NONE', #40355 ) ; +#10768 = CIRCLE ( 'NONE', #302, 5.500000000083335117 ) ; +#10769 = AXIS2_PLACEMENT_3D ( 'NONE', #34965, #20053, #26221 ) ; +#10770 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3708, #35169, #38062, #16185, #10065, #32143 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10771 = CARTESIAN_POINT ( 'NONE', ( -20.51860925439517658, 209.4696347946357662, 75.57087777984216359 ) ) ; +#10772 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971528487 ) ) ; +#10773 = DIRECTION ( 'NONE', ( 0.0005884949961236033691, -0.2249510543439074417, 0.9743698870671260170 ) ) ; +#10774 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7872, #32816, #4796, #17255 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999999704799078515 ), + .UNSPECIFIED. ) ; +#10775 = DIRECTION ( 'NONE', ( 0.7856637149787887298, -0.6186538021912810770, 0.000000000000000000 ) ) ; +#10776 = ORIENTED_EDGE ( 'NONE', *, *, #23539, .F. ) ; +#10777 = CARTESIAN_POINT ( 'NONE', ( -2.453444137526474833, 207.4083922041706103, 77.08315768838481574 ) ) ; +#10778 = EDGE_CURVE ( 'NONE', #9171, #16546, #15036, .T. ) ; +#10779 = CARTESIAN_POINT ( 'NONE', ( 1.757321110795265096, 189.3959765346186259, 103.7979996257443105 ) ) ; +#10780 = CARTESIAN_POINT ( 'NONE', ( 3.062734419220130455, 191.5259964270285025, 103.8683342040099831 ) ) ; +#10781 = LINE ( 'NONE', #14048, #13831 ) ; +#10782 = CARTESIAN_POINT ( 'NONE', ( -26.14636603714999907, 191.5356462786000122, 103.7498177085000037 ) ) ; +#10783 = LINE ( 'NONE', #23054, #22509 ) ; +#10784 = CARTESIAN_POINT ( 'NONE', ( -29.20280672794129373, 149.0670272684989186, 94.08539458806572497 ) ) ; +#10785 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319383117124 ) ) ; +#10786 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #7576, #33327, #20446, #11464 ), + ( #17774, #35765, #17169, #17369 ), + ( #1651, #23738, #20039, #36190 ), + ( #29875, #36404, #4504, #23336 ), + ( #8411, #1441, #39054, #13923 ), + ( #26405, #8194, #38852, #26812 ), + ( #14139, #20662, #1857, #26612 ), + ( #39257, #17578, #23950, #2066 ), + ( #27022, #10869, #7772, #39453 ), + ( #20243, #32731, #20869, #37216 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.01667090743663000169, 0.000000000000000000, 0.2499990538965000120, 0.4999981579182999902, 0.7499972619401999996, 0.9999963377155000055, 1.000000000000000000, 1.017542216337000038 ), + ( 2.915096369016000249E-07, 1.000017816366000067 ), + .UNSPECIFIED. ) ; +#10787 = CARTESIAN_POINT ( 'NONE', ( -15.83323285334240360, 138.1594705225070072, 91.73016490536959111 ) ) ; +#10788 = EDGE_LOOP ( 'NONE', ( #21996, #2791, #24028, #19183 ) ) ; +#10789 = EDGE_CURVE ( 'NONE', #14004, #25364, #9502, .T. ) ; +#10790 = AXIS2_PLACEMENT_3D ( 'NONE', #22364, #38085, #34787 ) ; +#10791 = CARTESIAN_POINT ( 'NONE', ( -2.953326078383014419, 207.8686482947481124, 77.27881662713799926 ) ) ; +#10792 = ADVANCED_FACE ( 'NONE', ( #30980 ), #38837, .F. ) ; +#10793 = VECTOR ( 'NONE', #37371, 1000.000000000000000 ) ; +#10794 = CARTESIAN_POINT ( 'NONE', ( -24.94096241724887264, 117.2068880492941787, 170.8291735276115730 ) ) ; +#10795 = LINE ( 'NONE', #14267, #5537 ) ; +#10796 = CARTESIAN_POINT ( 'NONE', ( 37.43538425564999983, 190.5468385801999887, 106.5747605329000010 ) ) ; +#10797 = CARTESIAN_POINT ( 'NONE', ( 36.19056769187381661, 192.0352611420189817, 106.4236211497759967 ) ) ; +#10798 = VECTOR ( 'NONE', #8803, 1000.000000000000114 ) ; +#10799 = PLANE ( 'NONE', #4408 ) ; +#10800 = EDGE_CURVE ( 'NONE', #16069, #2058, #24874, .T. ) ; +#10801 = ADVANCED_FACE ( 'NONE', ( #37260 ), #30733, .T. ) ; +#10802 = FACE_OUTER_BOUND ( 'NONE', #17717, .T. ) ; +#10803 = EDGE_LOOP ( 'NONE', ( #25344, #1692, #38682, #14475 ) ) ; +#10804 = EDGE_CURVE ( 'NONE', #38902, #4989, #9839, .T. ) ; +#10805 = LINE ( 'NONE', #7924, #203 ) ; +#10806 = CARTESIAN_POINT ( 'NONE', ( 28.46531727888097407, 128.0270319182838250, 91.75885866990255124 ) ) ; +#10807 = EDGE_CURVE ( 'NONE', #22883, #20598, #22132, .T. ) ; +#10808 = CARTESIAN_POINT ( 'NONE', ( 36.03695478788529272, 115.8404287910482822, 87.24601887434940295 ) ) ; +#10809 = CARTESIAN_POINT ( 'NONE', ( -20.33314853376290543, 191.4513222512928508, 104.2073383542079625 ) ) ; +#10810 = ORIENTED_EDGE ( 'NONE', *, *, #18840, .F. ) ; +#10811 = CARTESIAN_POINT ( 'NONE', ( -39.60387704732063696, 119.5152883936298025, 90.00593015133101460 ) ) ; +#10812 = CARTESIAN_POINT ( 'NONE', ( 4.035676231980001027, 136.7932109853310010, 93.79744583390555590 ) ) ; +#10813 = ORIENTED_EDGE ( 'NONE', *, *, #15854, .F. ) ; +#10814 = PLANE ( 'NONE', #24564 ) ; +#10815 = CARTESIAN_POINT ( 'NONE', ( 25.17505429875322776, 212.3492621108707965, 73.54312482419744867 ) ) ; +#10816 = ORIENTED_EDGE ( 'NONE', *, *, #37096, .F. ) ; +#10817 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10818 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385907860 ) ) ; +#10819 = CARTESIAN_POINT ( 'NONE', ( 3.064415859742461112, 190.8780989022363883, 106.7976082717191417 ) ) ; +#10820 = AXIS2_PLACEMENT_3D ( 'NONE', #27059, #33561, #8233 ) ; +#10821 = CARTESIAN_POINT ( 'NONE', ( -30.06899859699403876, 176.9708773808299895, 103.4130022359367587 ) ) ; +#10822 = CARTESIAN_POINT ( 'NONE', ( -20.49852834491502307, 151.4051363116404900, 97.18569326181511769 ) ) ; +#10823 = ORIENTED_EDGE ( 'NONE', *, *, #21989, .F. ) ; +#10824 = VECTOR ( 'NONE', #8005, 1000.000000000000114 ) ; +#10825 = EDGE_LOOP ( 'NONE', ( #24172, #11465, #36181, #3128 ) ) ; +#10826 = CARTESIAN_POINT ( 'NONE', ( -23.36013623391100325, 181.0108636162488267, 104.5355957067678219 ) ) ; +#10827 = ADVANCED_FACE ( 'NONE', ( #6766 ), #22901, .F. ) ; +#10828 = CARTESIAN_POINT ( 'NONE', ( 42.83487131658635860, 120.7910107177264081, 92.64688251868899727 ) ) ; +#10829 = VECTOR ( 'NONE', #27262, 1000.000000000000114 ) ; +#10830 = VECTOR ( 'NONE', #2133, 1000.000000000000227 ) ; +#10831 = FACE_OUTER_BOUND ( 'NONE', #1912, .T. ) ; +#10832 = VECTOR ( 'NONE', #7932, 1000.000000000000114 ) ; +#10833 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#10834 = CONICAL_SURFACE ( 'NONE', #32366, 48.00000000001811884, 0.7853981633973075027 ) ; +#10835 = ORIENTED_EDGE ( 'NONE', *, *, #13946, .T. ) ; +#10836 = CARTESIAN_POINT ( 'NONE', ( 25.51044001015309703, 191.4790671403759745, 106.3785283636754855 ) ) ; +#10837 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28053, #6349, #31307, #28441 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10838 = CARTESIAN_POINT ( 'NONE', ( -39.39285454264343400, 114.3643166784735712, 151.6767146082210047 ) ) ; +#10839 = CARTESIAN_POINT ( 'NONE', ( 36.69057616380133879, 165.6296374286519892, 191.7157049021380715 ) ) ; +#10840 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319379670445 ) ) ; +#10841 = ADVANCED_FACE ( 'NONE', ( #35161 ), #39871, .F. ) ; +#10842 = CARTESIAN_POINT ( 'NONE', ( 31.79572351860000978, 225.9002260771066517, 76.03930080930153679 ) ) ; +#10843 = CARTESIAN_POINT ( 'NONE', ( 25.89203641490000507, 191.6305662588000018, 106.7726749487000006 ) ) ; +#10844 = EDGE_CURVE ( 'NONE', #10712, #9444, #9864, .T. ) ; +#10845 = DIRECTION ( 'NONE', ( -0.7857089111626770483, 0.6185964006681257121, 0.000000000000000000 ) ) ; +#10846 = CARTESIAN_POINT ( 'NONE', ( 26.22160995721886323, 122.3003350589623466, 87.87234068927691055 ) ) ; +#10847 = ORIENTED_EDGE ( 'NONE', *, *, #37407, .T. ) ; +#10848 = ADVANCED_FACE ( 'NONE', ( #837 ), #20280, .F. ) ; +#10849 = FACE_OUTER_BOUND ( 'NONE', #8650, .T. ) ; +#10850 = FACE_OUTER_BOUND ( 'NONE', #19328, .T. ) ; +#10851 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319375842127 ) ) ; +#10852 = DIRECTION ( 'NONE', ( 0.0006039748319385504537, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#10853 = VECTOR ( 'NONE', #7713, 1000.000000000000227 ) ; +#10854 = CARTESIAN_POINT ( 'NONE', ( -20.50022561091320128, 193.4754546137064892, 103.9384250774701712 ) ) ; +#10855 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #12748, #16946, #15800, #25437 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.1815409218495399601, 1.571531679974982776 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8453711073098789663, 0.8453711073098789663, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#10856 = AXIS2_PLACEMENT_3D ( 'NONE', #9132, #5858, #18310 ) ; +#10857 = EDGE_LOOP ( 'NONE', ( #39225, #15015, #35584, #1460 ) ) ; +#10858 = ORIENTED_EDGE ( 'NONE', *, *, #15900, .F. ) ; +#10859 = ADVANCED_FACE ( 'NONE', ( #38850 ), #19827, .F. ) ; +#10860 = VERTEX_POINT ( 'NONE', #35978 ) ; +#10861 = CARTESIAN_POINT ( 'NONE', ( -13.50718409113456886, 124.3648481134796242, 88.37302201493642428 ) ) ; +#10862 = CIRCLE ( 'NONE', #24595, 4.999999999999990230 ) ; +#10863 = CARTESIAN_POINT ( 'NONE', ( 5.666454502190154230, 124.0172541041007293, 91.08205378008646846 ) ) ; +#10864 = ORIENTED_EDGE ( 'NONE', *, *, #21383, .T. ) ; +#10865 = FACE_BOUND ( 'NONE', #9722, .T. ) ; +#10866 = DIRECTION ( 'NONE', ( -0.7730662169443226484, -0.5272861007345266415, -0.3526159273084134571 ) ) ; +#10867 = CARTESIAN_POINT ( 'NONE', ( -39.42814403217000319, 120.3902538954999955, 87.47098505926000200 ) ) ; +#10868 = LINE ( 'NONE', #5109, #26848 ) ; +#10869 = CARTESIAN_POINT ( 'NONE', ( -37.80938064989999958, 118.7890831608000042, 87.39100579507000077 ) ) ; +#10870 = ORIENTED_EDGE ( 'NONE', *, *, #18993, .F. ) ; +#10871 = CARTESIAN_POINT ( 'NONE', ( 3.501248163491682774, 185.3093324233526005, 105.1696495633186288 ) ) ; +#10872 = ORIENTED_EDGE ( 'NONE', *, *, #25723, .F. ) ; +#10873 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; +#10874 = CARTESIAN_POINT ( 'NONE', ( -23.04612012923000108, 118.1131156702000169, 13.53038997162000001 ) ) ; +#10875 = DIRECTION ( 'NONE', ( -1.734723476152105595E-15, 0.9743700557921589622, 0.2249510932971544308 ) ) ; +#10876 = ORIENTED_EDGE ( 'NONE', *, *, #27758, .T. ) ; +#10877 = CARTESIAN_POINT ( 'NONE', ( -0.4376699881329659814, 188.6098915369740041, 103.1945603907900164 ) ) ; +#10878 = CARTESIAN_POINT ( 'NONE', ( 3.499876193431697313, 126.7284862091015185, 89.25048713327655037 ) ) ; +#10879 = CARTESIAN_POINT ( 'NONE', ( 8.188077193987783886, 161.3225763900416609, 97.06327911995997226 ) ) ; +#10880 = CIRCLE ( 'NONE', #16085, 8.500000000041749715 ) ; +#10881 = ORIENTED_EDGE ( 'NONE', *, *, #31631, .T. ) ; +#10882 = CARTESIAN_POINT ( 'NONE', ( 22.59408136249981425, 154.4094276889290427, 95.28750111188634264 ) ) ; +#10883 = CARTESIAN_POINT ( 'NONE', ( -23.80390059618266108, 214.0116903629666751, 76.07246561699776066 ) ) ; +#10884 = CONICAL_SURFACE ( 'NONE', #445, 22.50000000000898837, 0.7853981633973132759 ) ; +#10885 = ORIENTED_EDGE ( 'NONE', *, *, #22807, .T. ) ; +#10886 = ORIENTED_EDGE ( 'NONE', *, *, #30881, .T. ) ; +#10887 = VECTOR ( 'NONE', #3375, 1000.000000000000000 ) ; +#10888 = EDGE_CURVE ( 'NONE', #38838, #18878, #26938, .T. ) ; +#10889 = VECTOR ( 'NONE', #3719, 1000.000000000000000 ) ; +#10890 = EDGE_CURVE ( 'NONE', #14788, #39309, #20970, .T. ) ; +#10891 = ORIENTED_EDGE ( 'NONE', *, *, #22108, .T. ) ; +#10892 = EDGE_CURVE ( 'NONE', #38645, #3220, #35131, .T. ) ; +#10893 = ORIENTED_EDGE ( 'NONE', *, *, #31623, .T. ) ; +#10894 = AXIS2_PLACEMENT_3D ( 'NONE', #4255, #22895, #39013 ) ; +#10895 = EDGE_CURVE ( 'NONE', #24926, #34340, #10868, .T. ) ; +#10896 = CARTESIAN_POINT ( 'NONE', ( -28.25302560543209651, 186.4513372582409829, 105.2762999796510002 ) ) ; +#10897 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971562904 ) ) ; +#10898 = CARTESIAN_POINT ( 'NONE', ( 27.87465140964610200, 149.3918682064020516, 291.5417083442604280 ) ) ; +#10899 = ORIENTED_EDGE ( 'NONE', *, *, #37539, .F. ) ; +#10900 = ADVANCED_FACE ( 'NONE', ( #17577 ), #35294, .F. ) ; +#10901 = CARTESIAN_POINT ( 'NONE', ( 26.00069614921000394, 120.1373339117999990, 90.44931475037999746 ) ) ; +#10902 = CARTESIAN_POINT ( 'NONE', ( 20.50029382560668267, 151.8610500380989947, 95.21357841101577435 ) ) ; +#10904 = CARTESIAN_POINT ( 'NONE', ( -10.97961932939787566, 153.8967050738901321, 95.18940742154448742 ) ) ; +#10903 = CARTESIAN_POINT ( 'NONE', ( 25.49185141408513999, 210.1694363959666703, 75.54314407219717964 ) ) ; +#10905 = EDGE_LOOP ( 'NONE', ( #2197, #25394, #20705, #28436, #23646, #28944 ) ) ; +#10906 = EDGE_CURVE ( 'NONE', #27866, #9290, #30322, .T. ) ; +#10907 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927785862613, 0.0005734119022076208027 ) ) ; +#10908 = EDGE_LOOP ( 'NONE', ( #30114, #21930, #16174, #6046, #22839, #2699, #14836, #17113 ) ) ; +#10909 = AXIS2_PLACEMENT_3D ( 'NONE', #6906, #20112, #3630 ) ; +#10910 = DIRECTION ( 'NONE', ( -0.0004161288024545937514, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#10911 = VECTOR ( 'NONE', #9155, 999.9999999999998863 ) ; +#10912 = AXIS2_PLACEMENT_3D ( 'NONE', #28247, #213, #12693 ) ; +#10913 = EDGE_LOOP ( 'NONE', ( #37704, #14419, #37876, #25337 ) ) ; +#10914 = CARTESIAN_POINT ( 'NONE', ( -22.54148966027999990, 176.5965135413000269, 28.07991271570000080 ) ) ; +#10915 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; +#10916 = EDGE_CURVE ( 'NONE', #2346, #37891, #8388, .T. ) ; +#10917 = FACE_OUTER_BOUND ( 'NONE', #16270, .T. ) ; +#10918 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319384230599 ) ) ; +#10919 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#10920 = CARTESIAN_POINT ( 'NONE', ( 36.41644495559000205, 191.8199172630999954, 104.3707800657000178 ) ) ; +#10921 = CIRCLE ( 'NONE', #8279, 2.499999999950359264 ) ; +#10922 = ORIENTED_EDGE ( 'NONE', *, *, #4314, .F. ) ; +#10923 = ORIENTED_EDGE ( 'NONE', *, *, #28791, .F. ) ; +#10924 = LINE ( 'NONE', #20301, #469 ) ; +#10925 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28487, #13150, #31962, #34783 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#10926 = EDGE_LOOP ( 'NONE', ( #3859, #35385, #7448, #7974 ) ) ; +#10927 = PLANE ( 'NONE', #14134 ) ; +#10928 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319388572829 ) ) ; +#10929 = CARTESIAN_POINT ( 'NONE', ( 3.075283387903953614, 190.8485281250639218, 106.8022040810427313 ) ) ; +#10930 = VERTEX_POINT ( 'NONE', #8410 ) ; +#10931 = CARTESIAN_POINT ( 'NONE', ( 37.32820081582953264, 168.0249161464118117, 183.6187219225678859 ) ) ; +#10932 = CARTESIAN_POINT ( 'NONE', ( 15.50029468042244396, 126.6919968860542838, 89.40586344971805488 ) ) ; +#10933 = CARTESIAN_POINT ( 'NONE', ( -25.50111726777775090, 120.6553742016506874, 88.03695713991920968 ) ) ; +#10934 = CARTESIAN_POINT ( 'NONE', ( -14.91027383994646272, 151.7163915728016548, 177.9904694539845025 ) ) ; +#10935 = ADVANCED_FACE ( 'NONE', ( #14537 ), #27635, .T. ) ; +#10936 = AXIS2_PLACEMENT_3D ( 'NONE', #5371, #17825, #12719 ) ; +#10937 = ORIENTED_EDGE ( 'NONE', *, *, #26919, .T. ) ; +#10938 = EDGE_CURVE ( 'NONE', #17057, #33799, #15110, .T. ) ; +#10939 = EDGE_CURVE ( 'NONE', #28499, #28666, #15339, .T. ) ; +#10940 = CARTESIAN_POINT ( 'NONE', ( -13.83205090667458670, 150.4111611012818628, 179.9705989528482917 ) ) ; +#10941 = VECTOR ( 'NONE', #11750, 1000.000000000000114 ) ; +#10942 = CARTESIAN_POINT ( 'NONE', ( -2.437027990547441014, 191.0000000396348128, 104.2633722229568605 ) ) ; +#10943 = VERTEX_POINT ( 'NONE', #3647 ) ; +#10944 = EDGE_CURVE ( 'NONE', #15218, #4804, #32724, .T. ) ; +#10945 = CARTESIAN_POINT ( 'NONE', ( 33.51443528077827239, 81.86012571781209601, 287.9887764040152547 ) ) ; +#10946 = CARTESIAN_POINT ( 'NONE', ( -38.53363287338000021, 118.3434021919999992, 89.55002640806999636 ) ) ; +#10947 = EDGE_CURVE ( 'NONE', #282, #23181, #37414, .T. ) ; +#10948 = ORIENTED_EDGE ( 'NONE', *, *, #18606, .F. ) ; +#10949 = ORIENTED_EDGE ( 'NONE', *, *, #14211, .T. ) ; +#10950 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#10951 = DIRECTION ( 'NONE', ( 0.6087906217132987852, -0.7729786229956010501, -0.1785441886642060716 ) ) ; +#10952 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 82.27946979429644614, 322.5967026918629017 ) ) ; +#10953 = ORIENTED_EDGE ( 'NONE', *, *, #13373, .F. ) ; +#10954 = ORIENTED_EDGE ( 'NONE', *, *, #4816, .T. ) ; +#10955 = CARTESIAN_POINT ( 'NONE', ( -3.170187833920075970, 183.7988232230405572, 102.0881399076664593 ) ) ; +#10956 = ORIENTED_EDGE ( 'NONE', *, *, #25311, .T. ) ; +#10957 = VERTEX_POINT ( 'NONE', #16131 ) ; +#10958 = EDGE_LOOP ( 'NONE', ( #31024, #25795, #33751, #18903 ) ) ; +#10959 = DIRECTION ( 'NONE', ( 0.0002393071182785211099, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#10960 = EDGE_CURVE ( 'NONE', #39311, #38692, #2011, .T. ) ; +#10961 = CONICAL_SURFACE ( 'NONE', #39694, 2.250000000020516921, 0.7853981633778843729 ) ; +#10962 = ORIENTED_EDGE ( 'NONE', *, *, #6902, .F. ) ; +#10963 = CARTESIAN_POINT ( 'NONE', ( -45.37719511632801783, 116.4273876922947153, 122.4606002276863848 ) ) ; +#10964 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#10965 = CARTESIAN_POINT ( 'NONE', ( 38.27613113168000325, 118.4065472851000038, 87.79665044522000983 ) ) ; +#10966 = CARTESIAN_POINT ( 'NONE', ( 25.99858048705007008, 120.0662502775363123, 90.40623698262325547 ) ) ; +#10967 = CARTESIAN_POINT ( 'NONE', ( 1.752038607023885142, 151.6655334627390914, 130.5892090252970661 ) ) ; +#10968 = AXIS2_PLACEMENT_3D ( 'NONE', #38287, #16601, #7403 ) ; +#10969 = EDGE_LOOP ( 'NONE', ( #31980, #37714, #21243, #33549 ) ) ; +#10970 = CARTESIAN_POINT ( 'NONE', ( -21.57293378737277223, 176.1767418382142694, 103.2474204113453879 ) ) ; +#10971 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; +#10972 = ORIENTED_EDGE ( 'NONE', *, *, #6433, .T. ) ; +#10973 = LINE ( 'NONE', #30181, #37524 ) ; +#10974 = CARTESIAN_POINT ( 'NONE', ( -39.79500347691000428, 182.5468005769366187, 106.5836252739005658 ) ) ; +#10975 = CARTESIAN_POINT ( 'NONE', ( 20.49976360197975112, 195.7358879765328936, 104.4182221658072507 ) ) ; +#10976 = CARTESIAN_POINT ( 'NONE', ( -13.54365902012251155, 127.5920554465911607, 178.0186555151901473 ) ) ; +#10977 = VERTEX_POINT ( 'NONE', #35111 ) ; +#10978 = CARTESIAN_POINT ( 'NONE', ( -75.39652672445234316, 196.3653591838614147, 189.1162797731339822 ) ) ; +#10979 = CARTESIAN_POINT ( 'NONE', ( 1.766903094796105966, 189.4031650064154064, 103.8000672188349114 ) ) ; +#10980 = FACE_OUTER_BOUND ( 'NONE', #20554, .T. ) ; +#10981 = ORIENTED_EDGE ( 'NONE', *, *, #13929, .T. ) ; +#10982 = DIRECTION ( 'NONE', ( -7.338309297537026246E-11, -0.9743700557756715952, -0.2249510933685688052 ) ) ; +#10983 = VERTEX_POINT ( 'NONE', #21885 ) ; +#10984 = EDGE_CURVE ( 'NONE', #4954, #6620, #37950, .T. ) ; +#10985 = CARTESIAN_POINT ( 'NONE', ( -26.15746170179000174, 191.4561040044000038, 103.7271919721000017 ) ) ; +#10986 = EDGE_CURVE ( 'NONE', #37514, #7165, #193, .T. ) ; +#10987 = DIRECTION ( 'NONE', ( 0.0005884949961266384847, -0.2249510543439063315, 0.9743698870671264611 ) ) ; +#10988 = CARTESIAN_POINT ( 'NONE', ( 14.78500024124773304, 129.1259577792816629, 89.96821972116190125 ) ) ; +#10989 = DIRECTION ( 'NONE', ( -0.7069397808360943225, 0.6508952239913948778, 0.2767156548816978590 ) ) ; +#10990 = VERTEX_POINT ( 'NONE', #6515 ) ; +#10991 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319394906738 ) ) ; +#10992 = CIRCLE ( 'NONE', #36458, 2.999999999998230304 ) ; +#10993 = ADVANCED_FACE ( 'NONE', ( #17316 ), #29010, .T. ) ; +#10994 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37525, #9524, #22001, #6429 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.001732890349273856316, 0.003708228055068993681 ), + .UNSPECIFIED. ) ; +#10995 = VECTOR ( 'NONE', #39144, 999.9999999999998863 ) ; +#10996 = CARTESIAN_POINT ( 'NONE', ( 16.49964056686251013, 136.6766879063869453, 180.9853436342004898 ) ) ; +#10997 = CARTESIAN_POINT ( 'NONE', ( 15.50147167064367437, 126.2420947773427997, 91.35460322390918009 ) ) ; +#10998 = CARTESIAN_POINT ( 'NONE', ( -18.61079839510214029, 126.0371735097383095, 174.9248182282352957 ) ) ; +#10999 = CARTESIAN_POINT ( 'NONE', ( -3.955049870755343200, 137.2594250647584317, 91.77268855263983482 ) ) ; +#11000 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #40049, #33915, #5913, #18164 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11001 = CARTESIAN_POINT ( 'NONE', ( 38.04963484502000171, 190.2021038149999868, 106.7594576531000001 ) ) ; +#11002 = CARTESIAN_POINT ( 'NONE', ( -42.36217678049914781, 170.6443158288746815, 189.3365560754358228 ) ) ; +#11003 = CARTESIAN_POINT ( 'NONE', ( -5.666923135161506586, 130.1263008745872867, 92.47646040638427678 ) ) ; +#11004 = LINE ( 'NONE', #31878, #4722 ) ; +#11005 = CARTESIAN_POINT ( 'NONE', ( -38.36814232060637408, 118.8282003920224668, 87.72026801873936108 ) ) ; +#11006 = EDGE_LOOP ( 'NONE', ( #261, #11612, #36040, #29996 ) ) ; +#11007 = FACE_OUTER_BOUND ( 'NONE', #21391, .T. ) ; +#11008 = CYLINDRICAL_SURFACE ( 'NONE', #30782, 5.000000000000007994 ) ; +#11009 = DIRECTION ( 'NONE', ( -0.9029530701559865813, -0.4297388226321038340, 0.0005453610282712744936 ) ) ; +#11010 = ORIENTED_EDGE ( 'NONE', *, *, #1673, .T. ) ; +#11011 = CARTESIAN_POINT ( 'NONE', ( 13.50176803619674004, 127.0692004836212448, 92.06300581097160318 ) ) ; +#11012 = VERTEX_POINT ( 'NONE', #32286 ) ; +#11013 = AXIS2_PLACEMENT_3D ( 'NONE', #3443, #30685, #9011 ) ; +#11014 = CARTESIAN_POINT ( 'NONE', ( -16.54520785153081164, 151.9090420533067913, 184.2667482906656460 ) ) ; +#11015 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#11016 = EDGE_LOOP ( 'NONE', ( #9673, #29922, #32507, #29446 ) ) ; +#11017 = FACE_OUTER_BOUND ( 'NONE', #25757, .T. ) ; +#11018 = EDGE_CURVE ( 'NONE', #12044, #21775, #36642, .T. ) ; +#11019 = VECTOR ( 'NONE', #34339, 1000.000000000000000 ) ; +#11020 = FACE_OUTER_BOUND ( 'NONE', #13936, .T. ) ; +#11021 = AXIS2_PLACEMENT_3D ( 'NONE', #3573, #19906, #38335 ) ; +#11022 = DIRECTION ( 'NONE', ( 0.0005884949521151187956, -0.2249510543284071740, 0.9743698870707311332 ) ) ; +#11023 = LINE ( 'NONE', #14703, #11639 ) ; +#11024 = DIRECTION ( 'NONE', ( 0.0005884949961235587000, -0.2249510543439063037, 0.9743698870671264611 ) ) ; +#11025 = CARTESIAN_POINT ( 'NONE', ( 15.99999411728631671, 174.5114300543024513, 99.93239967722463746 ) ) ; +#11026 = ORIENTED_EDGE ( 'NONE', *, *, #22462, .F. ) ; +#11027 = ADVANCED_FACE ( 'NONE', ( #1193 ), #39900, .F. ) ; +#11028 = DIRECTION ( 'NONE', ( 0.0005884949961235587000, -0.2249510543439063037, 0.9743698870671264611 ) ) ; +#11029 = CARTESIAN_POINT ( 'NONE', ( 12.63519044092067567, 181.7451889061886163, 101.6793939867825287 ) ) ; +#11030 = CARTESIAN_POINT ( 'NONE', ( 48.26140840130958054, 61.07709620987316868, 291.5293952538879125 ) ) ; +#11031 = CARTESIAN_POINT ( 'NONE', ( -45.32207284385599877, 123.9952506376050394, 92.99168501725661429 ) ) ; +#11032 = EDGE_CURVE ( 'NONE', #27515, #25396, #20522, .T. ) ; +#11033 = ORIENTED_EDGE ( 'NONE', *, *, #18065, .T. ) ; +#11034 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971540700 ) ) ; +#11035 = ADVANCED_FACE ( 'NONE', ( #30635 ), #2628, .T. ) ; +#11037 = EDGE_CURVE ( 'NONE', #3242, #35968, #40213, .T. ) ; +#11036 = CARTESIAN_POINT ( 'NONE', ( 20.33512933904179221, 151.3759901152849636, 97.32511934184164204 ) ) ; +#11038 = CARTESIAN_POINT ( 'NONE', ( -27.87558292050999853, 125.0785051656000064, 90.97322914094000623 ) ) ; +#11039 = CARTESIAN_POINT ( 'NONE', ( 32.21870153402343817, 137.6089111963648861, 94.31084469150592042 ) ) ; +#11040 = CARTESIAN_POINT ( 'NONE', ( -28.44043104824569923, 124.7785142762178765, 91.38535058895490693 ) ) ; +#11041 = DIRECTION ( 'NONE', ( -0.0005884949961241524091, 0.2249510543439059707, -0.9743698870671263501 ) ) ; +#11042 = CONICAL_SURFACE ( 'NONE', #3837, 8.000000001551294204, 0.7853981633973023957 ) ; +#11043 = CARTESIAN_POINT ( 'NONE', ( 29.20104124104027576, 148.3999055379004517, 96.97501579703776997 ) ) ; +#11044 = DIRECTION ( 'NONE', ( 0.0005734119072319879013, 1.265515853068973323E-14, 0.9999998355993788834 ) ) ; +#11045 = ORIENTED_EDGE ( 'NONE', *, *, #32516, .F. ) ; +#11046 = DIRECTION ( 'NONE', ( -0.0005884949961238380989, 0.2249510543439045829, -0.9743698870671267942 ) ) ; +#11047 = CARTESIAN_POINT ( 'NONE', ( -21.57293377266096357, 129.4069791430369492, 92.44976792907745278 ) ) ; +#11048 = CIRCLE ( 'NONE', #15614, 4.999999999999990230 ) ; +#11049 = PLANE ( 'NONE', #3845 ) ; +#11050 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; +#11051 = AXIS2_PLACEMENT_3D ( 'NONE', #5552, #39901, #18012 ) ; +#11052 = AXIS2_PLACEMENT_3D ( 'NONE', #23200, #16838, #35632 ) ; +#11053 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#11054 = VERTEX_POINT ( 'NONE', #21444 ) ; +#11055 = ORIENTED_EDGE ( 'NONE', *, *, #36552, .F. ) ; +#11056 = EDGE_LOOP ( 'NONE', ( #21112, #3507, #7110, #25063 ) ) ; +#11057 = CARTESIAN_POINT ( 'NONE', ( -13.50128150735577748, 124.5478689764576359, 88.66604936023510675 ) ) ; +#11058 = DIRECTION ( 'NONE', ( -0.4271071565734249620, -0.4480007094940485213, -0.7854138024612203894 ) ) ; +#11059 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32204, #31597, #19507, #19701 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11060 = ORIENTED_EDGE ( 'NONE', *, *, #9685, .T. ) ; +#11061 = DIRECTION ( 'NONE', ( -0.0004161288024657052516, -0.5299192578509964724, -0.8480479980493255132 ) ) ; +#11062 = FACE_OUTER_BOUND ( 'NONE', #24872, .T. ) ; +#11063 = LINE ( 'NONE', #2270, #10544 ) ; +#11064 = VERTEX_POINT ( 'NONE', #30020 ) ; +#11065 = CARTESIAN_POINT ( 'NONE', ( 37.79411860435257609, 218.5902260770999987, 73.03567738180412050 ) ) ; +#11066 = VERTEX_POINT ( 'NONE', #11408 ) ; +#11067 = CARTESIAN_POINT ( 'NONE', ( -25.99154525261003457, 196.5784392977548407, 103.8908015617383995 ) ) ; +#11068 = CARTESIAN_POINT ( 'NONE', ( 35.55462690928660408, 112.7627284812108996, 90.24631073547891447 ) ) ; +#11069 = CARTESIAN_POINT ( 'NONE', ( 30.07478355117409308, 177.7951688118731681, 100.6820556990014950 ) ) ; +#11070 = ORIENTED_EDGE ( 'NONE', *, *, #12188, .T. ) ; +#11071 = ORIENTED_EDGE ( 'NONE', *, *, #2538, .T. ) ; +#11072 = CONICAL_SURFACE ( 'NONE', #26110, 2.503098569411387420, 0.7853981633649038674 ) ; +#11073 = EDGE_CURVE ( 'NONE', #6578, #9198, #23894, .T. ) ; +#11074 = CARTESIAN_POINT ( 'NONE', ( -2.877428494186000218, 190.4461576289999982, 103.6226212142999970 ) ) ; +#11075 = CARTESIAN_POINT ( 'NONE', ( 0.8177663066029530192, 189.0253564221259808, 103.7033406197609793 ) ) ; +#11076 = CARTESIAN_POINT ( 'NONE', ( 34.29442123011752841, 218.5902260770999987, 73.53779120251549273 ) ) ; +#11077 = CIRCLE ( 'NONE', #19548, 51.90509899272669969 ) ; +#11078 = ORIENTED_EDGE ( 'NONE', *, *, #1122, .F. ) ; +#11079 = EDGE_LOOP ( 'NONE', ( #5007, #4783, #4161, #36073 ) ) ; +#11080 = CARTESIAN_POINT ( 'NONE', ( -2.372094777808882782, 209.5677220771418376, 75.55993702015497604 ) ) ; +#11081 = ORIENTED_EDGE ( 'NONE', *, *, #8927, .T. ) ; +#11082 = ADVANCED_FACE ( 'NONE', ( #24099 ), #14699, .T. ) ; +#11083 = ORIENTED_EDGE ( 'NONE', *, *, #2979, .F. ) ; +#11084 = CIRCLE ( 'NONE', #39135, 6.000000000278002510 ) ; +#11085 = EDGE_CURVE ( 'NONE', #26640, #189, #3803, .T. ) ; +#11086 = EDGE_CURVE ( 'NONE', #1525, #19998, #6468, .T. ) ; +#11087 = ORIENTED_EDGE ( 'NONE', *, *, #40274, .F. ) ; +#11088 = ORIENTED_EDGE ( 'NONE', *, *, #5475, .F. ) ; +#11089 = CARTESIAN_POINT ( 'NONE', ( -27.50624184847999842, 187.5021564911999974, 106.0367333465000002 ) ) ; +#11090 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#11091 = ORIENTED_EDGE ( 'NONE', *, *, #33820, .T. ) ; +#11092 = LINE ( 'NONE', #39084, #7439 ) ; +#11093 = ORIENTED_EDGE ( 'NONE', *, *, #5847, .T. ) ; +#11094 = CARTESIAN_POINT ( 'NONE', ( 28.26060338730999888, 125.1349112909999945, 91.09114387335000629 ) ) ; +#11095 = LINE ( 'NONE', #23371, #31303 ) ; +#11097 = CARTESIAN_POINT ( 'NONE', ( -28.52670407937950969, 187.4270078119665754, 102.9410870260050928 ) ) ; +#11096 = LINE ( 'NONE', #27666, #34160 ) ; +#11098 = ORIENTED_EDGE ( 'NONE', *, *, #27736, .T. ) ; +#11099 = VECTOR ( 'NONE', #22090, 1000.000000000000114 ) ; +#11100 = VECTOR ( 'NONE', #13767, 1000.000000000000114 ) ; +#11101 = VERTEX_POINT ( 'NONE', #9764 ) ; +#11102 = AXIS2_PLACEMENT_3D ( 'NONE', #13262, #6702, #16708 ) ; +#11103 = AXIS2_PLACEMENT_3D ( 'NONE', #38393, #7301, #1175 ) ; +#11104 = CONICAL_SURFACE ( 'NONE', #39809, 5.000000517016990109, 0.7853981634346335339 ) ; +#11105 = ORIENTED_EDGE ( 'NONE', *, *, #24527, .F. ) ; +#11106 = CARTESIAN_POINT ( 'NONE', ( 39.38831168086999668, 119.0002552818999959, 89.54346710420000477 ) ) ; +#11107 = PLANE ( 'NONE', #4789 ) ; +#11108 = CARTESIAN_POINT ( 'NONE', ( -38.40287610445658117, 121.6088961281960366, 92.88326245006905424 ) ) ; +#11109 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16872, #13631, #16481, #12835 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11110 = CARTESIAN_POINT ( 'NONE', ( 40.93452692291575090, 180.9368392483152093, 106.5322820562371078 ) ) ; +#11111 = LINE ( 'NONE', #36240, #33941 ) ; +#11112 = ADVANCED_FACE ( 'NONE', ( #24918 ), #4638, .T. ) ; +#11113 = ORIENTED_EDGE ( 'NONE', *, *, #20419, .T. ) ; +#11114 = EDGE_CURVE ( 'NONE', #8051, #32274, #22928, .T. ) ; +#11115 = EDGE_CURVE ( 'NONE', #22787, #15773, #21639, .T. ) ; +#11116 = LINE ( 'NONE', #30325, #31189 ) ; +#11117 = CARTESIAN_POINT ( 'NONE', ( 26.53578290824999897, 123.9660816091000015, 88.77004744939999625 ) ) ; +#11118 = ORIENTED_EDGE ( 'NONE', *, *, #6628, .F. ) ; +#11119 = EDGE_CURVE ( 'NONE', #17425, #25568, #19075, .T. ) ; +#11120 = CARTESIAN_POINT ( 'NONE', ( -35.79968611446999915, 192.2947011702999873, 106.6046827446999998 ) ) ; +#11121 = EDGE_CURVE ( 'NONE', #14482, #11663, #22644, .T. ) ; +#11122 = CARTESIAN_POINT ( 'NONE', ( 2.730734721350000616, 190.9310010506000026, 106.4668547351000143 ) ) ; +#11123 = VERTEX_POINT ( 'NONE', #23042 ) ; +#11124 = CARTESIAN_POINT ( 'NONE', ( -19.99823416871255333, 118.9403737594142854, 90.20346087292681148 ) ) ; +#11125 = ADVANCED_FACE ( 'NONE', ( #35070 ), #23589, .F. ) ; +#11126 = VECTOR ( 'NONE', #28924, 1000.000000000000000 ) ; +#11127 = CIRCLE ( 'NONE', #26808, 6.000000000000007994 ) ; +#11128 = LINE ( 'NONE', #13783, #10830 ) ; +#11129 = CARTESIAN_POINT ( 'NONE', ( -3.168077782478838866, 185.2310913118877238, 105.4977280106237032 ) ) ; +#11130 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#11131 = CIRCLE ( 'NONE', #29434, 2.499999999979101162 ) ; +#11132 = ORIENTED_EDGE ( 'NONE', *, *, #26086, .F. ) ; +#11133 = VECTOR ( 'NONE', #18149, 1000.000000000000227 ) ; +#11134 = CARTESIAN_POINT ( 'NONE', ( 15.89560151159956369, 127.1356608655976004, 179.2951883097113637 ) ) ; +#11135 = CARTESIAN_POINT ( 'NONE', ( 21.73276882011762012, 213.2744563870097352, 75.54536777968174022 ) ) ; +#11136 = ORIENTED_EDGE ( 'NONE', *, *, #28288, .T. ) ; +#11137 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#11139 = CARTESIAN_POINT ( 'NONE', ( -38.89762471436931435, 77.14301703112144537, 288.8348295601788323 ) ) ; +#11138 = CARTESIAN_POINT ( 'NONE', ( 2.519705707365920144, 209.3774083710533489, 75.55686016564037288 ) ) ; +#11140 = ORIENTED_EDGE ( 'NONE', *, *, #10616, .F. ) ; +#11141 = ORIENTED_EDGE ( 'NONE', *, *, #19030, .F. ) ; +#11142 = LINE ( 'NONE', #23822, #12093 ) ; +#11143 = CARTESIAN_POINT ( 'NONE', ( 37.31104746592299648, 191.0675100092497303, 106.2960058513086068 ) ) ; +#11144 = LINE ( 'NONE', #10952, #27971 ) ; +#11145 = ORIENTED_EDGE ( 'NONE', *, *, #15207, .T. ) ; +#11146 = VERTEX_POINT ( 'NONE', #11517 ) ; +#11147 = CARTESIAN_POINT ( 'NONE', ( -5.342929950734402134, 181.6874047080202388, 101.6019927272797645 ) ) ; +#11148 = ORIENTED_EDGE ( 'NONE', *, *, #23925, .F. ) ; +#11149 = ORIENTED_EDGE ( 'NONE', *, *, #5100, .T. ) ; +#11150 = LINE ( 'NONE', #26295, #23061 ) ; +#11151 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.702666754117757870E-16, 0.0006039748319385827629 ) ) ; +#11152 = AXIS2_PLACEMENT_3D ( 'NONE', #7023, #32192, #31992 ) ; +#11153 = CARTESIAN_POINT ( 'NONE', ( 2.480477375137999818, 209.5058064405000096, 73.55699242858000275 ) ) ; +#11154 = ORIENTED_EDGE ( 'NONE', *, *, #20677, .F. ) ; +#11155 = EDGE_CURVE ( 'NONE', #15629, #6504, #12716, .T. ) ; +#11156 = CIRCLE ( 'NONE', #21624, 3.000000000000000888 ) ; +#11157 = ADVANCED_FACE ( 'NONE', ( #16677 ), #3959, .T. ) ; +#11158 = ORIENTED_EDGE ( 'NONE', *, *, #11398, .T. ) ; +#11159 = DIRECTION ( 'NONE', ( 0.0006039748319380209294, 1.272619257381173226E-14, 0.9999998176071845934 ) ) ; +#11160 = AXIS2_PLACEMENT_3D ( 'NONE', #12075, #8608, #33116 ) ; +#11161 = EDGE_CURVE ( 'NONE', #5771, #37119, #36864, .T. ) ; +#11162 = CARTESIAN_POINT ( 'NONE', ( -28.45933928643433575, 130.3430211585376810, 92.84111053953343173 ) ) ; +#11163 = CARTESIAN_POINT ( 'NONE', ( -35.76252955891000340, 191.5251398679000090, 103.7620077331999937 ) ) ; +#11164 = CARTESIAN_POINT ( 'NONE', ( 36.17084115905999653, 191.3515283555000224, 103.6762829166000017 ) ) ; +#11165 = CARTESIAN_POINT ( 'NONE', ( -25.67020520147000084, 120.8710716303999959, 87.91589439144999574 ) ) ; +#11166 = CARTESIAN_POINT ( 'NONE', ( 20.66261634646922118, 151.6624695158917007, 197.7430731246994355 ) ) ; +#11167 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178617807513E-05, -0.0002331579774917555924 ) ) ; +#11168 = ORIENTED_EDGE ( 'NONE', *, *, #30101, .T. ) ; +#11169 = ADVANCED_FACE ( 'NONE', ( #2731 ), #34381, .F. ) ; +#11170 = CARTESIAN_POINT ( 'NONE', ( -20.51855873943445374, 209.2345604776454024, 75.60470198948848974 ) ) ; +#11171 = DIRECTION ( 'NONE', ( 0.0005884949961176016596, -0.2249510543439068588, 0.9743698870671261281 ) ) ; +#11172 = CARTESIAN_POINT ( 'NONE', ( -20.49970533570471787, 160.6243682191729363, 97.26151316895288801 ) ) ; +#11173 = DIRECTION ( 'NONE', ( -1.063726576259922572E-07, -0.9742386546489418819, -0.2255194975779448163 ) ) ; +#11174 = ORIENTED_EDGE ( 'NONE', *, *, #36552, .T. ) ; +#11176 = ADVANCED_FACE ( 'NONE', ( #30937 ), #26204, .F. ) ; +#11175 = FACE_OUTER_BOUND ( 'NONE', #15183, .T. ) ; +#11177 = CARTESIAN_POINT ( 'NONE', ( 2.563555756422899901, 190.9701280411995867, 104.2517884403214197 ) ) ; +#11178 = FACE_OUTER_BOUND ( 'NONE', #14556, .T. ) ; +#11179 = ORIENTED_EDGE ( 'NONE', *, *, #4, .T. ) ; +#11180 = CARTESIAN_POINT ( 'NONE', ( -29.94629656132548590, 104.1131156707188694, 90.28587165215870414 ) ) ; +#11181 = ORIENTED_EDGE ( 'NONE', *, *, #19678, .T. ) ; +#11182 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34285, #15884, #3607, #18949, #28190, #28377, #28582 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 4 ), + ( 2.569378776076547217E-06, 7.549873607158256243E-06, 0.0005638757658064486684 ), + .UNSPECIFIED. ) ; +#11183 = CARTESIAN_POINT ( 'NONE', ( -25.87072552548999838, 191.8632371752999859, 104.0535259812000106 ) ) ; +#11184 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30722, #10207, #22678, #32076 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11185 = CONICAL_SURFACE ( 'NONE', #25004, 6.500001377281787285, 0.7853982184479049167 ) ; +#11186 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560406 ) ) ; +#11187 = CARTESIAN_POINT ( 'NONE', ( 25.88929766374999986, 192.0796316800000056, 104.0269976617999959 ) ) ; +#11188 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178410593438E-05, 0.0002331579774918190453 ) ) ; +#11189 = VECTOR ( 'NONE', #36576, 1000.000000000000000 ) ; +#11190 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559574 ) ) ; +#11191 = ORIENTED_EDGE ( 'NONE', *, *, #8734, .F. ) ; +#11192 = CIRCLE ( 'NONE', #24256, 2.000000000000011546 ) ; +#11193 = VECTOR ( 'NONE', #5734, 1000.000000000000000 ) ; +#11194 = CARTESIAN_POINT ( 'NONE', ( -20.46513762259074909, 138.6415954987478187, 152.4706522797113450 ) ) ; +#11195 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; +#11196 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18270, #27717, #6209, #37097, #39744, #24026, #18665 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 4 ), + ( 0.000000000000000000, 0.004000000000000010492, 0.006447902106031735622 ), + .UNSPECIFIED. ) ; +#11197 = CARTESIAN_POINT ( 'NONE', ( -3.871698300499220480, 137.2778037606856856, 91.69128680615639837 ) ) ; +#11198 = CARTESIAN_POINT ( 'NONE', ( 37.19332676483216460, 178.1386719297145476, 136.6947527228966521 ) ) ; +#11199 = PLANE ( 'NONE', #3266 ) ; +#11200 = CARTESIAN_POINT ( 'NONE', ( 35.54796035643903451, 209.7096538831000032, 78.03703491705788053 ) ) ; +#11201 = CARTESIAN_POINT ( 'NONE', ( -38.66420181945734669, 119.1055528796190686, 87.73959189466469866 ) ) ; +#11202 = ORIENTED_EDGE ( 'NONE', *, *, #13940, .T. ) ; +#11203 = CARTESIAN_POINT ( 'NONE', ( -19.99970578248555597, 118.1172805411119811, 90.27986416034981687 ) ) ; +#11204 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 82.27946979429644614, 322.5967026918628449 ) ) ; +#11205 = VERTEX_POINT ( 'NONE', #15392 ) ; +#11206 = LINE ( 'NONE', #21019, #29119 ) ; +#11207 = ADVANCED_FACE ( 'NONE', ( #21741, #31142 ), #28084, .F. ) ; +#11208 = DIRECTION ( 'NONE', ( -0.0005734119072319609047, 0.000000000000000000, -0.9999998355993788834 ) ) ; +#11209 = CIRCLE ( 'NONE', #39274, 2.500000000021942448 ) ; +#11210 = ADVANCED_FACE ( 'NONE', ( #24211 ), #8669, .F. ) ; +#11211 = EDGE_LOOP ( 'NONE', ( #28862, #12978, #14849, #21914 ) ) ; +#11212 = AXIS2_PLACEMENT_3D ( 'NONE', #21041, #8154, #2033 ) ; +#11213 = CIRCLE ( 'NONE', #30810, 2.499999999804313866 ) ; +#11214 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#11215 = CARTESIAN_POINT ( 'NONE', ( 10.03420218876596692, 144.2154580076550019, 92.93854428129607470 ) ) ; +#11216 = ORIENTED_EDGE ( 'NONE', *, *, #1313, .T. ) ; +#11217 = CARTESIAN_POINT ( 'NONE', ( 36.20178035809213668, 192.0381767638097585, 106.3948639845850010 ) ) ; +#11218 = CARTESIAN_POINT ( 'NONE', ( 1.222756100067673435, 140.3958132876599620, 157.8527939211185753 ) ) ; +#11219 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673442394, 158.6807756965775127, 96.79226424649958460 ) ) ; +#11220 = CARTESIAN_POINT ( 'NONE', ( -40.80896188004905412, 127.4737362100950833, 89.10719945852390822 ) ) ; +#11221 = CARTESIAN_POINT ( 'NONE', ( 29.62326790002893162, 185.7454482597306651, 103.0308995128836216 ) ) ; +#11222 = VERTEX_POINT ( 'NONE', #13133 ) ; +#11223 = ORIENTED_EDGE ( 'NONE', *, *, #36237, .F. ) ; +#11224 = CARTESIAN_POINT ( 'NONE', ( 36.06517739910999865, 192.1776130000999956, 106.5431043960000039 ) ) ; +#11225 = CARTESIAN_POINT ( 'NONE', ( -20.33315071731424339, 120.3151545898319057, 87.78425597831352434 ) ) ; +#11226 = DIRECTION ( 'NONE', ( 0.7933531821996063771, 0.5932639600174075545, 0.1364866368485285197 ) ) ; +#11227 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -7.450515246535590627E-18, -0.0006039748319384396482 ) ) ; +#11228 = VERTEX_POINT ( 'NONE', #15776 ) ; +#11229 = CARTESIAN_POINT ( 'NONE', ( 20.00000279695219874, 118.8155797008581374, 87.25566994753728522 ) ) ; +#11230 = CARTESIAN_POINT ( 'NONE', ( -41.52752186953456004, 120.6413918639734533, 90.60917506750070061 ) ) ; +#11231 = CARTESIAN_POINT ( 'NONE', ( 14.78718619285897518, 182.9114187639047486, 104.4381813414848779 ) ) ; +#11232 = CARTESIAN_POINT ( 'NONE', ( -30.06946242413328108, 177.7873465568342510, 100.7165273984233949 ) ) ; +#11233 = EDGE_CURVE ( 'NONE', #6019, #32811, #10526, .T. ) ; +#11234 = CARTESIAN_POINT ( 'NONE', ( -23.21813688330802705, 214.0904152527463395, 73.07252725527422399 ) ) ; +#11235 = AXIS2_PLACEMENT_3D ( 'NONE', #8819, #27643, #21295 ) ; +#11236 = CARTESIAN_POINT ( 'NONE', ( -25.56982011077967343, 209.7142227182705199, 73.51402136040893254 ) ) ; +#11237 = AXIS2_PLACEMENT_3D ( 'NONE', #25075, #6838, #28537 ) ; +#11238 = AXIS2_PLACEMENT_3D ( 'NONE', #28549, #37943, #20738 ) ; +#11239 = LINE ( 'NONE', #23927, #14685 ) ; +#11240 = CARTESIAN_POINT ( 'NONE', ( 3.652795731156965875, 182.6431225764332567, 101.8172044301328611 ) ) ; +#11241 = VERTEX_POINT ( 'NONE', #38454 ) ; +#11242 = PLANE ( 'NONE', #22453 ) ; +#11243 = CARTESIAN_POINT ( 'NONE', ( -15.10537794304822512, 128.9348610681433911, 92.50791545010099526 ) ) ; +#11244 = DIRECTION ( 'NONE', ( -0.1305262051639064502, 0.9658997602660150950, 0.2236080563923502629 ) ) ; +#11245 = DIRECTION ( 'NONE', ( -0.0005884949961219008464, 0.2249510543439048049, -0.9743698870671267942 ) ) ; +#11247 = ORIENTED_EDGE ( 'NONE', *, *, #12921, .T. ) ; +#11246 = DIRECTION ( 'NONE', ( -0.0002393071182782277790, -0.2252352986010052460, 0.9743043687658488050 ) ) ; +#11248 = VERTEX_POINT ( 'NONE', #1045 ) ; +#11249 = VERTEX_POINT ( 'NONE', #25817 ) ; +#11250 = ORIENTED_EDGE ( 'NONE', *, *, #19324, .F. ) ; +#11251 = CARTESIAN_POINT ( 'NONE', ( -23.36089625005118364, 177.5048766144409171, 100.8897441404802748 ) ) ; +#11252 = CARTESIAN_POINT ( 'NONE', ( -22.49999922076898784, 174.5126133868687930, 99.95592377110770599 ) ) ; +#11253 = EDGE_CURVE ( 'NONE', #38430, #40304, #27543, .T. ) ; +#11254 = ORIENTED_EDGE ( 'NONE', *, *, #2901, .F. ) ; +#11255 = EDGE_CURVE ( 'NONE', #11332, #456, #10770, .T. ) ; +#11256 = VERTEX_POINT ( 'NONE', #13533 ) ; +#11257 = CARTESIAN_POINT ( 'NONE', ( -15.50165717152687073, 187.4006599591204747, 102.9271374898027460 ) ) ; +#11258 = CARTESIAN_POINT ( 'NONE', ( -39.00037151387275713, 161.9658780281123143, 193.3805663919430344 ) ) ; +#11259 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 166.8945455544008780, 183.3579980745095952 ) ) ; +#11260 = CARTESIAN_POINT ( 'NONE', ( -18.98875009441257333, 125.3860450160050277, 176.2394239049030773 ) ) ; +#11261 = VERTEX_POINT ( 'NONE', #39265 ) ; +#11262 = LINE ( 'NONE', #33329, #16033 ) ; +#11263 = VERTEX_POINT ( 'NONE', #2073 ) ; +#11264 = CARTESIAN_POINT ( 'NONE', ( -15.99974174651862313, 174.5231975350379514, 99.95452847233616467 ) ) ; +#11265 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927729918594, -0.0005734119022086387601 ) ) ; +#11266 = CONICAL_SURFACE ( 'NONE', #33462, 2.249999999906822978, 0.7853981633778703841 ) ; +#11267 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971522936 ) ) ; +#11268 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455649311516, -31.54510897440487938, 136.4474729010643159 ) ) ; +#11269 = VERTEX_POINT ( 'NONE', #29677 ) ; +#11270 = CARTESIAN_POINT ( 'NONE', ( -1.678434217228109926, 188.9071424656620195, 103.2652159385340127 ) ) ; +#11271 = CARTESIAN_POINT ( 'NONE', ( 0.9780674619574000195, 188.9146087942000349, 103.5382103106999949 ) ) ; +#11272 = FACE_OUTER_BOUND ( 'NONE', #17085, .T. ) ; +#11273 = CARTESIAN_POINT ( 'NONE', ( -26.69629712807436661, 110.6131156702000027, 90.28390873375987269 ) ) ; +#11274 = ORIENTED_EDGE ( 'NONE', *, *, #2449, .T. ) ; +#11275 = CARTESIAN_POINT ( 'NONE', ( -20.16704315820402726, 118.1226467942143046, 87.44728621956237191 ) ) ; +#11276 = ORIENTED_EDGE ( 'NONE', *, *, #9742, .F. ) ; +#11277 = ORIENTED_EDGE ( 'NONE', *, *, #21973, .T. ) ; +#11278 = EDGE_CURVE ( 'NONE', #7563, #8188, #7782, .T. ) ; +#11279 = ORIENTED_EDGE ( 'NONE', *, *, #807, .T. ) ; +#11280 = CARTESIAN_POINT ( 'NONE', ( -38.59197811685999824, 118.5863865315999988, 89.70884965135999778 ) ) ; +#11281 = ORIENTED_EDGE ( 'NONE', *, *, #39440, .F. ) ; +#11282 = LINE ( 'NONE', #23154, #10824 ) ; +#11283 = CARTESIAN_POINT ( 'NONE', ( -15.99999440082457447, 126.8010213445309660, 88.93691041956509480 ) ) ; +#11284 = ORIENTED_EDGE ( 'NONE', *, *, #26487, .F. ) ; +#11285 = DIRECTION ( 'NONE', ( 0.0006039748319377988848, 1.383702340315400350E-14, 0.9999998176071845934 ) ) ; +#11286 = AXIS2_PLACEMENT_3D ( 'NONE', #31829, #37951, #28948 ) ; +#11287 = VERTEX_POINT ( 'NONE', #27031 ) ; +#11288 = EDGE_CURVE ( 'NONE', #25855, #4296, #1053, .T. ) ; +#11289 = CARTESIAN_POINT ( 'NONE', ( 26.24119167140629827, 121.6923229128020125, 90.81265462304880032 ) ) ; +#11290 = LINE ( 'NONE', #1474, #4516 ) ; +#11291 = AXIS2_PLACEMENT_3D ( 'NONE', #20749, #33205, #8500 ) ; +#11293 = CARTESIAN_POINT ( 'NONE', ( -9.336298587753999456, 176.9278851743999894, 103.3279195673000004 ) ) ; +#11292 = FACE_OUTER_BOUND ( 'NONE', #5825, .T. ) ; +#11294 = ORIENTED_EDGE ( 'NONE', *, *, #14176, .T. ) ; +#11295 = EDGE_CURVE ( 'NONE', #29062, #11382, #32342, .T. ) ; +#11296 = AXIS2_PLACEMENT_3D ( 'NONE', #29612, #11404, #1593 ) ; +#11297 = EDGE_LOOP ( 'NONE', ( #26034, #15828, #14425, #4675 ) ) ; +#11298 = ADVANCED_FACE ( 'NONE', ( #4308 ), #29276, .F. ) ; +#11299 = EDGE_CURVE ( 'NONE', #11987, #34762, #32279, .T. ) ; +#11300 = ORIENTED_EDGE ( 'NONE', *, *, #17296, .T. ) ; +#11301 = EDGE_CURVE ( 'NONE', #39888, #25148, #5937, .T. ) ; +#11302 = CARTESIAN_POINT ( 'NONE', ( -0.02845919973435177830, 93.66652340833722690, 291.5585611238757906 ) ) ; +#11303 = EDGE_CURVE ( 'NONE', #38457, #22508, #15683, .T. ) ; +#11304 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20453, #14547, #39061, #11069 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11305 = DIRECTION ( 'NONE', ( 0.7933532411131101192, 0.5932638852154232811, 0.1364866195435442964 ) ) ; +#11306 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561517 ) ) ; +#11307 = ORIENTED_EDGE ( 'NONE', *, *, #39768, .T. ) ; +#11308 = ORIENTED_EDGE ( 'NONE', *, *, #7780, .T. ) ; +#11309 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825900558579956, 0.0005734119028333956253 ) ) ; +#11310 = CARTESIAN_POINT ( 'NONE', ( 25.99848225943999935, 121.1300010189000034, 87.60220639217000382 ) ) ; +#11311 = ORIENTED_EDGE ( 'NONE', *, *, #5807, .F. ) ; +#11312 = CARTESIAN_POINT ( 'NONE', ( 5.704476631508000217, 114.0103269029000188, 152.4718672074000381 ) ) ; +#11313 = CIRCLE ( 'NONE', #32219, 2.499999999838638409 ) ; +#11314 = VECTOR ( 'NONE', #38050, 1000.000000000000114 ) ; +#11315 = CARTESIAN_POINT ( 'NONE', ( 3.075434283316646145, 190.8748117897712291, 106.8097967079540496 ) ) ; +#11316 = EDGE_LOOP ( 'NONE', ( #2607, #33822, #39822, #6698 ) ) ; +#11317 = CARTESIAN_POINT ( 'NONE', ( -20.51952305719562020, 208.4669380606572986, 73.74576352674176860 ) ) ; +#11318 = CARTESIAN_POINT ( 'NONE', ( 44.87593640572824683, 182.0270868175781516, 126.4518070426717884 ) ) ; +#11319 = CARTESIAN_POINT ( 'NONE', ( 13.53014302533999924, 174.3879284816999871, 152.4718672074000381 ) ) ; +#11320 = CARTESIAN_POINT ( 'NONE', ( 32.54317059607360818, 141.6784348688667308, 281.4642677191529856 ) ) ; +#11321 = ORIENTED_EDGE ( 'NONE', *, *, #20187, .T. ) ; +#11322 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#11323 = CARTESIAN_POINT ( 'NONE', ( 30.05084667745524385, 127.2908262436609164, 89.53532598631991846 ) ) ; +#11324 = ORIENTED_EDGE ( 'NONE', *, *, #12362, .F. ) ; +#11325 = ADVANCED_FACE ( 'NONE', ( #21009 ), #19098, .T. ) ; +#11326 = PLANE ( 'NONE', #35819 ) ; +#11328 = CARTESIAN_POINT ( 'NONE', ( -45.70040756943009086, 187.3695729804526309, 106.0171126674183739 ) ) ; +#11327 = CARTESIAN_POINT ( 'NONE', ( 14.02952888319053848, 135.5741572108938726, 90.94420826922019785 ) ) ; +#11329 = ORIENTED_EDGE ( 'NONE', *, *, #22024, .F. ) ; +#11331 = VERTEX_POINT ( 'NONE', #20383 ) ; +#11330 = EDGE_CURVE ( 'NONE', #30360, #39055, #17101, .T. ) ; +#11332 = VERTEX_POINT ( 'NONE', #17714 ) ; +#11333 = CARTESIAN_POINT ( 'NONE', ( 6.035675884398634672, 174.7938253141263090, 102.5693725772094780 ) ) ; +#11334 = CARTESIAN_POINT ( 'NONE', ( -19.99984748064912665, 127.7403057018771904, 89.15611954941233819 ) ) ; +#11335 = CARTESIAN_POINT ( 'NONE', ( 30.05202364328564713, 126.8409241029907832, 91.48406572326082653 ) ) ; +#11337 = ORIENTED_EDGE ( 'NONE', *, *, #32170, .T. ) ; +#11336 = CIRCLE ( 'NONE', #5474, 2.499999999925774041 ) ; +#11338 = EDGE_LOOP ( 'NONE', ( #35172, #22057, #10923, #9224 ) ) ; +#11339 = CARTESIAN_POINT ( 'NONE', ( -14.55129769642598703, 176.2445762652153007, 103.4298910492225616 ) ) ; +#11340 = ORIENTED_EDGE ( 'NONE', *, *, #19761, .F. ) ; +#11341 = ORIENTED_EDGE ( 'NONE', *, *, #30906, .F. ) ; +#11342 = ORIENTED_EDGE ( 'NONE', *, *, #21841, .T. ) ; +#11343 = EDGE_CURVE ( 'NONE', #11781, #32839, #31516, .T. ) ; +#11344 = PLANE ( 'NONE', #35418 ) ; +#11345 = CARTESIAN_POINT ( 'NONE', ( 3.044143313360999858, 209.0096362941999928, 73.10508458982999969 ) ) ; +#11346 = ORIENTED_EDGE ( 'NONE', *, *, #17823, .T. ) ; +#11347 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #3635, #16120 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11348 = ORIENTED_EDGE ( 'NONE', *, *, #14397, .F. ) ; +#11349 = CARTESIAN_POINT ( 'NONE', ( 28.64561701362920942, 225.5077044868850180, 73.54120293868254521 ) ) ; +#11350 = CARTESIAN_POINT ( 'NONE', ( 30.05352354161590966, 104.1131156705860690, 87.24963271661329145 ) ) ; +#11351 = CARTESIAN_POINT ( 'NONE', ( -35.85345603705000173, 191.4686808538999969, 103.7494084754000028 ) ) ; +#11352 = FACE_OUTER_BOUND ( 'NONE', #2012, .T. ) ; +#11353 = VERTEX_POINT ( 'NONE', #5249 ) ; +#11354 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; +#11355 = CARTESIAN_POINT ( 'NONE', ( -35.94720140322999669, 113.8881156701999942, 88.78949577449999708 ) ) ; +#11356 = ORIENTED_EDGE ( 'NONE', *, *, #9608, .T. ) ; +#11357 = DIRECTION ( 'NONE', ( -0.0005884949961658158049, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#11358 = CARTESIAN_POINT ( 'NONE', ( -3.668404232153524180, 126.2395570190490162, 91.36559546079023164 ) ) ; +#11359 = DIRECTION ( 'NONE', ( -0.0005884949961241434102, 0.2249510543439057764, -0.9743698870671265722 ) ) ; +#11360 = ORIENTED_EDGE ( 'NONE', *, *, #4472, .T. ) ; +#11361 = CARTESIAN_POINT ( 'NONE', ( 0.7125860357380395804, 188.6156347743453523, 103.1978435822155546 ) ) ; +#11362 = DIRECTION ( 'NONE', ( -0.0001408404360371445828, 0.2249510911114003808, -0.9743700461178812500 ) ) ; +#11363 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; +#11364 = FACE_OUTER_BOUND ( 'NONE', #27178, .T. ) ; +#11365 = ORIENTED_EDGE ( 'NONE', *, *, #23172, .F. ) ; +#11366 = CARTESIAN_POINT ( 'NONE', ( -43.19244318869828447, 171.2650756620451773, 189.4798566108720479 ) ) ; +#11367 = CARTESIAN_POINT ( 'NONE', ( 2.562970451984335707, 190.9961858171923552, 104.2592840632188711 ) ) ; +#11368 = VECTOR ( 'NONE', #31909, 1000.000000000000114 ) ; +#11369 = AXIS2_PLACEMENT_3D ( 'NONE', #29620, #32871, #33275 ) ; +#11370 = CARTESIAN_POINT ( 'NONE', ( 40.79509051822999766, 219.0860688542000219, 73.28386491556000237 ) ) ; +#11371 = ORIENTED_EDGE ( 'NONE', *, *, #14397, .T. ) ; +#11372 = CARTESIAN_POINT ( 'NONE', ( 37.65039792813953312, 188.7571058070083154, 106.2871081217155904 ) ) ; +#11373 = ORIENTED_EDGE ( 'NONE', *, *, #26407, .T. ) ; +#11374 = VERTEX_POINT ( 'NONE', #39196 ) ; +#11375 = ORIENTED_EDGE ( 'NONE', *, *, #18793, .T. ) ; +#11376 = AXIS2_PLACEMENT_3D ( 'NONE', #6497, #15710, #15320 ) ; +#11377 = CARTESIAN_POINT ( 'NONE', ( 3.166377416628577190, 128.5876387387983186, 89.33781556475464924 ) ) ; +#11378 = LINE ( 'NONE', #20367, #21893 ) ; +#11379 = CARTESIAN_POINT ( 'NONE', ( -25.52046747694037521, 211.4175358512202649, 73.57353344520571170 ) ) ; +#11380 = CARTESIAN_POINT ( 'NONE', ( 17.08428676098631271, 152.4729553475051773, 182.2640658063840249 ) ) ; +#11381 = CARTESIAN_POINT ( 'NONE', ( -41.62559112316809262, 119.2042779649247137, 92.33005894222831955 ) ) ; +#11382 = VERTEX_POINT ( 'NONE', #2205 ) ; +#11383 = EDGE_CURVE ( 'NONE', #26640, #28773, #23670, .T. ) ; +#11384 = ADVANCED_FACE ( 'NONE', ( #39794 ), #17804, .T. ) ; +#11385 = EDGE_CURVE ( 'NONE', #5211, #7165, #541, .T. ) ; +#11386 = DIRECTION ( 'NONE', ( 0.0005884949961235587000, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#11387 = LINE ( 'NONE', #27369, #22482 ) ; +#11388 = CARTESIAN_POINT ( 'NONE', ( -20.33177681178267093, 119.7903260068696767, 90.05777432457695397 ) ) ; +#11389 = ADVANCED_FACE ( 'NONE', ( #31625 ), #13253, .T. ) ; +#11390 = DIRECTION ( 'NONE', ( 0.0005884949961193586092, -0.2249510543439039167, 0.9743698870671270162 ) ) ; +#11391 = DIRECTION ( 'NONE', ( -0.6087611427424954869, -0.7731004630501228103, -0.1781166615410720300 ) ) ; +#11392 = CARTESIAN_POINT ( 'NONE', ( -46.09662356910047265, 125.3295157413326422, 91.69427356735783974 ) ) ; +#11393 = DIRECTION ( 'NONE', ( 1.142687604679795709E-08, -0.9743700583596238696, -0.2249510821762432111 ) ) ; +#11394 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 1.850371707708593577E-15, 0.0006039748319387284797 ) ) ; +#11395 = ORIENTED_EDGE ( 'NONE', *, *, #695, .T. ) ; +#11396 = AXIS2_PLACEMENT_3D ( 'NONE', #21259, #11855, #39641 ) ; +#11398 = EDGE_CURVE ( 'NONE', #19682, #16029, #6690, .T. ) ; +#11397 = CARTESIAN_POINT ( 'NONE', ( 29.05533563819793486, 110.6131156702000027, 90.25023614447037801 ) ) ; +#11399 = CARTESIAN_POINT ( 'NONE', ( 3.736461764213575343, 144.1696738225713830, 93.14231161134939896 ) ) ; +#11400 = CARTESIAN_POINT ( 'NONE', ( -31.26880281748162105, 135.2089707299881525, 90.88725736883857564 ) ) ; +#11401 = CIRCLE ( 'NONE', #14690, 2.000000034091465650 ) ; +#11402 = ORIENTED_EDGE ( 'NONE', *, *, #5100, .F. ) ; +#11403 = LINE ( 'NONE', #8555, #2978 ) ; +#11404 = DIRECTION ( 'NONE', ( 0.0005884949961239134509, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#11405 = VERTEX_POINT ( 'NONE', #6452 ) ; +#11406 = EDGE_CURVE ( 'NONE', #29469, #34643, #8679, .T. ) ; +#11407 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#11408 = CARTESIAN_POINT ( 'NONE', ( -4.036264727110095762, 167.9338357148023704, 100.9917020970900410 ) ) ; +#11409 = VERTEX_POINT ( 'NONE', #15859 ) ; +#11410 = CARTESIAN_POINT ( 'NONE', ( 36.27518175044473026, 191.8909916473900807, 106.3924565537250686 ) ) ; +#11411 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#11412 = CARTESIAN_POINT ( 'NONE', ( -35.94660609010693264, 113.3342141080062220, 89.77519709294587358 ) ) ; +#11413 = CARTESIAN_POINT ( 'NONE', ( 3.064236136099508290, 190.8512031035150471, 106.7914583158460573 ) ) ; +#11414 = CARTESIAN_POINT ( 'NONE', ( 2.546554931846081615, 207.4083916547160982, 77.08013917124165459 ) ) ; +#11415 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31351, #462, #28878, #18849, #6587, #3724, #13892 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 4 ), + ( 0.0001323339547882564549, 0.0008556500706447302002, 0.002105438866673375268 ), + .UNSPECIFIED. ) ; +#11416 = LINE ( 'NONE', #39412, #14509 ) ; +#11417 = ORIENTED_EDGE ( 'NONE', *, *, #8815, .T. ) ; +#11418 = CARTESIAN_POINT ( 'NONE', ( 39.82218138461000478, 120.0420031177999931, 87.73456314343999907 ) ) ; +#11419 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684999240, 226.4002260771032695, 75.57961659100007523 ) ) ; +#11420 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391903498 ) ) ; +#11421 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20415, #14299, #26989, #11231 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11422 = ORIENTED_EDGE ( 'NONE', *, *, #6902, .T. ) ; +#11423 = CARTESIAN_POINT ( 'NONE', ( -59.73339157696374713, 30.14292508904275891, 149.3998115772221240 ) ) ; +#11424 = ORIENTED_EDGE ( 'NONE', *, *, #35132, .T. ) ; +#11425 = DIRECTION ( 'NONE', ( 0.0005884952295944861867, -0.2249510549294950756, 0.9743698869317913847 ) ) ; +#11426 = CARTESIAN_POINT ( 'NONE', ( -20.24985248663000093, 124.0104318696999997, 88.55179139119999832 ) ) ; +#11427 = VECTOR ( 'NONE', #19901, 1000.000000000000114 ) ; +#11428 = CARTESIAN_POINT ( 'NONE', ( 22.33189175409000171, 176.6322471953999980, 103.4971154297000027 ) ) ; +#11429 = DIRECTION ( 'NONE', ( 0.5605692862036780744, -0.2602880237709899736, -0.7861375325262695002 ) ) ; +#11430 = CARTESIAN_POINT ( 'NONE', ( -25.67969535978464179, 211.0902257898999892, 73.40427696411113345 ) ) ; +#11431 = CIRCLE ( 'NONE', #21250, 2.000000000000011546 ) ; +#11432 = CARTESIAN_POINT ( 'NONE', ( -25.94168657766944719, 211.8745996369106592, 73.07417221104321925 ) ) ; +#11433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #6550, #25193 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11434 = EDGE_CURVE ( 'NONE', #30774, #28807, #37127, .T. ) ; +#11435 = VECTOR ( 'NONE', #7406, 1000.000000000000114 ) ; +#11436 = ADVANCED_FACE ( 'NONE', ( #16261 ), #23214, .F. ) ; +#11437 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971579280 ) ) ; +#11438 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #7778, #39667, #33332, #4918 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.891461175462934463, 6.462631112830672819 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8046497850432340337, 0.8046497850432340337, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#11439 = CARTESIAN_POINT ( 'NONE', ( 18.99767128196905830, 125.6058446513852118, 175.3475295528536151 ) ) ; +#11440 = CARTESIAN_POINT ( 'NONE', ( -30.07171558222000129, 177.1876876990598930, 101.0912387270526125 ) ) ; +#11441 = CARTESIAN_POINT ( 'NONE', ( 39.10206850925001021, 118.7782697286999962, 89.52650283721999358 ) ) ; +#11442 = ORIENTED_EDGE ( 'NONE', *, *, #13168, .F. ) ; +#11443 = CARTESIAN_POINT ( 'NONE', ( 16.21976467472907757, 122.6436220881636814, 172.0961230653717564 ) ) ; +#11444 = CARTESIAN_POINT ( 'NONE', ( -21.70069621149593075, 129.3400573276139482, 92.26334425727345945 ) ) ; +#11445 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22390, #28519, #10114, #4557, #23578, #32780, #29321, #31988, #7420, #1492, #7221, #3951, #4147, #1707 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999985012, 0.3749999999999977796, 0.4999999999999970024, 0.6249999999999962252, 0.6875000000000301981, 0.7500000000000640599, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11446 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218859315, 3.782205735272607244E-12, 297.5295786860754674 ) ) ; +#11447 = CARTESIAN_POINT ( 'NONE', ( 26.01073959733328067, 191.4239670711786516, 106.8751801458234496 ) ) ; +#11448 = CYLINDRICAL_SURFACE ( 'NONE', #29148, 2.250000000000011102 ) ; +#11449 = VERTEX_POINT ( 'NONE', #36066 ) ; +#11450 = ORIENTED_EDGE ( 'NONE', *, *, #28332, .F. ) ; +#11451 = CARTESIAN_POINT ( 'NONE', ( -39.74908053984227507, 182.4717680925825789, 106.9353792437991473 ) ) ; +#11452 = VERTEX_POINT ( 'NONE', #29755 ) ; +#11453 = DIRECTION ( 'NONE', ( -0.9999998142111129473, -1.291838595167527226E-06, 0.0006095703986303101099 ) ) ; +#11454 = CARTESIAN_POINT ( 'NONE', ( -43.94721011010098266, 112.7011882844193309, 88.77749572683383406 ) ) ; +#11455 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26998, #32505, #23713, #4480 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 1.418495674889627305E-09, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11456 = DIRECTION ( 'NONE', ( 0.0005884949961232422214, -0.2249510543439050547, 0.9743698870671266832 ) ) ; +#11457 = VERTEX_POINT ( 'NONE', #7452 ) ; +#11458 = VECTOR ( 'NONE', #13347, 1000.000000000000114 ) ; +#11459 = CARTESIAN_POINT ( 'NONE', ( 40.71170686885982093, 217.7719115883058123, 73.20058192865329261 ) ) ; +#11460 = ADVANCED_FACE ( 'NONE', ( #19916 ), #20122, .F. ) ; +#11461 = CARTESIAN_POINT ( 'NONE', ( -13.49672688080367955, 187.4156453043676436, 105.6637477070206330 ) ) ; +#11462 = AXIS2_PLACEMENT_3D ( 'NONE', #5349, #27054, #39691 ) ; +#11463 = VECTOR ( 'NONE', #18955, 1000.000000000000114 ) ; +#11464 = CARTESIAN_POINT ( 'NONE', ( -36.09575936301000354, 112.8288696677000047, 87.93843057770999394 ) ) ; +#11465 = ORIENTED_EDGE ( 'NONE', *, *, #30320, .F. ) ; +#11466 = CONICAL_SURFACE ( 'NONE', #34300, 59.40509898898601904, 0.7853981633972927368 ) ; +#11467 = CARTESIAN_POINT ( 'NONE', ( -37.15110912804633614, 71.94901892143192867, 323.0119659673088677 ) ) ; +#11468 = ORIENTED_EDGE ( 'NONE', *, *, #27256, .F. ) ; +#11469 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; +#11470 = CARTESIAN_POINT ( 'NONE', ( 4.035676230724123847, 143.6517845921996184, 95.38087260549148994 ) ) ; +#11471 = VECTOR ( 'NONE', #24766, 1000.000000000000227 ) ; +#11472 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 1.018502060646766849E-15, 0.0006039748319386956284 ) ) ; +#11473 = CARTESIAN_POINT ( 'NONE', ( -14.55294119842380063, 130.1498083917327904, 89.70916153464222020 ) ) ; +#11474 = VERTEX_POINT ( 'NONE', #4589 ) ; +#11475 = CARTESIAN_POINT ( 'NONE', ( -18.59008601221150414, 148.0291187291159076, 184.1143154653856868 ) ) ; +#11476 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; +#11477 = CARTESIAN_POINT ( 'NONE', ( -35.48525329021664731, 192.2684899157669349, 106.9345235387465749 ) ) ; +#11478 = ORIENTED_EDGE ( 'NONE', *, *, #12774, .F. ) ; +#11479 = DIRECTION ( 'NONE', ( -0.0005884949961224831714, 0.2249510543439058596, -0.9743698870671263501 ) ) ; +#11480 = VERTEX_POINT ( 'NONE', #17051 ) ; +#11481 = ORIENTED_EDGE ( 'NONE', *, *, #36419, .F. ) ; +#11482 = CIRCLE ( 'NONE', #38904, 48.00000000000465405 ) ; +#11483 = ORIENTED_EDGE ( 'NONE', *, *, #3890, .F. ) ; +#11484 = ADVANCED_FACE ( 'NONE', ( #14010 ), #26693, .T. ) ; +#11485 = CARTESIAN_POINT ( 'NONE', ( -26.12106630525807915, 190.7095951053924239, 103.6974793579260705 ) ) ; +#11487 = EDGE_CURVE ( 'NONE', #6270, #21098, #1946, .T. ) ; +#11486 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23862, #39582, #18905, #18099 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11488 = AXIS2_PLACEMENT_3D ( 'NONE', #10040, #22920, #16758 ) ; +#11489 = CARTESIAN_POINT ( 'NONE', ( 20.99160458755498482, 212.6262139143010188, 73.54599130854555256 ) ) ; +#11490 = CARTESIAN_POINT ( 'NONE', ( 39.36767498017007227, 179.7113605310591140, 119.0972000649790061 ) ) ; +#11491 = CARTESIAN_POINT ( 'NONE', ( -37.51239921474475381, 190.9875310483616033, 106.3313789827213469 ) ) ; +#11492 = EDGE_LOOP ( 'NONE', ( #26455, #8635, #37734, #39959 ) ) ; +#11493 = CARTESIAN_POINT ( 'NONE', ( -21.27838756171884427, 135.9818880619076822, 91.05966546721936083 ) ) ; +#11494 = CARTESIAN_POINT ( 'NONE', ( -20.49921872406353529, 118.1134456025284152, 89.78002774633898753 ) ) ; +#11495 = ORIENTED_EDGE ( 'NONE', *, *, #14675, .T. ) ; +#11496 = CIRCLE ( 'NONE', #28488, 54.50273826250054299 ) ; +#11497 = CARTESIAN_POINT ( 'NONE', ( 28.22659100348150218, 124.4203685683400096, 91.44127834639000696 ) ) ; +#11498 = CARTESIAN_POINT ( 'NONE', ( -26.00939886961985792, 210.1698433795000085, 76.07526738668336463 ) ) ; +#11499 = VECTOR ( 'NONE', #15586, 1000.000000000000227 ) ; +#11501 = CYLINDRICAL_SURFACE ( 'NONE', #26647, 2.000000000000014655 ) ; +#11500 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#11502 = ORIENTED_EDGE ( 'NONE', *, *, #16626, .T. ) ; +#11503 = EDGE_LOOP ( 'NONE', ( #23326, #23724, #7518 ) ) ; +#11504 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #5709, #21467 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11505 = VERTEX_POINT ( 'NONE', #5609 ) ; +#11506 = CARTESIAN_POINT ( 'NONE', ( -35.87604402749855126, 115.6689223804922477, 87.28945252364509599 ) ) ; +#11507 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566790 ) ) ; +#11508 = DIRECTION ( 'NONE', ( 0.1203539036806679369, -1.261872400103888735E-14, -0.9927310501182202707 ) ) ; +#11509 = CARTESIAN_POINT ( 'NONE', ( 36.32277147154000829, 191.7121955142999923, 104.1910060713999968 ) ) ; +#11510 = ORIENTED_EDGE ( 'NONE', *, *, #12587, .F. ) ; +#11511 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #31365, #11753 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11512 = ORIENTED_EDGE ( 'NONE', *, *, #39303, .F. ) ; +#11513 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #11451, #10702, #21271, #8183 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( -4.440892098500626162E-15, 0.1808055686694189090 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9972776337013501413, 0.9972776337013501413, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#11514 = DIRECTION ( 'NONE', ( 0.0005884949961229525225, -0.2249510543439062205, 0.9743698870671264611 ) ) ; +#11515 = LINE ( 'NONE', #26662, #4399 ) ; +#11516 = CIRCLE ( 'NONE', #16720, 2.499999999970894393 ) ; +#11517 = CARTESIAN_POINT ( 'NONE', ( -25.50006284340070906, 118.1130153187805689, 89.78316558933853742 ) ) ; +#11518 = CONICAL_SURFACE ( 'NONE', #21311, 3.003184325552035627, 0.7853589132226472813 ) ; +#11519 = CARTESIAN_POINT ( 'NONE', ( 15.91451890771963384, 186.5505280237283614, 102.7118944487342702 ) ) ; +#11520 = ORIENTED_EDGE ( 'NONE', *, *, #26027, .T. ) ; +#11521 = VERTEX_POINT ( 'NONE', #39951 ) ; +#11522 = CARTESIAN_POINT ( 'NONE', ( -36.31234050319358886, 190.8460812281299752, 106.8195530359479903 ) ) ; +#11523 = VECTOR ( 'NONE', #19848, 1000.000000000000000 ) ; +#11524 = ADVANCED_FACE ( 'NONE', ( #30356 ), #195, .F. ) ; +#11525 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14274, #14069, #8132, #38400, #22877, #7309, #16901, #19974, #35305, #4650 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999688582, 0.3749999999999033551, 0.4374999999998851474, 0.4999999999998669953, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11526 = CIRCLE ( 'NONE', #9544, 4.999999999999990230 ) ; +#11527 = CARTESIAN_POINT ( 'NONE', ( 3.080879273494560255, 190.8603769821775131, 106.8113866482030403 ) ) ; +#11528 = ORIENTED_EDGE ( 'NONE', *, *, #39016, .F. ) ; +#11529 = CARTESIAN_POINT ( 'NONE', ( 44.05441677404904510, 112.7011882844093122, 88.72434494936726423 ) ) ; +#11530 = EDGE_CURVE ( 'NONE', #36212, #27113, #11196, .T. ) ; +#11531 = DIRECTION ( 'NONE', ( -0.0005884949961250770167, 0.2249510543439080523, -0.9743698870671260170 ) ) ; +#11532 = CARTESIAN_POINT ( 'NONE', ( -35.93819496018398496, 196.1181868593052400, 103.7014435179598024 ) ) ; +#11533 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#11534 = ORIENTED_EDGE ( 'NONE', *, *, #39303, .T. ) ; +#11535 = EDGE_CURVE ( 'NONE', #1525, #12760, #24363, .T. ) ; +#11536 = EDGE_CURVE ( 'NONE', #25074, #1952, #9092, .T. ) ; +#11537 = DIRECTION ( 'NONE', ( 0.7075337282838612962, -1.167224528853440884E-08, 0.7066795761451855062 ) ) ; +#11538 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; +#11539 = EDGE_CURVE ( 'NONE', #20406, #31599, #19508, .T. ) ; +#11540 = ORIENTED_EDGE ( 'NONE', *, *, #25031, .F. ) ; +#11541 = CONICAL_SURFACE ( 'NONE', #18031, 2.503203150234936114, 0.7853981633958105890 ) ; +#11542 = CARTESIAN_POINT ( 'NONE', ( 31.99328622544151557, 77.52049695843601285, 291.3934239983018415 ) ) ; +#11543 = CIRCLE ( 'NONE', #12865, 2.499999999978613996 ) ; +#11544 = VECTOR ( 'NONE', #24986, 1000.000000000000000 ) ; +#11546 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927781994451, 0.0005734119022073636300 ) ) ; +#11545 = DIRECTION ( 'NONE', ( 0.7856637144487861324, -0.6186538028643616682, 0.000000000000000000 ) ) ; +#11547 = ORIENTED_EDGE ( 'NONE', *, *, #17207, .F. ) ; +#11548 = VERTEX_POINT ( 'NONE', #34412 ) ; +#11549 = DIRECTION ( 'NONE', ( 5.065392549852286813E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#11550 = CARTESIAN_POINT ( 'NONE', ( 38.73395728598254095, 118.6163391431395269, 89.66332909972722121 ) ) ; +#11551 = EDGE_LOOP ( 'NONE', ( #21286, #33112, #2500, #34214, #6792, #17477, #22705, #17608 ) ) ; +#11552 = CARTESIAN_POINT ( 'NONE', ( 2.594002776560000001, 209.5556663168000000, 75.67900503539999590 ) ) ; +#11553 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 77.27946979429634666, 315.0857197240631535 ) ) ; +#11554 = CARTESIAN_POINT ( 'NONE', ( 12.64143545761593401, 177.6650210183138370, 100.7720088105692611 ) ) ; +#11555 = ORIENTED_EDGE ( 'NONE', *, *, #1356, .T. ) ; +#11556 = VERTEX_POINT ( 'NONE', #22773 ) ; +#11557 = CARTESIAN_POINT ( 'NONE', ( -42.80963178801611235, 120.9007511611746395, 91.83847750760833151 ) ) ; +#11558 = ORIENTED_EDGE ( 'NONE', *, *, #3629, .F. ) ; +#11559 = ORIENTED_EDGE ( 'NONE', *, *, #19900, .F. ) ; +#11560 = DIRECTION ( 'NONE', ( 0.0004161288024567914292, -0.8480480897914314253, 0.5299191110329237731 ) ) ; +#11561 = CARTESIAN_POINT ( 'NONE', ( -33.45586840016203922, 218.5902260770999987, 73.07871058857431024 ) ) ; +#11562 = EDGE_CURVE ( 'NONE', #5503, #40259, #16015, .T. ) ; +#11563 = DIRECTION ( 'NONE', ( -0.0005884949961259294164, 0.2255194585872565272, -0.9742384859325513569 ) ) ; +#11564 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.271205595054999941E-14, -1.000000000000000000 ) ) ; +#11565 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250096516, 130.6631156595383914, 90.34290178553547435 ) ) ; +#11566 = ORIENTED_EDGE ( 'NONE', *, *, #16259, .T. ) ; +#11567 = ORIENTED_EDGE ( 'NONE', *, *, #15057, .T. ) ; +#11568 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#11569 = LINE ( 'NONE', #24260, #3479 ) ; +#11570 = CARTESIAN_POINT ( 'NONE', ( -35.42347339415000107, 191.8427034982000237, 103.8024170491000007 ) ) ; +#11571 = CARTESIAN_POINT ( 'NONE', ( 36.59227142547000255, 191.6001556585999879, 104.2198836891000013 ) ) ; +#11572 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23593, #36045, #37076, #37273 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11573 = ORIENTED_EDGE ( 'NONE', *, *, #21659, .T. ) ; +#11574 = CARTESIAN_POINT ( 'NONE', ( -25.66789927443999986, 120.7343807225000063, 87.88418875662000573 ) ) ; +#11575 = VERTEX_POINT ( 'NONE', #28115 ) ; +#11576 = ORIENTED_EDGE ( 'NONE', *, *, #21131, .T. ) ; +#11577 = CARTESIAN_POINT ( 'NONE', ( -21.44517133422852240, 176.2436636369649534, 103.4338440792942890 ) ) ; +#11578 = CARTESIAN_POINT ( 'NONE', ( -40.30153468720526178, 187.7974083947837585, 108.1652340796715492 ) ) ; +#11579 = ORIENTED_EDGE ( 'NONE', *, *, #28570, .T. ) ; +#11580 = CARTESIAN_POINT ( 'NONE', ( -22.49852798326304537, 127.1804730653442732, 91.59419604361356448 ) ) ; +#11581 = CARTESIAN_POINT ( 'NONE', ( -20.33320694052968847, 160.6589237444172511, 97.09841172752761906 ) ) ; +#11582 = LINE ( 'NONE', #11989, #38573 ) ; +#11583 = EDGE_LOOP ( 'NONE', ( #24434, #39500, #3486, #39572 ) ) ; +#11584 = CARTESIAN_POINT ( 'NONE', ( -19.33628163003497136, 125.2773345192583463, 177.1639040494593473 ) ) ; +#11585 = EDGE_CURVE ( 'NONE', #39651, #12644, #17127, .T. ) ; +#11586 = CARTESIAN_POINT ( 'NONE', ( 1.746097794442228235, 189.3876538975366088, 103.7956058557226413 ) ) ; +#11587 = CARTESIAN_POINT ( 'NONE', ( 45.26991834669612302, 123.8840750961899744, 93.35648333539963062 ) ) ; +#11588 = ADVANCED_FACE ( 'NONE', ( #6407 ), #37903, .F. ) ; +#11589 = ORIENTED_EDGE ( 'NONE', *, *, #30096, .T. ) ; +#11590 = CARTESIAN_POINT ( 'NONE', ( -13.49823529424839386, 151.2934838775255173, 97.66884040908654185 ) ) ; +#11591 = ORIENTED_EDGE ( 'NONE', *, *, #19629, .T. ) ; +#11592 = DIRECTION ( 'NONE', ( 0.6087614115774880874, -0.7730004600455407937, -0.1785492440296700956 ) ) ; +#11593 = EDGE_CURVE ( 'NONE', #26460, #26211, #25547, .T. ) ; +#11594 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#11595 = CARTESIAN_POINT ( 'NONE', ( 37.90425712323814622, 118.7059984729880284, 87.38624778410084559 ) ) ; +#11596 = ADVANCED_FACE ( 'NONE', ( #16215 ), #26856, .F. ) ; +#11597 = EDGE_CURVE ( 'NONE', #15150, #21705, #39295, .T. ) ; +#11598 = CARTESIAN_POINT ( 'NONE', ( 16.04431205530701732, 152.7224556247752503, 181.6155002255999875 ) ) ; +#11599 = CARTESIAN_POINT ( 'NONE', ( 6.028492984770688068, 134.9588829526484801, 90.86045477491234124 ) ) ; +#11600 = ORIENTED_EDGE ( 'NONE', *, *, #15059, .F. ) ; +#11601 = CARTESIAN_POINT ( 'NONE', ( 23.69156854525416733, 130.3499206859899857, 92.81120348820789445 ) ) ; +#11602 = CARTESIAN_POINT ( 'NONE', ( 15.99999299640773209, 127.4309269374402618, 89.06300497221934620 ) ) ; +#11603 = DIRECTION ( 'NONE', ( -0.9914445057216533241, 0.1269824404756555725, 0.03022005766363166854 ) ) ; +#11604 = CARTESIAN_POINT ( 'NONE', ( -16.04788717431955902, 121.9883658730552156, 174.5026492558828295 ) ) ; +#11605 = CONICAL_SURFACE ( 'NONE', #3732, 6.503080769914698855, 0.7853981634031134140 ) ; +#11606 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 132.9726895863779532, 90.34121396988804520 ) ) ; +#11607 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11858, #36997, #37198, #37588, #5716, #40243, #34494, #24747, #39844, #34308 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000363598, 0.3750000000000597855, 0.4375000000000662803, 0.5000000000000728306, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11608 = CARTESIAN_POINT ( 'NONE', ( 32.26714755882673558, 176.5669744895979250, 100.3971325049669474 ) ) ; +#11609 = CARTESIAN_POINT ( 'NONE', ( 6.065815740701999914, 165.2216646563843199, 152.9217693939943388 ) ) ; +#11610 = CARTESIAN_POINT ( 'NONE', ( 20.36364106976845889, 116.6764208835006258, 90.25548571027178468 ) ) ; +#11611 = AXIS2_PLACEMENT_3D ( 'NONE', #20481, #35804, #27479 ) ; +#11612 = ORIENTED_EDGE ( 'NONE', *, *, #15579, .T. ) ; +#11613 = CARTESIAN_POINT ( 'NONE', ( 3.666638755409086681, 184.0129645450027738, 102.6466012127862371 ) ) ; +#11614 = DIRECTION ( 'NONE', ( -4.655231785096015457E-10, 0.9743700556873108320, 0.2249510937513014008 ) ) ; +#11615 = CARTESIAN_POINT ( 'NONE', ( -32.55028072398723538, 136.9683251281930723, 91.29421039092950707 ) ) ; +#11616 = ORIENTED_EDGE ( 'NONE', *, *, #40087, .F. ) ; +#11617 = CARTESIAN_POINT ( 'NONE', ( 5.665497765363915583, 182.0055596162654012, 102.1015474221518105 ) ) ; +#11618 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1157, #26320, #35469, #19748 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11619 = CARTESIAN_POINT ( 'NONE', ( 36.44436247437651133, 190.8511614233640330, 106.7712946021073606 ) ) ; +#11620 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15474, #132, #25098, #28748, #27969, #6259, #31626, #37543, #9545, #22023, #34455, #15860, #6453, #18922, #25295, #28355, #37737, #9749, #29355, #29756 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000079103, 0.1875000000000118794, 0.2187500000000148492, 0.2343750000000163203, 0.2500000000000178191, 0.5000000000000767164, 0.6250000000001121325, 0.6875000000001232348, 0.7187500000001195710, 0.7343750000001172396, 0.7500000000001149081, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11621 = ORIENTED_EDGE ( 'NONE', *, *, #33490, .T. ) ; +#11622 = CARTESIAN_POINT ( 'NONE', ( -17.26178222639411430, 121.7713432978476220, 175.3684242141576703 ) ) ; +#11623 = DIRECTION ( 'NONE', ( 0.6087614810001747978, -0.7729390313185978689, -0.1788147452385885350 ) ) ; +#11624 = CARTESIAN_POINT ( 'NONE', ( -21.86693707914052354, 143.9814420783045819, 28.36825712350903572 ) ) ; +#11625 = ORIENTED_EDGE ( 'NONE', *, *, #35641, .T. ) ; +#11626 = CARTESIAN_POINT ( 'NONE', ( 35.56500850657381108, 192.5994943120849427, 106.8645618244048165 ) ) ; +#11627 = EDGE_CURVE ( 'NONE', #15600, #22159, #22937, .T. ) ; +#11628 = ADVANCED_FACE ( 'NONE', ( #22972 ), #35400, .F. ) ; +#11629 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921579630, 0.2249510932971582611 ) ) ; +#11630 = ADVANCED_FACE ( 'NONE', ( #38896 ), #32371, .T. ) ; +#11631 = CARTESIAN_POINT ( 'NONE', ( -38.54565956053704667, 119.1564759897554211, 90.30561907418552892 ) ) ; +#11632 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#11633 = DIRECTION ( 'NONE', ( 0.0005884949961202267299, -0.2249510543439067478, 0.9743698870671262391 ) ) ; +#11634 = ORIENTED_EDGE ( 'NONE', *, *, #18862, .F. ) ; +#11635 = ORIENTED_EDGE ( 'NONE', *, *, #6623, .F. ) ; +#11636 = EDGE_CURVE ( 'NONE', #36542, #38645, #4083, .T. ) ; +#11637 = DIRECTION ( 'NONE', ( 0.6087613502019254552, -0.7729389820454567461, -0.1788154035167601463 ) ) ; +#11638 = DIRECTION ( 'NONE', ( -0.5988682214889347044, 0.8008475843072014877, 0.000000000000000000 ) ) ; +#11639 = VECTOR ( 'NONE', #27184, 1000.000000000000227 ) ; +#11640 = DIRECTION ( 'NONE', ( 0.0005884949961178157895, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#11641 = ORIENTED_EDGE ( 'NONE', *, *, #25972, .T. ) ; +#11642 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#11643 = CARTESIAN_POINT ( 'NONE', ( -41.28588602987048262, 120.5676951715817040, 90.59201490058906359 ) ) ; +#11644 = CIRCLE ( 'NONE', #9682, 6.000000000000007994 ) ; +#11645 = CARTESIAN_POINT ( 'NONE', ( 20.50147081773584290, 151.4111479308915023, 97.16231817868397513 ) ) ; +#11646 = CARTESIAN_POINT ( 'NONE', ( -28.52057520163999982, 124.7657109742000046, 91.42876534255999843 ) ) ; +#11647 = EDGE_CURVE ( 'NONE', #31352, #37651, #13884, .T. ) ; +#11648 = PLANE ( 'NONE', #39750 ) ; +#11649 = LINE ( 'NONE', #8990, #28083 ) ; +#11650 = DIRECTION ( 'NONE', ( -0.0005884949961246306507, 0.2249510543439059429, -0.9743698870671264611 ) ) ; +#11651 = EDGE_CURVE ( 'NONE', #13604, #5116, #35416, .T. ) ; +#11652 = COORDINATED_UNIVERSAL_TIME_OFFSET ( 8, 0, .AHEAD. ) ; +#11653 = CARTESIAN_POINT ( 'NONE', ( 26.11275506546840575, 121.8657365086856998, 87.77207143543530776 ) ) ; +#11654 = DIRECTION ( 'NONE', ( -0.0005884949961241158715, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#11655 = CARTESIAN_POINT ( 'NONE', ( -20.49960732757744353, 118.8154816606033393, 87.78015075453545535 ) ) ; +#11656 = CARTESIAN_POINT ( 'NONE', ( -36.63401976618238365, 138.1498686812657866, 288.6643242991708007 ) ) ; +#11657 = CARTESIAN_POINT ( 'NONE', ( -23.00127433124000476, 115.6131156702010401, 87.78148031792994743 ) ) ; +#11658 = ORIENTED_EDGE ( 'NONE', *, *, #37164, .F. ) ; +#11659 = CARTESIAN_POINT ( 'NONE', ( 13.46612284730906950, 158.3062971533392158, 96.19268454968825210 ) ) ; +#11660 = ORIENTED_EDGE ( 'NONE', *, *, #38114, .F. ) ; +#11661 = ORIENTED_EDGE ( 'NONE', *, *, #29619, .F. ) ; +#11662 = LINE ( 'NONE', #8604, #11435 ) ; +#11663 = VERTEX_POINT ( 'NONE', #8448 ) ; +#11664 = CARTESIAN_POINT ( 'NONE', ( 47.95567328239271632, 139.9374889060051146, 291.1737358715798791 ) ) ; +#11665 = VECTOR ( 'NONE', #37970, 999.9999999999998863 ) ; +#11666 = CARTESIAN_POINT ( 'NONE', ( 3.166350703034567449, 184.1264558197564156, 102.1599558388959537 ) ) ; +#11667 = AXIS2_PLACEMENT_3D ( 'NONE', #21774, #34800, #27924 ) ; +#11668 = VERTEX_POINT ( 'NONE', #5562 ) ; +#11669 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#11670 = PLANE ( 'NONE', #16877 ) ; +#11671 = FACE_OUTER_BOUND ( 'NONE', #24350, .T. ) ; +#11672 = ORIENTED_EDGE ( 'NONE', *, *, #15362, .T. ) ; +#11673 = CARTESIAN_POINT ( 'NONE', ( 17.25788849119799195, 152.5371962406647413, 182.4889206688251306 ) ) ; +#11674 = EDGE_CURVE ( 'NONE', #22341, #9096, #25785, .T. ) ; +#11675 = EDGE_CURVE ( 'NONE', #30982, #18267, #35060, .T. ) ; +#11676 = CARTESIAN_POINT ( 'NONE', ( 3.166590646707283963, 186.2330553830380211, 102.6462995303112251 ) ) ; +#11677 = EDGE_CURVE ( 'NONE', #39055, #4945, #27879, .T. ) ; +#11678 = DIRECTION ( 'NONE', ( -0.0006039748319386906410, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#11679 = CARTESIAN_POINT ( 'NONE', ( -12.64043733723593022, 181.1121611747635143, 104.4670379097046862 ) ) ; +#11680 = ORIENTED_EDGE ( 'NONE', *, *, #3082, .F. ) ; +#11681 = EDGE_LOOP ( 'NONE', ( #11865, #28280 ) ) ; +#11682 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#11683 = CARTESIAN_POINT ( 'NONE', ( 0.5972205428943000438, 188.8838611128000196, 103.5283297331999961 ) ) ; +#11684 = EDGE_CURVE ( 'NONE', #30982, #1942, #11944, .T. ) ; +#11685 = ORIENTED_EDGE ( 'NONE', *, *, #21557, .T. ) ; +#11686 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -4.437389905419016117E-16, 0.0006039748319385540316 ) ) ; +#11687 = ORIENTED_EDGE ( 'NONE', *, *, #3846, .F. ) ; +#11688 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #26782, #26182, #10839, #13687 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.536617029295737069, 5.967414621972016775 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8365544822326859142, 0.8365544822326859142, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#11689 = ADVANCED_FACE ( 'NONE', ( #6963 ), #28259, .F. ) ; +#11690 = CIRCLE ( 'NONE', #21483, 2.999999999999997335 ) ; +#11691 = AXIS2_PLACEMENT_3D ( 'NONE', #30901, #9423, #18195 ) ; +#11692 = ORIENTED_EDGE ( 'NONE', *, *, #13376, .T. ) ; +#11693 = CARTESIAN_POINT ( 'NONE', ( -25.75626117398395465, 122.6043567611443024, 88.48707144345416964 ) ) ; +#11694 = VECTOR ( 'NONE', #14611, 1000.000000000000000 ) ; +#11695 = ORIENTED_EDGE ( 'NONE', *, *, #9718, .F. ) ; +#11696 = EDGE_CURVE ( 'NONE', #15849, #21074, #4740, .T. ) ; +#11697 = CARTESIAN_POINT ( 'NONE', ( -36.06278304189000039, 192.0164624370000297, 105.0249046332999967 ) ) ; +#11698 = CIRCLE ( 'NONE', #40394, 6.500000000017553070 ) ; +#11699 = DIRECTION ( 'NONE', ( -0.1305262453914154686, 0.9659761156053645603, 0.2232779508683992165 ) ) ; +#11700 = CARTESIAN_POINT ( 'NONE', ( -25.51388077191477066, 211.0902258580313742, 75.57405363378009611 ) ) ; +#11701 = EDGE_CURVE ( 'NONE', #14988, #32614, #31128, .T. ) ; +#11702 = ORIENTED_EDGE ( 'NONE', *, *, #32662, .F. ) ; +#11703 = CARTESIAN_POINT ( 'NONE', ( 44.86515336672585619, 186.3325894068457558, 107.7750559962144905 ) ) ; +#11704 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31086, #22084, #34510, #6514 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11705 = CARTESIAN_POINT ( 'NONE', ( -25.02112439774744246, 181.4181497952224333, 104.6306287658777450 ) ) ; +#11706 = ORIENTED_EDGE ( 'NONE', *, *, #27809, .T. ) ; +#11707 = CARTESIAN_POINT ( 'NONE', ( 26.12522142770999878, 121.2586743417000008, 90.71091124750999768 ) ) ; +#11708 = CARTESIAN_POINT ( 'NONE', ( -35.81215698510654022, 191.6412655454669505, 103.9150230815284459 ) ) ; +#11710 = DIRECTION ( 'NONE', ( -5.204170427930391307E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#11709 = CARTESIAN_POINT ( 'NONE', ( -0.4015627557743999820, 209.0000000000000000, 162.9824824849000322 ) ) ; +#11711 = ORIENTED_EDGE ( 'NONE', *, *, #24206, .F. ) ; +#11712 = ORIENTED_EDGE ( 'NONE', *, *, #36578, .T. ) ; +#11713 = ORIENTED_EDGE ( 'NONE', *, *, #36786, .T. ) ; +#11714 = CARTESIAN_POINT ( 'NONE', ( -30.31843644206924537, 127.1600984872847704, 89.19950512931269770 ) ) ; +#11715 = FACE_OUTER_BOUND ( 'NONE', #13472, .T. ) ; +#11716 = CYLINDRICAL_SURFACE ( 'NONE', #33293, 2.000000000000000000 ) ; +#11717 = ORIENTED_EDGE ( 'NONE', *, *, #38445, .F. ) ; +#11718 = VECTOR ( 'NONE', #32004, 1000.000000000000114 ) ; +#11719 = EDGE_LOOP ( 'NONE', ( #26627, #36132, #39448, #14769, #5538, #18510, #1775, #11959, #8348, #36247, #19931, #25216 ) ) ; +#11721 = EDGE_CURVE ( 'NONE', #37113, #12309, #28287, .T. ) ; +#11720 = CARTESIAN_POINT ( 'NONE', ( -0.4373757873778362781, 189.0000005053102257, 103.6849946747920228 ) ) ; +#11722 = PLANE ( 'NONE', #13552 ) ; +#11723 = EDGE_CURVE ( 'NONE', #8, #31162, #10763, .T. ) ; +#11724 = CIRCLE ( 'NONE', #38468, 2.500000000185293114 ) ; +#11725 = DIRECTION ( 'NONE', ( 0.7856007465113978849, 0.6187337610642675845, 0.000000000000000000 ) ) ; +#11726 = CARTESIAN_POINT ( 'NONE', ( 26.34169637600000158, 122.6976311872000025, 87.96391511826999476 ) ) ; +#11727 = ORIENTED_EDGE ( 'NONE', *, *, #23172, .T. ) ; +#11728 = ORIENTED_EDGE ( 'NONE', *, *, #27201, .T. ) ; +#11729 = CARTESIAN_POINT ( 'NONE', ( 20.00153785277168339, 160.0757089691884971, 99.67622395206049646 ) ) ; +#11730 = CARTESIAN_POINT ( 'NONE', ( -28.55555411531191012, 225.5077044902969021, 75.57575137751560135 ) ) ; +#11731 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31788, #18472, #3540, #16021, #2944, #3147 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11732 = ORIENTED_EDGE ( 'NONE', *, *, #27629, .F. ) ; +#11733 = EDGE_CURVE ( 'NONE', #7935, #19997, #9755, .T. ) ; +#11734 = CARTESIAN_POINT ( 'NONE', ( 2.735590141264424346, 189.5786277718560200, 106.5043399991846371 ) ) ; +#11735 = CARTESIAN_POINT ( 'NONE', ( 30.06862252804693014, 175.3593846892391923, 100.1196662352797802 ) ) ; +#11736 = CARTESIAN_POINT ( 'NONE', ( 39.01961099994073123, 121.1792603210347608, 123.5275808920352603 ) ) ; +#11737 = DIRECTION ( 'NONE', ( -0.0006039748319380209294, -1.272619257381173226E-14, -0.9999998176071845934 ) ) ; +#11738 = CARTESIAN_POINT ( 'NONE', ( 23.68458193633999187, 135.2968916867860685, 91.38751720632269837 ) ) ; +#11739 = VERTEX_POINT ( 'NONE', #14031 ) ; +#11740 = LINE ( 'NONE', #24229, #2952 ) ; +#11741 = CARTESIAN_POINT ( 'NONE', ( 20.50147081420385931, 173.9561948828717561, 102.3672533376207952 ) ) ; +#11742 = AXIS2_PLACEMENT_3D ( 'NONE', #38961, #10971, #7886 ) ; +#11743 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33060, #33465, #32673, #32861 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11744 = EDGE_LOOP ( 'NONE', ( #12813, #11635, #7797, #35818 ) ) ; +#11745 = VECTOR ( 'NONE', #32624, 999.9999999999998863 ) ; +#11746 = VECTOR ( 'NONE', #38917, 1000.000000000000114 ) ; +#11747 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971575949 ) ) ; +#11748 = ORIENTED_EDGE ( 'NONE', *, *, #35575, .F. ) ; +#11750 = DIRECTION ( 'NONE', ( 0.7933533411652596845, -0.5930537057990512562, -0.1373964268091844299 ) ) ; +#11749 = CARTESIAN_POINT ( 'NONE', ( -15.66509696366853710, 185.3064862987275205, 105.1805686752921076 ) ) ; +#11751 = EDGE_LOOP ( 'NONE', ( #38893, #33227, #26737, #10684, #1230, #33937 ) ) ; +#11752 = ORIENTED_EDGE ( 'NONE', *, *, #1987, .F. ) ; +#11753 = CARTESIAN_POINT ( 'NONE', ( 15.05621097240102912, 151.2968320376545819, 177.4259961740748963 ) ) ; +#11754 = ORIENTED_EDGE ( 'NONE', *, *, #19243, .T. ) ; +#11755 = CARTESIAN_POINT ( 'NONE', ( 2.831202620881000165, 209.6616513977000125, 75.93512161779000280 ) ) ; +#11756 = EDGE_CURVE ( 'NONE', #19724, #37514, #31502, .T. ) ; +#11757 = PLANE ( 'NONE', #20278 ) ; +#11758 = DIRECTION ( 'NONE', ( 1.272130549047321246E-14, -1.000000000000000000, 1.387778780778895919E-14 ) ) ; +#11759 = ORIENTED_EDGE ( 'NONE', *, *, #32297, .T. ) ; +#11760 = ORIENTED_EDGE ( 'NONE', *, *, #39072, .T. ) ; +#11761 = CARTESIAN_POINT ( 'NONE', ( 37.33832944776210638, 168.0120548916972041, 183.6157512033705927 ) ) ; +#11762 = EDGE_LOOP ( 'NONE', ( #29501, #12924, #38853, #40347 ) ) ; +#11763 = EDGE_LOOP ( 'NONE', ( #40082, #14765, #9977, #6432 ) ) ; +#11764 = CARTESIAN_POINT ( 'NONE', ( 15.75014751337000263, 127.2185294120999970, 89.27069610494000074 ) ) ; +#11765 = EDGE_CURVE ( 'NONE', #12880, #38531, #25029, .T. ) ; +#11766 = CARTESIAN_POINT ( 'NONE', ( 19.70892818629356569, 149.4293184409359014, 181.7720440811204412 ) ) ; +#11767 = FACE_OUTER_BOUND ( 'NONE', #20745, .T. ) ; +#11768 = CARTESIAN_POINT ( 'NONE', ( 19.46094516130095542, 125.6747539604571813, 178.4426934156100231 ) ) ; +#11769 = CARTESIAN_POINT ( 'NONE', ( 36.07413075020000548, 192.3934985084000004, 104.3746197141000067 ) ) ; +#11770 = EDGE_LOOP ( 'NONE', ( #24644, #40325, #2899, #379 ) ) ; +#11771 = ORIENTED_EDGE ( 'NONE', *, *, #37329, .T. ) ; +#11772 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825907063166864, 0.0005734119026844853358 ) ) ; +#11774 = ADVANCED_FACE ( 'NONE', ( #14436 ), #26921, .F. ) ; +#11773 = FACE_OUTER_BOUND ( 'NONE', #20712, .T. ) ; +#11775 = CARTESIAN_POINT ( 'NONE', ( -35.83164568235000047, 191.4815149080000083, 103.7524294659999953 ) ) ; +#11776 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #35904, #28988 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 0.9999976022235548268 ), + .UNSPECIFIED. ) ; +#11777 = EDGE_CURVE ( 'NONE', #20455, #12963, #21078, .T. ) ; +#11778 = ORIENTED_EDGE ( 'NONE', *, *, #7822, .F. ) ; +#11779 = CARTESIAN_POINT ( 'NONE', ( -25.50947195507000131, 120.9974785633000067, 88.11608534222000344 ) ) ; +#11780 = VECTOR ( 'NONE', #7734, 1000.000000000000114 ) ; +#11781 = VERTEX_POINT ( 'NONE', #19295 ) ; +#11782 = LINE ( 'NONE', #39357, #38883 ) ; +#11783 = CARTESIAN_POINT ( 'NONE', ( -37.83775869339968523, 191.4135373898145360, 104.3802259897112776 ) ) ; +#11784 = CARTESIAN_POINT ( 'NONE', ( 25.99285328131546891, 207.8686442202041746, 77.26134345907178158 ) ) ; +#11785 = AXIS2_PLACEMENT_3D ( 'NONE', #38354, #37958, #9958 ) ; +#11786 = ORIENTED_EDGE ( 'NONE', *, *, #9840, .T. ) ; +#11787 = ADVANCED_FACE ( 'NONE', ( #25668 ), #38120, .T. ) ; +#11788 = CARTESIAN_POINT ( 'NONE', ( 0.7304943002959288778, 188.6176604254382596, 103.1983004245615092 ) ) ; +#11789 = VECTOR ( 'NONE', #30546, 1000.000000000000000 ) ; +#11790 = CYLINDRICAL_SURFACE ( 'NONE', #26807, 2.000000000000001332 ) ; +#11791 = CARTESIAN_POINT ( 'NONE', ( 0.03597117087483431980, -13.74990928990360750, 59.55738949995969023 ) ) ; +#11792 = LINE ( 'NONE', #11366, #15913 ) ; +#11793 = FACE_OUTER_BOUND ( 'NONE', #19536, .T. ) ; +#11794 = CYLINDRICAL_SURFACE ( 'NONE', #19517, 1.999999999999989564 ) ; +#11795 = ORIENTED_EDGE ( 'NONE', *, *, #23111, .F. ) ; +#11796 = CARTESIAN_POINT ( 'NONE', ( 75.31247730783820771, 195.3485392357280261, 195.0764703131155500 ) ) ; +#11797 = EDGE_LOOP ( 'NONE', ( #335, #38675, #34508, #25230 ) ) ; +#11798 = DIRECTION ( 'NONE', ( -0.0004161288024530937577, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#11799 = CARTESIAN_POINT ( 'NONE', ( 15.50029468042244396, 126.6919968860542838, 89.40586344971805488 ) ) ; +#11800 = CARTESIAN_POINT ( 'NONE', ( 36.19118544004999904, 112.3688938107000013, 89.61224238968999600 ) ) ; +#11801 = CARTESIAN_POINT ( 'NONE', ( 6.033442795662184110, 135.0969017969509594, 91.08132727238057669 ) ) ; +#11802 = ORIENTED_EDGE ( 'NONE', *, *, #35093, .T. ) ; +#11803 = LINE ( 'NONE', #27158, #6342 ) ; +#11804 = AXIS2_PLACEMENT_3D ( 'NONE', #497, #28328, #10124 ) ; +#11805 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#11806 = CIRCLE ( 'NONE', #34622, 2.500000000028141489 ) ; +#11807 = CARTESIAN_POINT ( 'NONE', ( 20.89286828480348035, 176.3842452922319524, 100.3618186666556369 ) ) ; +#11808 = DIRECTION ( 'NONE', ( 0.9914448496661263377, 0.1271951663094869622, 0.02930016617724668163 ) ) ; +#11809 = CONICAL_SURFACE ( 'NONE', #9184, 5.999999999758601099, 0.7853981633210409541 ) ; +#11810 = CARTESIAN_POINT ( 'NONE', ( 19.46056981307119926, 126.3953319292994451, 175.3169314365064224 ) ) ; +#11811 = CARTESIAN_POINT ( 'NONE', ( -15.83309504418939717, 151.9366289530009908, 94.91101439893938618 ) ) ; +#11812 = FACE_OUTER_BOUND ( 'NONE', #22378, .T. ) ; +#11813 = DIRECTION ( 'NONE', ( 0.0005884949961299158110, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#11814 = DIRECTION ( 'NONE', ( 2.843962595571598640E-13, 0.9743700556834007376, 0.2249510937682375755 ) ) ; +#11815 = ORIENTED_EDGE ( 'NONE', *, *, #32975, .T. ) ; +#11816 = VERTEX_POINT ( 'NONE', #7024 ) ; +#11817 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#11818 = FACE_OUTER_BOUND ( 'NONE', #35752, .T. ) ; +#11819 = EDGE_CURVE ( 'NONE', #22903, #17689, #34634, .T. ) ; +#11820 = CARTESIAN_POINT ( 'NONE', ( -19.37135277734932259, 148.5061081704852768, 180.6320852586945875 ) ) ; +#11821 = DIRECTION ( 'NONE', ( -9.020562075119553066E-15, 0.9743700557921584071, 0.2249510932971565402 ) ) ; +#11822 = ORIENTED_EDGE ( 'NONE', *, *, #31570, .T. ) ; +#11823 = CARTESIAN_POINT ( 'NONE', ( -20.00000588364686038, 174.5066637885302896, 99.95304239614711150 ) ) ; +#11824 = EDGE_CURVE ( 'NONE', #7776, #13881, #16114, .T. ) ; +#11825 = EDGE_CURVE ( 'NONE', #19078, #9147, #2447, .T. ) ; +#11826 = ORIENTED_EDGE ( 'NONE', *, *, #12369, .T. ) ; +#11827 = CARTESIAN_POINT ( 'NONE', ( -38.51028687318000010, 118.9650807552999936, 87.72827849888000173 ) ) ; +#11828 = EDGE_CURVE ( 'NONE', #2793, #10320, #22962, .T. ) ; +#11829 = EDGE_CURVE ( 'NONE', #16953, #1494, #20272, .T. ) ; +#11830 = CARTESIAN_POINT ( 'NONE', ( -3.566911285291269440, 143.5401626538130984, 95.84111064223441190 ) ) ; +#11831 = ORIENTED_EDGE ( 'NONE', *, *, #18525, .T. ) ; +#11832 = CARTESIAN_POINT ( 'NONE', ( 10.03420395425098555, 168.4982496180797682, 98.54774839024014454 ) ) ; +#11833 = CARTESIAN_POINT ( 'NONE', ( 19.46082894524516149, 125.8979155071039742, 177.4746511243711780 ) ) ; +#11834 = CARTESIAN_POINT ( 'NONE', ( 16.06470767884826500, 121.9811400020297896, 174.6065274053796657 ) ) ; +#11835 = LINE ( 'NONE', #37367, #30697 ) ; +#11836 = CARTESIAN_POINT ( 'NONE', ( -5.670826124484550590, 124.5797135749217546, 88.71086237486835557 ) ) ; +#11837 = VERTEX_POINT ( 'NONE', #1468 ) ; +#11838 = ORIENTED_EDGE ( 'NONE', *, *, #27854, .T. ) ; +#11839 = AXIS2_PLACEMENT_3D ( 'NONE', #29520, #1101, #4362 ) ; +#11840 = DIRECTION ( 'NONE', ( -0.6086215548477215131, -0.7730393818215736124, -0.1788572534946829551 ) ) ; +#11841 = AXIS2_PLACEMENT_3D ( 'NONE', #18610, #34360, #9040 ) ; +#11842 = CARTESIAN_POINT ( 'NONE', ( 42.45642095825782292, 103.5646128624151885, 168.7183387323667887 ) ) ; +#11843 = CARTESIAN_POINT ( 'NONE', ( 37.71832435473301359, 191.4189981270610303, 104.3344995016596073 ) ) ; +#11844 = VECTOR ( 'NONE', #37210, 1000.000000000000000 ) ; +#11845 = AXIS2_PLACEMENT_3D ( 'NONE', #20452, #10672, #23343 ) ; +#11846 = CARTESIAN_POINT ( 'NONE', ( -16.53307911521251583, 121.8496102454072485, 177.5840153248893785 ) ) ; +#11847 = ORIENTED_EDGE ( 'NONE', *, *, #16983, .F. ) ; +#11848 = CARTESIAN_POINT ( 'NONE', ( 3.882702609241409419, 148.0331269928226732, 129.7473673639308345 ) ) ; +#11849 = CARTESIAN_POINT ( 'NONE', ( -42.22554410189300711, 120.8118904731670682, 90.64895936832934353 ) ) ; +#11850 = CARTESIAN_POINT ( 'NONE', ( -19.44534333246823721, 148.3822623830060365, 180.6034369735336895 ) ) ; +#11851 = CARTESIAN_POINT ( 'NONE', ( -36.21067597575999741, 191.7496623399999862, 104.2838814501999991 ) ) ; +#11852 = CARTESIAN_POINT ( 'NONE', ( -25.47195991445609664, 212.8394811963306381, 73.07388850790900392 ) ) ; +#11853 = CARTESIAN_POINT ( 'NONE', ( 8.428362648054749329, 177.5952526073304796, 27.36579594574504526 ) ) ; +#11854 = CARTESIAN_POINT ( 'NONE', ( 14.78600921306619576, 183.3613208809844366, 102.4894415693095340 ) ) ; +#11855 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.000000000000000000, 1.000000000000000000 ) ) ; +#11856 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927732809619, -0.0005734119021876268136 ) ) ; +#11857 = CARTESIAN_POINT ( 'NONE', ( 43.14456005852381537, 112.6780295318855565, 129.4537069268840526 ) ) ; +#11858 = CARTESIAN_POINT ( 'NONE', ( -20.49853057565002601, 184.3993303303604705, 104.8029991440840973 ) ) ; +#11859 = EDGE_CURVE ( 'NONE', #7608, #15505, #13954, .T. ) ; +#11860 = CARTESIAN_POINT ( 'NONE', ( -0.4555724343627732265, 211.0000000000011653, 73.55877932795836216 ) ) ; +#11861 = CARTESIAN_POINT ( 'NONE', ( 39.05648265166797017, 127.5103312055594955, 92.14632397477382142 ) ) ; +#11862 = AXIS2_PLACEMENT_3D ( 'NONE', #39866, #2863, #24764 ) ; +#11863 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142367503004439, 137.4659008082804519, 177.5714312369109393 ) ) ; +#11864 = VERTEX_POINT ( 'NONE', #33545 ) ; +#11865 = ORIENTED_EDGE ( 'NONE', *, *, #11696, .F. ) ; +#11866 = VECTOR ( 'NONE', #20411, 1000.000000000000000 ) ; +#11867 = CARTESIAN_POINT ( 'NONE', ( -2.894529877367415516, 190.6472786124893730, 103.6690642133140017 ) ) ; +#11868 = EDGE_CURVE ( 'NONE', #3485, #4354, #971, .T. ) ; +#11869 = CONICAL_SURFACE ( 'NONE', #38597, 2.500000001920880344, 0.7853981633737419088 ) ; +#11870 = ORIENTED_EDGE ( 'NONE', *, *, #12137, .F. ) ; +#11871 = CARTESIAN_POINT ( 'NONE', ( 20.29463841047894235, 126.8274035292942017, 91.69923547483881521 ) ) ; +#11872 = ADVANCED_FACE ( 'NONE', ( #30508 ), #18458, .F. ) ; +#11873 = CARTESIAN_POINT ( 'NONE', ( -8.472443769278077852, 160.9680296444896328, 99.38619809799159555 ) ) ; +#11874 = LINE ( 'NONE', #5105, #28539 ) ; +#11875 = ORIENTED_EDGE ( 'NONE', *, *, #6117, .T. ) ; +#11876 = CYLINDRICAL_SURFACE ( 'NONE', #36144, 48.00000000000002132 ) ; +#11877 = EDGE_CURVE ( 'NONE', #7892, #7683, #21511, .T. ) ; +#11878 = CARTESIAN_POINT ( 'NONE', ( -15.03362232196302095, 125.0996412702250211, 171.3811097074177212 ) ) ; +#11879 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#11880 = FACE_BOUND ( 'NONE', #30940, .T. ) ; +#11881 = EDGE_LOOP ( 'NONE', ( #20802, #39050, #8107, #26424 ) ) ; +#11882 = CARTESIAN_POINT ( 'NONE', ( -35.95425951642922513, 207.4083918145335588, 77.10339231470923949 ) ) ; +#11883 = CARTESIAN_POINT ( 'NONE', ( 23.36625798079915484, 177.0273801772071636, 103.4614646118997854 ) ) ; +#11884 = FACE_OUTER_BOUND ( 'NONE', #22276, .T. ) ; +#11885 = DIRECTION ( 'NONE', ( -0.0005884949961231549431, 0.2249510543439031118, -0.9743698870671271273 ) ) ; +#11886 = FACE_OUTER_BOUND ( 'NONE', #1030, .T. ) ; +#11887 = ORIENTED_EDGE ( 'NONE', *, *, #12234, .F. ) ; +#11888 = ORIENTED_EDGE ( 'NONE', *, *, #8050, .F. ) ; +#11889 = CARTESIAN_POINT ( 'NONE', ( 44.87054245545689923, 186.3366208751881743, 107.7759764278890486 ) ) ; +#11890 = CARTESIAN_POINT ( 'NONE', ( 1.112032568174920355, 189.0842896917700102, 103.7185439348499898 ) ) ; +#11891 = CARTESIAN_POINT ( 'NONE', ( 40.67360545558243956, 184.2591260079552740, 105.2468408042174275 ) ) ; +#11892 = CARTESIAN_POINT ( 'NONE', ( -12.64523939051215073, 134.9174765714697344, 90.80875027841997849 ) ) ; +#11893 = ORIENTED_EDGE ( 'NONE', *, *, #2929, .T. ) ; +#11894 = VECTOR ( 'NONE', #18435, 1000.000000000000000 ) ; +#11895 = CARTESIAN_POINT ( 'NONE', ( -5.958856852865682896, 148.4703916786008904, 97.01252450521799631 ) ) ; +#11896 = ORIENTED_EDGE ( 'NONE', *, *, #3066, .F. ) ; +#11897 = AXIS2_PLACEMENT_3D ( 'NONE', #39589, #23663, #29594 ) ; +#11898 = ORIENTED_EDGE ( 'NONE', *, *, #38109, .F. ) ; +#11899 = EDGE_LOOP ( 'NONE', ( #31124, #37653, #3366, #4572 ) ) ; +#11900 = FACE_OUTER_BOUND ( 'NONE', #33413, .T. ) ; +#11901 = CARTESIAN_POINT ( 'NONE', ( -37.05748002013000075, 191.5156164059999924, 104.1710418975000039 ) ) ; +#11902 = CARTESIAN_POINT ( 'NONE', ( 14.78718341405425818, 175.4478817342403545, 102.7150877355488063 ) ) ; +#11903 = FACE_OUTER_BOUND ( 'NONE', #27541, .T. ) ; +#11904 = VERTEX_POINT ( 'NONE', #12902 ) ; +#11905 = CARTESIAN_POINT ( 'NONE', ( -12.63752691925692240, 134.5929303039996228, 93.51283432846918231 ) ) ; +#11906 = ORIENTED_EDGE ( 'NONE', *, *, #39114, .F. ) ; +#11907 = EDGE_CURVE ( 'NONE', #11261, #32876, #7774, .T. ) ; +#11908 = CARTESIAN_POINT ( 'NONE', ( 26.18897216877000034, 122.5795457392000003, 90.67356684192000671 ) ) ; +#11909 = EDGE_CURVE ( 'NONE', #25874, #11248, #19201, .T. ) ; +#11910 = CARTESIAN_POINT ( 'NONE', ( -35.98606117377973135, 191.5275217759125894, 103.8920091762606006 ) ) ; +#11911 = EDGE_CURVE ( 'NONE', #1910, #23240, #37052, .T. ) ; +#11912 = EDGE_CURVE ( 'NONE', #7897, #11123, #6143, .T. ) ; +#11914 = CARTESIAN_POINT ( 'NONE', ( -25.50870663471662780, 209.7066555246269104, 75.57407794464953099 ) ) ; +#11913 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; +#11915 = ORIENTED_EDGE ( 'NONE', *, *, #8020, .F. ) ; +#11916 = ORIENTED_EDGE ( 'NONE', *, *, #19273, .F. ) ; +#11917 = ORIENTED_EDGE ( 'NONE', *, *, #10052, .T. ) ; +#11918 = EDGE_CURVE ( 'NONE', #26621, #37534, #23435, .T. ) ; +#11919 = VECTOR ( 'NONE', #25166, 1000.000000000000000 ) ; +#11920 = VERTEX_POINT ( 'NONE', #14108 ) ; +#11922 = AXIS2_PLACEMENT_3D ( 'NONE', #30601, #39987, #11994 ) ; +#11921 = CARTESIAN_POINT ( 'NONE', ( -26.40259126664291145, 122.2015665119480730, 90.96023475316120255 ) ) ; +#11923 = EDGE_CURVE ( 'NONE', #26477, #7666, #39730, .T. ) ; +#11924 = AXIS2_PLACEMENT_3D ( 'NONE', #26894, #15611, #21576 ) ; +#11925 = CARTESIAN_POINT ( 'NONE', ( -39.63286418743903283, 165.2521965586124111, 181.9324630935838343 ) ) ; +#11926 = CARTESIAN_POINT ( 'NONE', ( 15.50147166947062871, 184.4041534623167991, 104.7823749529912760 ) ) ; +#11927 = CARTESIAN_POINT ( 'NONE', ( 12.63561059294855582, 130.7398924310956261, 90.07144258487507216 ) ) ; +#11928 = CARTESIAN_POINT ( 'NONE', ( -12.64058198101836084, 135.0096656203987209, 90.95638429151507864 ) ) ; +#11929 = VERTEX_POINT ( 'NONE', #39230 ) ; +#11930 = ORIENTED_EDGE ( 'NONE', *, *, #10938, .T. ) ; +#11931 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971549027 ) ) ; +#11932 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26236, #36007, #16799, #20688 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#11933 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #26216, #10476, #3360, #32734 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 5.554824330570662383, 6.283664472678903046 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9562204062000201343, 0.9562204062000201343, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#11934 = CARTESIAN_POINT ( 'NONE', ( -17.94609826176000311, 126.0030689618739927, 174.3309067020310010 ) ) ; +#11935 = EDGE_CURVE ( 'NONE', #13773, #37266, #19235, .T. ) ; +#11936 = ORIENTED_EDGE ( 'NONE', *, *, #30227, .T. ) ; +#11937 = CARTESIAN_POINT ( 'NONE', ( 35.80903082173799845, 209.7096537007933534, 75.77443985609707511 ) ) ; +#11938 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#11939 = CARTESIAN_POINT ( 'NONE', ( 3.045834296815999931, 190.5229117821999978, 106.7164120734999955 ) ) ; +#11940 = CARTESIAN_POINT ( 'NONE', ( -16.55838281596989248, 121.8568190709532786, 177.6124637991976272 ) ) ; +#11941 = CARTESIAN_POINT ( 'NONE', ( -36.75835926547845389, 190.5727201303276104, 106.7512168163608806 ) ) ; +#11942 = LINE ( 'NONE', #36463, #9831 ) ; +#11943 = CARTESIAN_POINT ( 'NONE', ( 3.706312568368710814, 145.6625114747673138, 93.27952375833829990 ) ) ; +#11944 = CIRCLE ( 'NONE', #22398, 2.000000000000011546 ) ; +#11945 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #621, #37640, #12491, #32120 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.001725546163888570577, 0.003699931228746131465 ), + .UNSPECIFIED. ) ; +#11946 = ORIENTED_EDGE ( 'NONE', *, *, #25537, .F. ) ; +#11947 = VECTOR ( 'NONE', #8565, 1000.000000000000114 ) ; +#11948 = CARTESIAN_POINT ( 'NONE', ( -61.84220049570045319, 78.72323700374752775, 282.5958934331605406 ) ) ; +#11949 = FACE_OUTER_BOUND ( 'NONE', #18021, .T. ) ; +#11950 = VECTOR ( 'NONE', #13739, 999.9999999999998863 ) ; +#11951 = VERTEX_POINT ( 'NONE', #8164 ) ; +#11952 = CARTESIAN_POINT ( 'NONE', ( -15.03056783443286903, 153.9206520343971079, 95.19738268539683190 ) ) ; +#11953 = VERTEX_POINT ( 'NONE', #20631 ) ; +#11954 = ADVANCED_FACE ( 'NONE', ( #30456 ), #21128, .T. ) ; +#11955 = EDGE_CURVE ( 'NONE', #34643, #796, #24120, .T. ) ; +#11957 = CARTESIAN_POINT ( 'NONE', ( -44.46121984373956337, 189.2577286604973210, 103.8865186576782804 ) ) ; +#11956 = CARTESIAN_POINT ( 'NONE', ( 12.31198009898977297, 134.9205818654068025, 90.79431936396761671 ) ) ; +#11958 = ORIENTED_EDGE ( 'NONE', *, *, #7632, .F. ) ; +#11959 = ORIENTED_EDGE ( 'NONE', *, *, #19273, .T. ) ; +#11960 = VERTEX_POINT ( 'NONE', #28001 ) ; +#11961 = CARTESIAN_POINT ( 'NONE', ( 3.120781379327000060, 209.6077888583999993, 76.19641638420999641 ) ) ; +#11962 = CC_DESIGN_PERSON_AND_ORGANIZATION_ASSIGNMENT ( #30665, #24126, ( #37519 ) ) ; +#11963 = PLANE ( 'NONE', #26174 ) ; +#11964 = DIRECTION ( 'NONE', ( -4.718447854718138476E-14, 0.9743700557921591843, 0.2249510932971532373 ) ) ; +#11965 = ORIENTED_EDGE ( 'NONE', *, *, #7600, .F. ) ; +#11966 = ORIENTED_EDGE ( 'NONE', *, *, #13873, .F. ) ; +#11967 = DIRECTION ( 'NONE', ( -0.7857167650892391553, 0.6185862428610305885, 0.0004745532376930718848 ) ) ; +#11968 = ORIENTED_EDGE ( 'NONE', *, *, #9235, .T. ) ; +#11969 = ORIENTED_EDGE ( 'NONE', *, *, #38572, .T. ) ; +#11970 = CARTESIAN_POINT ( 'NONE', ( 30.44899469349954302, 184.9368092152190002, 105.4094724642501859 ) ) ; +#11971 = CARTESIAN_POINT ( 'NONE', ( 28.70699186420280569, 148.4355579229025750, 96.47039304610791532 ) ) ; +#11972 = CARTESIAN_POINT ( 'NONE', ( 2.620081097049193453, 209.6213299886146331, 73.39025628380156263 ) ) ; +#11973 = AXIS2_PLACEMENT_3D ( 'NONE', #25845, #7811, #39088 ) ; +#11974 = EDGE_LOOP ( 'NONE', ( #18652, #28092, #12596, #35596, #17159, #28310 ) ) ; +#11975 = ORIENTED_EDGE ( 'NONE', *, *, #16495, .T. ) ; +#11976 = CARTESIAN_POINT ( 'NONE', ( -5.668571547460837579, 124.2905521247553366, 90.91684019452070231 ) ) ; +#11977 = CARTESIAN_POINT ( 'NONE', ( -23.40543042926000084, 191.9910753068000133, 28.07991271570000080 ) ) ; +#11978 = CARTESIAN_POINT ( 'NONE', ( -36.18473128549999984, 191.7673265768000022, 104.2866159423000028 ) ) ; +#11979 = AXIS2_PLACEMENT_3D ( 'NONE', #25300, #35058, #34663 ) ; +#11980 = EDGE_LOOP ( 'NONE', ( #30176, #29328, #7764, #5350 ) ) ; +#11981 = CARTESIAN_POINT ( 'NONE', ( 15.10714331102995800, 183.1006619385863701, 101.9159176678921312 ) ) ; +#11982 = EDGE_CURVE ( 'NONE', #288, #367, #33444, .T. ) ; +#11983 = VERTEX_POINT ( 'NONE', #36990 ) ; +#11984 = VECTOR ( 'NONE', #12023, 1000.000000000000000 ) ; +#11985 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265228896, 0.1368326740407718733 ) ) ; +#11986 = CARTESIAN_POINT ( 'NONE', ( -40.98114572698732871, 189.4837074447529233, 107.0019971788270823 ) ) ; +#11987 = VERTEX_POINT ( 'NONE', #12635 ) ; +#11988 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597321 ) ) ; +#11989 = CARTESIAN_POINT ( 'NONE', ( -2.937261516208995893, 196.5784392895002384, 103.8768773715001004 ) ) ; +#11990 = DIRECTION ( 'NONE', ( 0.7072735235867311232, 0.6508952295280636680, 0.2758614924392659429 ) ) ; +#11991 = CARTESIAN_POINT ( 'NONE', ( 40.66653928435549403, 188.1862069274984890, 107.8377757704891167 ) ) ; +#11992 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240802804 ) ) ; +#11993 = ORIENTED_EDGE ( 'NONE', *, *, #17394, .F. ) ; +#11994 = DIRECTION ( 'NONE', ( 0.1305262373691798983, -0.9659583596717404852, -0.2233547598295697878 ) ) ; +#11995 = ORIENTED_EDGE ( 'NONE', *, *, #38117, .F. ) ; +#11996 = CARTESIAN_POINT ( 'NONE', ( 3.166356130869399266, 127.3986506551390789, 89.06331644008139392 ) ) ; +#11997 = CARTESIAN_POINT ( 'NONE', ( 25.74045643010000006, 210.3999399800999868, 73.29295753731000218 ) ) ; +#11998 = FACE_OUTER_BOUND ( 'NONE', #5089, .T. ) ; +#11999 = ORIENTED_EDGE ( 'NONE', *, *, #675, .F. ) ; +#12000 = AXIS2_PLACEMENT_3D ( 'NONE', #26339, #38771, #23258 ) ; +#12001 = CARTESIAN_POINT ( 'NONE', ( 44.97084429314561049, 114.9968340379079166, 129.9902062988158491 ) ) ; +#12002 = ORIENTED_EDGE ( 'NONE', *, *, #6399, .T. ) ; +#12003 = CARTESIAN_POINT ( 'NONE', ( -22.78222448785095011, 163.9594641391059042, 100.5986201911018441 ) ) ; +#12004 = ADVANCED_FACE ( 'NONE', ( #15118 ), #30856, .T. ) ; +#12005 = VECTOR ( 'NONE', #3296, 1000.000000000000227 ) ; +#12007 = EDGE_CURVE ( 'NONE', #21782, #34652, #20259, .T. ) ; +#12006 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5440, #36724, #2392, #30198, #30396, #2192 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 4 ), + ( 0.000000000000000000, 0.3333328623389552048, 0.6666665902675604771, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12008 = CARTESIAN_POINT ( 'NONE', ( -35.95668941153999754, 225.9002260768000099, 73.08022102179975832 ) ) ; +#12009 = CIRCLE ( 'NONE', #22463, 1.750000000000001998 ) ; +#12010 = ORIENTED_EDGE ( 'NONE', *, *, #36312, .F. ) ; +#12011 = CYLINDRICAL_SURFACE ( 'NONE', #948, 8.999999999999996447 ) ; +#12012 = CARTESIAN_POINT ( 'NONE', ( 21.65621127755655095, 154.2664572072626470, 95.25506021940962853 ) ) ; +#12013 = CARTESIAN_POINT ( 'NONE', ( 26.01723252630338123, 191.6619263248034031, 103.8858301454409201 ) ) ; +#12014 = LINE ( 'NONE', #36738, #26786 ) ; +#12015 = CARTESIAN_POINT ( 'NONE', ( -38.01211212650550664, 119.1971871873620472, 87.30118044812934386 ) ) ; +#12016 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #799, #25771, #38223, #35518, #7535, #10232, #7135, #19606, #35726, #32880 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.002038048205810061037, 0.2515285361543575515, 0.5010190241029049973, 0.7505095120514525542, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12017 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#12018 = ORIENTED_EDGE ( 'NONE', *, *, #23399, .F. ) ; +#12019 = CYLINDRICAL_SURFACE ( 'NONE', #15185, 2.000000000000014655 ) ; +#12020 = CYLINDRICAL_SURFACE ( 'NONE', #1365, 7.999999999999993783 ) ; +#12021 = ORIENTED_EDGE ( 'NONE', *, *, #38794, .F. ) ; +#12022 = CARTESIAN_POINT ( 'NONE', ( 30.06438278973887535, 134.2480451416175811, 93.70732421818068758 ) ) ; +#12023 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#12024 = ORIENTED_EDGE ( 'NONE', *, *, #129, .T. ) ; +#12025 = CARTESIAN_POINT ( 'NONE', ( -38.57809401074000988, 119.0279522853000174, 87.73291911440999513 ) ) ; +#12026 = EDGE_CURVE ( 'NONE', #15729, #11269, #7078, .T. ) ; +#12027 = CARTESIAN_POINT ( 'NONE', ( 36.06296285845981942, 194.2771771405940058, 102.8764942496974442 ) ) ; +#12028 = ORIENTED_EDGE ( 'NONE', *, *, #35321, .F. ) ; +#12029 = CARTESIAN_POINT ( 'NONE', ( -38.63917769686599257, 119.2253121530902007, 90.31157676266975898 ) ) ; +#12030 = CIRCLE ( 'NONE', #20490, 6.000000000000001776 ) ; +#12031 = AXIS2_PLACEMENT_3D ( 'NONE', #23044, #19142, #31646 ) ; +#12032 = CARTESIAN_POINT ( 'NONE', ( 19.46071270196222613, 126.1210784313858397, 176.5066029477476377 ) ) ; +#12033 = CARTESIAN_POINT ( 'NONE', ( -25.63981465746000055, 190.7835523455999862, 106.4035544525000034 ) ) ; +#12034 = CARTESIAN_POINT ( 'NONE', ( 25.49921019565536184, 118.1133140256443426, 87.75227232668940758 ) ) ; +#12035 = CARTESIAN_POINT ( 'NONE', ( 0.5441253984803264832, 208.9999999999999716, 73.05817544431644706 ) ) ; +#12036 = ORIENTED_EDGE ( 'NONE', *, *, #13197, .F. ) ; +#12037 = ORIENTED_EDGE ( 'NONE', *, *, #33952, .T. ) ; +#12038 = LINE ( 'NONE', #23698, #24533 ) ; +#12039 = CARTESIAN_POINT ( 'NONE', ( 21.25891409511187291, 128.8498498509368915, 89.90056508924928380 ) ) ; +#12040 = CARTESIAN_POINT ( 'NONE', ( 36.54202398728305212, 191.7331444242542204, 104.3517902021189343 ) ) ; +#12041 = EDGE_CURVE ( 'NONE', #16970, #2805, #28589, .T. ) ; +#12042 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#12043 = VERTEX_POINT ( 'NONE', #7494 ) ; +#12044 = VERTEX_POINT ( 'NONE', #35290 ) ; +#12045 = CARTESIAN_POINT ( 'NONE', ( 18.00176548541284305, 179.0675989394117664, 104.0619768109754943 ) ) ; +#12046 = CARTESIAN_POINT ( 'NONE', ( 15.50029468041065606, 160.6294874787016909, 97.24095194477267512 ) ) ; +#12047 = CARTESIAN_POINT ( 'NONE', ( -19.44510777017706715, 147.9329884748811992, 182.5523163158060527 ) ) ; +#12048 = CARTESIAN_POINT ( 'NONE', ( 6.231540706066161839, 163.7419074641817360, 29.13324844072834452 ) ) ; +#12049 = EDGE_CURVE ( 'NONE', #20521, #25077, #6179, .T. ) ; +#12050 = CARTESIAN_POINT ( 'NONE', ( -37.21052966546948682, 132.5657015190818697, 337.0064682716691777 ) ) ; +#12051 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32499, #20206, #26578, #11229 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 1.425987289115625436E-06, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12052 = CARTESIAN_POINT ( 'NONE', ( 12.64209925790531308, 131.0231129754641302, 89.89439459407216759 ) ) ; +#12053 = EDGE_CURVE ( 'NONE', #35348, #28905, #17161, .T. ) ; +#12054 = EDGE_CURVE ( 'NONE', #3137, #4942, #24207, .T. ) ; +#12055 = CARTESIAN_POINT ( 'NONE', ( -30.05261222213120931, 184.7446961453429424, 104.8885090255323718 ) ) ; +#12056 = EDGE_CURVE ( 'NONE', #11256, #17270, #18475, .T. ) ; +#12057 = CARTESIAN_POINT ( 'NONE', ( 19.15700822158549244, 125.8492576213503185, 175.4093116928347058 ) ) ; +#12058 = EDGE_CURVE ( 'NONE', #9096, #14254, #36860, .T. ) ; +#12059 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25444, #11820, #5675, #18125, #36944, #40393, #39172, #17074 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 4 ), + ( 0.000000000000000000, 0.0004334691909605219921, 0.0008669383819210439842, 0.001733876763842038746 ), + .UNSPECIFIED. ) ; +#12060 = PERSON_AND_ORGANIZATION_ROLE ( 'design_supplier' ) ; +#12061 = DIRECTION ( 'NONE', ( -9.869203562998891317E-14, 0.9743700558298823422, 0.2249510931337564412 ) ) ; +#12062 = AXIS2_PLACEMENT_3D ( 'NONE', #29631, #2029, #14094 ) ; +#12063 = CARTESIAN_POINT ( 'NONE', ( 4.034499240731888037, 144.1016867008996201, 93.43213283136152825 ) ) ; +#12064 = LINE ( 'NONE', #21472, #34874 ) ; +#12065 = CARTESIAN_POINT ( 'NONE', ( -13.46986788395000012, 174.3879284816999871, 152.4718672074000381 ) ) ; +#12066 = CARTESIAN_POINT ( 'NONE', ( 37.68743879864511115, 191.4261428820249762, 104.2800299550340100 ) ) ; +#12067 = AXIS2_PLACEMENT_3D ( 'NONE', #5091, #39436, #24130 ) ; +#12068 = ORIENTED_EDGE ( 'NONE', *, *, #10031, .T. ) ; +#12070 = ORIENTED_EDGE ( 'NONE', *, *, #33343, .F. ) ; +#12069 = CARTESIAN_POINT ( 'NONE', ( 36.67157185893000104, 191.2359882216000244, 106.4438479881000035 ) ) ; +#12071 = ORIENTED_EDGE ( 'NONE', *, *, #39138, .F. ) ; +#12072 = ORIENTED_EDGE ( 'NONE', *, *, #19367, .F. ) ; +#12073 = PLANE ( 'NONE', #7511 ) ; +#12074 = DIRECTION ( 'NONE', ( -0.7075337269410232333, 4.349513441062974412E-15, -0.7066795774896466042 ) ) ; +#12075 = CARTESIAN_POINT ( 'NONE', ( 2.804646158948000068, 201.9934155195000187, 90.47669623104000891 ) ) ; +#12076 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#12077 = ORIENTED_EDGE ( 'NONE', *, *, #15230, .T. ) ; +#12078 = CARTESIAN_POINT ( 'NONE', ( 14.27749844727565076, 135.1700550567618961, 93.92967703643782329 ) ) ; +#12079 = CARTESIAN_POINT ( 'NONE', ( -15.99983570302001468, 128.1046851893773066, 89.23788144415702561 ) ) ; +#12080 = CARTESIAN_POINT ( 'NONE', ( -20.00000737806465523, 151.9608748777371545, 94.74793644920653435 ) ) ; +#12081 = ORIENTED_EDGE ( 'NONE', *, *, #34576, .F. ) ; +#12082 = LINE ( 'NONE', #24565, #25171 ) ; +#12083 = CARTESIAN_POINT ( 'NONE', ( 25.99199080364422443, 211.0901596425212574, 76.04279652306830428 ) ) ; +#12084 = CARTESIAN_POINT ( 'NONE', ( -13.49869758878000070, 124.2895155477322078, 90.92133008163705199 ) ) ; +#12085 = DIRECTION ( 'NONE', ( 0.0005884949961201063834, -0.2249510543439072752, 0.9743698870671261281 ) ) ; +#12086 = CONICAL_SURFACE ( 'NONE', #17266, 2.503114877936384097, 0.7853981634120447142 ) ; +#12087 = VERTEX_POINT ( 'NONE', #23865 ) ; +#12088 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971560961 ) ) ; +#12089 = CARTESIAN_POINT ( 'NONE', ( 2.503116965328639587, 190.4798029275779925, 104.1246707405189937 ) ) ; +#12090 = CONICAL_SURFACE ( 'NONE', #15973, 5.999999999996507682, 0.7853981634382131150 ) ; +#12091 = VECTOR ( 'NONE', #27602, 1000.000000000000114 ) ; +#12092 = CARTESIAN_POINT ( 'NONE', ( 16.19311320487878447, 152.0208732148549586, 180.9787873967511018 ) ) ; +#12093 = VECTOR ( 'NONE', #27107, 1000.000000000000227 ) ; +#12094 = VERTEX_POINT ( 'NONE', #36328 ) ; +#12095 = CARTESIAN_POINT ( 'NONE', ( -37.20408499830807614, 118.8543451047710278, 123.0175147464529886 ) ) ; +#12096 = ORIENTED_EDGE ( 'NONE', *, *, #14189, .T. ) ; +#12097 = EDGE_CURVE ( 'NONE', #38882, #39941, #8326, .T. ) ; +#12098 = EDGE_CURVE ( 'NONE', #33342, #21583, #18308, .T. ) ; +#12099 = LINE ( 'NONE', #24585, #33407 ) ; +#12100 = CARTESIAN_POINT ( 'NONE', ( -37.93576619606000122, 191.2843283846000020, 104.9448776480000021 ) ) ; +#12101 = EDGE_CURVE ( 'NONE', #21459, #22181, #30914, .T. ) ; +#12102 = LINE ( 'NONE', #27470, #10416 ) ; +#12103 = ADVANCED_FACE ( 'NONE', ( #13160 ), #38087, .F. ) ; +#12104 = CARTESIAN_POINT ( 'NONE', ( 15.83996889870756952, 151.8963954173656248, 180.3028429317488133 ) ) ; +#12105 = CARTESIAN_POINT ( 'NONE', ( 12.63852066808000352, 177.1933417920457998, 101.0667481643646539 ) ) ; +#12106 = CARTESIAN_POINT ( 'NONE', ( -36.29559416469999888, 191.0453341742000077, 106.7255111497999991 ) ) ; +#12107 = VERTEX_POINT ( 'NONE', #21202 ) ; +#12108 = CARTESIAN_POINT ( 'NONE', ( -23.02035068621188785, 211.0902260608000347, 73.06925090625777841 ) ) ; +#12109 = CARTESIAN_POINT ( 'NONE', ( -42.84327062420202026, 120.8099927651375936, 92.42850709477329474 ) ) ; +#12110 = CARTESIAN_POINT ( 'NONE', ( 22.50176656780242723, 137.8364378046804575, 94.54354019036699697 ) ) ; +#12112 = CARTESIAN_POINT ( 'NONE', ( 1.561641312891000055, 176.6294975753000074, 103.5090253406000045 ) ) ; +#12111 = LINE ( 'NONE', #22322, #26488 ) ; +#12113 = ORIENTED_EDGE ( 'NONE', *, *, #9045, .F. ) ; +#12114 = ORIENTED_EDGE ( 'NONE', *, *, #27097, .F. ) ; +#12115 = CIRCLE ( 'NONE', #36229, 55.00273826248748321 ) ; +#12116 = AXIS2_PLACEMENT_3D ( 'NONE', #9380, #24936, #28387 ) ; +#12117 = ORIENTED_EDGE ( 'NONE', *, *, #2451, .F. ) ; +#12118 = AXIS2_PLACEMENT_3D ( 'NONE', #19559, #13634, #32834 ) ; +#12119 = AXIS2_PLACEMENT_3D ( 'NONE', #38206, #10212, #12668 ) ; +#12120 = VERTEX_POINT ( 'NONE', #2790 ) ; +#12121 = CARTESIAN_POINT ( 'NONE', ( 39.52184518373000088, 119.8270887776999984, 90.51129334396000559 ) ) ; +#12122 = DIRECTION ( 'NONE', ( -0.0006039748319386177827, -1.312069532538339473E-14, -0.9999998176071847045 ) ) ; +#12123 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#12124 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921579630, -0.2249510932971586774 ) ) ; +#12125 = DIRECTION ( 'NONE', ( 0.9914446600486714889, -0.1270322995874082761, -0.03000468167651997725 ) ) ; +#12126 = EDGE_LOOP ( 'NONE', ( #27468, #18711, #5230, #10378 ) ) ; +#12127 = ORIENTED_EDGE ( 'NONE', *, *, #29507, .F. ) ; +#12128 = CARTESIAN_POINT ( 'NONE', ( -2.437027990547441014, 191.0000000396348128, 104.2633722229568605 ) ) ; +#12129 = LINE ( 'NONE', #25213, #12895 ) ; +#12130 = DIRECTION ( 'NONE', ( -1.227018180789439535E-16, 0.9743700557922200245, 0.2249510932968896981 ) ) ; +#12131 = ORIENTED_EDGE ( 'NONE', *, *, #30878, .T. ) ; +#12132 = CARTESIAN_POINT ( 'NONE', ( 35.82223221909334399, 209.7096535410589695, 75.76122250247870227 ) ) ; +#12133 = EDGE_CURVE ( 'NONE', #11668, #17225, #34984, .T. ) ; +#12134 = CARTESIAN_POINT ( 'NONE', ( -8.332516381469520894, 161.3691698881907541, 97.25506481891379451 ) ) ; +#12135 = EDGE_CURVE ( 'NONE', #5771, #21705, #27568, .T. ) ; +#12136 = VECTOR ( 'NONE', #33266, 1000.000000000000000 ) ; +#12137 = EDGE_CURVE ( 'NONE', #21843, #10701, #38700, .T. ) ; +#12138 = EDGE_CURVE ( 'NONE', #18677, #3193, #16348, .T. ) ; +#12139 = CARTESIAN_POINT ( 'NONE', ( 1.550063599131999981, 189.2339692129000071, 105.8038991500000066 ) ) ; +#12140 = AXIS2_PLACEMENT_3D ( 'NONE', #2716, #24190, #26851 ) ; +#12141 = ORIENTED_EDGE ( 'NONE', *, *, #30797, .T. ) ; +#12142 = CARTESIAN_POINT ( 'NONE', ( 5.667899326860613485, 130.6342804221140739, 90.14085528663672164 ) ) ; +#12143 = CIRCLE ( 'NONE', #34324, 2.000000003389833303 ) ; +#12144 = CYLINDRICAL_SURFACE ( 'NONE', #38222, 6.000000000000008882 ) ; +#12145 = FACE_OUTER_BOUND ( 'NONE', #6025, .T. ) ; +#12146 = CARTESIAN_POINT ( 'NONE', ( 19.23419947629634308, 148.6673374613704084, 183.4523375473061151 ) ) ; +#12147 = CIRCLE ( 'NONE', #8884, 2.500000000000000888 ) ; +#12148 = EDGE_CURVE ( 'NONE', #9446, #10983, #23683, .T. ) ; +#12149 = CARTESIAN_POINT ( 'NONE', ( -19.99931527105535878, 118.1256151686936420, 90.27945241601419468 ) ) ; +#12150 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118071, 107.3101052615539714, 174.7154016153159830 ) ) ; +#12151 = EDGE_CURVE ( 'NONE', #35342, #37208, #3524, .T. ) ; +#12152 = VERTEX_POINT ( 'NONE', #34793 ) ; +#12153 = CARTESIAN_POINT ( 'NONE', ( -5.668308741210207558, 188.0533248580316297, 103.3198754439989813 ) ) ; +#12154 = ORIENTED_EDGE ( 'NONE', *, *, #3690, .T. ) ; +#12156 = CARTESIAN_POINT ( 'NONE', ( 35.64150636403998362, 191.9836673600688357, 103.9000245735707608 ) ) ; +#12155 = DIRECTION ( 'NONE', ( -0.0005884949961245180021, 0.2249510543439046939, -0.9743698870671267942 ) ) ; +#12157 = VERTEX_POINT ( 'NONE', #473 ) ; +#12158 = ADVANCED_FACE ( 'NONE', ( #21964 ), #28943, .F. ) ; +#12159 = ORIENTED_EDGE ( 'NONE', *, *, #36505, .T. ) ; +#12160 = CARTESIAN_POINT ( 'NONE', ( 38.58922224453577599, 118.4807708069047294, 89.66244680221666385 ) ) ; +#12161 = EDGE_LOOP ( 'NONE', ( #33583, #38807, #10548, #11752 ) ) ; +#12162 = CARTESIAN_POINT ( 'NONE', ( 3.083319845196999864, 209.7208286977000000, 76.19224769502000072 ) ) ; +#12163 = CARTESIAN_POINT ( 'NONE', ( -26.74382575616715130, 120.3580507813137075, 171.5572023280520000 ) ) ; +#12164 = CARTESIAN_POINT ( 'NONE', ( 12.63909004533367764, 177.5096400689760685, 100.8691027646205498 ) ) ; +#12165 = ORIENTED_EDGE ( 'NONE', *, *, #20804, .T. ) ; +#12166 = AXIS2_PLACEMENT_3D ( 'NONE', #17104, #23883, #36342 ) ; +#12167 = ORIENTED_EDGE ( 'NONE', *, *, #36679, .F. ) ; +#12168 = ORIENTED_EDGE ( 'NONE', *, *, #23203, .F. ) ; +#12169 = AXIS2_PLACEMENT_3D ( 'NONE', #34156, #6150, #24589 ) ; +#12170 = ORIENTED_EDGE ( 'NONE', *, *, #14707, .T. ) ; +#12171 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971562349 ) ) ; +#12172 = FACE_OUTER_BOUND ( 'NONE', #9624, .T. ) ; +#12173 = LINE ( 'NONE', #6813, #25287 ) ; +#12174 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385906776 ) ) ; +#12175 = VERTEX_POINT ( 'NONE', #16009 ) ; +#12176 = VECTOR ( 'NONE', #28708, 1000.000000000000114 ) ; +#12177 = VERTEX_POINT ( 'NONE', #13166 ) ; +#12178 = ORIENTED_EDGE ( 'NONE', *, *, #13694, .F. ) ; +#12179 = CARTESIAN_POINT ( 'NONE', ( -2.938441475009767156, 191.9759150222000130, 101.9232220854079856 ) ) ; +#12180 = CARTESIAN_POINT ( 'NONE', ( 20.07272550364178798, 128.0187529663550663, 89.19625550058378849 ) ) ; +#12181 = EDGE_LOOP ( 'NONE', ( #825, #17157, #17286, #4749 ) ) ; +#12182 = DIRECTION ( 'NONE', ( 0.0002393071043249488713, 0.2255680020170700018, -0.9742273960416720779 ) ) ; +#12183 = EDGE_LOOP ( 'NONE', ( #36080, #11875, #28358, #9906 ) ) ; +#12184 = EDGE_LOOP ( 'NONE', ( #18244, #11341, #25429, #10652, #20482, #32207, #38788, #28477, #30792, #25954 ) ) ; +#12185 = CARTESIAN_POINT ( 'NONE', ( 19.84759055312880704, 148.9730819504834756, 184.3419776361884885 ) ) ; +#12186 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319356112900 ) ) ; +#12187 = EDGE_LOOP ( 'NONE', ( #4876, #19679, #14364, #20249, #20827, #24572, #25499, #20857, #39139, #5076, #15377 ) ) ; +#12188 = EDGE_CURVE ( 'NONE', #21074, #15849, #5444, .T. ) ; +#12189 = EDGE_CURVE ( 'NONE', #9483, #30394, #1212, .T. ) ; +#12190 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#12191 = CARTESIAN_POINT ( 'NONE', ( -15.91450692093356345, 126.1598053719804255, 88.78881894041531098 ) ) ; +#12192 = DIRECTION ( 'NONE', ( -1.586032892343862782E-14, -1.000000000000000000, 1.586032892343862782E-14 ) ) ; +#12193 = CARTESIAN_POINT ( 'NONE', ( -13.49052885539015278, 188.3420772061585353, 103.1432726234667427 ) ) ; +#12194 = EDGE_CURVE ( 'NONE', #5670, #10712, #29034, .T. ) ; +#12195 = AXIS2_PLACEMENT_3D ( 'NONE', #31461, #31254, #30864 ) ; +#12196 = EDGE_LOOP ( 'NONE', ( #33202, #36370, #3867, #17696 ) ) ; +#12197 = DIRECTION ( 'NONE', ( 0.7933532970003738249, 0.5930762008556724751, 0.1372995488602876402 ) ) ; +#12198 = CARTESIAN_POINT ( 'NONE', ( -30.07053858952056302, 176.7377855889365037, 103.0399784971898498 ) ) ; +#12199 = VECTOR ( 'NONE', #23126, 1000.000000000000000 ) ; +#12200 = CARTESIAN_POINT ( 'NONE', ( -38.02975100090999661, 118.2512589216999999, 87.84359524929000429 ) ) ; +#12201 = VECTOR ( 'NONE', #17956, 1000.000000000000114 ) ; +#12202 = CARTESIAN_POINT ( 'NONE', ( 37.58649206415999799, 117.1725957489999956, 89.52667883109999991 ) ) ; +#12203 = EDGE_CURVE ( 'NONE', #9411, #10555, #6091, .T. ) ; +#12204 = LINE ( 'NONE', #15466, #16722 ) ; +#12205 = ORIENTED_EDGE ( 'NONE', *, *, #24582, .T. ) ; +#12206 = VECTOR ( 'NONE', #38756, 1000.000000000000000 ) ; +#12207 = CARTESIAN_POINT ( 'NONE', ( -38.20662297452999923, 118.7287161886000035, 90.14649827262999793 ) ) ; +#12208 = EDGE_CURVE ( 'NONE', #21584, #29495, #20437, .T. ) ; +#12209 = CARTESIAN_POINT ( 'NONE', ( 5.675840488321574284, 188.3446150673902650, 103.1322824216947396 ) ) ; +#12210 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24963, #9213, #2679, #27443, #12079, #40066 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12211 = VERTEX_POINT ( 'NONE', #38093 ) ; +#12212 = FACE_OUTER_BOUND ( 'NONE', #11770, .T. ) ; +#12213 = CARTESIAN_POINT ( 'NONE', ( 15.99998378901094576, 184.9656665294078266, 102.3459542884652365 ) ) ; +#12214 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971579835 ) ) ; +#12215 = DIRECTION ( 'NONE', ( -0.0001408404391176450643, 0.2255194953501120092, -0.9742386449843803975 ) ) ; +#12216 = FACE_OUTER_BOUND ( 'NONE', #23568, .T. ) ; +#12217 = LINE ( 'NONE', #15083, #10218 ) ; +#12218 = ORIENTED_EDGE ( 'NONE', *, *, #37474, .F. ) ; +#12219 = DIRECTION ( 'NONE', ( 0.0004161288024535961770, 0.5299192578740949955, 0.8480479980348919478 ) ) ; +#12220 = CARTESIAN_POINT ( 'NONE', ( -24.13644154089634952, 149.3966794002155041, 197.0808772690376998 ) ) ; +#12221 = VECTOR ( 'NONE', #17846, 1000.000000000000114 ) ; +#12222 = VERTEX_POINT ( 'NONE', #37688 ) ; +#12223 = CARTESIAN_POINT ( 'NONE', ( 30.06909869252190148, 134.7508913421523289, 93.39317358598317753 ) ) ; +#12224 = VECTOR ( 'NONE', #37802, 1000.000000000000227 ) ; +#12225 = ORIENTED_EDGE ( 'NONE', *, *, #27629, .T. ) ; +#12226 = CARTESIAN_POINT ( 'NONE', ( 15.10588229656246639, 129.6118588884834537, 89.56705289901165656 ) ) ; +#12227 = CIRCLE ( 'NONE', #25953, 2.000000003952151051 ) ; +#12228 = FACE_OUTER_BOUND ( 'NONE', #24776, .T. ) ; +#12229 = ORIENTED_EDGE ( 'NONE', *, *, #22077, .T. ) ; +#12230 = CARTESIAN_POINT ( 'NONE', ( 35.64226591835503655, 192.1362045434372590, 106.8982047678648826 ) ) ; +#12231 = CARTESIAN_POINT ( 'NONE', ( 25.49063000826092562, 211.0902260967494897, 73.54299573436949800 ) ) ; +#12232 = CARTESIAN_POINT ( 'NONE', ( -38.25695912633000262, 118.9336418487000060, 90.29207677415999456 ) ) ; +#12233 = EDGE_CURVE ( 'NONE', #15042, #12808, #26331, .T. ) ; +#12234 = EDGE_CURVE ( 'NONE', #1497, #5410, #36765, .T. ) ; +#12235 = CARTESIAN_POINT ( 'NONE', ( 30.07127320806394977, 177.0037652588377739, 103.4184075945244388 ) ) ; +#12236 = CARTESIAN_POINT ( 'NONE', ( 22.00409069237373316, 127.5719638939032450, 179.3950931670769080 ) ) ; +#12237 = ORIENTED_EDGE ( 'NONE', *, *, #9653, .F. ) ; +#12238 = DIRECTION ( 'NONE', ( 0.0006039748319385504537, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#12239 = CARTESIAN_POINT ( 'NONE', ( 42.36531273491009841, 136.3168495591860392, 337.8274922784121941 ) ) ; +#12240 = CARTESIAN_POINT ( 'NONE', ( 37.96380763661293400, 191.4135383555317844, 104.3344495138068595 ) ) ; +#12241 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14984, #15386, #22754, #657 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12242 = CARTESIAN_POINT ( 'NONE', ( -16.53460274203917635, 121.8354022778151204, 177.5673403339679055 ) ) ; +#12243 = ORIENTED_EDGE ( 'NONE', *, *, #32612, .F. ) ; +#12244 = DIRECTION ( 'NONE', ( -6.167905692338912296E-15, -0.9743700557921579630, -0.2249510932971586219 ) ) ; +#12245 = CARTESIAN_POINT ( 'NONE', ( 12.31324332228320806, 135.0455449219146260, 90.99420773906884108 ) ) ; +#12246 = CARTESIAN_POINT ( 'NONE', ( 25.81316146412230594, 212.1057043653514427, 73.04291357969384535 ) ) ; +#12247 = FACE_OUTER_BOUND ( 'NONE', #35292, .T. ) ; +#12248 = CARTESIAN_POINT ( 'NONE', ( -25.71903582428170409, 189.5947562258769779, 106.0039061072679942 ) ) ; +#12249 = AXIS2_PLACEMENT_3D ( 'NONE', #28915, #13183, #25665 ) ; +#12250 = VECTOR ( 'NONE', #23775, 1000.000000000000114 ) ; +#12251 = CARTESIAN_POINT ( 'NONE', ( -35.38988506213597418, 77.14301703112144537, 290.1978808180363671 ) ) ; +#12252 = EDGE_CURVE ( 'NONE', #39292, #16264, #35437, .T. ) ; +#12253 = APPROVAL_STATUS ( 'not_yet_approved' ) ; +#12254 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#12255 = ORIENTED_EDGE ( 'NONE', *, *, #30837, .F. ) ; +#12256 = CARTESIAN_POINT ( 'NONE', ( -35.94604301394655010, 113.4338301994345386, 87.78258508858034759 ) ) ; +#12257 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524157562, 149.3470289647612219, 130.0514119197758305 ) ) ; +#12258 = CARTESIAN_POINT ( 'NONE', ( 62.08695490598599775, 78.64495961329345164, 282.5210433287024898 ) ) ; +#12259 = CARTESIAN_POINT ( 'NONE', ( 36.36530412196980677, 191.8376229407879805, 104.3480272023119824 ) ) ; +#12261 = ORIENTED_EDGE ( 'NONE', *, *, #22074, .T. ) ; +#12260 = CARTESIAN_POINT ( 'NONE', ( 35.95966625969001029, 191.1315741047999950, 106.9740560316000000 ) ) ; +#12262 = ORIENTED_EDGE ( 'NONE', *, *, #24829, .F. ) ; +#12263 = EDGE_LOOP ( 'NONE', ( #1287, #23797, #15754, #35588 ) ) ; +#12264 = CARTESIAN_POINT ( 'NONE', ( -5.652752471618317287, 134.9384505426030216, 90.80933139859830305 ) ) ; +#12265 = DIRECTION ( 'NONE', ( 0.0006039748319110907569, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#12266 = EDGE_CURVE ( 'NONE', #33548, #16187, #27658, .T. ) ; +#12267 = DIRECTION ( 'NONE', ( -7.677760455958669993E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#12268 = CARTESIAN_POINT ( 'NONE', ( 25.50041447495308233, 118.1134306400200416, 89.75249416949174019 ) ) ; +#12269 = ORIENTED_EDGE ( 'NONE', *, *, #29633, .T. ) ; +#12270 = CARTESIAN_POINT ( 'NONE', ( -38.74767328483999762, 119.4454340065999958, 90.48510276766000970 ) ) ; +#12271 = CARTESIAN_POINT ( 'NONE', ( -38.12831867127404450, 119.0711346055105793, 87.44068710121472066 ) ) ; +#12272 = CARTESIAN_POINT ( 'NONE', ( -15.99999263269153182, 160.7450692216915513, 96.77351201758563093 ) ) ; +#12273 = CARTESIAN_POINT ( 'NONE', ( -21.21281385531639430, 128.6733510584166140, 91.93807758298277122 ) ) ; +#12274 = CARTESIAN_POINT ( 'NONE', ( -15.74838202838000178, 144.4617537176999917, 95.83639389565999522 ) ) ; +#12275 = ORIENTED_EDGE ( 'NONE', *, *, #18837, .F. ) ; +#12276 = CARTESIAN_POINT ( 'NONE', ( 40.79660045530999923, 220.4002260649999982, 75.78386445958000195 ) ) ; +#12277 = CARTESIAN_POINT ( 'NONE', ( 23.36437573944527557, 176.9425577232293278, 103.3257217497975091 ) ) ; +#12278 = EDGE_CURVE ( 'NONE', #28042, #35389, #30501, .T. ) ; +#12279 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37831, #9843, #3677, #22314 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12280 = EDGE_CURVE ( 'NONE', #6206, #22776, #37786, .T. ) ; +#12281 = DIRECTION ( 'NONE', ( -0.0005884949961187157857, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#12282 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251384259, 134.5978788018760497, 93.30392147953956794 ) ) ; +#12283 = AXIS2_PLACEMENT_3D ( 'NONE', #20743, #8900, #20533 ) ; +#12284 = PLANE ( 'NONE', #13199 ) ; +#12285 = EDGE_CURVE ( 'NONE', #26219, #30625, #28315, .T. ) ; +#12286 = EDGE_LOOP ( 'NONE', ( #10948, #40398, #20462, #13181 ) ) ; +#12287 = CARTESIAN_POINT ( 'NONE', ( -26.13862405872000139, 191.6276511288999984, 103.7705029747000083 ) ) ; +#12288 = CARTESIAN_POINT ( 'NONE', ( 2.601069743092999875, 189.8879886073000023, 103.6444425284999937 ) ) ; +#12289 = FACE_OUTER_BOUND ( 'NONE', #17412, .T. ) ; +#12290 = ORIENTED_EDGE ( 'NONE', *, *, #37521, .F. ) ; +#12291 = CARTESIAN_POINT ( 'NONE', ( 3.667815741532966189, 126.2406713581920599, 91.36142183184406917 ) ) ; +#12292 = ORIENTED_EDGE ( 'NONE', *, *, #12921, .F. ) ; +#12293 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25551, #38590, #10003, #22481 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12294 = CARTESIAN_POINT ( 'NONE', ( 37.79502456659257348, 218.5902260770999987, 74.53567710821411652 ) ) ; +#12295 = CARTESIAN_POINT ( 'NONE', ( -20.01961944020480288, 207.8020456100749698, 73.42312337888193952 ) ) ; +#12296 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#12297 = CARTESIAN_POINT ( 'NONE', ( -12.63831731427420202, 134.4151836745020603, 93.62390314900453347 ) ) ; +#12298 = CARTESIAN_POINT ( 'NONE', ( -36.32609607807000174, 191.0210417671000016, 106.7202350431000042 ) ) ; +#12299 = ORIENTED_EDGE ( 'NONE', *, *, #12266, .F. ) ; +#12300 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#12301 = CIRCLE ( 'NONE', #14932, 40.50000000000954259 ) ; +#12302 = DIRECTION ( 'NONE', ( 0.7933532970003733809, 0.5930762008556731413, 0.1372995488602877234 ) ) ; +#12303 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971548194 ) ) ; +#12305 = LINE ( 'NONE', #28061, #17443 ) ; +#12304 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921577410, 0.2249510932971595101 ) ) ; +#12306 = ORIENTED_EDGE ( 'NONE', *, *, #9876, .T. ) ; +#12307 = EDGE_CURVE ( 'NONE', #4523, #7538, #21665, .T. ) ; +#12308 = CARTESIAN_POINT ( 'NONE', ( -3.870875394724502261, 175.2781318081764539, 100.4635098585889921 ) ) ; +#12309 = VERTEX_POINT ( 'NONE', #29499 ) ; +#12310 = CARTESIAN_POINT ( 'NONE', ( -26.93661275769384034, 123.1497222377761744, 91.17945632601555417 ) ) ; +#12311 = EDGE_CURVE ( 'NONE', #33189, #22702, #707, .T. ) ; +#12312 = CARTESIAN_POINT ( 'NONE', ( 1.222756636386816309, 140.3954820326998458, 157.8542268366375652 ) ) ; +#12313 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#12314 = CARTESIAN_POINT ( 'NONE', ( -21.82845866733090290, 176.0428982100538633, 102.8745730682872335 ) ) ; +#12315 = VERTEX_POINT ( 'NONE', #31972 ) ; +#12316 = ORIENTED_EDGE ( 'NONE', *, *, #33974, .T. ) ; +#12317 = DIRECTION ( 'NONE', ( 0.0004270746993296996698, 0.7071067811865993091, 0.7071066522152992251 ) ) ; +#12318 = EDGE_CURVE ( 'NONE', #3145, #7166, #8712, .T. ) ; +#12319 = ADVANCED_FACE ( 'NONE', ( #26648 ), #1496, .F. ) ; +#12320 = CARTESIAN_POINT ( 'NONE', ( 45.36467309445081497, 70.87416510410297121, 322.7139789007268291 ) ) ; +#12321 = DIRECTION ( 'NONE', ( -0.9914446600486714889, -0.1273122826259382445, -0.02879355402772584838 ) ) ; +#12322 = ADVANCED_FACE ( 'NONE', ( #29100 ), #10302, .T. ) ; +#12323 = EDGE_LOOP ( 'NONE', ( #35895, #21306, #9368, #33769 ) ) ; +#12324 = AXIS2_PLACEMENT_3D ( 'NONE', #12502, #12123, #28266 ) ; +#12325 = CARTESIAN_POINT ( 'NONE', ( 6.034202883963867059, 175.3568768315410011, 100.1305289580489557 ) ) ; +#12326 = EDGE_CURVE ( 'NONE', #31407, #23412, #35394, .T. ) ; +#12327 = CARTESIAN_POINT ( 'NONE', ( 3.199984553827000422, 190.8627815815999895, 106.9328179595000137 ) ) ; +#12328 = AXIS2_PLACEMENT_3D ( 'NONE', #26085, #28740, #32015 ) ; +#12329 = ORIENTED_EDGE ( 'NONE', *, *, #7893, .T. ) ; +#12330 = EDGE_LOOP ( 'NONE', ( #9124, #2465, #25284, #32224 ) ) ; +#12331 = CARTESIAN_POINT ( 'NONE', ( 3.051314052528018905, 190.5208653972618436, 106.7217979537678758 ) ) ; +#12332 = CIRCLE ( 'NONE', #33201, 17.00000000000405009 ) ; +#12333 = CARTESIAN_POINT ( 'NONE', ( 13.49907723755937106, 124.5624338866822001, 88.66815556345785865 ) ) ; +#12334 = CYLINDRICAL_SURFACE ( 'NONE', #31359, 4.000000000000000000 ) ; +#12335 = CARTESIAN_POINT ( 'NONE', ( 22.49999746303471682, 151.9741732817970217, 94.72226965095939022 ) ) ; +#12336 = EDGE_LOOP ( 'NONE', ( #9606, #24115, #6326, #24467 ) ) ; +#12337 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989940797, 0.1373964268091562024 ) ) ; +#12338 = FACE_OUTER_BOUND ( 'NONE', #33236, .T. ) ; +#12339 = EDGE_LOOP ( 'NONE', ( #6837, #15134, #24215, #4592 ) ) ; +#12340 = DIRECTION ( 'NONE', ( 0.0005884949961280472970, -0.2249510543439049715, 0.9743698870671265722 ) ) ; +#12341 = VERTEX_POINT ( 'NONE', #34993 ) ; +#12343 = CARTESIAN_POINT ( 'NONE', ( 0.5626164669235433902, 188.9999987160578598, 103.6843922204118940 ) ) ; +#12342 = CARTESIAN_POINT ( 'NONE', ( -10.89647426556150833, 124.3650862926009779, 88.37149036441144290 ) ) ; +#12344 = ORIENTED_EDGE ( 'NONE', *, *, #38625, .T. ) ; +#12345 = VERTEX_POINT ( 'NONE', #10502 ) ; +#12346 = CARTESIAN_POINT ( 'NONE', ( 25.49081330879218044, 207.9931395123781215, 73.86028207133186640 ) ) ; +#12347 = VERTEX_POINT ( 'NONE', #29707 ) ; +#12348 = CARTESIAN_POINT ( 'NONE', ( 3.090413119796000085, 209.7016413904999865, 76.19244424849999575 ) ) ; +#12349 = EDGE_CURVE ( 'NONE', #11263, #20341, #7005, .T. ) ; +#12350 = AXIS2_PLACEMENT_3D ( 'NONE', #23398, #36261, #5173 ) ; +#12351 = CARTESIAN_POINT ( 'NONE', ( 15.59457679776800276, 126.7501638806706126, 179.2035388441636030 ) ) ; +#12352 = AXIS2_PLACEMENT_3D ( 'NONE', #26388, #20428, #10851 ) ; +#12353 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#12354 = ORIENTED_EDGE ( 'NONE', *, *, #39628, .F. ) ; +#12355 = ORIENTED_EDGE ( 'NONE', *, *, #15722, .T. ) ; +#12356 = CIRCLE ( 'NONE', #15618, 9.999999999999996447 ) ; +#12357 = EDGE_LOOP ( 'NONE', ( #13406, #3340, #1868, #24563 ) ) ; +#12358 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971560961 ) ) ; +#12359 = EDGE_CURVE ( 'NONE', #6112, #7629, #16407, .T. ) ; +#12360 = PLANE ( 'NONE', #19391 ) ; +#12361 = CARTESIAN_POINT ( 'NONE', ( 2.780936256401183027, 209.6646845776446639, 73.22349160306428928 ) ) ; +#12362 = EDGE_CURVE ( 'NONE', #1613, #38340, #8039, .T. ) ; +#12363 = VERTEX_POINT ( 'NONE', #22967 ) ; +#12364 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36669, #9074, #2533, #15002 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12365 = ORIENTED_EDGE ( 'NONE', *, *, #9973, .T. ) ; +#12366 = DIRECTION ( 'NONE', ( -0.6974360921310663874, 0.000000000000000000, 0.7166469824069217065 ) ) ; +#12367 = LINE ( 'NONE', #2770, #35027 ) ; +#12368 = CARTESIAN_POINT ( 'NONE', ( -26.93797805943999890, 123.8239009188999944, 88.25611663338999335 ) ) ; +#12369 = EDGE_CURVE ( 'NONE', #37610, #10990, #11313, .T. ) ; +#12370 = EDGE_LOOP ( 'NONE', ( #30935, #1986, #36112, #35541 ) ) ; +#12371 = CARTESIAN_POINT ( 'NONE', ( -6.035970131895957103, 134.2433943441971849, 93.72800934087076996 ) ) ; +#12372 = CARTESIAN_POINT ( 'NONE', ( -10.03626368673879909, 143.6497483427974089, 95.38890159966688032 ) ) ; +#12373 = EDGE_LOOP ( 'NONE', ( #17723, #21380, #37319, #33136 ) ) ; +#12374 = CARTESIAN_POINT ( 'NONE', ( 6.035541027891230925, 134.8446529991751390, 93.34637782540107764 ) ) ; +#12375 = LINE ( 'NONE', #9317, #9853 ) ; +#12376 = CARTESIAN_POINT ( 'NONE', ( -15.97823384701243654, 126.4186299334870682, 88.84861179911453632 ) ) ; +#12377 = VECTOR ( 'NONE', #23433, 999.9999999999998863 ) ; +#12378 = CARTESIAN_POINT ( 'NONE', ( -44.92182064607283820, 181.3727636826805849, 101.7243074837133463 ) ) ; +#12379 = CARTESIAN_POINT ( 'NONE', ( -13.49368727016981317, 188.3420864354374942, 103.1432701936051330 ) ) ; +#12380 = AXIS2_PLACEMENT_3D ( 'NONE', #29844, #11429, #1617 ) ; +#12381 = ORIENTED_EDGE ( 'NONE', *, *, #34047, .T. ) ; +#12382 = CARTESIAN_POINT ( 'NONE', ( -38.95487693986203936, 209.7096538831000316, 76.08203239908557691 ) ) ; +#12383 = ORIENTED_EDGE ( 'NONE', *, *, #37145, .F. ) ; +#12384 = CARTESIAN_POINT ( 'NONE', ( 42.09376931258240262, 76.09060330161743479, 288.9541785520312942 ) ) ; +#12385 = DIRECTION ( 'NONE', ( 0.0005884949961215158462, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#12386 = CONICAL_SURFACE ( 'NONE', #8482, 2.503000005691713437, 0.7853981633624692593 ) ; +#12387 = CARTESIAN_POINT ( 'NONE', ( 36.19070910591000256, 112.4013982383000041, 89.61166937401999633 ) ) ; +#12388 = VERTEX_POINT ( 'NONE', #26242 ) ; +#12389 = DIRECTION ( 'NONE', ( -6.560328681078656304E-13, -0.9743700555413093989, -0.2249510943837032262 ) ) ; +#12390 = ORIENTED_EDGE ( 'NONE', *, *, #4633, .T. ) ; +#12391 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #2455, #14917, #27204, #15125 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 6.279468620546222901, 9.421061274136016905 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.3333333333333330373, 0.3333333333333330373, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#12392 = CARTESIAN_POINT ( 'NONE', ( -13.49852954174878050, 185.3437907798762012, 105.0168226363017823 ) ) ; +#12393 = ORIENTED_EDGE ( 'NONE', *, *, #16046, .T. ) ; +#12394 = ADVANCED_FACE ( 'NONE', ( #23164 ), #35594, .F. ) ; +#12395 = CARTESIAN_POINT ( 'NONE', ( 25.53626815854681098, 191.3673954314083119, 104.3312944428767253 ) ) ; +#12396 = EDGE_CURVE ( 'NONE', #35551, #27237, #11096, .T. ) ; +#12397 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#12398 = CARTESIAN_POINT ( 'NONE', ( -37.29435884442529670, 164.6092402323636463, 198.2106787237848948 ) ) ; +#12399 = ADVANCED_FACE ( 'NONE', ( #39289 ), #36440, .T. ) ; +#12400 = CARTESIAN_POINT ( 'NONE', ( -3.587237990978591196, 174.6869248071862728, 103.0110717490532863 ) ) ; +#12401 = ADVANCED_FACE ( 'NONE', ( #20902 ), #30259, .F. ) ; +#12402 = CARTESIAN_POINT ( 'NONE', ( -0.4540625018068648600, 211.4999999999330385, 76.05877887195120479 ) ) ; +#12403 = ORIENTED_EDGE ( 'NONE', *, *, #24940, .T. ) ; +#12404 = ORIENTED_EDGE ( 'NONE', *, *, #18800, .T. ) ; +#12406 = AXIS2_PLACEMENT_3D ( 'NONE', #37813, #37220, #25165 ) ; +#12405 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#12407 = CIRCLE ( 'NONE', #17617, 2.749999999947594809 ) ; +#12408 = LINE ( 'NONE', #28172, #3324 ) ; +#12409 = EDGE_CURVE ( 'NONE', #2748, #23210, #39697, .T. ) ; +#12410 = CIRCLE ( 'NONE', #15669, 9.499999999959616304 ) ; +#12411 = ORIENTED_EDGE ( 'NONE', *, *, #17107, .F. ) ; +#12412 = CARTESIAN_POINT ( 'NONE', ( 30.06907885326216956, 134.5379029013527372, 93.52626355848663309 ) ) ; +#12413 = AXIS2_PLACEMENT_3D ( 'NONE', #28000, #25132, #21247 ) ; +#12414 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.265515830298980555E-14, 0.9999998176071847045 ) ) ; +#12415 = EDGE_LOOP ( 'NONE', ( #5678, #29420, #25415, #33015 ) ) ; +#12416 = FACE_BOUND ( 'NONE', #29102, .T. ) ; +#12417 = ADVANCED_FACE ( 'NONE', ( #11292 ), #17975, .T. ) ; +#12418 = CARTESIAN_POINT ( 'NONE', ( 36.44436247437651133, 190.8511614233640330, 106.7712946021073606 ) ) ; +#12419 = VERTEX_POINT ( 'NONE', #39492 ) ; +#12420 = CARTESIAN_POINT ( 'NONE', ( 20.00179988782546303, 151.3105026749326498, 97.65252212824069034 ) ) ; +#12421 = LINE ( 'NONE', #14894, #32904 ) ; +#12422 = CARTESIAN_POINT ( 'NONE', ( -26.12776248260999878, 191.4935114680999959, 107.0493518302999973 ) ) ; +#12423 = DIRECTION ( 'NONE', ( -0.9914448496661262267, -0.1271951663094869345, -0.02930016617724677530 ) ) ; +#12424 = DIRECTION ( 'NONE', ( -0.0004161288024423686130, 0.8480480898092171982, -0.5299191110044603192 ) ) ; +#12425 = EDGE_LOOP ( 'NONE', ( #19387, #27381, #32611, #6939 ) ) ; +#12426 = CARTESIAN_POINT ( 'NONE', ( 20.00172860684155296, 119.4205927620089511, 90.29021467756710706 ) ) ; +#12427 = LINE ( 'NONE', #12239, #19231 ) ; +#12428 = CARTESIAN_POINT ( 'NONE', ( 41.20365586323013218, 166.2350915183740199, 182.1795392662229460 ) ) ; +#12429 = CARTESIAN_POINT ( 'NONE', ( -46.09104340708901759, 125.3201889036950121, 91.70237867473788640 ) ) ; +#12430 = VERTEX_POINT ( 'NONE', #8444 ) ; +#12431 = CARTESIAN_POINT ( 'NONE', ( 35.54748823936935764, 207.8686442304273783, 77.25557267514689386 ) ) ; +#12432 = CARTESIAN_POINT ( 'NONE', ( -28.47589466077455356, 181.0102030230047774, 104.5385275604374868 ) ) ; +#12433 = LINE ( 'NONE', #5703, #11133 ) ; +#12434 = CARTESIAN_POINT ( 'NONE', ( 12.63858367850300901, 181.2871484996189224, 104.3452895154150610 ) ) ; +#12435 = VECTOR ( 'NONE', #17433, 1000.000000000000000 ) ; +#12436 = VECTOR ( 'NONE', #9159, 1000.000000000000000 ) ; +#12437 = CARTESIAN_POINT ( 'NONE', ( 43.13643525274928692, 121.2996634179292244, 90.62573206238681678 ) ) ; +#12438 = CARTESIAN_POINT ( 'NONE', ( -36.05289769043999826, 191.5977046145999907, 104.0138136777000000 ) ) ; +#12439 = CARTESIAN_POINT ( 'NONE', ( -27.14198910785439622, 187.2709762456960334, 105.4665680530039964 ) ) ; +#12440 = AXIS2_PLACEMENT_3D ( 'NONE', #17160, #35546, #7359 ) ; +#12441 = VECTOR ( 'NONE', #436, 999.9999999999998863 ) ; +#12442 = CARTESIAN_POINT ( 'NONE', ( -12.63996651235540902, 181.7913221907940056, 101.7730704815222111 ) ) ; +#12443 = CARTESIAN_POINT ( 'NONE', ( 4.661812031426219249, 181.8946891593557496, 101.6438055088770938 ) ) ; +#12444 = ORIENTED_EDGE ( 'NONE', *, *, #28884, .T. ) ; +#12445 = CARTESIAN_POINT ( 'NONE', ( 20.79310939989340667, 105.5805168952036865, 87.25522577498226440 ) ) ; +#12446 = DIRECTION ( 'NONE', ( 0.0005559617641628925759, -0.3907311284886304525, 0.9205046855592415866 ) ) ; +#12447 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; +#12448 = CYLINDRICAL_SURFACE ( 'NONE', #644, 40.00000000000000000 ) ; +#12449 = CARTESIAN_POINT ( 'NONE', ( 36.67679961381649179, 191.6498457339000367, 104.3241930055519902 ) ) ; +#12450 = EDGE_CURVE ( 'NONE', #24015, #410, #36845, .T. ) ; +#12451 = ORIENTED_EDGE ( 'NONE', *, *, #37508, .F. ) ; +#12452 = CARTESIAN_POINT ( 'NONE', ( 36.48844669939000340, 190.9983962132999977, 106.6711395593000020 ) ) ; +#12453 = ORIENTED_EDGE ( 'NONE', *, *, #1364, .T. ) ; +#12454 = ORIENTED_EDGE ( 'NONE', *, *, #4, .F. ) ; +#12455 = CARTESIAN_POINT ( 'NONE', ( -5.886983627058991253, 134.9177829378408546, 90.80470137495024119 ) ) ; +#12456 = CARTESIAN_POINT ( 'NONE', ( -20.00017858637951207, 184.9560350789418237, 102.3655360699851400 ) ) ; +#12457 = CARTESIAN_POINT ( 'NONE', ( -35.79114221331672496, 138.5178166623233267, 284.1865182878368046 ) ) ; +#12458 = LINE ( 'NONE', #27827, #12224 ) ; +#12459 = ORIENTED_EDGE ( 'NONE', *, *, #26815, .T. ) ; +#12460 = CARTESIAN_POINT ( 'NONE', ( 36.19901194252000209, 191.5845064965000120, 103.9677379098999950 ) ) ; +#12461 = VECTOR ( 'NONE', #823, 1000.000000000000000 ) ; +#12462 = CARTESIAN_POINT ( 'NONE', ( -29.20280672789058585, 163.6356169074005038, 97.44881913872031021 ) ) ; +#12463 = CARTESIAN_POINT ( 'NONE', ( 3.534206243108678702, 168.5015396740323581, 98.55243403413919623 ) ) ; +#12464 = DIRECTION ( 'NONE', ( 0.9999998175395372613, 1.407738652158796084E-07, -0.0006040868085093890937 ) ) ; +#12465 = EDGE_LOOP ( 'NONE', ( #6761, #35183, #34498, #10216 ) ) ; +#12466 = DIRECTION ( 'NONE', ( -0.0006039748319391171662, -1.156185249762965862E-14, -0.9999998176071845934 ) ) ; +#12467 = DIRECTION ( 'NONE', ( -0.9999998268370372534, -0.0001323821189253526732, 0.0005734116061135543282 ) ) ; +#12468 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#12469 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319392994206 ) ) ; +#12470 = ORIENTED_EDGE ( 'NONE', *, *, #15151, .F. ) ; +#12471 = EDGE_CURVE ( 'NONE', #37217, #38178, #27185, .T. ) ; +#12472 = CARTESIAN_POINT ( 'NONE', ( 41.48445246824149990, 178.0501759457868047, 154.4334962872288486 ) ) ; +#12473 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21998, #38322, #13191, #35023 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12474 = CARTESIAN_POINT ( 'NONE', ( 1.549369715379940171, 189.2660695586559996, 103.7710140332699922 ) ) ; +#12475 = CARTESIAN_POINT ( 'NONE', ( 21.70411919715960636, 123.1894919172633820, 176.5216962859745138 ) ) ; +#12476 = ORIENTED_EDGE ( 'NONE', *, *, #24386, .F. ) ; +#12477 = CARTESIAN_POINT ( 'NONE', ( -3.787401097931438976, 136.7351866886963307, 94.04403444543387991 ) ) ; +#12478 = ORIENTED_EDGE ( 'NONE', *, *, #20100, .F. ) ; +#12479 = DIRECTION ( 'NONE', ( 0.7933532411498429582, 0.5931841216338330502, 0.1368328637372506207 ) ) ; +#12480 = CARTESIAN_POINT ( 'NONE', ( 20.00075430379012431, 195.1419555450835901, 105.8098312386177611 ) ) ; +#12481 = AXIS2_PLACEMENT_3D ( 'NONE', #6970, #14538, #10666 ) ; +#12482 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700561807850935, -0.2249510916138304228 ) ) ; +#12483 = VECTOR ( 'NONE', #4261, 1000.000000000000114 ) ; +#12484 = LINE ( 'NONE', #28836, #34382 ) ; +#12485 = AXIS2_PLACEMENT_3D ( 'NONE', #38765, #16887, #10785 ) ; +#12486 = FACE_OUTER_BOUND ( 'NONE', #14291, .T. ) ; +#12487 = FACE_OUTER_BOUND ( 'NONE', #26029, .T. ) ; +#12488 = CARTESIAN_POINT ( 'NONE', ( -36.62664004177000265, 191.5516215956000110, 106.2738151150000050 ) ) ; +#12489 = ORIENTED_EDGE ( 'NONE', *, *, #20573, .F. ) ; +#12490 = DIRECTION ( 'NONE', ( 1.110223024658119567E-14, 0.9743700557921588512, 0.2249510932971552357 ) ) ; +#12491 = CARTESIAN_POINT ( 'NONE', ( 18.96935628814378205, 149.0855185795807358, 180.7389095938138723 ) ) ; +#12492 = PLANE ( 'NONE', #13115 ) ; +#12493 = EDGE_CURVE ( 'NONE', #8120, #35545, #3591, .T. ) ; +#12494 = EDGE_CURVE ( 'NONE', #36048, #24997, #17612, .T. ) ; +#12496 = CARTESIAN_POINT ( 'NONE', ( 45.34583945090627566, 78.07328829186270980, 291.5311561844757193 ) ) ; +#12495 = CYLINDRICAL_SURFACE ( 'NONE', #37602, 4.999999999999990230 ) ; +#12497 = EDGE_LOOP ( 'NONE', ( #4849, #11145, #23600, #26347 ) ) ; +#12498 = EDGE_CURVE ( 'NONE', #10320, #33584, #23982, .T. ) ; +#12499 = ORIENTED_EDGE ( 'NONE', *, *, #17365, .F. ) ; +#12500 = ORIENTED_EDGE ( 'NONE', *, *, #533, .T. ) ; +#12501 = LINE ( 'NONE', #19228, #2198 ) ; +#12502 = CARTESIAN_POINT ( 'NONE', ( -35.43925701460831590, 191.9759150222000130, 101.9428517635840308 ) ) ; +#12503 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319378242551 ) ) ; +#12504 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971521271 ) ) ; +#12505 = CARTESIAN_POINT ( 'NONE', ( -5.669876885524050891, 185.9078784969169647, 102.5734907446166488 ) ) ; +#12506 = ORIENTED_EDGE ( 'NONE', *, *, #17648, .T. ) ; +#12507 = CARTESIAN_POINT ( 'NONE', ( 3.667815741540035646, 183.5629855103865964, 104.5953232250576406 ) ) ; +#12508 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8890, #15014, #2747, #6004, #24639, #74 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 3.469446951953614189E-18, 0.0003816501766251246077, 0.0007633003532502457460 ), + .UNSPECIFIED. ) ; +#12509 = ORIENTED_EDGE ( 'NONE', *, *, #4426, .T. ) ; +#12510 = DIRECTION ( 'NONE', ( 0.0001408404346086777274, -0.2255194953558356530, 0.9742386449830560124 ) ) ; +#12511 = AXIS2_PLACEMENT_3D ( 'NONE', #6772, #10477, #15982 ) ; +#12512 = CARTESIAN_POINT ( 'NONE', ( -38.94514605625099080, 127.5103311478221428, 92.19343525405152207 ) ) ; +#12513 = ORIENTED_EDGE ( 'NONE', *, *, #25489, .T. ) ; +#12514 = EDGE_CURVE ( 'NONE', #27328, #1942, #33767, .T. ) ; +#12515 = DIRECTION ( 'NONE', ( 0.0005884950030978173272, -0.2249510543490929049, 0.9743698870659246447 ) ) ; +#12516 = CARTESIAN_POINT ( 'NONE', ( 3.019577864247297683, 190.5696393177559855, 103.6475677936285393 ) ) ; +#12517 = CARTESIAN_POINT ( 'NONE', ( -26.01010085237201608, 207.3561686807771025, 73.63559236472087832 ) ) ; +#12518 = CARTESIAN_POINT ( 'NONE', ( -23.36405564437416160, 181.2107043992663193, 104.4107232363765405 ) ) ; +#12519 = VERTEX_POINT ( 'NONE', #27265 ) ; +#12520 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#12521 = ORIENTED_EDGE ( 'NONE', *, *, #24096, .F. ) ; +#12522 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34920, #4256, #19404, #13681, #20001, #16925, #29230, #6936, #16338, #28824, #1204, #26172, #13289, #38610, #7134, #38221, #10231, #22700, #39416, #14900 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000276168, 0.1875000000000308087, 0.2187500000000323630, 0.2343750000000343892, 0.2500000000000363598, 0.5000000000000545120, 0.6250000000000563993, 0.6875000000000517364, 0.7187500000000448530, 0.7343750000000406342, 0.7500000000000364153, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12523 = CARTESIAN_POINT ( 'NONE', ( 13.49908594566202247, 124.5584662421294411, 88.66180599625475622 ) ) ; +#12524 = DIRECTION ( 'NONE', ( 0.6087614810001803489, -0.7729390313185898753, -0.1788147452386047442 ) ) ; +#12525 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250614502, 179.6252109630515861, 101.6466942236996545 ) ) ; +#12526 = ADVANCED_FACE ( 'NONE', ( #39902 ), #14575, .F. ) ; +#12527 = ORIENTED_EDGE ( 'NONE', *, *, #17883, .T. ) ; +#12528 = CARTESIAN_POINT ( 'NONE', ( -26.00034782847161097, 118.8155664120999973, 94.28348912735243914 ) ) ; +#12529 = CARTESIAN_POINT ( 'NONE', ( 25.01965291402757074, 130.5048960499642874, 90.28039427238843473 ) ) ; +#12530 = ADVANCED_FACE ( 'NONE', ( #14367 ), #24398, .F. ) ; +#12531 = ORIENTED_EDGE ( 'NONE', *, *, #36305, .T. ) ; +#12532 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; +#12533 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2648, #27796, #17742, #2036 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12534 = CARTESIAN_POINT ( 'NONE', ( 3.333124212584731350, 128.5496412282928134, 89.49999704006384604 ) ) ; +#12535 = EDGE_CURVE ( 'NONE', #37266, #24828, #17273, .T. ) ; +#12536 = AXIS2_PLACEMENT_3D ( 'NONE', #30694, #5742, #9223 ) ; +#12537 = EDGE_CURVE ( 'NONE', #32614, #23325, #19293, .T. ) ; +#12539 = CARTESIAN_POINT ( 'NONE', ( -12.63633280681442450, 127.9091152082197596, 92.26961196159911083 ) ) ; +#12538 = CARTESIAN_POINT ( 'NONE', ( 36.28391671458184931, 191.9163365515095450, 104.3733954516321205 ) ) ; +#12540 = EDGE_CURVE ( 'NONE', #26136, #35217, #30442, .T. ) ; +#12541 = ORIENTED_EDGE ( 'NONE', *, *, #1459, .F. ) ; +#12542 = VECTOR ( 'NONE', #33847, 1000.000000000000114 ) ; +#12543 = CARTESIAN_POINT ( 'NONE', ( 25.49062705787940430, 209.2715578566350985, 73.54304421361712230 ) ) ; +#12544 = EDGE_CURVE ( 'NONE', #7316, #25177, #2299, .T. ) ; +#12545 = AXIS2_PLACEMENT_3D ( 'NONE', #10209, #29208, #35099 ) ; +#12546 = EDGE_LOOP ( 'NONE', ( #12984, #22394, #32576, #23357 ) ) ; +#12547 = CARTESIAN_POINT ( 'NONE', ( -14.78542069845082807, 129.1241041573916561, 89.98565157148227911 ) ) ; +#12548 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#12549 = ORIENTED_EDGE ( 'NONE', *, *, #29537, .T. ) ; +#12550 = ORIENTED_EDGE ( 'NONE', *, *, #26635, .T. ) ; +#12551 = FACE_OUTER_BOUND ( 'NONE', #31286, .T. ) ; +#12552 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684999950, 226.4002260771010810, 75.57961659099107976 ) ) ; +#12553 = CARTESIAN_POINT ( 'NONE', ( 36.46831602377621806, 265.1087381855853664, 205.0355407830140848 ) ) ; +#12554 = FACE_OUTER_BOUND ( 'NONE', #36985, .T. ) ; +#12555 = VERTEX_POINT ( 'NONE', #21530 ) ; +#12556 = ORIENTED_EDGE ( 'NONE', *, *, #24110, .T. ) ; +#12557 = ORIENTED_EDGE ( 'NONE', *, *, #36164, .F. ) ; +#12558 = PLANE ( 'NONE', #6302 ) ; +#12559 = CARTESIAN_POINT ( 'NONE', ( 20.48129703347667530, 210.1695351468016213, 75.54578054753540073 ) ) ; +#12560 = CYLINDRICAL_SURFACE ( 'NONE', #3926, 2.000000000000014655 ) ; +#12561 = ORIENTED_EDGE ( 'NONE', *, *, #20337, .F. ) ; +#12562 = CARTESIAN_POINT ( 'NONE', ( -26.58079033504462885, 156.9880731489196535, 180.0252060707828434 ) ) ; +#12563 = CARTESIAN_POINT ( 'NONE', ( -28.70875734540877389, 163.5999644878620245, 97.95344188170561495 ) ) ; +#12564 = VERTEX_POINT ( 'NONE', #19021 ) ; +#12565 = AXIS2_PLACEMENT_3D ( 'NONE', #3605, #16289, #9568 ) ; +#12566 = CARTESIAN_POINT ( 'NONE', ( 3.931232797397531620, 174.7711649246031698, 102.6726659245351669 ) ) ; +#12567 = CARTESIAN_POINT ( 'NONE', ( -5.667065257250070154, 187.5516406194990964, 105.8752373800145250 ) ) ; +#12568 = VECTOR ( 'NONE', #7342, 1000.000000000000227 ) ; +#12569 = CARTESIAN_POINT ( 'NONE', ( 15.05323202847136876, 135.9260618574729165, 94.10374647281754790 ) ) ; +#12570 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178630073228E-05, 0.0002331579774917273760 ) ) ; +#12571 = ADVANCED_FACE ( 'NONE', ( #9643 ), #3616, .F. ) ; +#12572 = ORIENTED_EDGE ( 'NONE', *, *, #34270, .T. ) ; +#12573 = DIRECTION ( 'NONE', ( 0.0006039748319381496242, 1.231904546584163304E-14, 0.9999998176071845934 ) ) ; +#12574 = ORIENTED_EDGE ( 'NONE', *, *, #30483, .F. ) ; +#12575 = CARTESIAN_POINT ( 'NONE', ( 34.60472611796191700, 77.14301703111517838, 291.5376435477833184 ) ) ; +#12576 = CARTESIAN_POINT ( 'NONE', ( -12.59997215317999952, 114.0103269030000064, 152.4718672074000381 ) ) ; +#12577 = CARTESIAN_POINT ( 'NONE', ( 38.28154465117000171, 117.9980501572999998, 89.51170082983999521 ) ) ; +#12578 = EDGE_CURVE ( 'NONE', #4594, #23181, #12111, .T. ) ; +#12579 = CARTESIAN_POINT ( 'NONE', ( -28.47344760044883216, 181.6851202344923308, 101.6154648382260035 ) ) ; +#12580 = ORIENTED_EDGE ( 'NONE', *, *, #30924, .T. ) ; +#12581 = CARTESIAN_POINT ( 'NONE', ( -37.83642973982261282, 190.5638649247831324, 106.5787699739197194 ) ) ; +#12582 = ORIENTED_EDGE ( 'NONE', *, *, #19324, .T. ) ; +#12583 = ADVANCED_FACE ( 'NONE', ( #37445 ), #8222, .T. ) ; +#12584 = PLANE ( 'NONE', #4689 ) ; +#12585 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10028, #9232, #28437, #3670, #6146, #12480, #413, #16155, #38028, #22512 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.1624485751913120335, 0.3718364313934839904, 0.5812242875956560306, 0.7906121437978279598, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12586 = FACE_OUTER_BOUND ( 'NONE', #31239, .T. ) ; +#12587 = EDGE_CURVE ( 'NONE', #13011, #18476, #19219, .T. ) ; +#12588 = AXIS2_PLACEMENT_3D ( 'NONE', #5014, #29971, #1968 ) ; +#12589 = CARTESIAN_POINT ( 'NONE', ( 3.501239785661707238, 126.2036380141990435, 91.52403092931761819 ) ) ; +#12590 = ORIENTED_EDGE ( 'NONE', *, *, #12639, .F. ) ; +#12591 = CARTESIAN_POINT ( 'NONE', ( 37.84431823005125040, 145.7926053428699333, 287.8095652956209847 ) ) ; +#12592 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#12593 = CARTESIAN_POINT ( 'NONE', ( -32.93322112599078366, 163.3558671954971544, 188.7454894968532244 ) ) ; +#12594 = CARTESIAN_POINT ( 'NONE', ( 9.991643147283999937, 184.7670343400000377, 28.07991271570000080 ) ) ; +#12595 = AXIS2_PLACEMENT_3D ( 'NONE', #10751, #29557, #14018 ) ; +#12596 = ORIENTED_EDGE ( 'NONE', *, *, #11935, .F. ) ; +#12597 = CARTESIAN_POINT ( 'NONE', ( -37.91235354210377295, 118.6199237442390313, 90.29068295074328887 ) ) ; +#12598 = EDGE_LOOP ( 'NONE', ( #5660, #36830 ) ) ; +#12599 = VERTEX_POINT ( 'NONE', #2894 ) ; +#12600 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.295171136338797037E-14 ) ) ; +#12601 = AXIS2_PLACEMENT_3D ( 'NONE', #2281, #24167, #2079 ) ; +#12602 = DIRECTION ( 'NONE', ( -0.7947983679126053858, 0.5912140607310470974, 0.1369725839625021979 ) ) ; +#12603 = VERTEX_POINT ( 'NONE', #15375 ) ; +#12604 = CARTESIAN_POINT ( 'NONE', ( 22.78079353263602869, 153.8098031058628692, 95.66210622315543333 ) ) ; +#12605 = CARTESIAN_POINT ( 'NONE', ( -31.19629630733280123, 110.6131156702000027, 90.28662662044676779 ) ) ; +#12606 = ORIENTED_EDGE ( 'NONE', *, *, #854, .F. ) ; +#12607 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927789280832, 0.0005734119022080210902 ) ) ; +#12608 = CARTESIAN_POINT ( 'NONE', ( -20.24985248663000093, 167.5688041279000231, 98.60803583700000274 ) ) ; +#12609 = LINE ( 'NONE', #21832, #2548 ) ; +#12610 = CARTESIAN_POINT ( 'NONE', ( -30.07188603208757627, 134.6282626475015718, 93.49931109589789457 ) ) ; +#12611 = EDGE_LOOP ( 'NONE', ( #50, #12404, #4958, #28066 ) ) ; +#12612 = CARTESIAN_POINT ( 'NONE', ( 28.42171666135000052, 125.3747123081999888, 88.75240862220999816 ) ) ; +#12613 = CARTESIAN_POINT ( 'NONE', ( -0.4015619331524885594, 189.0000000000001705, 162.9824824844031923 ) ) ; +#12614 = DIRECTION ( 'NONE', ( 0.0005884949961247478529, -0.2249510543439059707, 0.9743698870671264611 ) ) ; +#12615 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16093, #12426, #25321, #13041 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12616 = LINE ( 'NONE', #18341, #8509 ) ; +#12617 = CARTESIAN_POINT ( 'NONE', ( 6.026693642215255053, 134.9199437178238838, 90.79804054718465522 ) ) ; +#12618 = ORIENTED_EDGE ( 'NONE', *, *, #32122, .F. ) ; +#12619 = CARTESIAN_POINT ( 'NONE', ( -14.02928418406383493, 177.4085734206051370, 100.6193928479417821 ) ) ; +#12620 = LINE ( 'NONE', #25124, #12091 ) ; +#12621 = VECTOR ( 'NONE', #15264, 1000.000000000000114 ) ; +#12622 = CARTESIAN_POINT ( 'NONE', ( -30.17790789685632546, 126.0796628920969624, 91.85784452133538025 ) ) ; +#12623 = ADVANCED_FACE ( 'NONE', ( #28060 ), #34363, .T. ) ; +#12624 = ADVANCED_FACE ( 'NONE', ( #427 ), #33002, .F. ) ; +#12625 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#12626 = EDGE_CURVE ( 'NONE', #1454, #26218, #22166, .T. ) ; +#12627 = VERTEX_POINT ( 'NONE', #18415 ) ; +#12628 = CIRCLE ( 'NONE', #30262, 5.000000000000007994 ) ; +#12629 = CARTESIAN_POINT ( 'NONE', ( 38.48677490565238202, 119.0290109290786660, 90.25014311654231847 ) ) ; +#12630 = ADVANCED_FACE ( 'NONE', ( #223 ), #35581, .F. ) ; +#12631 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15247, #18681, #31588, #27548 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12632 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; +#12633 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319438170742 ) ) ; +#12634 = AXIS2_PLACEMENT_3D ( 'NONE', #23229, #1963, #17262 ) ; +#12635 = CARTESIAN_POINT ( 'NONE', ( -3.169881913554984720, 185.9062129263137138, 102.5746722649703315 ) ) ; +#12636 = CARTESIAN_POINT ( 'NONE', ( -35.90108692076000096, 191.4428160530999889, 103.7426355487000080 ) ) ; +#12637 = CARTESIAN_POINT ( 'NONE', ( -25.50472234486060330, 190.9264852796360117, 106.3095200974499903 ) ) ; +#12638 = ORIENTED_EDGE ( 'NONE', *, *, #8308, .T. ) ; +#12639 = EDGE_CURVE ( 'NONE', #16029, #37703, #11433, .T. ) ; +#12640 = CARTESIAN_POINT ( 'NONE', ( -19.44498782237791090, 147.7042974102395476, 183.5443419389730479 ) ) ; +#12641 = EDGE_CURVE ( 'NONE', #15470, #20231, #29976, .T. ) ; +#12642 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#12643 = DIRECTION ( 'NONE', ( 0.0006039748319385408043, -1.387778780781445676E-14, 0.9999998176071847045 ) ) ; +#12644 = VERTEX_POINT ( 'NONE', #22120 ) ; +#12645 = FACE_OUTER_BOUND ( 'NONE', #5229, .T. ) ; +#12646 = DIRECTION ( 'NONE', ( 0.6087614115766663003, -0.7730004587899187429, -0.1785492494684860765 ) ) ; +#12647 = CARTESIAN_POINT ( 'NONE', ( 18.58912714118548237, 148.0271172827300177, 184.1229846802908128 ) ) ; +#12648 = CARTESIAN_POINT ( 'NONE', ( 37.96500512368779567, 190.9590560386920401, 106.3030183870149870 ) ) ; +#12649 = CARTESIAN_POINT ( 'NONE', ( 36.28049130005999956, 190.7845793118999893, 106.9053359681000046 ) ) ; +#12650 = VERTEX_POINT ( 'NONE', #3476 ) ; +#12651 = ORIENTED_EDGE ( 'NONE', *, *, #28113, .F. ) ; +#12652 = ORIENTED_EDGE ( 'NONE', *, *, #312, .F. ) ; +#12653 = ADVANCED_FACE ( 'NONE', ( #3093 ), #14772, .T. ) ; +#12654 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#12655 = AXIS2_PLACEMENT_3D ( 'NONE', #23649, #36098, #8101 ) ; +#12656 = CARTESIAN_POINT ( 'NONE', ( -14.55294119842380063, 130.1498083917327904, 89.70916153464222020 ) ) ; +#12657 = AXIS2_PLACEMENT_3D ( 'NONE', #34990, #23318, #264 ) ; +#12658 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971560129 ) ) ; +#12659 = ORIENTED_EDGE ( 'NONE', *, *, #27859, .T. ) ; +#12660 = CARTESIAN_POINT ( 'NONE', ( -1.207315383879569826, 135.0326567407394123, 181.1141214092984910 ) ) ; +#12661 = AXIS2_PLACEMENT_3D ( 'NONE', #28446, #423, #12300 ) ; +#12662 = EDGE_LOOP ( 'NONE', ( #20454, #37305, #5626, #28351 ) ) ; +#12663 = CARTESIAN_POINT ( 'NONE', ( 36.02454694495000354, 114.4457312457000171, 87.61277106880000076 ) ) ; +#12664 = AXIS2_PLACEMENT_3D ( 'NONE', #39658, #5515, #7120 ) ; +#12665 = CARTESIAN_POINT ( 'NONE', ( -14.78542071362066679, 136.5876434558166750, 91.70874570386088465 ) ) ; +#12666 = CARTESIAN_POINT ( 'NONE', ( -36.85476990611584824, 191.5514496331472571, 104.3846969233319584 ) ) ; +#12667 = ORIENTED_EDGE ( 'NONE', *, *, #19120, .F. ) ; +#12668 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#12669 = CARTESIAN_POINT ( 'NONE', ( -43.30038974941377461, 190.4174923657541285, 106.7193308803196601 ) ) ; +#12670 = CARTESIAN_POINT ( 'NONE', ( 26.03373140117899709, 191.5260202047026041, 103.8544635878054976 ) ) ; +#12671 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; +#12672 = CARTESIAN_POINT ( 'NONE', ( -9.336298582408000257, 134.5427877351000063, 93.54254700600999684 ) ) ; +#12673 = CARTESIAN_POINT ( 'NONE', ( -38.95668886436793343, 209.7096538830999748, 73.08203294638809666 ) ) ; +#12674 = ORIENTED_EDGE ( 'NONE', *, *, #13776, .F. ) ; +#12675 = VERTEX_POINT ( 'NONE', #33964 ) ; +#12676 = CARTESIAN_POINT ( 'NONE', ( 42.42192200091505327, 180.1607944338011862, 148.5017479457221441 ) ) ; +#12677 = CARTESIAN_POINT ( 'NONE', ( 1.316965049921220210, 189.1517910606459907, 103.7366099239109900 ) ) ; +#12678 = LINE ( 'NONE', #37031, #33192 ) ; +#12679 = ADVANCED_FACE ( 'NONE', ( #15956 ), #12495, .T. ) ; +#12680 = ORIENTED_EDGE ( 'NONE', *, *, #7127, .F. ) ; +#12681 = FACE_OUTER_BOUND ( 'NONE', #35001, .T. ) ; +#12682 = ADVANCED_FACE ( 'NONE', ( #37841 ), #16693, .F. ) ; +#12683 = ORIENTED_EDGE ( 'NONE', *, *, #27156, .F. ) ; +#12684 = CONICAL_SURFACE ( 'NONE', #11462, 2.503100609244825581, 0.7853981633679828489 ) ; +#12685 = CARTESIAN_POINT ( 'NONE', ( -40.95638651213572956, 220.4002260740000168, 73.58324080466404382 ) ) ; +#12686 = CONICAL_SURFACE ( 'NONE', #25113, 2.503000016660633875, 0.7853981634016408142 ) ; +#12687 = VECTOR ( 'NONE', #29598, 1000.000000000000227 ) ; +#12688 = PLANE ( 'NONE', #39108 ) ; +#12689 = EDGE_CURVE ( 'NONE', #15505, #9438, #16167, .T. ) ; +#12690 = LINE ( 'NONE', #16156, #12568 ) ; +#12691 = VECTOR ( 'NONE', #21262, 999.9999999999998863 ) ; +#12692 = CARTESIAN_POINT ( 'NONE', ( -12.63221799298840864, 177.0485776882449045, 103.5236562007907253 ) ) ; +#12693 = DIRECTION ( 'NONE', ( -0.6974360921310663874, 0.000000000000000000, 0.7166469824069217065 ) ) ; +#12694 = EDGE_CURVE ( 'NONE', #8209, #24036, #23217, .T. ) ; +#12695 = CARTESIAN_POINT ( 'NONE', ( -2.317981455665000023, 208.9360348893000037, 73.76998536309000087 ) ) ; +#12696 = CARTESIAN_POINT ( 'NONE', ( -1.414596400301315615, 189.2545725590069878, 105.8118447122918724 ) ) ; +#12697 = ORIENTED_EDGE ( 'NONE', *, *, #6038, .F. ) ; +#12698 = CARTESIAN_POINT ( 'NONE', ( 35.56237296993458585, 191.9759150222000130, 101.8999685582081582 ) ) ; +#12699 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319385852566 ) ) ; +#12700 = CARTESIAN_POINT ( 'NONE', ( 42.85442617173308832, 113.6598254356972149, 123.5406245648973993 ) ) ; +#12701 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4224, #16891, #29596, #35691 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12702 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921569638, -0.2249510932971630905 ) ) ; +#12703 = ORIENTED_EDGE ( 'NONE', *, *, #6901, .T. ) ; +#12704 = EDGE_CURVE ( 'NONE', #10196, #18677, #36780, .T. ) ; +#12705 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12272, #2862, #34127, #40464 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12706 = VERTEX_POINT ( 'NONE', #4285 ) ; +#12707 = LINE ( 'NONE', #26205, #3674 ) ; +#12708 = ORIENTED_EDGE ( 'NONE', *, *, #18022, .F. ) ; +#12709 = AXIS2_PLACEMENT_3D ( 'NONE', #3821, #10389, #16694 ) ; +#12710 = PLANE ( 'NONE', #16220 ) ; +#12711 = CARTESIAN_POINT ( 'NONE', ( -38.36472071045999854, 118.8248333581999958, 87.72051653428999884 ) ) ; +#12712 = CIRCLE ( 'NONE', #18558, 2.499999999928080641 ) ; +#12713 = AXIS2_PLACEMENT_3D ( 'NONE', #23348, #22549, #10282 ) ; +#12714 = DIRECTION ( 'NONE', ( 0.0004270953949661438322, 0.7071067811864922836, 0.7071066522029061385 ) ) ; +#12715 = ORIENTED_EDGE ( 'NONE', *, *, #8641, .T. ) ; +#12716 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33379, #16476, #28966, #25918 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12717 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#12718 = ORIENTED_EDGE ( 'NONE', *, *, #13565, .F. ) ; +#12719 = DIRECTION ( 'NONE', ( 0.0006039748319389621253, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#12720 = CONICAL_SURFACE ( 'NONE', #23812, 2.503079361083045296, 0.7853981633955212649 ) ; +#12721 = CARTESIAN_POINT ( 'NONE', ( -35.95556595676193723, 218.5902260770999987, 73.58022043445957650 ) ) ; +#12722 = CARTESIAN_POINT ( 'NONE', ( 39.71644276554569331, 128.0354526761064164, 94.31825870285607039 ) ) ; +#12723 = ORIENTED_EDGE ( 'NONE', *, *, #31200, .T. ) ; +#12724 = DIRECTION ( 'NONE', ( -0.0005884949961230211525, 0.2249510543439048049, -0.9743698870671267942 ) ) ; +#12725 = CARTESIAN_POINT ( 'NONE', ( 1.881914426046564559, 188.9882964918864729, 103.2831730894914841 ) ) ; +#12726 = CARTESIAN_POINT ( 'NONE', ( 13.85386899177591680, 154.7523313006220747, 161.1669414970386356 ) ) ; +#12727 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#12728 = ORIENTED_EDGE ( 'NONE', *, *, #33318, .F. ) ; +#12729 = EDGE_CURVE ( 'NONE', #25569, #9483, #13448, .T. ) ; +#12730 = VERTEX_POINT ( 'NONE', #7761 ) ; +#12731 = CARTESIAN_POINT ( 'NONE', ( 3.995985193436066396, 151.9650325797582013, 28.08107861490884716 ) ) ; +#12732 = CARTESIAN_POINT ( 'NONE', ( -36.38548184428417898, 111.7974789269056402, 175.7340771781224475 ) ) ; +#12733 = EDGE_CURVE ( 'NONE', #17327, #3510, #6892, .T. ) ; +#12734 = ORIENTED_EDGE ( 'NONE', *, *, #26774, .T. ) ; +#12735 = CARTESIAN_POINT ( 'NONE', ( 20.50044205129516328, 117.7855619557941509, 89.75569409557486722 ) ) ; +#12736 = CARTESIAN_POINT ( 'NONE', ( -45.39606049366843621, 123.6566771517818637, 91.23024032489176705 ) ) ; +#12737 = CARTESIAN_POINT ( 'NONE', ( -26.20735541984999983, 121.1118354415000056, 90.84748486943999524 ) ) ; +#12738 = ORIENTED_EDGE ( 'NONE', *, *, #26448, .T. ) ; +#12739 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37875, #35185, #28874, #6580 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12740 = CARTESIAN_POINT ( 'NONE', ( -23.02059183176825741, 214.0904033191889084, 73.07235108223721909 ) ) ; +#12741 = CYLINDRICAL_SURFACE ( 'NONE', #27798, 7.000000000000007994 ) ; +#12742 = DIRECTION ( 'NONE', ( 0.0005884949961243167741, -0.2249510543353384351, 0.9743698870691043235 ) ) ; +#12743 = AXIS2_PLACEMENT_3D ( 'NONE', #39377, #24280, #1778 ) ; +#12744 = VECTOR ( 'NONE', #35164, 1000.000000000000114 ) ; +#12745 = AXIS2_PLACEMENT_3D ( 'NONE', #22801, #1105, #25271 ) ; +#12746 = ORIENTED_EDGE ( 'NONE', *, *, #6492, .F. ) ; +#12747 = CARTESIAN_POINT ( 'NONE', ( -22.78369572533207332, 147.9575508264125290, 94.33852688745618309 ) ) ; +#12748 = CARTESIAN_POINT ( 'NONE', ( 42.78873758771006663, 120.8665316288775102, 92.29373204621693105 ) ) ; +#12749 = VECTOR ( 'NONE', #25159, 1000.000000000000227 ) ; +#12751 = CARTESIAN_POINT ( 'NONE', ( 35.66812328572578394, 191.9358431683554898, 103.8995260772395000 ) ) ; +#12750 = CARTESIAN_POINT ( 'NONE', ( -35.98817295377529746, 191.5260130662397273, 103.8919236801626340 ) ) ; +#12752 = ORIENTED_EDGE ( 'NONE', *, *, #14594, .F. ) ; +#12753 = ADVANCED_FACE ( 'NONE', ( #26390 ), #36945, .F. ) ; +#12754 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #31094, #34139 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12755 = LINE ( 'NONE', #34602, #26841 ) ; +#12756 = EDGE_LOOP ( 'NONE', ( #12470, #26300, #1469, #19727 ) ) ; +#12757 = FACE_OUTER_BOUND ( 'NONE', #30636, .T. ) ; +#12758 = CARTESIAN_POINT ( 'NONE', ( 38.46700359482129272, 118.8212168396402717, 87.67371270529410765 ) ) ; +#12759 = LINE ( 'NONE', #9495, #18811 ) ; +#12760 = VERTEX_POINT ( 'NONE', #20226 ) ; +#12761 = EDGE_LOOP ( 'NONE', ( #12957, #3395, #17134, #16143 ) ) ; +#12762 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#12763 = CARTESIAN_POINT ( 'NONE', ( 45.87579465106376375, 187.3127717824060312, 105.4163742558925065 ) ) ; +#12764 = FACE_OUTER_BOUND ( 'NONE', #31573, .T. ) ; +#12765 = CARTESIAN_POINT ( 'NONE', ( 21.96459776557462007, 135.5515918021118011, 90.93420605039376881 ) ) ; +#12766 = CARTESIAN_POINT ( 'NONE', ( 36.13357069258000109, 191.6670482327000116, 104.0248038887000206 ) ) ; +#12767 = EDGE_LOOP ( 'NONE', ( #10744, #25024, #36054, #37558 ) ) ; +#12768 = ADVANCED_FACE ( 'NONE', ( #32123 ), #23900, .T. ) ; +#12769 = ORIENTED_EDGE ( 'NONE', *, *, #37502, .F. ) ; +#12770 = CARTESIAN_POINT ( 'NONE', ( 16.66545457307292111, 121.3218471137176095, 173.8434147940178320 ) ) ; +#12771 = DIRECTION ( 'NONE', ( 2.312964634635739900E-15, 0.9743700557921587402, 0.2249510932971554578 ) ) ; +#12772 = VECTOR ( 'NONE', #5769, 1000.000000000000227 ) ; +#12773 = DIRECTION ( 'NONE', ( -0.0005884949961181157882, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#12774 = EDGE_CURVE ( 'NONE', #39699, #5859, #38833, .T. ) ; +#12775 = ORIENTED_EDGE ( 'NONE', *, *, #34274, .T. ) ; +#12776 = LINE ( 'NONE', #31386, #19300 ) ; +#12777 = CARTESIAN_POINT ( 'NONE', ( -25.82475235543668290, 191.8548145595347592, 104.1003246049598516 ) ) ; +#12778 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#12779 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16557, #38842, #38441, #10658, #830, #10863, #1640, #38249, #23520, #29459 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999381606, 0.3749999999998667177, 0.4374999999998712696, 0.4999999999998757660, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12780 = VERTEX_POINT ( 'NONE', #38435 ) ; +#12781 = CIRCLE ( 'NONE', #6230, 2.000000003776789548 ) ; +#12782 = VECTOR ( 'NONE', #39722, 1000.000000000000000 ) ; +#12783 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30677, #12455, #12264, #380, #24956, #18766, #9400, #21874, #15331, #18978, #34316, #28219, #15717, #2671, #27824, #25345, #186, #34501, #15912, #28410 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000245637, 0.1875000000000348332, 0.2187500000000429934, 0.2343750000000467126, 0.2500000000000504596, 0.5000000000001307843, 0.6250000000001642020, 0.6875000000001809664, 0.7187500000001794120, 0.7343750000001696421, 0.7500000000001598721, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12784 = CIRCLE ( 'NONE', #2991, 2.000002475912143751 ) ; +#12785 = EDGE_CURVE ( 'NONE', #39550, #31534, #28648, .T. ) ; +#12786 = CARTESIAN_POINT ( 'NONE', ( -75.75833988736154367, 195.1192334286142227, 194.9863546504234080 ) ) ; +#12787 = EDGE_CURVE ( 'NONE', #37534, #31170, #19426, .T. ) ; +#12788 = ORIENTED_EDGE ( 'NONE', *, *, #32900, .F. ) ; +#12789 = CARTESIAN_POINT ( 'NONE', ( -14.13091635336139085, 124.4233634052935429, 88.38685240744268867 ) ) ; +#12790 = EDGE_CURVE ( 'NONE', #2217, #37526, #27025, .T. ) ; +#12791 = CARTESIAN_POINT ( 'NONE', ( -0.5977874941283000121, 188.5301565615999948, 106.1048331864000005 ) ) ; +#12792 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; +#12793 = VERTEX_POINT ( 'NONE', #25596 ) ; +#12794 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -5.029098237799274788E-18, 0.0006039748319384018096 ) ) ; +#12795 = ORIENTED_EDGE ( 'NONE', *, *, #26223, .F. ) ; +#12796 = CARTESIAN_POINT ( 'NONE', ( -3.589080272436853125, 149.3464402607426962, 130.0539584787920830 ) ) ; +#12797 = CARTESIAN_POINT ( 'NONE', ( -38.39983927658001051, 118.6516195866999936, 87.83943466679001233 ) ) ; +#12798 = CARTESIAN_POINT ( 'NONE', ( 19.71670726246199123, 125.1288345936551423, 175.0446023669997260 ) ) ; +#12799 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319392650514 ) ) ; +#12800 = ORIENTED_EDGE ( 'NONE', *, *, #22633, .F. ) ; +#12801 = DIRECTION ( 'NONE', ( 0.1943643238945209628, -0.07321898756438961764, 0.9781929714821464561 ) ) ; +#12802 = ORIENTED_EDGE ( 'NONE', *, *, #7770, .T. ) ; +#12803 = AXIS2_PLACEMENT_3D ( 'NONE', #3795, #16669, #935 ) ; +#12804 = CARTESIAN_POINT ( 'NONE', ( 43.53522428377826259, 122.0090548114814766, 87.79422213383789142 ) ) ; +#12805 = AXIS2_PLACEMENT_3D ( 'NONE', #15757, #6751, #31315 ) ; +#12806 = CARTESIAN_POINT ( 'NONE', ( 21.44693687352840783, 182.5616219828937687, 101.7876413893260974 ) ) ; +#12807 = ORIENTED_EDGE ( 'NONE', *, *, #32765, .F. ) ; +#12808 = VERTEX_POINT ( 'NONE', #23119 ) ; +#12809 = LINE ( 'NONE', #7055, #20560 ) ; +#12810 = LINE ( 'NONE', #16654, #37893 ) ; +#12811 = VECTOR ( 'NONE', #25618, 1000.000000000000114 ) ; +#12812 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#12813 = ORIENTED_EDGE ( 'NONE', *, *, #11343, .T. ) ; +#12814 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; +#12815 = VERTEX_POINT ( 'NONE', #10256 ) ; +#12816 = ORIENTED_EDGE ( 'NONE', *, *, #31157, .T. ) ; +#12817 = FACE_OUTER_BOUND ( 'NONE', #10905, .T. ) ; +#12818 = CARTESIAN_POINT ( 'NONE', ( -37.47349530422577857, 212.6956747321397074, 75.91447098462606391 ) ) ; +#12819 = DIRECTION ( 'NONE', ( 0.0005884949961229053597, -0.2249510543439064147, 0.9743698870671262391 ) ) ; +#12820 = EDGE_CURVE ( 'NONE', #23677, #20569, #22720, .T. ) ; +#12821 = ORIENTED_EDGE ( 'NONE', *, *, #35963, .T. ) ; +#12822 = CARTESIAN_POINT ( 'NONE', ( 19.98078417920676486, 207.3564579907497887, 73.60829347036683146 ) ) ; +#12823 = CARTESIAN_POINT ( 'NONE', ( -25.49272541574507756, 191.9759150222000130, 101.9368443076606781 ) ) ; +#12824 = ORIENTED_EDGE ( 'NONE', *, *, #124, .F. ) ; +#12825 = CARTESIAN_POINT ( 'NONE', ( 0.04412548967667000166, 9.379164112032999336E-13, 73.05847743171000275 ) ) ; +#12826 = ADVANCED_FACE ( 'NONE', ( #10452 ), #17323, .F. ) ; +#12827 = CARTESIAN_POINT ( 'NONE', ( -14.72161250470031035, 176.7237221642146778, 100.4617005973079671 ) ) ; +#12828 = VERTEX_POINT ( 'NONE', #31928 ) ; +#12829 = CARTESIAN_POINT ( 'NONE', ( 28.18914615730000151, 125.0573841749000081, 88.50759441822999918 ) ) ; +#12830 = EDGE_CURVE ( 'NONE', #22181, #28955, #25868, .T. ) ; +#12831 = AXIS2_PLACEMENT_3D ( 'NONE', #21590, #5627, #27732 ) ; +#12832 = CARTESIAN_POINT ( 'NONE', ( -12.15421709199686617, 125.0604765512531884, 178.7580882214065525 ) ) ; +#12833 = DIRECTION ( 'NONE', ( -1.713307136766813101E-15, 0.9743700557921585181, 0.2249510932971561239 ) ) ; +#12834 = CIRCLE ( 'NONE', #23247, 7.999999999957683627 ) ; +#12835 = CARTESIAN_POINT ( 'NONE', ( -35.45668950309346457, 209.7097078344999943, 73.07991903445761750 ) ) ; +#12836 = EDGE_CURVE ( 'NONE', #853, #7306, #4490, .T. ) ; +#12837 = CARTESIAN_POINT ( 'NONE', ( 22.16743659223149265, 158.3069173260788034, 96.18756534121445156 ) ) ; +#12838 = EDGE_CURVE ( 'NONE', #23690, #25663, #2179, .T. ) ; +#12839 = ORIENTED_EDGE ( 'NONE', *, *, #37164, .T. ) ; +#12840 = CARTESIAN_POINT ( 'NONE', ( 20.31780324046303221, 211.0873987128438500, 75.70971466294412267 ) ) ; +#12841 = ADVANCED_FACE ( 'NONE', ( #27432 ), #14123, .F. ) ; +#12842 = CARTESIAN_POINT ( 'NONE', ( -37.95406977588713460, 119.1353498738898651, 87.29774169588188215 ) ) ; +#12843 = CARTESIAN_POINT ( 'NONE', ( 23.36350214669958802, 176.7448593272447681, 103.0093387772721485 ) ) ; +#12844 = CIRCLE ( 'NONE', #35646, 59.40509898897001761 ) ; +#12845 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749385498, 179.6299767372515817, 101.6260513915996739 ) ) ; +#12846 = ORIENTED_EDGE ( 'NONE', *, *, #37027, .F. ) ; +#12847 = EDGE_LOOP ( 'NONE', ( #18628, #36866, #18939, #31881 ) ) ; +#12848 = FACE_OUTER_BOUND ( 'NONE', #6153, .T. ) ; +#12849 = CYLINDRICAL_SURFACE ( 'NONE', #4199, 2.250000000000011102 ) ; +#12850 = FACE_OUTER_BOUND ( 'NONE', #17007, .T. ) ; +#12851 = CARTESIAN_POINT ( 'NONE', ( 12.63858181338016173, 181.3023367127953520, 104.3357988664218823 ) ) ; +#12852 = CARTESIAN_POINT ( 'NONE', ( 14.42541055625604507, 182.6274970736112095, 101.9781413242667014 ) ) ; +#12853 = CARTESIAN_POINT ( 'NONE', ( -25.50335236864900068, 190.9443044115478187, 106.3136331412189008 ) ) ; +#12854 = ORIENTED_EDGE ( 'NONE', *, *, #7829, .F. ) ; +#12855 = DIRECTION ( 'NONE', ( -0.0006039748319383107366, -1.234791622901071989E-14, -0.9999998176071845934 ) ) ; +#12856 = DIRECTION ( 'NONE', ( -0.0005884949961242402295, 0.2249510543439063315, -0.9743698870671264611 ) ) ; +#12857 = CARTESIAN_POINT ( 'NONE', ( -12.63810003589398256, 137.3539737265348890, 91.36813903047330143 ) ) ; +#12858 = VERTEX_POINT ( 'NONE', #23513 ) ; +#12859 = CARTESIAN_POINT ( 'NONE', ( 27.29501362713000034, 103.8631156702000027, 90.00129928933000656 ) ) ; +#12860 = CARTESIAN_POINT ( 'NONE', ( 23.35435660873492125, 181.0170614477807476, 104.5088077577469221 ) ) ; +#12861 = CIRCLE ( 'NONE', #38325, 59.40509898896999630 ) ; +#12862 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557843820720, -0.2249510933308394578 ) ) ; +#12863 = CARTESIAN_POINT ( 'NONE', ( 36.36613122512999752, 191.7602783439000120, 105.7174599309999934 ) ) ; +#12864 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33047, #5036, #11599, #29995, #1993, #39785, #14463, #36530, #26946, #39380, #36329, #33242, #11801, #36727, #30609, #15070, #27569 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999178713, 0.1874999999998768208, 0.2187499999998250011, 0.2343749999997991051, 0.2499999999997732092, 0.3749999999998051003, 0.4374999999998210320, 0.4687499999998289701, 0.4999999999998369082, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12865 = AXIS2_PLACEMENT_3D ( 'NONE', #17665, #10747, #5000 ) ; +#12866 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#12867 = CARTESIAN_POINT ( 'NONE', ( 36.35871695389000280, 190.7175962013000117, 106.8891365664000119 ) ) ; +#12868 = VECTOR ( 'NONE', #15948, 1000.000000000000114 ) ; +#12869 = ORIENTED_EDGE ( 'NONE', *, *, #36650, .F. ) ; +#12870 = PLANE ( 'NONE', #2307 ) ; +#12871 = CARTESIAN_POINT ( 'NONE', ( -20.33561058857197068, 184.8849765532865206, 102.6939075168818221 ) ) ; +#12872 = ADVANCED_FACE ( 'NONE', ( #8392 ), #17350, .F. ) ; +#12873 = VECTOR ( 'NONE', #2516, 1000.000000000000114 ) ; +#12874 = EDGE_CURVE ( 'NONE', #25208, #37405, #1656, .T. ) ; +#12875 = CARTESIAN_POINT ( 'NONE', ( -2.455538055765680738, 209.0000002601700544, 73.61629604161946361 ) ) ; +#12876 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901496, 179.0675991013200701, 104.0619761093405771 ) ) ; +#12877 = VERTEX_POINT ( 'NONE', #2255 ) ; +#12878 = CARTESIAN_POINT ( 'NONE', ( 44.90072207509915359, 127.0650837324493523, 92.04000096660296037 ) ) ; +#12879 = EDGE_CURVE ( 'NONE', #11929, #14375, #17762, .T. ) ; +#12880 = VERTEX_POINT ( 'NONE', #8799 ) ; +#12881 = ADVANCED_FACE ( 'NONE', ( #2463 ), #1843, .F. ) ; +#12882 = CARTESIAN_POINT ( 'NONE', ( -3.255264691931540444, 129.2253544352344932, 89.48891097144958451 ) ) ; +#12883 = CARTESIAN_POINT ( 'NONE', ( -13.50000254471398264, 127.7447170053348771, 89.15018747604320026 ) ) ; +#12884 = EDGE_LOOP ( 'NONE', ( #7381, #27441, #40170, #33931 ) ) ; +#12885 = EDGE_CURVE ( 'NONE', #8372, #2746, #32567, .T. ) ; +#12886 = PLANE ( 'NONE', #14065 ) ; +#12887 = FACE_OUTER_BOUND ( 'NONE', #30974, .T. ) ; +#12888 = FACE_OUTER_BOUND ( 'NONE', #8142, .T. ) ; +#12889 = CARTESIAN_POINT ( 'NONE', ( 16.88249520720069441, 127.4209172357130342, 171.9069182253847430 ) ) ; +#12890 = EDGE_CURVE ( 'NONE', #34620, #23353, #33714, .T. ) ; +#12891 = EDGE_LOOP ( 'NONE', ( #17187, #26859, #3368, #2936 ) ) ; +#12892 = CARTESIAN_POINT ( 'NONE', ( 12.64059569365333324, 176.8205385886645331, 103.1388713076008372 ) ) ; +#12893 = DIRECTION ( 'NONE', ( 0.0002393071182785117316, 0.2252352986010040803, -0.9743043687658490271 ) ) ; +#12894 = DIRECTION ( 'NONE', ( 0.0001358647752418049677, 0.9743700647852354679, 0.2249510133144081714 ) ) ; +#12895 = VECTOR ( 'NONE', #21740, 1000.000000000000000 ) ; +#12896 = CARTESIAN_POINT ( 'NONE', ( -36.62841445464000145, 191.5124353941000095, 104.2533201470999984 ) ) ; +#12897 = ORIENTED_EDGE ( 'NONE', *, *, #19954, .F. ) ; +#12898 = FACE_OUTER_BOUND ( 'NONE', #27104, .T. ) ; +#12899 = ORIENTED_EDGE ( 'NONE', *, *, #25005, .T. ) ; +#12900 = VECTOR ( 'NONE', #20076, 1000.000000000000227 ) ; +#12901 = EDGE_CURVE ( 'NONE', #9552, #11960, #4096, .T. ) ; +#12902 = CARTESIAN_POINT ( 'NONE', ( -3.669581230397975791, 128.4724600144964484, 89.82849395191713882 ) ) ; +#12903 = CARTESIAN_POINT ( 'NONE', ( -28.53030869656295110, 124.6043131503039803, 91.51623810099293621 ) ) ; +#12904 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32032, #14017, #16463, #26494 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12905 = CARTESIAN_POINT ( 'NONE', ( -16.42363997277514898, 152.5170915174298329, 181.7137745456617495 ) ) ; +#12906 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#12907 = CARTESIAN_POINT ( 'NONE', ( 20.48231950984458649, 205.5677633305384120, 76.28703242847967658 ) ) ; +#12908 = CARTESIAN_POINT ( 'NONE', ( -1.469607249925116266, 189.2865446493801755, 105.8210556326310297 ) ) ; +#12909 = VERTEX_POINT ( 'NONE', #27217 ) ; +#12910 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#12911 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178617807513E-05, -0.0002331579774917555924 ) ) ; +#12912 = CARTESIAN_POINT ( 'NONE', ( 76.10689632611000377, 156.0355272971999909, 97.17005189866002013 ) ) ; +#12913 = CARTESIAN_POINT ( 'NONE', ( 15.99999439207489615, 185.9093013714976053, 102.5638074086867846 ) ) ; +#12914 = ORIENTED_EDGE ( 'NONE', *, *, #28210, .F. ) ; +#12915 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32452, #17694, #17287, #23860 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12916 = ORIENTED_EDGE ( 'NONE', *, *, #20155, .T. ) ; +#12917 = CARTESIAN_POINT ( 'NONE', ( 5.674778016381245571, 131.0223034755605909, 89.89838139801142347 ) ) ; +#12918 = ADVANCED_FACE ( 'NONE', ( #39848 ), #27215, .F. ) ; +#12919 = AXIS2_PLACEMENT_3D ( 'NONE', #6930, #38009, #28818 ) ; +#12920 = CARTESIAN_POINT ( 'NONE', ( -19.46394794124172023, 125.6806896231740751, 178.4345049239138064 ) ) ; +#12921 = EDGE_CURVE ( 'NONE', #22764, #8895, #23934, .T. ) ; +#12922 = EDGE_CURVE ( 'NONE', #14938, #36888, #18668, .T. ) ; +#12923 = CIRCLE ( 'NONE', #29883, 2.000000000000011546 ) ; +#12924 = ORIENTED_EDGE ( 'NONE', *, *, #14079, .F. ) ; +#12925 = CARTESIAN_POINT ( 'NONE', ( -15.46635816504221772, 147.8788101534005932, 152.4730815186126733 ) ) ; +#12926 = CARTESIAN_POINT ( 'NONE', ( 13.53173156088000084, 162.3883503090999909, 152.4718672074000381 ) ) ; +#12927 = DIRECTION ( 'NONE', ( -0.0005884949961235722525, 0.2249510543439049715, -0.9743698870671265722 ) ) ; +#12928 = CARTESIAN_POINT ( 'NONE', ( -38.14120756220999908, 119.0850948817000017, 87.44152985738000439 ) ) ; +#12929 = DIRECTION ( 'NONE', ( 0.0006039748319383739456, -3.094196748328522329E-15, 0.9999998176071845934 ) ) ; +#12930 = VERTEX_POINT ( 'NONE', #14124 ) ; +#12931 = ADVANCED_FACE ( 'NONE', ( #27005 ), #11448, .F. ) ; +#12932 = CARTESIAN_POINT ( 'NONE', ( 17.27144937936713376, 122.5454421133972289, 172.0731752994966541 ) ) ; +#12933 = ORIENTED_EDGE ( 'NONE', *, *, #7816, .F. ) ; +#12934 = LINE ( 'NONE', #9869, #9623 ) ; +#12935 = CARTESIAN_POINT ( 'NONE', ( -23.35635573182313607, 131.0183818788550241, 89.91503395410319399 ) ) ; +#12936 = EDGE_CURVE ( 'NONE', #40319, #29818, #20646, .T. ) ; +#12937 = ORIENTED_EDGE ( 'NONE', *, *, #36677, .T. ) ; +#12938 = PLANE ( 'NONE', #29804 ) ; +#12939 = CARTESIAN_POINT ( 'NONE', ( 0.8647791692335055069, 188.6306482529823256, 103.2012177966641815 ) ) ; +#12940 = CARTESIAN_POINT ( 'NONE', ( -26.01060144688746689, 209.2224318440115383, 73.07376367569236209 ) ) ; +#12941 = PLANE ( 'NONE', #27363 ) ; +#12942 = VERTEX_POINT ( 'NONE', #36393 ) ; +#12943 = ORIENTED_EDGE ( 'NONE', *, *, #12409, .T. ) ; +#12944 = CARTESIAN_POINT ( 'NONE', ( 20.27054642785542882, 118.1107986174901896, 87.52574972040859791 ) ) ; +#12945 = CARTESIAN_POINT ( 'NONE', ( -37.83775869347861942, 191.4135374006265806, 104.3802260088867513 ) ) ; +#12946 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28284, #12735, #25227, #37676, #9674, #22957, #2038, #14909, #33091, #29842 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12947 = ORIENTED_EDGE ( 'NONE', *, *, #23748, .T. ) ; +#12948 = PLANE ( 'NONE', #22564 ) ; +#12949 = CARTESIAN_POINT ( 'NONE', ( -13.50000253664885719, 151.9690088118221922, 94.74282098678578734 ) ) ; +#12950 = CARTESIAN_POINT ( 'NONE', ( -25.70074763801000017, 121.3279312843000071, 90.36970767171999341 ) ) ; +#12951 = CIRCLE ( 'NONE', #40360, 2.499999999874955137 ) ; +#12952 = ORIENTED_EDGE ( 'NONE', *, *, #22579, .F. ) ; +#12953 = CARTESIAN_POINT ( 'NONE', ( -16.55117160943531118, 121.8277038752011521, 177.5442054669605909 ) ) ; +#12954 = CARTESIAN_POINT ( 'NONE', ( 3.044162730076025447, 208.9211496123335507, 73.11923083669719858 ) ) ; +#12955 = CIRCLE ( 'NONE', #35759, 6.000000000011024071 ) ; +#12956 = CARTESIAN_POINT ( 'NONE', ( 41.04584544117999911, 220.4002260691000004, 74.53371369385999401 ) ) ; +#12957 = ORIENTED_EDGE ( 'NONE', *, *, #34092, .F. ) ; +#12958 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #34359, #19019 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.02271787902114467267, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#12959 = DIRECTION ( 'NONE', ( -0.7069397806862420808, 0.6508951186658792354, 0.2767159030128537589 ) ) ; +#12960 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#12962 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#12961 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319364164186 ) ) ; +#12963 = VERTEX_POINT ( 'NONE', #20852 ) ; +#12964 = CARTESIAN_POINT ( 'NONE', ( -48.18910981145552341, 141.1918910709570980, 290.9667924317506049 ) ) ; +#12965 = CARTESIAN_POINT ( 'NONE', ( -0.09191864964710037833, 291.0964424001293196, 217.1925188927256158 ) ) ; +#12966 = LINE ( 'NONE', #28701, #19497 ) ; +#12967 = EDGE_CURVE ( 'NONE', #25568, #35358, #37404, .T. ) ; +#12968 = EDGE_LOOP ( 'NONE', ( #35314, #28779, #36597, #1674 ) ) ; +#12969 = ADVANCED_FACE ( 'NONE', ( #28214 ), #14052, .F. ) ; +#12970 = VERTEX_POINT ( 'NONE', #16899 ) ; +#12971 = CYLINDRICAL_SURFACE ( 'NONE', #19153, 4.999999999999990230 ) ; +#12972 = AXIS2_PLACEMENT_3D ( 'NONE', #7368, #19825, #4298 ) ; +#12973 = DIRECTION ( 'NONE', ( 0.7075229308291650643, 0.000000000000000000, 0.7066903864854172657 ) ) ; +#12974 = DIRECTION ( 'NONE', ( -0.9999998268365983822, -0.0001323826716410795928, 0.0005734122438485214851 ) ) ; +#12975 = CARTESIAN_POINT ( 'NONE', ( 35.89709686227286056, 192.3543251505955141, 104.2022112152945965 ) ) ; +#12976 = ORIENTED_EDGE ( 'NONE', *, *, #40132, .F. ) ; +#12977 = CIRCLE ( 'NONE', #11691, 5.000000000000007994 ) ; +#12978 = ORIENTED_EDGE ( 'NONE', *, *, #6354, .F. ) ; +#12979 = CARTESIAN_POINT ( 'NONE', ( -6.036122723735069862, 176.7409673271154702, 103.0261968760796378 ) ) ; +#12980 = VECTOR ( 'NONE', #37633, 1000.000000000000114 ) ; +#12981 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#12982 = DIRECTION ( 'NONE', ( -0.0005884949961265727820, 0.2249510543439056931, -0.9743698870671265722 ) ) ; +#12983 = CIRCLE ( 'NONE', #11667, 2.000000000000011546 ) ; +#12984 = ORIENTED_EDGE ( 'NONE', *, *, #15875, .F. ) ; +#12985 = CARTESIAN_POINT ( 'NONE', ( -25.65798556230555505, 191.8454707520358227, 104.2666281073695984 ) ) ; +#12986 = EDGE_LOOP ( 'NONE', ( #30966, #31758, #2055, #21333 ) ) ; +#12987 = CARTESIAN_POINT ( 'NONE', ( -36.73835199021345943, 116.0420298664398757, 89.74139269884751968 ) ) ; +#12988 = ORIENTED_EDGE ( 'NONE', *, *, #35082, .T. ) ; +#12989 = FACE_OUTER_BOUND ( 'NONE', #40076, .T. ) ; +#12990 = ORIENTED_EDGE ( 'NONE', *, *, #16046, .F. ) ; +#12991 = CARTESIAN_POINT ( 'NONE', ( -37.28133731252471961, 166.8593197691344017, 188.5736935233141196 ) ) ; +#12992 = EDGE_CURVE ( 'NONE', #520, #15252, #4319, .T. ) ; +#12993 = CARTESIAN_POINT ( 'NONE', ( -2.303974314047999794, 190.8754367445000071, 106.1362474393000213 ) ) ; +#12994 = CARTESIAN_POINT ( 'NONE', ( -2.435784540106990192, 190.9902839124212335, 106.3131295316380545 ) ) ; +#12995 = ORIENTED_EDGE ( 'NONE', *, *, #37605, .F. ) ; +#12996 = CARTESIAN_POINT ( 'NONE', ( 22.78281254372720355, 153.7346105515276804, 98.21050616309901216 ) ) ; +#12997 = ORIENTED_EDGE ( 'NONE', *, *, #3663, .F. ) ; +#12998 = CARTESIAN_POINT ( 'NONE', ( 32.02693021685336561, 77.14301703111976849, 291.5392004719097372 ) ) ; +#12999 = FACE_OUTER_BOUND ( 'NONE', #18831, .T. ) ; +#13000 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #31207, #6447, #15657, #27961 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.603140784247877537, 4.612408630352550887 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9169010176874472506, 0.9169010176874472506, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#13001 = CARTESIAN_POINT ( 'NONE', ( 13.49642010767728095, 123.7543391407038769, 91.24249921288263465 ) ) ; +#13002 = VECTOR ( 'NONE', #13274, 1000.000000000000227 ) ; +#13003 = LINE ( 'NONE', #25485, #25892 ) ; +#13004 = ORIENTED_EDGE ( 'NONE', *, *, #9133, .T. ) ; +#13005 = EDGE_CURVE ( 'NONE', #10050, #39311, #29412, .T. ) ; +#13006 = CIRCLE ( 'NONE', #31926, 6.000000000154989799 ) ; +#13007 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#13008 = CIRCLE ( 'NONE', #35822, 22.00000000001089973 ) ; +#13009 = CARTESIAN_POINT ( 'NONE', ( -38.55398926386000369, 118.3669049012000016, 89.55270650478000505 ) ) ; +#13010 = EDGE_CURVE ( 'NONE', #12930, #20721, #11516, .T. ) ; +#13011 = VERTEX_POINT ( 'NONE', #1376 ) ; +#13012 = ORIENTED_EDGE ( 'NONE', *, *, #12058, .T. ) ; +#13013 = FACE_OUTER_BOUND ( 'NONE', #1933, .T. ) ; +#13014 = DIRECTION ( 'NONE', ( 0.0004161288024548960270, 0.5299192578740949955, 0.8480479980348919478 ) ) ; +#13015 = FACE_OUTER_BOUND ( 'NONE', #32596, .T. ) ; +#13016 = EDGE_CURVE ( 'NONE', #14032, #9488, #23596, .T. ) ; +#13017 = ADVANCED_FACE ( 'NONE', ( #10802 ), #34347, .F. ) ; +#13018 = CARTESIAN_POINT ( 'NONE', ( -0.4558744329272819695, 211.4999999999972431, 73.05877941915380802 ) ) ; +#13019 = ORIENTED_EDGE ( 'NONE', *, *, #39788, .T. ) ; +#13020 = VERTEX_POINT ( 'NONE', #4235 ) ; +#13021 = CARTESIAN_POINT ( 'NONE', ( 1.936912818046955476, 189.5456747395250545, 105.8934727691335382 ) ) ; +#13022 = LINE ( 'NONE', #28757, #30107 ) ; +#13023 = EDGE_CURVE ( 'NONE', #31407, #4383, #11347, .T. ) ; +#13024 = ORIENTED_EDGE ( 'NONE', *, *, #40, .T. ) ; +#13025 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#13026 = VERTEX_POINT ( 'NONE', #10602 ) ; +#13027 = DIRECTION ( 'NONE', ( 0.0006039748319385908944, 1.293414132305980107E-14, 0.9999998176071845934 ) ) ; +#13028 = CIRCLE ( 'NONE', #30009, 2.499999999899970682 ) ; +#13029 = CARTESIAN_POINT ( 'NONE', ( -39.82458058703250003, 191.0388296339007752, 103.7817683317120867 ) ) ; +#13030 = ORIENTED_EDGE ( 'NONE', *, *, #6758, .T. ) ; +#13031 = CARTESIAN_POINT ( 'NONE', ( 28.33128032238000316, 125.4735004498999871, 88.94656419544999437 ) ) ; +#13032 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10442, #22909, #1621, #1830 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13033 = VECTOR ( 'NONE', #20103, 1000.000000000000227 ) ; +#13034 = DIRECTION ( 'NONE', ( 0.6087614115774880874, -0.7730004600455407937, -0.1785492440296700956 ) ) ; +#13035 = AXIS2_PLACEMENT_3D ( 'NONE', #27428, #5301, #14730 ) ; +#13036 = CARTESIAN_POINT ( 'NONE', ( -20.00000588364686038, 174.5066637885302896, 99.95304239614711150 ) ) ; +#13037 = FACE_OUTER_BOUND ( 'NONE', #37792, .T. ) ; +#13038 = AXIS2_PLACEMENT_3D ( 'NONE', #29293, #32358, #8006 ) ; +#13039 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#13040 = VERTEX_POINT ( 'NONE', #13854 ) ; +#13041 = CARTESIAN_POINT ( 'NONE', ( 20.00175897098971589, 118.8155681873422651, 90.25573236258343002 ) ) ; +#13042 = CARTESIAN_POINT ( 'NONE', ( 1.084781822741140100, 189.0693601363920493, 103.7040955045087571 ) ) ; +#13043 = CARTESIAN_POINT ( 'NONE', ( -2.421071065100592001, 189.3597238620783685, 106.4504356505698013 ) ) ; +#13044 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7909, #8329, #4636, #5236 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13045 = PLANE ( 'NONE', #5336 ) ; +#13046 = DIRECTION ( 'NONE', ( -0.0004161288024286937878, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#13047 = CARTESIAN_POINT ( 'NONE', ( 13.55543936442901476, 163.9642746141201144, 100.5777837385402904 ) ) ; +#13048 = DIRECTION ( 'NONE', ( -0.0001408422045155705395, 0.2255194951287508853, -0.9742386450353663907 ) ) ; +#13049 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38751, #13825, #29574, #20148, #20770, #32439, #5217, #36093, #39569, #1975, #1761 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000963118, 0.3750000000000788258, 0.4375000000001090794, 0.4687500000001241784, 0.5000000000001392220, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13050 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #15203, #27691, #24825, #27896 ), + ( #12327, #37269, #9269, #3116 ), + ( #16978, #26020, #29478, #6984 ), + ( #26222, #32544, #31953, #34967 ), + ( #13334, #16788, #38268, #34775 ), + ( #13939, #35569, #32153, #26422 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 4 ), + ( 4, 4 ), + ( -0.01998966095620999944, 0.000000000000000000, 1.000000000000000000, 1.019805502689000054 ), + ( -3.010002734666000098E-05, 0.9999999646031000333 ), + .UNSPECIFIED. ) ; +#13051 = CARTESIAN_POINT ( 'NONE', ( -20.49893885638800128, 193.5513712071386863, 106.1813727900049571 ) ) ; +#13052 = CARTESIAN_POINT ( 'NONE', ( -25.70739151542000300, 190.4681821343999957, 106.3783065876999956 ) ) ; +#13053 = ORIENTED_EDGE ( 'NONE', *, *, #31754, .F. ) ; +#13054 = EDGE_CURVE ( 'NONE', #39862, #18015, #22599, .T. ) ; +#13055 = CARTESIAN_POINT ( 'NONE', ( -11.79198343374907054, 125.9681876107315333, 176.0676422622361770 ) ) ; +#13056 = CARTESIAN_POINT ( 'NONE', ( -12.64495593087849024, 181.7027899428717888, 101.6313931463716216 ) ) ; +#13057 = ADVANCED_FACE ( 'NONE', ( #28800 ), #26152, .F. ) ; +#13058 = AXIS2_PLACEMENT_3D ( 'NONE', #35409, #25859, #16817 ) ; +#13059 = ORIENTED_EDGE ( 'NONE', *, *, #37789, .T. ) ; +#13060 = CARTESIAN_POINT ( 'NONE', ( 21.74023251323743011, 115.9285818112440865, 87.75444016076374965 ) ) ; +#13061 = CARTESIAN_POINT ( 'NONE', ( -25.99148323931970594, 191.8512832710823091, 103.9333748356177978 ) ) ; +#13062 = VECTOR ( 'NONE', #5588, 1000.000000000000114 ) ; +#13063 = DIRECTION ( 'NONE', ( 0.7947985590179719173, -0.5913221741348984040, -0.1365039814779489546 ) ) ; +#13064 = CARTESIAN_POINT ( 'NONE', ( -20.01839671862364867, 211.0902260915352429, 76.07059681904712534 ) ) ; +#13065 = AXIS2_PLACEMENT_3D ( 'NONE', #36793, #20848, #8796 ) ; +#13066 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17487, #14448, #11584, #20986, #39772, #30389, #15058, #5027, #21948, #34392 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( -0.0009603588719864617927, 0.0001952418026493195910, 0.0007730421399672324006, 0.001061942308626189022, 0.001350842477285145535 ), + .UNSPECIFIED. ) ; +#13067 = EDGE_CURVE ( 'NONE', #21490, #39537, #26501, .T. ) ; +#13068 = EDGE_CURVE ( 'NONE', #7608, #1836, #6913, .T. ) ; +#13069 = CARTESIAN_POINT ( 'NONE', ( -21.10694955292148478, 136.4999052006739078, 91.52125896335103050 ) ) ; +#13070 = VERTEX_POINT ( 'NONE', #35100 ) ; +#13071 = EDGE_CURVE ( 'NONE', #40304, #38430, #2391, .T. ) ; +#13072 = CARTESIAN_POINT ( 'NONE', ( -2.370405409122252394, 209.5734236807777222, 75.55993826224245424 ) ) ; +#13073 = EDGE_CURVE ( 'NONE', #2542, #19255, #35637, .T. ) ; +#13074 = CARTESIAN_POINT ( 'NONE', ( 20.33262371326216567, 196.2720655916053261, 103.7314557283780232 ) ) ; +#13075 = DIRECTION ( 'NONE', ( -0.7933533411653341805, -0.5931840316264885837, -0.1368326740407639630 ) ) ; +#13076 = ORIENTED_EDGE ( 'NONE', *, *, #9351, .T. ) ; +#13077 = CARTESIAN_POINT ( 'NONE', ( 5.666342389698421300, 128.5870658017565233, 89.33308585708306282 ) ) ; +#13078 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #14791, #36447, #5363, #5973 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.832522679881611438, 4.832536753587069356 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999834942033, 0.9999999999834942033, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#13079 = VERTEX_POINT ( 'NONE', #8548 ) ; +#13080 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825955341562035, 0.0005734119015741466268 ) ) ; +#13081 = FACE_OUTER_BOUND ( 'NONE', #23531, .T. ) ; +#13082 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#13083 = CYLINDRICAL_SURFACE ( 'NONE', #12919, 51.40509898897001051 ) ; +#13084 = CARTESIAN_POINT ( 'NONE', ( -30.06924898906426691, 176.9473508903192283, 103.3753521668471507 ) ) ; +#13085 = PLANE ( 'NONE', #32140 ) ; +#13086 = VERTEX_POINT ( 'NONE', #7922 ) ; +#13087 = AXIS2_PLACEMENT_3D ( 'NONE', #27341, #36713, #21603 ) ; +#13088 = CARTESIAN_POINT ( 'NONE', ( 21.23573982155677697, 129.5657464465189150, 89.55270472066885645 ) ) ; +#13089 = AXIS2_PLACEMENT_3D ( 'NONE', #37259, #14793, #33977 ) ; +#13090 = CARTESIAN_POINT ( 'NONE', ( -18.98875009441257333, 125.3860450160050277, 176.2394239049030773 ) ) ; +#13091 = FACE_OUTER_BOUND ( 'NONE', #10788, .T. ) ; +#13092 = AXIS2_PLACEMENT_3D ( 'NONE', #38201, #38394, #35097 ) ; +#13093 = CONICAL_SURFACE ( 'NONE', #14, 2.502986300332882497, 0.7853981634574371817 ) ; +#13094 = CARTESIAN_POINT ( 'NONE', ( -22.78268303310043308, 158.0258324527692366, 98.88663196571921787 ) ) ; +#13095 = VERTEX_POINT ( 'NONE', #5046 ) ; +#13096 = FACE_OUTER_BOUND ( 'NONE', #14889, .T. ) ; +#13097 = VERTEX_POINT ( 'NONE', #26546 ) ; +#13098 = CARTESIAN_POINT ( 'NONE', ( -39.76913700811847718, 108.4405668372959468, 169.8253437122761795 ) ) ; +#13099 = EDGE_CURVE ( 'NONE', #16908, #31409, #5997, .T. ) ; +#13100 = CARTESIAN_POINT ( 'NONE', ( 37.96499143901794326, 190.9636352903536363, 106.2831835502989719 ) ) ; +#13101 = CARTESIAN_POINT ( 'NONE', ( 20.00178331300101320, 191.9758063960465790, 106.9093738487591736 ) ) ; +#13102 = LINE ( 'NONE', #15947, #5185 ) ; +#13103 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714601725811, 0.5299193037554699170 ) ) ; +#13104 = EDGE_CURVE ( 'NONE', #25100, #12107, #39664, .T. ) ; +#13105 = CARTESIAN_POINT ( 'NONE', ( 20.48162925447415716, 206.2142141259708694, 75.21199830249389606 ) ) ; +#13106 = CARTESIAN_POINT ( 'NONE', ( 38.66209724894999766, 118.3740667178000194, 89.51289815417000284 ) ) ; +#13107 = EDGE_LOOP ( 'NONE', ( #19022, #2054, #487, #28413 ) ) ; +#13108 = ADVANCED_FACE ( 'NONE', ( #17513 ), #4840, .T. ) ; +#13109 = CARTESIAN_POINT ( 'NONE', ( 19.71691057019783955, 124.7851487048555725, 176.5356473463300233 ) ) ; +#13110 = CARTESIAN_POINT ( 'NONE', ( -58.64525294468500505, 246.4771452095119741, 202.1493000143418328 ) ) ; +#13111 = CARTESIAN_POINT ( 'NONE', ( 3.045988519791387628, 209.1419319775010877, 76.13893608185537687 ) ) ; +#13112 = ORIENTED_EDGE ( 'NONE', *, *, #5909, .F. ) ; +#13113 = EDGE_CURVE ( 'NONE', #21410, #18912, #14473, .T. ) ; +#13114 = AXIS2_PLACEMENT_3D ( 'NONE', #39365, #26317, #32832 ) ; +#13115 = AXIS2_PLACEMENT_3D ( 'NONE', #37443, #3281, #9441 ) ; +#13116 = ORIENTED_EDGE ( 'NONE', *, *, #507, .T. ) ; +#13117 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; +#13118 = CIRCLE ( 'NONE', #2685, 8.499999999969023889 ) ; +#13119 = LINE ( 'NONE', #25800, #16699 ) ; +#13120 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18957, #24735, #6688, #6099 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13121 = VECTOR ( 'NONE', #18674, 1000.000000000000227 ) ; +#13122 = CARTESIAN_POINT ( 'NONE', ( 21.44693687352840783, 182.5616219828937687, 101.7876413893260974 ) ) ; +#13123 = ORIENTED_EDGE ( 'NONE', *, *, #38518, .T. ) ; +#13124 = CARTESIAN_POINT ( 'NONE', ( 44.00666834743777400, 122.5942585552269577, 87.99047523027837769 ) ) ; +#13125 = CARTESIAN_POINT ( 'NONE', ( -33.63391334482336958, 159.2148480992196937, 186.9798810687557875 ) ) ; +#13126 = CARTESIAN_POINT ( 'NONE', ( -38.75768410615999926, 118.9340794893000037, 89.91572363038000049 ) ) ; +#13127 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -3.486209987973606947E-16, -0.0006039748319386279742 ) ) ; +#13128 = DIRECTION ( 'NONE', ( 0.7856246208753498994, 0.6187034467937467808, 0.000000000000000000 ) ) ; +#13129 = VERTEX_POINT ( 'NONE', #14067 ) ; +#13130 = CARTESIAN_POINT ( 'NONE', ( -19.40408387590019501, 124.8181396720960237, 178.2503323773021293 ) ) ; +#13131 = ORIENTED_EDGE ( 'NONE', *, *, #29064, .F. ) ; +#13132 = DIRECTION ( 'NONE', ( 0.7933531821996063771, 0.5932639600174075545, 0.1364866368485285197 ) ) ; +#13133 = CARTESIAN_POINT ( 'NONE', ( -3.537737212824113353, 144.2088358181959222, 92.94829169108382416 ) ) ; +#13134 = CARTESIAN_POINT ( 'NONE', ( -2.454301921840380096, 209.0000005845445230, 75.66282330657800514 ) ) ; +#13135 = ORIENTED_EDGE ( 'NONE', *, *, #35404, .T. ) ; +#13136 = ORIENTED_EDGE ( 'NONE', *, *, #12874, .F. ) ; +#13137 = CARTESIAN_POINT ( 'NONE', ( -15.66646917381426718, 160.6657006905813034, 97.09708742826067862 ) ) ; +#13138 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33212, #1538, #17675, #29562 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.8698163993620108281, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13139 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001722, 123.6868832756552479, 91.30891139640304743 ) ) ; +#13140 = CARTESIAN_POINT ( 'NONE', ( 33.10386533810220300, 142.0583947864083711, 287.8124284103819264 ) ) ; +#13141 = ORIENTED_EDGE ( 'NONE', *, *, #9141, .F. ) ; +#13142 = CIRCLE ( 'NONE', #5952, 4.500000000047791104 ) ; +#13143 = CARTESIAN_POINT ( 'NONE', ( -20.90347901032547639, 150.8128521043120429, 179.9383906111355031 ) ) ; +#13144 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#13145 = VERTEX_POINT ( 'NONE', #39797 ) ; +#13146 = AXIS2_PLACEMENT_3D ( 'NONE', #23188, #26461, #10928 ) ; +#13147 = AXIS2_PLACEMENT_3D ( 'NONE', #18746, #31247, #31866 ) ; +#13148 = DIRECTION ( 'NONE', ( -4.622231023467483304E-33, 1.000000000000000000, 2.791711714772432647E-36 ) ) ; +#13149 = CARTESIAN_POINT ( 'NONE', ( 36.22406557370990754, 191.4555988477227402, 103.8320530264872588 ) ) ; +#13150 = CARTESIAN_POINT ( 'NONE', ( -25.99977928218365264, 118.3467192240666748, 90.28348805439438252 ) ) ; +#13151 = EDGE_CURVE ( 'NONE', #24779, #20395, #1581, .T. ) ; +#13152 = CIRCLE ( 'NONE', #28158, 17.00000000000405009 ) ; +#13153 = EDGE_CURVE ( 'NONE', #12157, #28955, #13814, .T. ) ; +#13154 = ORIENTED_EDGE ( 'NONE', *, *, #4112, .T. ) ; +#13155 = VECTOR ( 'NONE', #8354, 999.9999999999998863 ) ; +#13156 = ADVANCED_FACE ( 'NONE', ( #134 ), #9546, .F. ) ; +#13157 = EDGE_CURVE ( 'NONE', #11960, #39810, #29903, .T. ) ; +#13158 = DIRECTION ( 'NONE', ( -0.7933533411653069800, 0.5930537057989941907, 0.1373964268091563412 ) ) ; +#13159 = CARTESIAN_POINT ( 'NONE', ( 35.04494061520995274, 225.9002260770261330, 73.03733781633900435 ) ) ; +#13160 = FACE_OUTER_BOUND ( 'NONE', #3577, .T. ) ; +#13161 = ORIENTED_EDGE ( 'NONE', *, *, #30659, .F. ) ; +#13162 = EDGE_CURVE ( 'NONE', #33001, #1519, #30411, .T. ) ; +#13163 = CARTESIAN_POINT ( 'NONE', ( 25.83456707447000156, 120.2191799910000185, 90.30159152596000638 ) ) ; +#13164 = FACE_OUTER_BOUND ( 'NONE', #12161, .T. ) ; +#13165 = CARTESIAN_POINT ( 'NONE', ( -15.99998595512920652, 185.9065961375156348, 102.5825112407314634 ) ) ; +#13167 = CARTESIAN_POINT ( 'NONE', ( -13.49829986130884762, 187.9919729796256149, 103.3620544560183845 ) ) ; +#13166 = CARTESIAN_POINT ( 'NONE', ( 5.675516847681189248, 187.6699105947183170, 106.0554762087619025 ) ) ; +#13168 = EDGE_CURVE ( 'NONE', #1098, #17766, #27964, .T. ) ; +#13169 = CARTESIAN_POINT ( 'NONE', ( 38.97204648811698036, 118.8228816124465368, 89.67376701884533929 ) ) ; +#13170 = ORIENTED_EDGE ( 'NONE', *, *, #18579, .F. ) ; +#13171 = DIRECTION ( 'NONE', ( 0.7933533411653341805, 0.5931840316264885837, 0.1368326740407639630 ) ) ; +#13172 = LINE ( 'NONE', #16412, #6421 ) ; +#13173 = CIRCLE ( 'NONE', #4011, 6.500000000041539217 ) ; +#13174 = ORIENTED_EDGE ( 'NONE', *, *, #18524, .T. ) ; +#13176 = VECTOR ( 'NONE', #26669, 1000.000000000000227 ) ; +#13175 = CARTESIAN_POINT ( 'NONE', ( 46.04655628321543759, 186.9737579288344307, 105.3571666265285245 ) ) ; +#13177 = EDGE_CURVE ( 'NONE', #36287, #11904, #31423, .T. ) ; +#13178 = CARTESIAN_POINT ( 'NONE', ( -46.16183276324471763, 125.5709539201926503, 91.75005335738366341 ) ) ; +#13179 = DIRECTION ( 'NONE', ( 0.0006039748319356123742, -6.151140898304641511E-15, 0.9999998176071847045 ) ) ; +#13180 = ORIENTED_EDGE ( 'NONE', *, *, #30939, .T. ) ; +#13181 = ORIENTED_EDGE ( 'NONE', *, *, #2730, .F. ) ; +#13182 = CARTESIAN_POINT ( 'NONE', ( -15.99819964153972585, 151.3054952985143302, 97.67310904513065850 ) ) ; +#13183 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#13184 = PLANE ( 'NONE', #39893 ) ; +#13185 = ORIENTED_EDGE ( 'NONE', *, *, #17890, .T. ) ; +#13186 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049046486, 177.1117171982197931, 103.6430084149422015 ) ) ; +#13187 = ORIENTED_EDGE ( 'NONE', *, *, #1956, .F. ) ; +#13188 = CARTESIAN_POINT ( 'NONE', ( -37.82797334295766944, 117.7727065943990112, 89.71767059357158303 ) ) ; +#13189 = ORIENTED_EDGE ( 'NONE', *, *, #32353, .T. ) ; +#13190 = FACE_OUTER_BOUND ( 'NONE', #8556, .T. ) ; +#13191 = CARTESIAN_POINT ( 'NONE', ( -20.49970531360714787, 187.0374610874570465, 103.3594676856533283 ) ) ; +#13192 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6086, #15301, #8975, #21451, #33891, #5887, #18342, #24925, #40220, #18537, #31042, #37368, #3410, #19556, #25925, #25319, #28375, #4013, #6677, #10179 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000030531, 0.1874999999999939770, 0.2187499999999790168, 0.2343749999999714950, 0.2499999999999639733, 0.4999999999999984457, 0.6250000000000148770, 0.6875000000000194289, 0.7187500000000219824, 0.7343750000000217604, 0.7500000000000214273, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13193 = CARTESIAN_POINT ( 'NONE', ( -2.280577236607999936, 189.8748397010000133, 106.1357350437999969 ) ) ; +#13194 = FACE_OUTER_BOUND ( 'NONE', #17209, .T. ) ; +#13195 = ORIENTED_EDGE ( 'NONE', *, *, #39299, .T. ) ; +#13196 = LINE ( 'NONE', #38135, #17106 ) ; +#13197 = EDGE_CURVE ( 'NONE', #38073, #35348, #12217, .T. ) ; +#13198 = FACE_OUTER_BOUND ( 'NONE', #9532, .T. ) ; +#13199 = AXIS2_PLACEMENT_3D ( 'NONE', #2483, #37221, #6133 ) ; +#13200 = EDGE_CURVE ( 'NONE', #35545, #22722, #12834, .T. ) ; +#13201 = CARTESIAN_POINT ( 'NONE', ( 20.53366021055622070, 212.8322404055747370, 73.04610226615776014 ) ) ; +#13202 = CARTESIAN_POINT ( 'NONE', ( 13.50019380982689832, 123.9831134393972292, 91.09954329858136646 ) ) ; +#13203 = CIRCLE ( 'NONE', #20357, 2.499999999980931698 ) ; +#13204 = CIRCLE ( 'NONE', #36028, 51.90509899264980476 ) ; +#13205 = CARTESIAN_POINT ( 'NONE', ( 13.24378962342656685, 148.9487049838880637, 184.3347202634957682 ) ) ; +#13206 = ORIENTED_EDGE ( 'NONE', *, *, #1500, .T. ) ; +#13207 = CC_DESIGN_PERSON_AND_ORGANIZATION_ASSIGNMENT ( #17756, #2456, ( #16623 ) ) ; +#13208 = CARTESIAN_POINT ( 'NONE', ( 22.49960432933178822, 158.3069096095373993, 96.18736459073451783 ) ) ; +#13209 = CARTESIAN_POINT ( 'NONE', ( -36.39978358780000178, 116.8027791505000010, 90.44031726887999412 ) ) ; +#13210 = ORIENTED_EDGE ( 'NONE', *, *, #1191, .F. ) ; +#13211 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28175, #3000, #9553, #336, #24507, #31223, #3197, #27773, #30629, #22239, #34463, #40016 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000004773959, 0.3750000000007719936, 0.4375000000009254819, 0.4687500000010021983, 0.4843750000009852674, 0.5000000000009683365, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13212 = ORIENTED_EDGE ( 'NONE', *, *, #14918, .T. ) ; +#13213 = CARTESIAN_POINT ( 'NONE', ( -28.45933928643433575, 130.3430211585376810, 92.84111053953343173 ) ) ; +#13214 = DIRECTION ( 'NONE', ( -0.0004161288024629910599, 0.8480480897827221698, -0.5299191110468615129 ) ) ; +#13215 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319388572829 ) ) ; +#13216 = CARTESIAN_POINT ( 'NONE', ( 25.28576755642145457, 131.0248848368917436, 89.88715223900155138 ) ) ; +#13217 = CARTESIAN_POINT ( 'NONE', ( -3.725674215038269566, 174.7211706731201275, 102.8770674905540119 ) ) ; +#13218 = FACE_BOUND ( 'NONE', #3812, .T. ) ; +#13219 = ORIENTED_EDGE ( 'NONE', *, *, #26033, .T. ) ; +#13220 = VERTEX_POINT ( 'NONE', #30820 ) ; +#13221 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#13222 = LINE ( 'NONE', #25708, #6065 ) ; +#13223 = ADVANCED_FACE ( 'NONE', ( #37351 ), #27578, .T. ) ; +#13224 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#13225 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; +#13226 = ORIENTED_EDGE ( 'NONE', *, *, #38111, .T. ) ; +#13227 = ORIENTED_EDGE ( 'NONE', *, *, #27708, .F. ) ; +#13228 = CARTESIAN_POINT ( 'NONE', ( -48.18911509790819991, 84.56867427379300750, 290.9580396635383863 ) ) ; +#13230 = AXIS2_PLACEMENT_3D ( 'NONE', #17517, #8552, #27173 ) ; +#13229 = CARTESIAN_POINT ( 'NONE', ( -39.01171000390000643, 118.7866544936999986, 89.56593668563999699 ) ) ; +#13231 = CARTESIAN_POINT ( 'NONE', ( 25.50773797008787369, 191.9759150222000130, 101.9060413058080030 ) ) ; +#13232 = VECTOR ( 'NONE', #27748, 1000.000000000000000 ) ; +#13233 = AXIS2_PLACEMENT_3D ( 'NONE', #31605, #35036, #12799 ) ; +#13234 = FACE_OUTER_BOUND ( 'NONE', #10279, .T. ) ; +#13235 = CARTESIAN_POINT ( 'NONE', ( -30.07362172845426684, 134.3271078994470429, 93.68749433934327442 ) ) ; +#13236 = ORIENTED_EDGE ( 'NONE', *, *, #14543, .F. ) ; +#13237 = CARTESIAN_POINT ( 'NONE', ( 28.43625476560000109, 125.3820951366000145, 88.75569124208999483 ) ) ; +#13238 = CARTESIAN_POINT ( 'NONE', ( -20.51753249963060455, 207.4552029855167916, 76.98361244602996578 ) ) ; +#13239 = CARTESIAN_POINT ( 'NONE', ( 35.80367347626000196, 111.2706431035999941, 87.49615981601000669 ) ) ; +#13240 = CARTESIAN_POINT ( 'NONE', ( 20.33352814078489601, 120.3153187450193116, 87.75972018744413106 ) ) ; +#13241 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #297, #12991, #3963 ), + ( #902, #25880, #16434 ), + ( #22402, #19305, #31191 ), + ( #16039, #13387, #25270 ) ), + .UNSPECIFIED., .F., .F., .T. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), + ( 3, 3 ), + ( 0.01799787490942297841, 0.02199506981245743717 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.7107876194677253956, 1.000000000000000000), + ( 1.000000000000000000, 0.7107793587187216655, 1.000000000000000000), + ( 1.000000000000000000, 0.7107710978257031353, 1.000000000000000000), + ( 1.000000000000000000, 0.7107628367886674736, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#13242 = EDGE_LOOP ( 'NONE', ( #655, #7189, #27497, #1980, #35753, #19527 ) ) ; +#13243 = CARTESIAN_POINT ( 'NONE', ( -22.64275039132591871, 134.9913333339589485, 90.83180188821697243 ) ) ; +#13244 = CARTESIAN_POINT ( 'NONE', ( 1.328729308773376472, 189.1484174852507465, 103.7267930124833697 ) ) ; +#13245 = LINE ( 'NONE', #32251, #40420 ) ; +#13246 = LINE ( 'NONE', #4021, #9264 ) ; +#13247 = ADVANCED_FACE ( 'NONE', ( #40008 ), #24298, .F. ) ; +#13248 = CARTESIAN_POINT ( 'NONE', ( 22.50029346826248755, 174.4060950772428953, 100.4173051754387416 ) ) ; +#13249 = EDGE_CURVE ( 'NONE', #26876, #13602, #5868, .T. ) ; +#13250 = CARTESIAN_POINT ( 'NONE', ( -26.01326056281665089, 211.0902258159713085, 76.07393268928584007 ) ) ; +#13251 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319392653766 ) ) ; +#13252 = CARTESIAN_POINT ( 'NONE', ( -43.16067970895235106, 137.0136042933273472, 338.0369414682852494 ) ) ; +#13253 = CONICAL_SURFACE ( 'NONE', #11286, 5.999999999954156671, 0.7853981633778982507 ) ; +#13254 = ORIENTED_EDGE ( 'NONE', *, *, #38254, .F. ) ; +#13255 = CONICAL_SURFACE ( 'NONE', #831, 2.503080759942041489, 0.7853981634198553552 ) ; +#13256 = CARTESIAN_POINT ( 'NONE', ( -12.64148697623542361, 181.7671068035208179, 101.7343189441936318 ) ) ; +#13257 = AXIS2_PLACEMENT_3D ( 'NONE', #24301, #2615, #40011 ) ; +#13258 = ORIENTED_EDGE ( 'NONE', *, *, #20389, .T. ) ; +#13259 = CARTESIAN_POINT ( 'NONE', ( -20.00017858637951207, 184.9560350789418237, 102.3655360699851400 ) ) ; +#13260 = CARTESIAN_POINT ( 'NONE', ( -25.99133652784204429, 191.8610009691903713, 103.9342624301125966 ) ) ; +#13261 = CYLINDRICAL_SURFACE ( 'NONE', #28734, 6.000000000000001776 ) ; +#13262 = CARTESIAN_POINT ( 'NONE', ( -34.95638760652207822, 217.7719116313999734, 73.57961695566920923 ) ) ; +#13263 = CARTESIAN_POINT ( 'NONE', ( -15.94527486429822538, 152.8203387458500231, 181.6302711725483050 ) ) ; +#13264 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 183.4515543678114966, 105.0773313099630855 ) ) ; +#13265 = EDGE_LOOP ( 'NONE', ( #17593, #9336, #31929, #7871, #31512 ) ) ; +#13266 = CARTESIAN_POINT ( 'NONE', ( -2.529975153310015212, 209.6207340275237527, 75.72670148088266728 ) ) ; +#13267 = EDGE_CURVE ( 'NONE', #901, #11474, #15283, .T. ) ; +#13268 = CARTESIAN_POINT ( 'NONE', ( 36.33494249648424557, 116.5913739965880751, 87.24583889724033270 ) ) ; +#13269 = CARTESIAN_POINT ( 'NONE', ( 25.65860266051481631, 211.0903045274443173, 75.70969401306156499 ) ) ; +#13270 = CARTESIAN_POINT ( 'NONE', ( -23.35807327067712080, 130.8185406474264312, 90.03995946608934275 ) ) ; +#13271 = ORIENTED_EDGE ( 'NONE', *, *, #33674, .F. ) ; +#13272 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319350647437 ) ) ; +#13273 = ORIENTED_EDGE ( 'NONE', *, *, #20222, .F. ) ; +#13274 = DIRECTION ( 'NONE', ( -0.7857167656192555194, 0.6185862421878133288, 0.0004745532380132049107 ) ) ; +#13275 = CARTESIAN_POINT ( 'NONE', ( 36.04678028602679518, 205.1071438019688458, 76.08304422344946261 ) ) ; +#13276 = AXIS2_PLACEMENT_3D ( 'NONE', #2603, #27753, #40187 ) ; +#13277 = CARTESIAN_POINT ( 'NONE', ( -21.82845866733090290, 176.0428982100538633, 102.8745730682872335 ) ) ; +#13278 = ADVANCED_FACE ( 'NONE', ( #3191 ), #19334, .T. ) ; +#13279 = DIRECTION ( 'NONE', ( 0.1305262453914154408, 0.9659620447682105704, 0.2233388173409121547 ) ) ; +#13280 = CONICAL_SURFACE ( 'NONE', #13951, 2.750000000041938453, 0.7853981633679587571 ) ; +#13281 = DIRECTION ( 'NONE', ( -0.6075492010474002891, 0.7738441339353229198, 0.1790229724939113032 ) ) ; +#13282 = LINE ( 'NONE', #28424, #7956 ) ; +#13283 = EDGE_LOOP ( 'NONE', ( #25466, #6605, #29593, #37619, #8181, #34946, #9027, #15524, #37093, #20080, #32287 ) ) ; +#13284 = ORIENTED_EDGE ( 'NONE', *, *, #36326, .T. ) ; +#13285 = EDGE_CURVE ( 'NONE', #18594, #349, #40218, .T. ) ; +#13286 = CARTESIAN_POINT ( 'NONE', ( 36.05503269261969734, 112.4664341864257437, 89.74600809124632406 ) ) ; +#13287 = AXIS2_PLACEMENT_3D ( 'NONE', #39799, #8956, #23886 ) ; +#13288 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24030, #32615, #33414, #11339 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13289 = CARTESIAN_POINT ( 'NONE', ( -4.839724896237716401, 177.4959176714667421, 100.6340075972825616 ) ) ; +#13290 = CARTESIAN_POINT ( 'NONE', ( -19.08360871869851039, 124.9158349820489349, 178.1622335866570950 ) ) ; +#13291 = CARTESIAN_POINT ( 'NONE', ( -37.18120336268000159, 191.3637114862000033, 104.2412399317999956 ) ) ; +#13292 = EDGE_CURVE ( 'NONE', #9277, #23170, #4532, .T. ) ; +#13293 = ORIENTED_EDGE ( 'NONE', *, *, #12733, .T. ) ; +#13294 = CARTESIAN_POINT ( 'NONE', ( -0.4373757873778362781, 189.0000005053102257, 103.6849946747920228 ) ) ; +#13295 = ORIENTED_EDGE ( 'NONE', *, *, #28882, .F. ) ; +#13296 = EDGE_CURVE ( 'NONE', #37740, #27991, #927, .T. ) ; +#13297 = EDGE_CURVE ( 'NONE', #15583, #31524, #26527, .T. ) ; +#13298 = EDGE_CURVE ( 'NONE', #39751, #33391, #33797, .T. ) ; +#13299 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178618805657E-05, -0.0002331579774917534240 ) ) ; +#13300 = CARTESIAN_POINT ( 'NONE', ( -12.63525319458499752, 176.9910806365248277, 103.4316440411400322 ) ) ; +#13301 = FACE_OUTER_BOUND ( 'NONE', #17253, .T. ) ; +#13302 = CARTESIAN_POINT ( 'NONE', ( -2.748867548853000109, 209.6363855390999902, 73.18061884123000027 ) ) ; +#13303 = CARTESIAN_POINT ( 'NONE', ( 38.31168112654999902, 118.7311881360000001, 90.10289129768000294 ) ) ; +#13304 = AXIS2_PLACEMENT_3D ( 'NONE', #19475, #7753, #32710 ) ; +#13305 = EDGE_LOOP ( 'NONE', ( #15341, #14539, #21103, #12021 ) ) ; +#13306 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066458952, 126.2392922536184869, 91.36674228553239629 ) ) ; +#13307 = CARTESIAN_POINT ( 'NONE', ( -36.40188783471693768, 191.5470103046220345, 106.4089595008395150 ) ) ; +#13308 = FACE_OUTER_BOUND ( 'NONE', #15654, .T. ) ; +#13309 = AXIS2_PLACEMENT_3D ( 'NONE', #22931, #1854, #7572 ) ; +#13310 = DIRECTION ( 'NONE', ( -0.0001408404346090450009, 0.2249510911124607548, -0.9743700461176366678 ) ) ; +#13311 = ORIENTED_EDGE ( 'NONE', *, *, #28727, .T. ) ; +#13312 = EDGE_LOOP ( 'NONE', ( #37222, #9851, #8321, #1735, #14960, #38253, #22134, #5355 ) ) ; +#13313 = AXIS2_PLACEMENT_3D ( 'NONE', #9355, #21827, #28176 ) ; +#13314 = ORIENTED_EDGE ( 'NONE', *, *, #35824, .T. ) ; +#13315 = CARTESIAN_POINT ( 'NONE', ( -13.50162388572643124, 124.5064902939847968, 88.59982987611769545 ) ) ; +#13316 = ORIENTED_EDGE ( 'NONE', *, *, #22760, .F. ) ; +#13317 = CARTESIAN_POINT ( 'NONE', ( -29.20280672789058585, 163.6356169074005038, 97.44881913872031021 ) ) ; +#13318 = CARTESIAN_POINT ( 'NONE', ( -38.46043494895000237, 118.4609868918000188, 89.70915274816999840 ) ) ; +#13319 = CARTESIAN_POINT ( 'NONE', ( -3.336458024821733037, 184.0854103654658331, 102.3254692012155260 ) ) ; +#13320 = DIRECTION ( 'NONE', ( -0.0005884949961189823910, 0.2249510543439030286, -0.9743698870671271273 ) ) ; +#13321 = DIRECTION ( 'NONE', ( 0.0005884949961213717558, -0.2249510543439036392, 0.9743698870671270162 ) ) ; +#13322 = ORIENTED_EDGE ( 'NONE', *, *, #12471, .F. ) ; +#13323 = CYLINDRICAL_SURFACE ( 'NONE', #31054, 22.50000000000000000 ) ; +#13324 = EDGE_CURVE ( 'NONE', #9812, #8915, #28850, .T. ) ; +#13325 = VERTEX_POINT ( 'NONE', #25297 ) ; +#13326 = CARTESIAN_POINT ( 'NONE', ( -34.30586824512814559, 218.5902260770999987, 73.07922396718733182 ) ) ; +#13327 = CARTESIAN_POINT ( 'NONE', ( 25.74914801116624830, 120.7206697623000053, 87.76455777158000160 ) ) ; +#13328 = CARTESIAN_POINT ( 'NONE', ( 3.499881331114640393, 185.8339625544691955, 102.8960692981967640 ) ) ; +#13329 = ORIENTED_EDGE ( 'NONE', *, *, #36972, .T. ) ; +#13330 = CARTESIAN_POINT ( 'NONE', ( -20.00025960434743766, 196.3511145673583655, 104.4227265746208815 ) ) ; +#13331 = CARTESIAN_POINT ( 'NONE', ( 18.59950176168990055, 126.0162487695453706, 174.9291204768238117 ) ) ; +#13332 = CIRCLE ( 'NONE', #30964, 2.499999999945713647 ) ; +#13333 = CIRCLE ( 'NONE', #15941, 22.50000000000899902 ) ; +#13334 = CARTESIAN_POINT ( 'NONE', ( 3.199692528962999827, 190.8181581636000033, 106.9231685249999941 ) ) ; +#13335 = EDGE_CURVE ( 'NONE', #16835, #10860, #37953, .T. ) ; +#13336 = ORIENTED_EDGE ( 'NONE', *, *, #39368, .T. ) ; +#13337 = VECTOR ( 'NONE', #27818, 1000.000000000000114 ) ; +#13338 = ORIENTED_EDGE ( 'NONE', *, *, #7766, .T. ) ; +#13339 = LINE ( 'NONE', #1055, #8066 ) ; +#13340 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#13341 = ADVANCED_FACE ( 'NONE', ( #10556 ), #20645, .F. ) ; +#13342 = ORIENTED_EDGE ( 'NONE', *, *, #10895, .T. ) ; +#13343 = EDGE_CURVE ( 'NONE', #19998, #40342, #1710, .T. ) ; +#13344 = FACE_OUTER_BOUND ( 'NONE', #22506, .T. ) ; +#13345 = CARTESIAN_POINT ( 'NONE', ( 36.49309513148966744, 191.3168920464451332, 103.7998675452271158 ) ) ; +#13346 = ORIENTED_EDGE ( 'NONE', *, *, #27675, .F. ) ; +#13347 = DIRECTION ( 'NONE', ( 3.880623682586550903E-28, -0.9743043966640312359, -0.2252353050503803078 ) ) ; +#13348 = CARTESIAN_POINT ( 'NONE', ( -3.169906973602109712, 126.7999172216492099, 88.92891361563410157 ) ) ; +#13349 = ORIENTED_EDGE ( 'NONE', *, *, #29825, .F. ) ; +#13350 = ORIENTED_EDGE ( 'NONE', *, *, #33062, .F. ) ; +#13351 = CARTESIAN_POINT ( 'NONE', ( 26.00137002222999882, 120.1094979734999981, 90.45180985473000135 ) ) ; +#13352 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2249510911124609769, 0.9743700461176366678 ) ) ; +#13354 = CARTESIAN_POINT ( 'NONE', ( -8.727334286726934565, 152.3139937905420709, 94.82264934010972013 ) ) ; +#13353 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#13355 = CONICAL_SURFACE ( 'NONE', #30342, 2.503080714813746166, 0.7853981633849203003 ) ; +#13356 = ORIENTED_EDGE ( 'NONE', *, *, #1595, .F. ) ; +#13357 = VECTOR ( 'NONE', #2390, 1000.000000000000114 ) ; +#13358 = VECTOR ( 'NONE', #2827, 1000.000000000000114 ) ; +#13359 = ORIENTED_EDGE ( 'NONE', *, *, #24803, .T. ) ; +#13360 = DIRECTION ( 'NONE', ( -0.2818286787186916609, -1.219892887796611130E-14, -0.9594647444547802495 ) ) ; +#13361 = LINE ( 'NONE', #25853, #39721 ) ; +#13363 = ORIENTED_EDGE ( 'NONE', *, *, #33316, .F. ) ; +#13362 = AXIS2_PLACEMENT_3D ( 'NONE', #821, #32317, #25791 ) ; +#13364 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18650, #21959, #8686, #21143, #33597, #5593 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000005551, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13365 = ORIENTED_EDGE ( 'NONE', *, *, #39066, .F. ) ; +#13366 = CARTESIAN_POINT ( 'NONE', ( 38.87252441036000050, 118.8954899181000116, 89.82344399277999969 ) ) ; +#13367 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927890451260, 0.0005734119022042158658 ) ) ; +#13368 = LINE ( 'NONE', #38304, #17358 ) ; +#13369 = FACE_OUTER_BOUND ( 'NONE', #14012, .T. ) ; +#13370 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; +#13371 = ADVANCED_FACE ( 'NONE', ( #7060 ), #19529, .T. ) ; +#13372 = ORIENTED_EDGE ( 'NONE', *, *, #19504, .T. ) ; +#13373 = EDGE_CURVE ( 'NONE', #19816, #16466, #6895, .T. ) ; +#13374 = EDGE_LOOP ( 'NONE', ( #34021, #3641, #30473, #8403 ) ) ; +#13375 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319397694222 ) ) ; +#13376 = EDGE_CURVE ( 'NONE', #7683, #1393, #32226, .T. ) ; +#13377 = PLANE ( 'NONE', #27246 ) ; +#13378 = DIRECTION ( 'NONE', ( 0.0006039748319386881474, 1.110222822128452674E-14, 0.9999998176071845934 ) ) ; +#13379 = ORIENTED_EDGE ( 'NONE', *, *, #23390, .F. ) ; +#13380 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #16825, #20498, #1291, #32783, #26263, #38699, #20093 ), + ( #7630, #4561, #35825, #26459, #4759, #38909, #29928 ), + ( #23386, #17224, #14197, #26665, #39111, #11120, #23585 ), + ( #32972, #1918, #14386, #3113, #2734, #2325, #33988 ), + ( #9266, #14804, #30740, #20926, #15201, #24620, #33789 ), + ( #40321, #18636, #18240, #28088, #39713, #36867, #5984 ), + ( #11522, #27894, #33383, #8873, #37268, #15395, #18437 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 4 ), + ( 4, 3, 4 ), + ( -1.202773222734000081E-12, 0.2500001068580000041, 0.5000004772762000060, 0.7500008476944000080, 0.9999999999962000397 ), + ( 0.1691542049473759857, 0.1756413776277999939, 0.8243586456702000076 ), + .UNSPECIFIED. ) ; +#13381 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971553467 ) ) ; +#13382 = ORIENTED_EDGE ( 'NONE', *, *, #5620, .T. ) ; +#13383 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22966, #20479, #19863, #1267, #13753, #35592, #32759, #35802, #17408, #39288 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13384 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971570121 ) ) ; +#13385 = CARTESIAN_POINT ( 'NONE', ( 3.666638747404721066, 185.7959654146000048, 103.0582394725000484 ) ) ; +#13386 = EDGE_LOOP ( 'NONE', ( #23574, #3014, #24308, #2986 ) ) ; +#13387 = CARTESIAN_POINT ( 'NONE', ( -39.71467534445723402, 163.7699042215536736, 187.8581907678305924 ) ) ; +#13388 = VECTOR ( 'NONE', #8265, 1000.000000000000114 ) ; +#13389 = ADVANCED_FACE ( 'NONE', ( #25905, #35254, #34852, #6860, #16658, #7456, #19921, #32424, #16460, #9750, #13415, #22229, #28751, #38348, #731, #13218, #10358, #29159 ), #2156, .F. ) ; +#13390 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#13391 = CONICAL_SURFACE ( 'NONE', #33601, 51.90509899263999927, 0.7853981633973041721 ) ; +#13392 = CONICAL_SURFACE ( 'NONE', #36230, 40.50000000002201972, 0.7853981633973078358 ) ; +#13393 = CARTESIAN_POINT ( 'NONE', ( 21.98714844736955243, 135.4477026564043740, 93.64701903591871712 ) ) ; +#13394 = ORIENTED_EDGE ( 'NONE', *, *, #13931, .T. ) ; +#13395 = LINE ( 'NONE', #37930, #34735 ) ; +#13396 = CIRCLE ( 'NONE', #6839, 4.499999999969371167 ) ; +#13397 = CARTESIAN_POINT ( 'NONE', ( -3.787588882752000341, 171.8694235010999876, 99.59096943880000197 ) ) ; +#13398 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490313130397, 156.2427122711478091, 96.23754757943613924 ) ) ; +#13399 = EDGE_CURVE ( 'NONE', #7067, #4804, #13288, .T. ) ; +#13400 = CARTESIAN_POINT ( 'NONE', ( -20.01841854128525711, 211.0875725380936103, 76.07063535483980843 ) ) ; +#13401 = VERTEX_POINT ( 'NONE', #5408 ) ; +#13402 = CARTESIAN_POINT ( 'NONE', ( 20.36743396996683941, 212.5991294476698101, 76.04826320807023876 ) ) ; +#13403 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23275, #38790, #13671, #23474, #4244, #36134, #26160, #4657, #2014, #20600, #10812 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000436873, 0.3750000000000741074, 0.4375000000001029177, 0.4687500000000824341, 0.5000000000000618394, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13404 = CARTESIAN_POINT ( 'NONE', ( 3.535970564804119753, 118.9434892789997917, 90.18996607748785266 ) ) ; +#13405 = CARTESIAN_POINT ( 'NONE', ( -37.43154220387000208, 117.0188670058000184, 89.57389268545000505 ) ) ; +#13406 = ORIENTED_EDGE ( 'NONE', *, *, #22353, .T. ) ; +#13407 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323826013271822287, 0.0005734119002331236311 ) ) ; +#13408 = ORIENTED_EDGE ( 'NONE', *, *, #25916, .T. ) ; +#13409 = PLANE ( 'NONE', #30347 ) ; +#13410 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 135.6474414654788347, 90.98047230848234790 ) ) ; +#13411 = CARTESIAN_POINT ( 'NONE', ( 23.68479074154343778, 130.4250414336578956, 90.26276162004360515 ) ) ; +#13412 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825906579923590, 0.0005734119026970681526 ) ) ; +#13413 = CARTESIAN_POINT ( 'NONE', ( 2.563994175896955774, 190.9709097722040099, 106.3045652864306874 ) ) ; +#13414 = ORIENTED_EDGE ( 'NONE', *, *, #211, .F. ) ; +#13415 = FACE_BOUND ( 'NONE', #11719, .T. ) ; +#13416 = ORIENTED_EDGE ( 'NONE', *, *, #16094, .T. ) ; +#13417 = VECTOR ( 'NONE', #13546, 1000.000000000000114 ) ; +#13418 = ORIENTED_EDGE ( 'NONE', *, *, #19600, .F. ) ; +#13419 = CARTESIAN_POINT ( 'NONE', ( 2.253991699705380825, 189.8990359204371430, 105.9958700672874983 ) ) ; +#13420 = CARTESIAN_POINT ( 'NONE', ( 24.53348384866004395, 103.6131156702660689, 87.75296677367606435 ) ) ; +#13421 = AXIS2_PLACEMENT_3D ( 'NONE', #27902, #5384, #5794 ) ; +#13422 = AXIS2_PLACEMENT_3D ( 'NONE', #19186, #17911, #27372 ) ; +#13423 = ORIENTED_EDGE ( 'NONE', *, *, #19804, .F. ) ; +#13424 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927779577222, 0.0005734119022075498959 ) ) ; +#13425 = EDGE_CURVE ( 'NONE', #39311, #27561, #415, .T. ) ; +#13426 = DIRECTION ( 'NONE', ( -3.908872061551316070E-11, 0.9743700557833805398, 0.2249510933351778486 ) ) ; +#13427 = CARTESIAN_POINT ( 'NONE', ( 35.94024013554000163, 116.1452443049000038, 87.11107922145001226 ) ) ; +#13428 = CARTESIAN_POINT ( 'NONE', ( 36.49039500768999744, 191.9046741359000237, 104.5106012823000015 ) ) ; +#13429 = EDGE_CURVE ( 'NONE', #4808, #9107, #23306, .T. ) ; +#13430 = CARTESIAN_POINT ( 'NONE', ( -32.37402305083713827, 138.3010815212902855, 91.60179504951790364 ) ) ; +#13431 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950931402, 137.3532831589782575, 178.0585834213011083 ) ) ; +#13432 = ORIENTED_EDGE ( 'NONE', *, *, #19216, .F. ) ; +#13433 = CARTESIAN_POINT ( 'NONE', ( 28.27269073377999931, 125.4370674547000135, 88.93739120006000576 ) ) ; +#13434 = EDGE_CURVE ( 'NONE', #14237, #1746, #35195, .T. ) ; +#13435 = DIRECTION ( 'NONE', ( 0.5987322044655852826, 0.8009492788783697526, 0.000000000000000000 ) ) ; +#13436 = DIRECTION ( 'NONE', ( -0.9914447998358270064, 0.1272259275658111088, 0.02916800016312352112 ) ) ; +#13437 = CARTESIAN_POINT ( 'NONE', ( -25.99968311866292225, 117.7306449258491483, 90.28348799631405086 ) ) ; +#13438 = LINE ( 'NONE', #35076, #24367 ) ; +#13439 = VERTEX_POINT ( 'NONE', #29959 ) ; +#13441 = EDGE_CURVE ( 'NONE', #17381, #17579, #10138, .T. ) ; +#13440 = CARTESIAN_POINT ( 'NONE', ( 20.94993391244204872, 135.9271259092254240, 94.10042936185872975 ) ) ; +#13442 = CARTESIAN_POINT ( 'NONE', ( 0.7287958894040964530, 189.0068360157825964, 103.6850172550924469 ) ) ; +#13443 = LINE ( 'NONE', #12843, #30638 ) ; +#13444 = AXIS2_PLACEMENT_3D ( 'NONE', #15720, #40459, #28222 ) ; +#13445 = CARTESIAN_POINT ( 'NONE', ( 39.77179625607292479, 161.6649588975980407, 197.0595923755708441 ) ) ; +#13446 = ORIENTED_EDGE ( 'NONE', *, *, #5058, .F. ) ; +#13447 = CARTESIAN_POINT ( 'NONE', ( -25.61544293745999923, 191.6801840824000180, 104.2956903261000008 ) ) ; +#13448 = CIRCLE ( 'NONE', #36282, 51.40509898895388119 ) ; +#13449 = CARTESIAN_POINT ( 'NONE', ( -21.82963564516986210, 182.7566075890955517, 102.3719474125277458 ) ) ; +#13450 = CARTESIAN_POINT ( 'NONE', ( -38.81660742513911089, 106.4213634552623517, 168.3324163836322782 ) ) ; +#13451 = LINE ( 'NONE', #26530, #36664 ) ; +#13452 = ADVANCED_FACE ( 'NONE', ( #1527 ), #13807, .F. ) ; +#13453 = CARTESIAN_POINT ( 'NONE', ( -15.99999411491280199, 138.1989450468032601, 91.56832761027415302 ) ) ; +#13454 = EDGE_LOOP ( 'NONE', ( #26534, #25520, #40455, #5235 ) ) ; +#13455 = AXIS2_PLACEMENT_3D ( 'NONE', #6710, #15719, #12658 ) ; +#13456 = VECTOR ( 'NONE', #14850, 1000.000000000000000 ) ; +#13457 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30701, #3265, #28238, #31491 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13458 = LINE ( 'NONE', #16702, #14821 ) ; +#13459 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971528487 ) ) ; +#13460 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385907860 ) ) ; +#13461 = CARTESIAN_POINT ( 'NONE', ( 39.85586901997003650, 129.5283103249424244, 336.2586849593528768 ) ) ; +#13462 = CARTESIAN_POINT ( 'NONE', ( 20.21383991100996269, 118.1108300582164787, 90.04354866822440329 ) ) ; +#13463 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971557353 ) ) ; +#13464 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#13465 = ORIENTED_EDGE ( 'NONE', *, *, #11859, .F. ) ; +#13466 = EDGE_LOOP ( 'NONE', ( #48, #12167, #32698, #27467 ) ) ; +#13467 = LINE ( 'NONE', #13663, #5563 ) ; +#13468 = CARTESIAN_POINT ( 'NONE', ( 45.79149803454951950, 77.27946979429611929, 297.5308881122152798 ) ) ; +#13469 = CARTESIAN_POINT ( 'NONE', ( 25.82532183281839266, 211.0902320845221425, 75.87621191852036873 ) ) ; +#13470 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#13471 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9278, #18648, #33999, #5999 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 2.912571049175206390E-08, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13472 = EDGE_LOOP ( 'NONE', ( #18762, #6214, #39946, #29126 ) ) ; +#13473 = CARTESIAN_POINT ( 'NONE', ( 17.25788849119799195, 152.5371962406647413, 182.4889206688251306 ) ) ; +#13474 = EDGE_CURVE ( 'NONE', #29279, #22385, #35693, .T. ) ; +#13475 = CARTESIAN_POINT ( 'NONE', ( 39.80472786507999672, 119.2917643122000158, 89.59599340385000232 ) ) ; +#13476 = EDGE_CURVE ( 'NONE', #35219, #8838, #31835, .T. ) ; +#13477 = ORIENTED_EDGE ( 'NONE', *, *, #23868, .F. ) ; +#13478 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #15495, #11833, #12032, #24515 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.442050030669437266, 1.442144067228308790 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999992630936863, 0.9999999992630936863, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#13479 = AXIS2_PLACEMENT_3D ( 'NONE', #33956, #27862, #12296 ) ; +#13480 = CARTESIAN_POINT ( 'NONE', ( 30.51059426112559336, 120.3902231267471592, 87.42876608316004194 ) ) ; +#13481 = ORIENTED_EDGE ( 'NONE', *, *, #25163, .F. ) ; +#13482 = CARTESIAN_POINT ( 'NONE', ( -14.16859888750098406, 182.3077195333686120, 104.3162949350999185 ) ) ; +#13483 = VECTOR ( 'NONE', #8710, 1000.000000000000227 ) ; +#13484 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319387939655 ) ) ; +#13485 = VECTOR ( 'NONE', #31996, 1000.000000000000114 ) ; +#13486 = CARTESIAN_POINT ( 'NONE', ( -12.63667137007742447, 130.6318338952480929, 90.15136591905226737 ) ) ; +#13487 = DIRECTION ( 'NONE', ( -6.234967242035079160E-13, 0.9743700560306142178, 0.2249510922642907751 ) ) ; +#13488 = ORIENTED_EDGE ( 'NONE', *, *, #34058, .T. ) ; +#13489 = CARTESIAN_POINT ( 'NONE', ( 6.034498894405269098, 175.2437274227258683, 100.6206328031571076 ) ) ; +#13490 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672195685, 160.1796136994820188, 99.19090620720055540 ) ) ; +#13491 = LINE ( 'NONE', #31906, #38431 ) ; +#13492 = CARTESIAN_POINT ( 'NONE', ( -20.51839817635225316, 206.2481896911439492, 75.19525730861990098 ) ) ; +#13493 = EDGE_LOOP ( 'NONE', ( #8610, #28117, #27267, #1897, #10726, #2258, #1150, #33265, #27983, #37683, #28663, #13941 ) ) ; +#13494 = CARTESIAN_POINT ( 'NONE', ( -29.41449785468654810, 161.0344709224577571, 187.1181755728296423 ) ) ; +#13495 = ADVANCED_FACE ( 'NONE', ( #20959 ), #10884, .T. ) ; +#13496 = CARTESIAN_POINT ( 'NONE', ( -2.937264483321980979, 191.5260295968394928, 103.8719657109621295 ) ) ; +#13497 = FACE_OUTER_BOUND ( 'NONE', #7053, .T. ) ; +#13498 = VECTOR ( 'NONE', #24356, 1000.000000000000000 ) ; +#13499 = FACE_OUTER_BOUND ( 'NONE', #7226, .T. ) ; +#13500 = CONICAL_SURFACE ( 'NONE', #15463, 2.503010214050041427, 0.7853981633707861620 ) ; +#13501 = CARTESIAN_POINT ( 'NONE', ( 25.62904724343999874, 191.3389271896000139, 106.4877437237000066 ) ) ; +#13502 = CARTESIAN_POINT ( 'NONE', ( 20.48202276548138201, 205.7984546665913399, 75.80227489523332451 ) ) ; +#13503 = CARTESIAN_POINT ( 'NONE', ( -37.40461156464999704, 191.1585361456999976, 106.2295896655000007 ) ) ; +#13504 = ORIENTED_EDGE ( 'NONE', *, *, #34326, .T. ) ; +#13505 = VECTOR ( 'NONE', #11305, 1000.000000000000114 ) ; +#13506 = EDGE_CURVE ( 'NONE', #12780, #19918, #11543, .T. ) ; +#13507 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 108.4362817545589905, 169.8438797714867405 ) ) ; +#13508 = CARTESIAN_POINT ( 'NONE', ( -36.33415831625617898, 191.6212860434504535, 106.4173599585499090 ) ) ; +#13509 = LINE ( 'NONE', #29251, #15725 ) ; +#13510 = CARTESIAN_POINT ( 'NONE', ( 2.545697083959657991, 209.0000005535759158, 75.65980364788404700 ) ) ; +#13511 = VERTEX_POINT ( 'NONE', #5196 ) ; +#13512 = ORIENTED_EDGE ( 'NONE', *, *, #30527, .F. ) ; +#13513 = ORIENTED_EDGE ( 'NONE', *, *, #4238, .T. ) ; +#13514 = CARTESIAN_POINT ( 'NONE', ( 25.49919833444198858, 118.8155663768459505, 87.75236248755290092 ) ) ; +#13515 = FACE_OUTER_BOUND ( 'NONE', #3885, .T. ) ; +#13516 = CARTESIAN_POINT ( 'NONE', ( -48.18910981145552341, 141.1918910709570980, 290.9667924317506049 ) ) ; +#13517 = ADVANCED_FACE ( 'NONE', ( #23419 ), #7665, .F. ) ; +#13518 = ADVANCED_FACE ( 'NONE', ( #29759 ), #33067, .F. ) ; +#13519 = ORIENTED_EDGE ( 'NONE', *, *, #31112, .F. ) ; +#13520 = EDGE_CURVE ( 'NONE', #16377, #27102, #29944, .T. ) ; +#13521 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999894129, 177.0581688370111522, 100.5408937737905859 ) ) ; +#13522 = FACE_OUTER_BOUND ( 'NONE', #30306, .T. ) ; +#13523 = CARTESIAN_POINT ( 'NONE', ( -38.24391925948000193, 118.9459941488999988, 87.57943140326000275 ) ) ; +#13524 = CARTESIAN_POINT ( 'NONE', ( 15.10890892604210478, 182.4258086152457849, 104.8390273514353481 ) ) ; +#13525 = ORIENTED_EDGE ( 'NONE', *, *, #30273, .F. ) ; +#13526 = CARTESIAN_POINT ( 'NONE', ( 19.45260910890439021, 147.6922889574200042, 183.5326060071998597 ) ) ; +#13527 = AXIS2_PLACEMENT_3D ( 'NONE', #15903, #19377, #7654 ) ; +#13528 = ORIENTED_EDGE ( 'NONE', *, *, #36129, .F. ) ; +#13529 = CARTESIAN_POINT ( 'NONE', ( 19.98251549220767487, 208.2807073928345858, 76.59383503248129443 ) ) ; +#13530 = VECTOR ( 'NONE', #20655, 1000.000000000000114 ) ; +#13531 = CARTESIAN_POINT ( 'NONE', ( 22.50143696189732267, 158.0318282207045968, 98.86066492189580401 ) ) ; +#13532 = FACE_OUTER_BOUND ( 'NONE', #34997, .T. ) ; +#13533 = CARTESIAN_POINT ( 'NONE', ( -15.94429972368852866, 121.8869921648800698, 174.4792395813007886 ) ) ; +#13534 = VECTOR ( 'NONE', #23664, 1000.000000000000114 ) ; +#13535 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596097999, 128.5887768395806177, 89.32567453967637050 ) ) ; +#13536 = VERTEX_POINT ( 'NONE', #34951 ) ; +#13537 = CARTESIAN_POINT ( 'NONE', ( -0.4376690092978329782, 188.6111834483369876, 103.1961845456950186 ) ) ; +#13538 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066962549, 129.9712533186751102, 92.22833354197516087 ) ) ; +#13539 = CARTESIAN_POINT ( 'NONE', ( 18.98894481338223272, 148.2010240902047542, 184.7157352475513221 ) ) ; +#13540 = ORIENTED_EDGE ( 'NONE', *, *, #21332, .T. ) ; +#13541 = CARTESIAN_POINT ( 'NONE', ( -20.39898617289156491, 212.6029615956409771, 73.07082455888718187 ) ) ; +#13542 = DIRECTION ( 'NONE', ( 0.0006039748319417797499, -6.167438909947000466E-15, 0.9999998176071845934 ) ) ; +#13543 = VERTEX_POINT ( 'NONE', #19225 ) ; +#13544 = CARTESIAN_POINT ( 'NONE', ( -38.93638499369696149, 190.3639747423779340, 106.7043395007530364 ) ) ; +#13545 = ORIENTED_EDGE ( 'NONE', *, *, #24272, .F. ) ; +#13546 = DIRECTION ( 'NONE', ( 0.0005885022774582036268, -0.2255194047039537075, 0.9742384984012096849 ) ) ; +#13547 = FACE_OUTER_BOUND ( 'NONE', #22637, .T. ) ; +#13548 = ORIENTED_EDGE ( 'NONE', *, *, #8463, .F. ) ; +#13549 = EDGE_LOOP ( 'NONE', ( #32905, #12590, #1090, #14864 ) ) ; +#13550 = EDGE_CURVE ( 'NONE', #15877, #19871, #10048, .T. ) ; +#13551 = CARTESIAN_POINT ( 'NONE', ( 25.50038493774000159, 120.2145571406999949, 89.95686844560999873 ) ) ; +#13552 = AXIS2_PLACEMENT_3D ( 'NONE', #14591, #14383, #20494 ) ; +#13553 = LINE ( 'NONE', #25842, #37140 ) ; +#13554 = AXIS2_PLACEMENT_3D ( 'NONE', #13851, #17913, #15082 ) ; +#13556 = CARTESIAN_POINT ( 'NONE', ( -15.49852919541870655, 185.3436308333990610, 105.0179936569041388 ) ) ; +#13555 = CARTESIAN_POINT ( 'NONE', ( 20.48239712991395933, 207.5021835839149560, 76.84848341814188188 ) ) ; +#13557 = EDGE_CURVE ( 'NONE', #15824, #19888, #22126, .T. ) ; +#13558 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501099925, 179.0628333272265138, 104.0826189413126741 ) ) ; +#13559 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#13560 = ORIENTED_EDGE ( 'NONE', *, *, #11385, .F. ) ; +#13561 = CARTESIAN_POINT ( 'NONE', ( -2.931788836712827084, 190.9017055503348104, 103.7278258144194041 ) ) ; +#13562 = CARTESIAN_POINT ( 'NONE', ( 21.70383481884618959, 176.1155659730582101, 103.0361080479357696 ) ) ; +#13563 = CARTESIAN_POINT ( 'NONE', ( 22.49960432933178822, 158.3069096095373993, 96.18736459073451783 ) ) ; +#13564 = ORIENTED_EDGE ( 'NONE', *, *, #26538, .F. ) ; +#13565 = EDGE_CURVE ( 'NONE', #25223, #19007, #6946, .T. ) ; +#13566 = ORIENTED_EDGE ( 'NONE', *, *, #13794, .T. ) ; +#13568 = EDGE_CURVE ( 'NONE', #38935, #27317, #6559, .T. ) ; +#13567 = CARTESIAN_POINT ( 'NONE', ( 38.52585389698000284, 119.2305566313000043, 90.41527115060999620 ) ) ; +#13569 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#13570 = ADVANCED_FACE ( 'NONE', ( #25400, #28655 ), #9859, .F. ) ; +#13571 = CARTESIAN_POINT ( 'NONE', ( 42.83827273200019903, 189.3718331974772582, 106.4258958018896095 ) ) ; +#13572 = CARTESIAN_POINT ( 'NONE', ( -46.22230826977606455, 125.8520600549444595, 91.81498836011172671 ) ) ; +#13573 = CARTESIAN_POINT ( 'NONE', ( 29.05352371370200615, 110.6131156702000027, 87.25023669171606855 ) ) ; +#13574 = CARTESIAN_POINT ( 'NONE', ( 35.74400150684999744, 192.1411023891000127, 104.0582773893000024 ) ) ; +#13575 = ORIENTED_EDGE ( 'NONE', *, *, #44, .F. ) ; +#13576 = CARTESIAN_POINT ( 'NONE', ( 19.73921667059327234, 149.8473492619755802, 180.1939462582248836 ) ) ; +#13577 = FACE_OUTER_BOUND ( 'NONE', #31318, .T. ) ; +#13578 = CARTESIAN_POINT ( 'NONE', ( 20.33485220578245745, 160.1455537809930547, 99.35001776957351183 ) ) ; +#13579 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -1.739499925770551072E-30, -0.0006039748319385906776 ) ) ; +#13580 = VERTEX_POINT ( 'NONE', #3291 ) ; +#13581 = CARTESIAN_POINT ( 'NONE', ( -3.501631960585971814, 127.9846833621704718, 91.93944743130187192 ) ) ; +#13582 = VERTEX_POINT ( 'NONE', #15030 ) ; +#13583 = VECTOR ( 'NONE', #36562, 1000.000000000000000 ) ; +#13584 = DIRECTION ( 'NONE', ( -0.0006039748319388209621, 4.551467604553135559E-16, -0.9999998176071845934 ) ) ; +#13585 = ORIENTED_EDGE ( 'NONE', *, *, #35580, .T. ) ; +#13586 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684792472, 217.7719116314000303, 75.57961659108507035 ) ) ; +#13587 = AXIS2_PLACEMENT_3D ( 'NONE', #15027, #33411, #30159 ) ; +#13588 = CARTESIAN_POINT ( 'NONE', ( -2.057474463150999799, 190.0654621610999868, 105.8854108991000089 ) ) ; +#13589 = FACE_OUTER_BOUND ( 'NONE', #14777, .T. ) ; +#13590 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921591843, -0.2249510932971527932 ) ) ; +#13591 = VERTEX_POINT ( 'NONE', #13122 ) ; +#13592 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; +#13593 = CARTESIAN_POINT ( 'NONE', ( 23.00039803961572460, 115.6131156701970895, 89.75408929892711285 ) ) ; +#13594 = CARTESIAN_POINT ( 'NONE', ( 13.50018918953322000, 123.9730592991513447, 91.10582582559948150 ) ) ; +#13595 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319380397945 ) ) ; +#13596 = EDGE_LOOP ( 'NONE', ( #31071, #16433, #2774, #11566 ) ) ; +#13597 = EDGE_CURVE ( 'NONE', #30815, #7776, #33248, .T. ) ; +#13598 = DIRECTION ( 'NONE', ( -0.0006039748319387941823, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#13599 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25014, #646, #13529, #38262, #3706, #20045 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13600 = CARTESIAN_POINT ( 'NONE', ( -38.13628578597000285, 117.9293585046000175, 89.55828210560000002 ) ) ; +#13602 = VERTEX_POINT ( 'NONE', #16172 ) ; +#13601 = ADVANCED_FACE ( 'NONE', ( #31519 ), #431, .T. ) ; +#13603 = CARTESIAN_POINT ( 'NONE', ( -20.33172310711824693, 118.8155446846155030, 89.94669117714120432 ) ) ; +#13604 = VERTEX_POINT ( 'NONE', #15963 ) ; +#13605 = CARTESIAN_POINT ( 'NONE', ( 9.888071695018501472, 159.3809512100619372, 96.44294207514620609 ) ) ; +#13606 = ADVANCED_FACE ( 'NONE', ( #30361 ), #27531, .F. ) ; +#13607 = AXIS2_PLACEMENT_3D ( 'NONE', #13630, #29379, #35465 ) ; +#13608 = FACE_OUTER_BOUND ( 'NONE', #18483, .T. ) ; +#13609 = CARTESIAN_POINT ( 'NONE', ( -31.70415073005798590, 220.4002260771000294, 75.57765305097056796 ) ) ; +#13610 = ORIENTED_EDGE ( 'NONE', *, *, #37597, .F. ) ; +#13611 = VERTEX_POINT ( 'NONE', #11761 ) ; +#13612 = CARTESIAN_POINT ( 'NONE', ( -2.935318997662724971, 190.8645861742403724, 106.7981712751157062 ) ) ; +#13613 = AXIS2_PLACEMENT_3D ( 'NONE', #22577, #16607, #35602 ) ; +#13614 = ORIENTED_EDGE ( 'NONE', *, *, #33672, .T. ) ; +#13615 = ORIENTED_EDGE ( 'NONE', *, *, #16182, .T. ) ; +#13616 = EDGE_LOOP ( 'NONE', ( #13322, #20484, #16290, #18062 ) ) ; +#13617 = EDGE_CURVE ( 'NONE', #33385, #28425, #31784, .T. ) ; +#13618 = CARTESIAN_POINT ( 'NONE', ( 1.424924794764945934, 189.1901564357632424, 105.7919554375150426 ) ) ; +#13619 = CARTESIAN_POINT ( 'NONE', ( -19.99848660742553008, 137.5076853405834072, 94.48997979116353463 ) ) ; +#13620 = ORIENTED_EDGE ( 'NONE', *, *, #2303, .F. ) ; +#13621 = CARTESIAN_POINT ( 'NONE', ( -45.07185612124388996, 188.2470601034457047, 105.6714885308213923 ) ) ; +#13622 = CARTESIAN_POINT ( 'NONE', ( 5.666342389540173663, 188.3482258674228547, 103.1300390205756656 ) ) ; +#13623 = CARTESIAN_POINT ( 'NONE', ( 36.33597607651999795, 191.7504636063000021, 104.2398877987999981 ) ) ; +#13624 = CARTESIAN_POINT ( 'NONE', ( 2.948063066966874590, 209.6962674796563704, 76.05661796956628962 ) ) ; +#13625 = ORIENTED_EDGE ( 'NONE', *, *, #26864, .F. ) ; +#13626 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772234801672, 136.6775772631780796, 180.9814965275865575 ) ) ; +#13627 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#13628 = ORIENTED_EDGE ( 'NONE', *, *, #16135, .F. ) ; +#13629 = PLANE ( 'NONE', #25114 ) ; +#13630 = CARTESIAN_POINT ( 'NONE', ( -25.91449223605999919, 130.7183056500000191, 90.10384766008000668 ) ) ; +#13631 = CARTESIAN_POINT ( 'NONE', ( -35.78982145051634234, 209.7096690542524016, 73.41345363205269337 ) ) ; +#13632 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319392907469 ) ) ; +#13633 = ORIENTED_EDGE ( 'NONE', *, *, #36644, .T. ) ; +#13634 = DIRECTION ( 'NONE', ( 0.0005884949961187157857, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#13635 = CARTESIAN_POINT ( 'NONE', ( 0.5988030922453946303, 189.0003911261687222, 103.6820589494512177 ) ) ; +#13636 = CARTESIAN_POINT ( 'NONE', ( -2.600533005549065635, 189.6267769006977346, 106.5121981042907748 ) ) ; +#13637 = VECTOR ( 'NONE', #8571, 1000.000000000000227 ) ; +#13638 = CARTESIAN_POINT ( 'NONE', ( -21.70206949589963230, 176.6347057442738731, 100.7874671074596904 ) ) ; +#13639 = CARTESIAN_POINT ( 'NONE', ( -26.12824141520999888, 191.8139679239000088, 103.7943665811000074 ) ) ; +#13640 = CARTESIAN_POINT ( 'NONE', ( 10.03567519175098255, 143.6524055185811619, 95.37739210866408257 ) ) ; +#13641 = VECTOR ( 'NONE', #27415, 1000.000000000000227 ) ; +#13642 = CARTESIAN_POINT ( 'NONE', ( 15.59065710780919289, 127.6518116315415483, 175.3064835111600814 ) ) ; +#13643 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621343400, 0.1788331191967954814 ) ) ; +#13644 = CARTESIAN_POINT ( 'NONE', ( 18.98781633385216239, 148.3617834207654766, 184.0293870428388345 ) ) ; +#13645 = ORIENTED_EDGE ( 'NONE', *, *, #37329, .F. ) ; +#13646 = EDGE_CURVE ( 'NONE', #11837, #6503, #28508, .T. ) ; +#13647 = EDGE_CURVE ( 'NONE', #26191, #34430, #31320, .T. ) ; +#13648 = ADVANCED_FACE ( 'NONE', ( #24451 ), #20681, .F. ) ; +#13649 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30627, #21435, #27770, #37548 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13650 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552080 ) ) ; +#13651 = CARTESIAN_POINT ( 'NONE', ( -0.4558744329272819695, 211.4999999999972431, 73.05877941915380802 ) ) ; +#13652 = VERTEX_POINT ( 'NONE', #18817 ) ; +#13653 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#13654 = CARTESIAN_POINT ( 'NONE', ( 23.35732905683231309, 181.2169419930002903, 104.3838998314656550 ) ) ; +#13655 = EDGE_CURVE ( 'NONE', #35994, #38340, #597, .T. ) ; +#13656 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927780347819, 0.0005734119022075944566 ) ) ; +#13657 = CARTESIAN_POINT ( 'NONE', ( 20.50100932471902482, 118.1127835883590365, 89.75563873136169946 ) ) ; +#13658 = FACE_OUTER_BOUND ( 'NONE', #11751, .T. ) ; +#13659 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#13660 = CARTESIAN_POINT ( 'NONE', ( 13.50156990940217483, 188.0525492886318943, 103.3109536029596711 ) ) ; +#13661 = ORIENTED_EDGE ( 'NONE', *, *, #26967, .F. ) ; +#13662 = EDGE_CURVE ( 'NONE', #27919, #14260, #12707, .T. ) ; +#13664 = CIRCLE ( 'NONE', #15610, 2.250000000000011102 ) ; +#13663 = CARTESIAN_POINT ( 'NONE', ( 20.24454251694270468, 122.4704376898559417, 162.2874104829967052 ) ) ; +#13665 = DIRECTION ( 'NONE', ( 0.0005884949961233868539, -0.2249510543439054988, 0.9743698870671265722 ) ) ; +#13666 = CARTESIAN_POINT ( 'NONE', ( 14.55482866507330009, 176.2484294118512196, 103.4132012473699973 ) ) ; +#13667 = FACE_OUTER_BOUND ( 'NONE', #33605, .T. ) ; +#13668 = EDGE_LOOP ( 'NONE', ( #38593, #30804, #3336, #10257 ) ) ; +#13669 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#13670 = AXIS2_PLACEMENT_3D ( 'NONE', #24795, #18413, #36844 ) ; +#13671 = CARTESIAN_POINT ( 'NONE', ( 3.656823241034720340, 136.7104492278974419, 94.16761506169929419 ) ) ; +#13672 = VERTEX_POINT ( 'NONE', #29051 ) ; +#13673 = DIRECTION ( 'NONE', ( 0.0006039748319386962789, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#13674 = ORIENTED_EDGE ( 'NONE', *, *, #35788, .T. ) ; +#13675 = FACE_OUTER_BOUND ( 'NONE', #32020, .T. ) ; +#13676 = CARTESIAN_POINT ( 'NONE', ( -45.29507009204370860, 186.0024229835559026, 106.1116092119197134 ) ) ; +#13677 = DIRECTION ( 'NONE', ( -0.0005884949961236880453, 0.2249510543439056931, -0.9743698870671265722 ) ) ; +#13678 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; +#13679 = ORIENTED_EDGE ( 'NONE', *, *, #5092, .T. ) ; +#13680 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567345 ) ) ; +#13681 = CARTESIAN_POINT ( 'NONE', ( -3.622252842473525192, 175.9919634367300318, 100.2860570176304975 ) ) ; +#13682 = DIRECTION ( 'NONE', ( -0.0005884949961256741953, 0.2249510543439056931, -0.9743698870671265722 ) ) ; +#13683 = ORIENTED_EDGE ( 'NONE', *, *, #491, .F. ) ; +#13684 = CARTESIAN_POINT ( 'NONE', ( -37.63792967983999915, 191.1259926255999915, 103.9223442539999951 ) ) ; +#13685 = ORIENTED_EDGE ( 'NONE', *, *, #38958, .T. ) ; +#13686 = CARTESIAN_POINT ( 'NONE', ( 4.034499241909815126, 137.2431130921461886, 91.84870606007839910 ) ) ; +#13687 = CARTESIAN_POINT ( 'NONE', ( 37.26954635975619823, 164.8944657675721999, 196.8584033196613916 ) ) ; +#13688 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31854, #22045, #34474, #31443 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 1.036004206351064581E-06, 0.001197053906935750247 ), + .UNSPECIFIED. ) ; +#13689 = CARTESIAN_POINT ( 'NONE', ( -2.436970329118646639, 191.4135392062368908, 104.3588452342733603 ) ) ; +#13690 = AXIS2_PLACEMENT_3D ( 'NONE', #25428, #19253, #6388 ) ; +#13691 = CARTESIAN_POINT ( 'NONE', ( -23.36043047071902734, 128.0201710902839807, 91.78857617566187344 ) ) ; +#13692 = AXIS2_PLACEMENT_3D ( 'NONE', #3831, #34700, #25747 ) ; +#13693 = EDGE_CURVE ( 'NONE', #1598, #15246, #12779, .T. ) ; +#13694 = EDGE_CURVE ( 'NONE', #25578, #1519, #8270, .T. ) ; +#13695 = CIRCLE ( 'NONE', #23501, 10.00000000000000355 ) ; +#13696 = LINE ( 'NONE', #1011, #2624 ) ; +#13697 = CARTESIAN_POINT ( 'NONE', ( 25.88624728018999832, 191.3092799362999870, 106.7436193634000006 ) ) ; +#13698 = CARTESIAN_POINT ( 'NONE', ( 38.11368864623999997, 119.4135589946000096, 87.13882848846000684 ) ) ; +#13699 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950931402, 137.3532831589782575, 178.0585834213011083 ) ) ; +#13700 = CARTESIAN_POINT ( 'NONE', ( 38.56668844754000247, 118.6267379033999987, 89.80763822784000183 ) ) ; +#13701 = ORIENTED_EDGE ( 'NONE', *, *, #27348, .T. ) ; +#13702 = CARTESIAN_POINT ( 'NONE', ( 13.49481983871936386, 124.3681642032378534, 88.35737770391504853 ) ) ; +#13703 = CARTESIAN_POINT ( 'NONE', ( 13.55544112991404582, 163.9635997609409799, 100.5807068482711486 ) ) ; +#13704 = CC_DESIGN_PERSON_AND_ORGANIZATION_ASSIGNMENT ( #27206, #8790, ( #26440 ) ) ; +#13705 = CARTESIAN_POINT ( 'NONE', ( -36.05314369314938716, 192.0743240283865987, 106.4401673789308802 ) ) ; +#13706 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082098698, 3.303940607880318766E-12, 297.5876476292050938 ) ) ; +#13707 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474981270974893, 155.7928101626038426, 98.18628735352585579 ) ) ; +#13708 = ORIENTED_EDGE ( 'NONE', *, *, #30561, .T. ) ; +#13709 = ORIENTED_EDGE ( 'NONE', *, *, #24984, .T. ) ; +#13710 = ORIENTED_EDGE ( 'NONE', *, *, #26780, .F. ) ; +#13711 = CARTESIAN_POINT ( 'NONE', ( -4.037441715711888257, 137.2418790766001280, 91.85329641528940670 ) ) ; +#13712 = CARTESIAN_POINT ( 'NONE', ( -31.75344637200825559, 110.2231456982486719, 198.5388746951014411 ) ) ; +#13713 = VERTEX_POINT ( 'NONE', #10262 ) ; +#13714 = FACE_BOUND ( 'NONE', #35784, .T. ) ; +#13715 = AXIS2_PLACEMENT_3D ( 'NONE', #17324, #21033, #24107 ) ; +#13716 = EDGE_CURVE ( 'NONE', #39471, #28651, #104, .T. ) ; +#13717 = CIRCLE ( 'NONE', #24194, 2.249999999984611421 ) ; +#13718 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319364164186 ) ) ; +#13719 = CARTESIAN_POINT ( 'NONE', ( -38.81769244209999670, 118.7847089182999980, 89.71781930851000197 ) ) ; +#13720 = CARTESIAN_POINT ( 'NONE', ( -38.35427756623000306, 119.0557098913999994, 87.58667636674000789 ) ) ; +#13721 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#13722 = ORIENTED_EDGE ( 'NONE', *, *, #3942, .F. ) ; +#13723 = CARTESIAN_POINT ( 'NONE', ( 19.30878489618914884, 148.2440988583769581, 183.5073535031560823 ) ) ; +#13724 = AXIS2_PLACEMENT_3D ( 'NONE', #31211, #3187, #28160 ) ; +#13725 = ORIENTED_EDGE ( 'NONE', *, *, #3079, .F. ) ; +#13726 = CARTESIAN_POINT ( 'NONE', ( -3.169886595064320467, 185.3115511372765241, 102.4373918823009291 ) ) ; +#13727 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319364155512 ) ) ; +#13728 = DIRECTION ( 'NONE', ( -0.0005884961822832421958, 0.2249510528375106844, -0.9743698874141887289 ) ) ; +#13729 = FACE_OUTER_BOUND ( 'NONE', #15356, .T. ) ; +#13730 = ORIENTED_EDGE ( 'NONE', *, *, #15852, .T. ) ; +#13731 = CARTESIAN_POINT ( 'NONE', ( -20.00100377755662961, 193.8169056301028945, 102.7149817412491473 ) ) ; +#13732 = CARTESIAN_POINT ( 'NONE', ( 20.00158012229879745, 184.2984082083453359, 105.2684676661315422 ) ) ; +#13733 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#13734 = ORIENTED_EDGE ( 'NONE', *, *, #15850, .T. ) ; +#13735 = DIRECTION ( 'NONE', ( 0.0005884949961203652909, -0.2249510543439047217, 0.9743698870671267942 ) ) ; +#13736 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -3.519737327345223780E-16, 0.0006039748319385488274 ) ) ; +#13737 = EDGE_LOOP ( 'NONE', ( #27829, #23631, #135, #23327 ) ) ; +#13738 = ORIENTED_EDGE ( 'NONE', *, *, #14263, .T. ) ; +#13739 = DIRECTION ( 'NONE', ( -0.0004161288024407980377, -0.5299192578934008857, -0.8480479980228282644 ) ) ; +#13740 = ORIENTED_EDGE ( 'NONE', *, *, #25084, .F. ) ; +#13741 = ADVANCED_FACE ( 'NONE', ( #19821 ), #22727, .F. ) ; +#13742 = EDGE_CURVE ( 'NONE', #15246, #27781, #19434, .T. ) ; +#13743 = DIRECTION ( 'NONE', ( 0.1305263947813612435, 0.9659212020967549162, 0.2235153050807487662 ) ) ; +#13744 = CARTESIAN_POINT ( 'NONE', ( 37.96420214258163384, 191.2635690687931742, 104.9840277876370180 ) ) ; +#13745 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825996983, 153.3598638654817989, 97.61100683840648173 ) ) ; +#13746 = CONICAL_SURFACE ( 'NONE', #6553, 3.002820406140098264, 0.7853589219061751781 ) ; +#13747 = AXIS2_PLACEMENT_3D ( 'NONE', #31035, #28178, #19137 ) ; +#13748 = EDGE_LOOP ( 'NONE', ( #29263, #15765, #7923, #33892 ) ) ; +#13749 = ORIENTED_EDGE ( 'NONE', *, *, #26027, .F. ) ; +#13750 = AXIS2_PLACEMENT_3D ( 'NONE', #32515, #1636, #38247 ) ; +#13751 = CARTESIAN_POINT ( 'NONE', ( 25.51085356005999927, 120.5811326495000060, 90.04130476496999336 ) ) ; +#13752 = VECTOR ( 'NONE', #1991, 1000.000000000000000 ) ; +#13753 = CARTESIAN_POINT ( 'NONE', ( -25.01815341717926700, 212.6267852834324401, 75.57388427013228238 ) ) ; +#13755 = DIRECTION ( 'NONE', ( 5.912089982110409952E-14, -0.9743700558141253909, -0.2249510932020070131 ) ) ; +#13754 = DIRECTION ( 'NONE', ( 1.179611963740366523E-14, 0.9743700557921581851, 0.2249510932971575672 ) ) ; +#13756 = ORIENTED_EDGE ( 'NONE', *, *, #354, .F. ) ; +#13757 = CARTESIAN_POINT ( 'NONE', ( -2.937820978892512702, 191.0281591032251356, 103.7570235660240598 ) ) ; +#13758 = CARTESIAN_POINT ( 'NONE', ( -36.11753663195067077, 191.9605956618226799, 104.4202166091810113 ) ) ; +#13759 = CARTESIAN_POINT ( 'NONE', ( 13.53838462004999954, 112.1320600213999938, 152.4718672074000381 ) ) ; +#13760 = CARTESIAN_POINT ( 'NONE', ( 25.53626815854681098, 191.3673954314083119, 104.3312944428767253 ) ) ; +#13761 = ORIENTED_EDGE ( 'NONE', *, *, #20486, .F. ) ; +#13762 = ORIENTED_EDGE ( 'NONE', *, *, #14443, .T. ) ; +#13763 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; +#13764 = EDGE_CURVE ( 'NONE', #32491, #22722, #38638, .T. ) ; +#13765 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15728, #38215, #25560, #3648 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13766 = CARTESIAN_POINT ( 'NONE', ( -46.02853908287293905, 123.4020261228890831, 92.97376805818757362 ) ) ; +#13767 = DIRECTION ( 'NONE', ( 0.9914446424033197536, 0.1273124132179038470, 0.02879358418792420105 ) ) ; +#13768 = CARTESIAN_POINT ( 'NONE', ( 36.12678806294000111, 191.5105650374999868, 103.8364947623000063 ) ) ; +#13769 = VERTEX_POINT ( 'NONE', #6964 ) ; +#13770 = ORIENTED_EDGE ( 'NONE', *, *, #26643, .F. ) ; +#13771 = ORIENTED_EDGE ( 'NONE', *, *, #36637, .T. ) ; +#13772 = CARTESIAN_POINT ( 'NONE', ( -23.36327211083497346, 134.3782720072525194, 93.65223075065752312 ) ) ; +#13773 = VERTEX_POINT ( 'NONE', #31933 ) ; +#13774 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749388340, 179.6299767372406109, 101.6260513916472377 ) ) ; +#13775 = AXIS2_PLACEMENT_3D ( 'NONE', #16822, #19496, #3547 ) ; +#13776 = EDGE_CURVE ( 'NONE', #19429, #7059, #5969, .T. ) ; +#13777 = VECTOR ( 'NONE', #14689, 1000.000000000000000 ) ; +#13778 = AXIS2_PLACEMENT_3D ( 'NONE', #36609, #14941, #33731 ) ; +#13779 = CARTESIAN_POINT ( 'NONE', ( 3.064469710411337644, 190.8904254212934291, 106.8027684456671551 ) ) ; +#13780 = VERTEX_POINT ( 'NONE', #26001 ) ; +#13781 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#13782 = EDGE_CURVE ( 'NONE', #20598, #18222, #16765, .T. ) ; +#13783 = CARTESIAN_POINT ( 'NONE', ( 33.54411937952203715, 218.5902260770999987, 73.03824427483984039 ) ) ; +#13784 = DIRECTION ( 'NONE', ( 0.6087613508141339613, -0.7729392138727744221, -0.1788143993438125190 ) ) ; +#13785 = CARTESIAN_POINT ( 'NONE', ( -6.081258327431999788, 191.9910753068000133, 28.07991271570000080 ) ) ; +#13786 = VERTEX_POINT ( 'NONE', #7568 ) ; +#13788 = EDGE_CURVE ( 'NONE', #36179, #20168, #2016, .T. ) ; +#13787 = CARTESIAN_POINT ( 'NONE', ( -25.50819987922450238, 205.5673820219388688, 76.31562095576882143 ) ) ; +#13789 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34446, #12581, #508, #6056 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13790 = EDGE_CURVE ( 'NONE', #15694, #35219, #29259, .T. ) ; +#13791 = LINE ( 'NONE', #34640, #33600 ) ; +#13792 = CARTESIAN_POINT ( 'NONE', ( 20.49234192179615377, 211.4170906440259898, 75.54575476972884474 ) ) ; +#13793 = ADVANCED_FACE ( 'NONE', ( #16370 ), #40247, .T. ) ; +#13794 = EDGE_CURVE ( 'NONE', #20853, #15440, #35002, .T. ) ; +#13795 = PLANE ( 'NONE', #16059 ) ; +#13796 = VERTEX_POINT ( 'NONE', #1434 ) ; +#13797 = CARTESIAN_POINT ( 'NONE', ( 33.03711258942921347, 80.00316997518478956, 289.8488960917472355 ) ) ; +#13798 = VECTOR ( 'NONE', #36140, 1000.000000000000114 ) ; +#13799 = CARTESIAN_POINT ( 'NONE', ( -36.84971820185000269, 116.5573134774000010, 89.86943891287999975 ) ) ; +#13800 = ORIENTED_EDGE ( 'NONE', *, *, #17883, .F. ) ; +#13801 = ORIENTED_EDGE ( 'NONE', *, *, #30313, .T. ) ; +#13802 = CARTESIAN_POINT ( 'NONE', ( 17.36823235697561074, 148.6268409572465430, 177.2656691734900107 ) ) ; +#13803 = FACE_OUTER_BOUND ( 'NONE', #9490, .T. ) ; +#13804 = CARTESIAN_POINT ( 'NONE', ( -13.49869758878028669, 124.2895155517476127, 90.92133008179847309 ) ) ; +#13805 = EDGE_LOOP ( 'NONE', ( #7405, #23020, #17310, #2387 ) ) ; +#13806 = ORIENTED_EDGE ( 'NONE', *, *, #22462, .T. ) ; +#13807 = PLANE ( 'NONE', #25278 ) ; +#13808 = ORIENTED_EDGE ( 'NONE', *, *, #2466, .T. ) ; +#13809 = ORIENTED_EDGE ( 'NONE', *, *, #24148, .T. ) ; +#13810 = ORIENTED_EDGE ( 'NONE', *, *, #39333, .F. ) ; +#13811 = PLANE ( 'NONE', #4763 ) ; +#13812 = EDGE_CURVE ( 'NONE', #34012, #20666, #1078, .T. ) ; +#13813 = CARTESIAN_POINT ( 'NONE', ( 19.56366993370219731, 124.7014302495635718, 177.5100158285456473 ) ) ; +#13814 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20176, #32671, #4648, #30006, #11005, #23465, #35914, #39199, #17305, #26958, #20385, #32858, #29812, #1795, #11201, #23676, #8129, #40203, #5669, #37154 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 0.000000000000000000, 0.001296679741553215769, 0.002598800354045131822, 0.005203041579031965000, 0.01041152402900263028, 0.01562000647896829436, 0.02082848892894396259, 0.03124545382888529316, 0.04166241872883661573, 0.06249634852871927687, 0.08333027832861193696, 0.1249981379283372634, 0.1666659975281625794, 0.2500017167276132324, 0.3333374359272638920, 0.5000030656840478427, 0.6666686954407318177, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13815 = ORIENTED_EDGE ( 'NONE', *, *, #6121, .T. ) ; +#13816 = CARTESIAN_POINT ( 'NONE', ( -25.50973903412187127, 207.9962874668275106, 73.88968492455964565 ) ) ; +#13817 = CARTESIAN_POINT ( 'NONE', ( 37.87388331012000009, 118.7446573730999972, 87.34471339006999813 ) ) ; +#13818 = CARTESIAN_POINT ( 'NONE', ( 36.34244127707000160, 191.7459956895999937, 104.2392664664999984 ) ) ; +#13819 = CARTESIAN_POINT ( 'NONE', ( -19.99999816303952471, 191.5261162992163690, 103.8822987450886046 ) ) ; +#13820 = ORIENTED_EDGE ( 'NONE', *, *, #15798, .T. ) ; +#13821 = CARTESIAN_POINT ( 'NONE', ( 19.99941580399983110, 118.1025156334579265, 87.25545403306659864 ) ) ; +#13822 = DIRECTION ( 'NONE', ( -0.0005884949961256741953, 0.2249510543439056931, -0.9743698870671265722 ) ) ; +#13823 = ORIENTED_EDGE ( 'NONE', *, *, #12054, .F. ) ; +#13824 = EDGE_CURVE ( 'NONE', #39966, #38112, #10242, .T. ) ; +#13825 = CARTESIAN_POINT ( 'NONE', ( -6.040498933618321686, 134.3049593577467249, 93.68954146900784963 ) ) ; +#13826 = DIRECTION ( 'NONE', ( -4.163336342552578951E-15, 0.9743700557921590732, 0.2249510932971538202 ) ) ; +#13827 = AXIS2_PLACEMENT_3D ( 'NONE', #22139, #18237, #3496 ) ; +#13828 = CARTESIAN_POINT ( 'NONE', ( -20.34617778358973439, 105.2139170254723695, 89.78007332956207165 ) ) ; +#13829 = CARTESIAN_POINT ( 'NONE', ( -12.72941739898650759, 126.5535087042000413, 177.7865292237629546 ) ) ; +#13830 = ORIENTED_EDGE ( 'NONE', *, *, #2132, .T. ) ; +#13831 = VECTOR ( 'NONE', #39578, 1000.000000000000114 ) ; +#13832 = CARTESIAN_POINT ( 'NONE', ( 20.00000725255388545, 187.1558174806605450, 102.8491768177758132 ) ) ; +#13833 = ADVANCED_FACE ( 'NONE', ( #15143 ), #4905, .F. ) ; +#13834 = CARTESIAN_POINT ( 'NONE', ( 2.210820436746682827, 189.8667456244558309, 103.9335390899887557 ) ) ; +#13835 = CARTESIAN_POINT ( 'NONE', ( 30.71594229360967887, 134.9841247066007668, 90.79791033182986837 ) ) ; +#13836 = ADVANCED_FACE ( 'NONE', ( #30481 ), #36805, .T. ) ; +#13837 = DIRECTION ( 'NONE', ( -0.5605692862037219282, -0.5785653851274223936, 0.5924729280713232349 ) ) ; +#13838 = CARTESIAN_POINT ( 'NONE', ( -25.36572124470999867, 191.4570433652999952, 104.5200422399999951 ) ) ; +#13839 = LINE ( 'NONE', #4427, #4843 ) ; +#13840 = CARTESIAN_POINT ( 'NONE', ( -19.37107429462388453, 124.6247342938447247, 178.2160518200376771 ) ) ; +#13841 = EDGE_CURVE ( 'NONE', #25077, #14950, #39252, .T. ) ; +#13842 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18952, #25932, #26128, #7287, #16294, #38567, #22456, #35284, #31655, #15888, #758, #4214, #16691, #29192, #355 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999418243, 0.3749999999998815392, 0.4374999999998763212, 0.4999999999998711031, 0.6249999999998721023, 0.6874999999998725464, 0.7499999999998729905, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13843 = LINE ( 'NONE', #4632, #40194 ) ; +#13844 = VERTEX_POINT ( 'NONE', #18178 ) ; +#13845 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989907490, 0.1373964268091706076 ) ) ; +#13846 = DIRECTION ( 'NONE', ( -3.965082230941001926E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; +#13847 = PLANE ( 'NONE', #12000 ) ; +#13848 = DIRECTION ( 'NONE', ( 0.7933535320750287889, -0.5931614265262138419, -0.1369295264925107780 ) ) ; +#13849 = LINE ( 'NONE', #17099, #28079 ) ; +#13850 = CARTESIAN_POINT ( 'NONE', ( 36.08518065169000266, 192.3710643713000081, 106.3864685818000027 ) ) ; +#13851 = CARTESIAN_POINT ( 'NONE', ( 53.45676556571323346, 4.842704760271224096, 161.2945539060282272 ) ) ; +#13852 = CIRCLE ( 'NONE', #26304, 7.499999999930377470 ) ; +#13853 = LINE ( 'NONE', #20799, #23007 ) ; +#13854 = CARTESIAN_POINT ( 'NONE', ( -34.20435832628550088, 218.5902260770999987, 75.57916311368344964 ) ) ; +#13855 = VERTEX_POINT ( 'NONE', #20438 ) ; +#13856 = ORIENTED_EDGE ( 'NONE', *, *, #37283, .F. ) ; +#13857 = AXIS2_PLACEMENT_3D ( 'NONE', #25809, #13721, #38448 ) ; +#13858 = DIRECTION ( 'NONE', ( 0.0002071431143271135504, -0.2252353002181516628, 0.9743043757611731248 ) ) ; +#13859 = CARTESIAN_POINT ( 'NONE', ( -2.851226056375999907, 209.7096532013000001, 76.06022722036999539 ) ) ; +#13860 = CIRCLE ( 'NONE', #17754, 2.000000000000011546 ) ; +#13861 = CARTESIAN_POINT ( 'NONE', ( -15.83166609114682721, 127.1075544891181153, 91.91543601929998886 ) ) ; +#13862 = CARTESIAN_POINT ( 'NONE', ( -12.63809837006106918, 177.7897768145701036, 100.7065200156251166 ) ) ; +#13863 = CARTESIAN_POINT ( 'NONE', ( -12.72918671000827295, 126.9094993052254381, 176.2474024732752582 ) ) ; +#13864 = ORIENTED_EDGE ( 'NONE', *, *, #5860, .T. ) ; +#13865 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927351710658, 0.0005734119022173938011 ) ) ; +#13866 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5800, #27701, #18253, #12149 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13867 = EDGE_LOOP ( 'NONE', ( #18300, #5407, #15456, #32386, #8970, #29606 ) ) ; +#13868 = FACE_OUTER_BOUND ( 'NONE', #36275, .T. ) ; +#13869 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971548471 ) ) ; +#13870 = VERTEX_POINT ( 'NONE', #17972 ) ; +#13871 = CARTESIAN_POINT ( 'NONE', ( 36.48161985942883234, 191.5996263034041647, 106.3711761288207498 ) ) ; +#13872 = EDGE_CURVE ( 'NONE', #12341, #6247, #36601, .T. ) ; +#13873 = EDGE_CURVE ( 'NONE', #17992, #39104, #6306, .T. ) ; +#13874 = PLANE ( 'NONE', #23144 ) ; +#13875 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971555410 ) ) ; +#13876 = LINE ( 'NONE', #23899, #5738 ) ; +#13877 = ADVANCED_FACE ( 'NONE', ( #39655 ), #16747, .F. ) ; +#13878 = LINE ( 'NONE', #38801, #33939 ) ; +#13879 = DIRECTION ( 'NONE', ( -0.0005559617643623586706, 0.3907311284892681646, -0.9205046855589708032 ) ) ; +#13880 = ORIENTED_EDGE ( 'NONE', *, *, #28578, .T. ) ; +#13881 = VERTEX_POINT ( 'NONE', #30681 ) ; +#13882 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319356122658 ) ) ; +#13883 = CARTESIAN_POINT ( 'NONE', ( -30.06885891806713573, 177.7007475763269326, 100.7706418980082930 ) ) ; +#13884 = CIRCLE ( 'NONE', #38674, 2.000000003952151051 ) ; +#13885 = FACE_OUTER_BOUND ( 'NONE', #37882, .T. ) ; +#13886 = EDGE_CURVE ( 'NONE', #5875, #39158, #33723, .T. ) ; +#13887 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36175, #23321, #26796, #7351 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13888 = CARTESIAN_POINT ( 'NONE', ( 30.06906075427019331, 177.1956492900629598, 101.0567532827656123 ) ) ; +#13889 = ORIENTED_EDGE ( 'NONE', *, *, #24272, .T. ) ; +#13890 = CIRCLE ( 'NONE', #23035, 2.000000000000011546 ) ; +#13891 = DIRECTION ( 'NONE', ( 0.0005884949961244146776, -0.2249510543439057209, 0.9743698870671265722 ) ) ; +#13892 = CARTESIAN_POINT ( 'NONE', ( 17.25783335673383689, 152.2632692426403196, 183.6728012514050477 ) ) ; +#13893 = EDGE_CURVE ( 'NONE', #22830, #11457, #1532, .T. ) ; +#13894 = AXIS2_PLACEMENT_3D ( 'NONE', #7146, #16743, #1211 ) ; +#13895 = DIRECTION ( 'NONE', ( -0.0002265441438622214161, 0.9034129951719994667, -0.4287713946056891934 ) ) ; +#13896 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 3.370379598151327408E-34, -0.0006039748319386880390 ) ) ; +#13897 = CARTESIAN_POINT ( 'NONE', ( 36.06386299210247870, 192.3813622508035905, 104.3665697773190715 ) ) ; +#13898 = CARTESIAN_POINT ( 'NONE', ( -20.49852834815464320, 160.1744661120611681, 99.21025293621499941 ) ) ; +#13899 = CARTESIAN_POINT ( 'NONE', ( 26.14714473431000386, 191.5389999363000015, 107.0224641065999975 ) ) ; +#13900 = EDGE_CURVE ( 'NONE', #9107, #4808, #20015, .T. ) ; +#13901 = CARTESIAN_POINT ( 'NONE', ( -45.38028798438312350, 123.7560755211207351, 91.33058355487838753 ) ) ; +#13902 = CARTESIAN_POINT ( 'NONE', ( -37.97047246110000174, 190.2037002657999949, 106.8058008725000150 ) ) ; +#13903 = ORIENTED_EDGE ( 'NONE', *, *, #27357, .F. ) ; +#13904 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#13905 = CARTESIAN_POINT ( 'NONE', ( -28.70875735419499364, 148.8778593096899669, 94.55457546971690874 ) ) ; +#13906 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #40412, #27177, #37161, #9157 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13907 = FACE_OUTER_BOUND ( 'NONE', #8002, .T. ) ; +#13908 = CARTESIAN_POINT ( 'NONE', ( -28.47344760044883216, 181.6851202344923308, 101.6154648382260035 ) ) ; +#13910 = ORIENTED_EDGE ( 'NONE', *, *, #31011, .F. ) ; +#13909 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 92.27946979429611929, 297.5967072516831422 ) ) ; +#13911 = ORIENTED_EDGE ( 'NONE', *, *, #17313, .T. ) ; +#13912 = ORIENTED_EDGE ( 'NONE', *, *, #362, .T. ) ; +#13913 = ORIENTED_EDGE ( 'NONE', *, *, #22620, .T. ) ; +#13914 = DIRECTION ( 'NONE', ( 0.0006039748319395907457, 1.291365685536980287E-14, 0.9999998176071847045 ) ) ; +#13915 = VECTOR ( 'NONE', #31660, 1000.000000000000227 ) ; +#13916 = DIRECTION ( 'NONE', ( -0.0006039748319384964604, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#13917 = CIRCLE ( 'NONE', #36770, 2.500000000068288042 ) ; +#13918 = EDGE_LOOP ( 'NONE', ( #12168, #2831, #17430, #37000 ) ) ; +#13919 = FACE_BOUND ( 'NONE', #19819, .T. ) ; +#13920 = AXIS2_PLACEMENT_3D ( 'NONE', #8962, #6074, #14888 ) ; +#13921 = CARTESIAN_POINT ( 'NONE', ( 28.46561152637904257, 183.4536495838093231, 105.0682559342871798 ) ) ; +#13922 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606776115838874, 137.3532831589803322, 178.0585834212922123 ) ) ; +#13923 = CARTESIAN_POINT ( 'NONE', ( -36.59501409695999996, 115.9050424665000065, 87.88340683977000367 ) ) ; +#13924 = ORIENTED_EDGE ( 'NONE', *, *, #33543, .F. ) ; +#13925 = CARTESIAN_POINT ( 'NONE', ( -26.00142186005520983, 120.7678123865047297, 87.55007858260474052 ) ) ; +#13926 = EDGE_CURVE ( 'NONE', #35367, #18185, #11874, .T. ) ; +#13927 = EDGE_LOOP ( 'NONE', ( #2053, #3177, #16960, #33322 ) ) ; +#13929 = EDGE_CURVE ( 'NONE', #1201, #23181, #2470, .T. ) ; +#13928 = CARTESIAN_POINT ( 'NONE', ( 12.31198009898977297, 134.9205818654068025, 90.79431936396761671 ) ) ; +#13930 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927775520409, 0.0005734119022077229346 ) ) ; +#13931 = EDGE_CURVE ( 'NONE', #14171, #10767, #23730, .T. ) ; +#13932 = CARTESIAN_POINT ( 'NONE', ( 20.23520089091118734, 184.3460486268157581, 105.0395362574031850 ) ) ; +#13933 = CARTESIAN_POINT ( 'NONE', ( -34.20496230111741909, 218.5902260770999987, 74.57916329611410333 ) ) ; +#13934 = CARTESIAN_POINT ( 'NONE', ( -20.33179760611627529, 190.9257021876913711, 106.4806516276633488 ) ) ; +#13935 = EDGE_LOOP ( 'NONE', ( #658, #3538, #28744, #32266, #27255, #32321 ) ) ; +#13936 = EDGE_LOOP ( 'NONE', ( #14844, #34451, #12170, #9291 ) ) ; +#13937 = CARTESIAN_POINT ( 'NONE', ( -2.882312078823639823, 190.4459497224870006, 103.6177516974930057 ) ) ; +#13938 = LINE ( 'NONE', #35176, #21861 ) ; +#13939 = CARTESIAN_POINT ( 'NONE', ( 3.199688738393000609, 190.8178714546999970, 106.9231052872000021 ) ) ; +#13940 = EDGE_CURVE ( 'NONE', #28905, #19509, #32917, .T. ) ; +#13941 = ORIENTED_EDGE ( 'NONE', *, *, #24289, .F. ) ; +#13942 = DIRECTION ( 'NONE', ( -0.9999998175971751557, 0.000000000000000000, 0.0006039914041785637844 ) ) ; +#13943 = CARTESIAN_POINT ( 'NONE', ( -25.50005604804929149, 118.3471990083214962, 89.78317637797779582 ) ) ; +#13944 = ORIENTED_EDGE ( 'NONE', *, *, #9556, .T. ) ; +#13945 = VERTEX_POINT ( 'NONE', #8187 ) ; +#13946 = EDGE_CURVE ( 'NONE', #921, #33034, #18109, .T. ) ; +#13947 = VECTOR ( 'NONE', #12446, 1000.000000000000000 ) ; +#13948 = VERTEX_POINT ( 'NONE', #11666 ) ; +#13949 = ORIENTED_EDGE ( 'NONE', *, *, #30879, .T. ) ; +#13950 = CARTESIAN_POINT ( 'NONE', ( 3.040951859482069697, 190.5315687460202128, 106.7176784835704524 ) ) ; +#13951 = AXIS2_PLACEMENT_3D ( 'NONE', #27674, #2514, #21116 ) ; +#13952 = CARTESIAN_POINT ( 'NONE', ( -28.25482047719070167, 186.4533228041470068, 105.2801804772170016 ) ) ; +#13953 = CARTESIAN_POINT ( 'NONE', ( -6.273952178503699351, 163.8304651410298334, 97.99310710002680480 ) ) ; +#13954 = LINE ( 'NONE', #32752, #38045 ) ; +#13955 = ADVANCED_FACE ( 'NONE', ( #27014 ), #40192, .F. ) ; +#13956 = VECTOR ( 'NONE', #6328, 1000.000000000000000 ) ; +#13957 = ORIENTED_EDGE ( 'NONE', *, *, #26188, .F. ) ; +#13958 = LINE ( 'NONE', #20476, #36850 ) ; +#13959 = ORIENTED_EDGE ( 'NONE', *, *, #23015, .F. ) ; +#13960 = CARTESIAN_POINT ( 'NONE', ( 26.00101267970367047, 120.0777975675569422, 90.42043399727945996 ) ) ; +#13961 = CARTESIAN_POINT ( 'NONE', ( 23.36350214670024172, 176.7448593257297773, 103.0093387781554384 ) ) ; +#13963 = LINE ( 'NONE', #22572, #12900 ) ; +#13962 = CARTESIAN_POINT ( 'NONE', ( 20.48140489407852272, 209.4114369237129551, 75.55886289686685586 ) ) ; +#13964 = ORIENTED_EDGE ( 'NONE', *, *, #39925, .T. ) ; +#13965 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#13966 = ORIENTED_EDGE ( 'NONE', *, *, #30375, .T. ) ; +#13967 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15217, #39731, #17844, #5596 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13968 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#13969 = EDGE_LOOP ( 'NONE', ( #33776, #26680, #23793, #23273 ) ) ; +#13970 = CARTESIAN_POINT ( 'NONE', ( -22.49970497330916075, 127.6303751971628060, 89.64545616911016168 ) ) ; +#13971 = CARTESIAN_POINT ( 'NONE', ( -44.54363022636869118, 124.4565585485832173, 93.47074073741023881 ) ) ; +#13972 = CARTESIAN_POINT ( 'NONE', ( -37.36309420899848277, 111.9429838260873851, 150.4031338454339561 ) ) ; +#13973 = ORIENTED_EDGE ( 'NONE', *, *, #37267, .T. ) ; +#13974 = AXIS2_PLACEMENT_3D ( 'NONE', #14657, #39369, #27344 ) ; +#13975 = VECTOR ( 'NONE', #20401, 1000.000000000000000 ) ; +#13976 = ORIENTED_EDGE ( 'NONE', *, *, #5449, .T. ) ; +#13977 = EDGE_LOOP ( 'NONE', ( #9670, #26652, #4491, #20399 ) ) ; +#13978 = ADVANCED_FACE ( 'NONE', ( #33321 ), #36943, .F. ) ; +#13979 = CARTESIAN_POINT ( 'NONE', ( -30.07038801301978026, 136.6761377446520385, 94.30416869769356936 ) ) ; +#13980 = CONICAL_SURFACE ( 'NONE', #37471, 2.749999999702389175, 0.7853981633701920817 ) ; +#13981 = EDGE_CURVE ( 'NONE', #31429, #15784, #3642, .T. ) ; +#13982 = VERTEX_POINT ( 'NONE', #15918 ) ; +#13983 = FACE_OUTER_BOUND ( 'NONE', #15162, .T. ) ; +#13984 = EDGE_CURVE ( 'NONE', #1363, #1746, #40283, .T. ) ; +#13985 = CARTESIAN_POINT ( 'NONE', ( 2.564171575070496534, 190.9919204788867262, 106.3097368431030532 ) ) ; +#13986 = ORIENTED_EDGE ( 'NONE', *, *, #35485, .T. ) ; +#13987 = LINE ( 'NONE', #38508, #9910 ) ; +#13988 = CARTESIAN_POINT ( 'NONE', ( 23.68587874345097077, 128.0263992037866103, 91.76159925728045152 ) ) ; +#13989 = CARTESIAN_POINT ( 'NONE', ( 20.19466032994544946, 152.9152984434986706, 94.94400332294932809 ) ) ; +#13990 = CARTESIAN_POINT ( 'NONE', ( -12.63766980425072184, 130.4202329703295788, 90.28358935384768813 ) ) ; +#13991 = ORIENTED_EDGE ( 'NONE', *, *, #39299, .F. ) ; +#13992 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#13993 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; +#13994 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082099409, 87.27946979429613350, 297.5876476292038433 ) ) ; +#13995 = VECTOR ( 'NONE', #36813, 1000.000000000000114 ) ; +#13996 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21403, #33438, #17688, #5430, #2964, #14856, #2584, #24677, #27945, #39571, #30186 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000464628, 0.3750000000000897060, 0.4375000000001306177, 0.4687500000001419420, 0.5000000000001533218, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#13997 = AXIS2_PLACEMENT_3D ( 'NONE', #36157, #13891, #32889 ) ; +#13998 = VECTOR ( 'NONE', #37969, 1000.000000000000114 ) ; +#13999 = ORIENTED_EDGE ( 'NONE', *, *, #13557, .T. ) ; +#14000 = CARTESIAN_POINT ( 'NONE', ( 12.64524319930002783, 177.7928828500099598, 100.6920447773197225 ) ) ; +#14001 = AXIS2_PLACEMENT_3D ( 'NONE', #13507, #29249, #32508 ) ; +#14003 = CARTESIAN_POINT ( 'NONE', ( -36.43486607269000643, 114.9103894214999997, 89.61052565925000124 ) ) ; +#14002 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971561517 ) ) ; +#14004 = VERTEX_POINT ( 'NONE', #9208 ) ; +#14005 = ORIENTED_EDGE ( 'NONE', *, *, #7350, .T. ) ; +#14006 = DIRECTION ( 'NONE', ( -0.7933532411131104523, -0.5932638852154226150, -0.1364866195435462393 ) ) ; +#14007 = EDGE_CURVE ( 'NONE', #629, #31589, #32755, .T. ) ; +#14008 = FACE_OUTER_BOUND ( 'NONE', #24439, .T. ) ; +#14009 = CARTESIAN_POINT ( 'NONE', ( 25.50046716662595969, 119.8278461341035523, 89.86771791572004986 ) ) ; +#14010 = FACE_OUTER_BOUND ( 'NONE', #12415, .T. ) ; +#14011 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971544308 ) ) ; +#14012 = EDGE_LOOP ( 'NONE', ( #9511, #26726, #21323, #33396 ) ) ; +#14013 = ORIENTED_EDGE ( 'NONE', *, *, #25465, .F. ) ; +#14014 = CARTESIAN_POINT ( 'NONE', ( -4.139184126008303544, 182.1714396567753909, 101.7130139884077096 ) ) ; +#14015 = ORIENTED_EDGE ( 'NONE', *, *, #32091, .F. ) ; +#14016 = ORIENTED_EDGE ( 'NONE', *, *, #15371, .T. ) ; +#14017 = CARTESIAN_POINT ( 'NONE', ( 20.33360375042520118, 118.8156395306597801, 87.58882291287987698 ) ) ; +#14018 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 1.387778780781445202E-14, 0.0006039748319484430396 ) ) ; +#14019 = EDGE_CURVE ( 'NONE', #27523, #5067, #12458, .T. ) ; +#14020 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971548194 ) ) ; +#14021 = CARTESIAN_POINT ( 'NONE', ( -22.49970497326000185, 153.8038087566390857, 95.68807060344595072 ) ) ; +#14023 = EDGE_CURVE ( 'NONE', #37130, #20447, #4430, .T. ) ; +#14022 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; +#14024 = CARTESIAN_POINT ( 'NONE', ( 36.43722455489999845, 115.9580984249000011, 87.59694388343000071 ) ) ; +#14025 = CARTESIAN_POINT ( 'NONE', ( 36.70584045868999823, 191.7769508183999960, 104.5054429551999959 ) ) ; +#14027 = ADVANCED_FACE ( 'NONE', ( #9404 ), #31271, .F. ) ; +#14026 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7476, #33223, #2180, #26927 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.007919380345415786421, 0.009892895677996241255 ), + .UNSPECIFIED. ) ; +#14028 = CARTESIAN_POINT ( 'NONE', ( -28.70758036415549697, 148.4279572010033519, 96.50331524374598757 ) ) ; +#14029 = AXIS2_PLACEMENT_3D ( 'NONE', #32405, #38329, #505 ) ; +#14030 = ADVANCED_FACE ( 'NONE', ( #40257 ), #24553, .T. ) ; +#14031 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 130.2884061588697477, 89.74324129540521255 ) ) ; +#14032 = VERTEX_POINT ( 'NONE', #25352 ) ; +#14033 = LINE ( 'NONE', #10765, #34952 ) ; +#14034 = CARTESIAN_POINT ( 'NONE', ( -0.09096142117404142080, 291.9973835945268661, 213.2953014176902684 ) ) ; +#14035 = ORIENTED_EDGE ( 'NONE', *, *, #33466, .T. ) ; +#14036 = CIRCLE ( 'NONE', #22538, 59.40509898897000340 ) ; +#14037 = CIRCLE ( 'NONE', #2904, 2.250000000000011102 ) ; +#14038 = CARTESIAN_POINT ( 'NONE', ( 0.5623190733617040582, 188.6124699482102756, 103.1972064621602527 ) ) ; +#14039 = CONICAL_SURFACE ( 'NONE', #38202, 2.503010280774284446, 0.7853981633971977017 ) ; +#14040 = DIRECTION ( 'NONE', ( -0.0008702664949568214786, 0.2253087660099396816, -0.9742870226967542679 ) ) ; +#14041 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26313, #4415, #38965, #39362 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.002706531821497740360, 0.003412669838136366852 ), + .UNSPECIFIED. ) ; +#14042 = CARTESIAN_POINT ( 'NONE', ( 9.336298587753999456, 177.4927349323999977, 100.8812869146999986 ) ) ; +#14043 = ORIENTED_EDGE ( 'NONE', *, *, #21751, .T. ) ; +#14044 = CARTESIAN_POINT ( 'NONE', ( -13.46474670641307192, 153.6042747584635890, 98.03125767508242916 ) ) ; +#14045 = CARTESIAN_POINT ( 'NONE', ( 1.500298425804543090, 189.2323929059827208, 103.7509457637548991 ) ) ; +#14046 = CARTESIAN_POINT ( 'NONE', ( 1.169582293534972672, 154.1625274373266166, 98.32235243253177259 ) ) ; +#14047 = ORIENTED_EDGE ( 'NONE', *, *, #29618, .F. ) ; +#14048 = CARTESIAN_POINT ( 'NONE', ( 40.24910017280793539, 69.86439126638083508, 297.5342355816429745 ) ) ; +#14049 = CARTESIAN_POINT ( 'NONE', ( -25.35703419792000091, 191.6937711645000206, 104.5554867752999968 ) ) ; +#14050 = CARTESIAN_POINT ( 'NONE', ( -44.96472012149743591, 114.9735949632774634, 130.1287737409121235 ) ) ; +#14051 = CARTESIAN_POINT ( 'NONE', ( -25.50772789673414920, 207.4083919362629160, 77.09708259040941414 ) ) ; +#14052 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #28405, #9396, #378, #18369 ), + ( #24750, #31262, #12069, #3240 ), + ( #3042, #15909, #30673, #2848 ), + ( #12867, #24545, #18568, #25343 ), + ( #9803, #182, #9199, #31072 ), + ( #27821, #15713, #15523, #37205 ), + ( #21677, #12452, #6309, #33918 ), + ( #5721, #37002, #9001, #28013 ), + ( #12649, #40451, #21478, #22275 ), + ( #30871, #24950, #18975, #5915 ), + ( #25145, #37791, #40248, #3433 ), + ( #18167, #2668, #15132, #15327 ), + ( #12260, #21869, #34115, #9593 ), + ( #6110, #27623, #37591, #6502 ), + ( #34313, #34497, #31466, #18763 ), + ( #571, #4037, #34900, #29209 ), + ( #35495, #22875, #26346, #6704 ), + ( #16506, #1180, #7513, #10404 ), + ( #16316, #32079, #7305, #25952 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -8.647373113754999534E-05, 0.0009118153858942000143, 0.001910104502926000033, 0.003906682736990000140, 0.007812926453889999789, 0.01562541388768999909, 0.03125038875529000115, 0.04687536362289999869, 0.06250033849048999834, 0.09375028822570000142, 0.1250002379609000125, 0.2500000369016999735, 0.3750000857495000006, 0.5000001345972999722, 0.7500002322929999465, 1.000000000000000000, 1.066647782683000090 ), + ( -2.826277697986999871E-08, 1.000838866515000092 ), + .UNSPECIFIED. ) ; +#14053 = CARTESIAN_POINT ( 'NONE', ( -45.98534017754115411, 187.3083424662111725, 103.4373877126195680 ) ) ; +#14054 = DIRECTION ( 'NONE', ( -0.0005884949961259294164, 0.2255194585872565272, -0.9742384859325513569 ) ) ; +#14055 = VERTEX_POINT ( 'NONE', #6511 ) ; +#14056 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20785, #31158, #31767, #12953, #16201, #34981, #19059 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 4 ), + ( 8.578795829086378872E-07, 3.033693725176223621E-05, 0.001294842039712246987 ), + .UNSPECIFIED. ) ; +#14057 = AXIS2_PLACEMENT_3D ( 'NONE', #6996, #38281, #22162 ) ; +#14058 = CARTESIAN_POINT ( 'NONE', ( -22.78364630492483656, 153.8037711675519859, 95.68823341888959533 ) ) ; +#14059 = CARTESIAN_POINT ( 'NONE', ( -35.94552286447999734, 192.4337292808999962, 104.1697190562999964 ) ) ; +#14061 = CARTESIAN_POINT ( 'NONE', ( -2.921522756988824465, 209.4523253363161075, 73.06026897222399441 ) ) ; +#14060 = CIRCLE ( 'NONE', #3590, 1.999999999999994893 ) ; +#14062 = EDGE_CURVE ( 'NONE', #29586, #16868, #38966, .T. ) ; +#14063 = CARTESIAN_POINT ( 'NONE', ( 36.76623636621000202, 191.1626283010999998, 106.4305375327000007 ) ) ; +#14064 = CARTESIAN_POINT ( 'NONE', ( 32.56861805024679768, 175.3596280205372011, 100.1182146692571138 ) ) ; +#14065 = AXIS2_PLACEMENT_3D ( 'NONE', #6928, #37418, #18989 ) ; +#14066 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319369175368 ) ) ; +#14067 = CARTESIAN_POINT ( 'NONE', ( -27.01791081220863333, 113.9384843682444739, 176.2313260275029734 ) ) ; +#14068 = ORIENTED_EDGE ( 'NONE', *, *, #9008, .T. ) ; +#14069 = CARTESIAN_POINT ( 'NONE', ( -5.674054448684419327, 181.0562813008041019, 104.4985371984615909 ) ) ; +#14070 = CARTESIAN_POINT ( 'NONE', ( 26.73277628323574717, 120.3821797830261033, 171.5759152015846496 ) ) ; +#14071 = EDGE_CURVE ( 'NONE', #7856, #18111, #7241, .T. ) ; +#14072 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; +#14073 = ORIENTED_EDGE ( 'NONE', *, *, #36025, .F. ) ; +#14074 = DIRECTION ( 'NONE', ( 0.7933532970003738249, 0.5930762008556724751, 0.1372995488602876402 ) ) ; +#14075 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474978710144656, 155.7928101624881663, 98.18628735359372683 ) ) ; +#14076 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29304, #1279, #25182, #31301 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14077 = EDGE_CURVE ( 'NONE', #19947, #12930, #3707, .T. ) ; +#14078 = ORIENTED_EDGE ( 'NONE', *, *, #25080, .T. ) ; +#14079 = EDGE_CURVE ( 'NONE', #31188, #27747, #36151, .T. ) ; +#14080 = EDGE_CURVE ( 'NONE', #18912, #32718, #37608, .T. ) ; +#14081 = PLANE ( 'NONE', #4829 ) ; +#14082 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319386956284 ) ) ; +#14083 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29374, #1971, #26924, #30179 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14084 = VERTEX_POINT ( 'NONE', #3050 ) ; +#14085 = CARTESIAN_POINT ( 'NONE', ( 36.47117602849728257, 191.6114442409242429, 106.3724499118136180 ) ) ; +#14086 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319370729030 ) ) ; +#14087 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#14088 = CARTESIAN_POINT ( 'NONE', ( -25.50111726777775090, 120.6553742016506874, 88.03695713991920968 ) ) ; +#14089 = LINE ( 'NONE', #26766, #18256 ) ; +#14090 = DIRECTION ( 'NONE', ( 1.017704439249174122E-14, -0.9743700557921587402, -0.2249510932971553467 ) ) ; +#14091 = AXIS2_PLACEMENT_3D ( 'NONE', #7495, #10989, #16888 ) ; +#14092 = ORIENTED_EDGE ( 'NONE', *, *, #6810, .T. ) ; +#14093 = CARTESIAN_POINT ( 'NONE', ( -12.63088703835403237, 131.0198726340251199, 89.90887950976862442 ) ) ; +#14094 = DIRECTION ( 'NONE', ( 0.7856007465113965527, 0.6187337610642694719, 0.000000000000000000 ) ) ; +#14095 = CIRCLE ( 'NONE', #17298, 2.500000000068516748 ) ; +#14096 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#14097 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #37686, #6796 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14098 = AXIS2_PLACEMENT_3D ( 'NONE', #25164, #9819, #34723 ) ; +#14099 = ORIENTED_EDGE ( 'NONE', *, *, #1941, .F. ) ; +#14100 = LINE ( 'NONE', #11423, #7958 ) ; +#14101 = ORIENTED_EDGE ( 'NONE', *, *, #9315, .T. ) ; +#14102 = AXIS2_PLACEMENT_3D ( 'NONE', #31798, #4152, #18886 ) ; +#14103 = VERTEX_POINT ( 'NONE', #15530 ) ; +#14104 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, -1.295171136338797037E-14 ) ) ; +#14105 = CARTESIAN_POINT ( 'NONE', ( 20.16857011096831442, 151.3424427607513678, 97.48851605858358482 ) ) ; +#14106 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#14107 = CARTESIAN_POINT ( 'NONE', ( 4.133313241595669041, 130.5370971685930499, 89.78728818282839086 ) ) ; +#14108 = CARTESIAN_POINT ( 'NONE', ( -22.49862694078846559, 157.6261014233649576, 99.13627282167615817 ) ) ; +#14109 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971555410 ) ) ; +#14110 = CYLINDRICAL_SURFACE ( 'NONE', #33268, 2.000000000000014655 ) ; +#14111 = CARTESIAN_POINT ( 'NONE', ( 25.90038763860000159, 190.9907937845999868, 106.6889637737999976 ) ) ; +#14112 = CARTESIAN_POINT ( 'NONE', ( 26.80533604859723340, 110.6131156702000027, 90.25159508795590568 ) ) ; +#14113 = CARTESIAN_POINT ( 'NONE', ( 3.312971681818163372, 183.3029474176353233, 101.9697422706757521 ) ) ; +#14114 = EDGE_LOOP ( 'NONE', ( #7645, #1442, #1435, #26801 ) ) ; +#14115 = ADVANCED_FACE ( 'NONE', ( #18769 ), #28020, .F. ) ; +#14116 = CARTESIAN_POINT ( 'NONE', ( 16.57679466784161804, 122.7580812988415460, 172.1226709236619286 ) ) ; +#14117 = DIRECTION ( 'NONE', ( -0.0005884949961245359998, 0.2249510543439058319, -0.9743698870671265722 ) ) ; +#14118 = EDGE_CURVE ( 'NONE', #25759, #25751, #188, .T. ) ; +#14119 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32681, #14698, #36137, #10815, #35713, #1806, #29614, #2017, #39206, #20191 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14120 = CARTESIAN_POINT ( 'NONE', ( 19.27401778716228620, 148.4626371618211067, 184.5957245738844961 ) ) ; +#14121 = CARTESIAN_POINT ( 'NONE', ( -23.36013443277664692, 183.4461002756636674, 105.1009555742510031 ) ) ; +#14122 = ADVANCED_FACE ( 'NONE', ( #38002 ), #15398, .F. ) ; +#14123 = CONICAL_SURFACE ( 'NONE', #37632, 2.502994747345931970, 0.7853981633840819709 ) ; +#14124 = CARTESIAN_POINT ( 'NONE', ( -20.89133279417689337, 135.6510826495900517, 94.06197212497137627 ) ) ; +#14125 = AXIS2_PLACEMENT_3D ( 'NONE', #8438, #27471, #9238 ) ; +#14126 = ORIENTED_EDGE ( 'NONE', *, *, #30497, .F. ) ; +#14127 = ORIENTED_EDGE ( 'NONE', *, *, #21094, .F. ) ; +#14128 = ADVANCED_FACE ( 'NONE', ( #25554 ), #22882, .T. ) ; +#14129 = ORIENTED_EDGE ( 'NONE', *, *, #15628, .F. ) ; +#14130 = CARTESIAN_POINT ( 'NONE', ( -13.50129746631583849, 124.5395215374018818, 88.65269067405510839 ) ) ; +#14131 = CIRCLE ( 'NONE', #34330, 2.500000093254001854 ) ; +#14132 = CARTESIAN_POINT ( 'NONE', ( -23.01879311717446086, 214.0903458147471383, 76.07243274013872281 ) ) ; +#14133 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391912172 ) ) ; +#14134 = AXIS2_PLACEMENT_3D ( 'NONE', #36038, #17636, #10718 ) ; +#14135 = VERTEX_POINT ( 'NONE', #10413 ) ; +#14136 = FACE_BOUND ( 'NONE', #29096, .T. ) ; +#14137 = EDGE_CURVE ( 'NONE', #38350, #1132, #36596, .T. ) ; +#14138 = CARTESIAN_POINT ( 'NONE', ( -28.46590577390901444, 183.5585884066778419, 104.6137160372684036 ) ) ; +#14139 = CARTESIAN_POINT ( 'NONE', ( -37.22196800321000154, 118.5277161940000212, 87.16415279387000226 ) ) ; +#14140 = EDGE_LOOP ( 'NONE', ( #12476, #27171, #4135, #17178 ) ) ; +#14141 = CARTESIAN_POINT ( 'NONE', ( -13.50000076883903510, 154.4042507776735818, 95.30811371979322644 ) ) ; +#14142 = ORIENTED_EDGE ( 'NONE', *, *, #1929, .T. ) ; +#14143 = DIRECTION ( 'NONE', ( -0.0005559617644274909235, 0.3907311284892684422, -0.9205046855589705812 ) ) ; +#14144 = CARTESIAN_POINT ( 'NONE', ( 35.55533445361766098, 112.4664342211686971, 90.24631030758727945 ) ) ; +#14145 = DIRECTION ( 'NONE', ( 0.0006039748319378934272, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#14146 = ORIENTED_EDGE ( 'NONE', *, *, #21101, .F. ) ; +#14147 = EDGE_CURVE ( 'NONE', #38809, #9250, #26585, .T. ) ; +#14148 = ORIENTED_EDGE ( 'NONE', *, *, #36265, .T. ) ; +#14149 = CARTESIAN_POINT ( 'NONE', ( -20.00002391410913560, 191.9758546681010785, 103.9335315410770448 ) ) ; +#14150 = CARTESIAN_POINT ( 'NONE', ( 0.6435323986543000085, 188.8721228995999866, 103.5282549655999986 ) ) ; +#14151 = CARTESIAN_POINT ( 'NONE', ( -35.43583965384924994, 192.6933639929883668, 106.8920161462278315 ) ) ; +#14152 = AXIS2_PLACEMENT_3D ( 'NONE', #9505, #21785, #34422 ) ; +#14153 = ORIENTED_EDGE ( 'NONE', *, *, #20901, .F. ) ; +#14154 = VERTEX_POINT ( 'NONE', #7519 ) ; +#14155 = CARTESIAN_POINT ( 'NONE', ( 16.88249520720069441, 127.4209172357130342, 171.9069182253847430 ) ) ; +#14156 = CARTESIAN_POINT ( 'NONE', ( -25.50005904708520887, 118.5813826976429937, 89.78317938063858605 ) ) ; +#14157 = AXIS2_PLACEMENT_3D ( 'NONE', #17163, #35549, #14133 ) ; +#14158 = VERTEX_POINT ( 'NONE', #19779 ) ; +#14159 = EDGE_LOOP ( 'NONE', ( #40414, #11754, #1095, #37824 ) ) ; +#14160 = CIRCLE ( 'NONE', #8271, 2.749999999950412999 ) ; +#14161 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34221, #31379, #33832, #9108 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14162 = CIRCLE ( 'NONE', #37638, 2.000000000015665691 ) ; +#14163 = ORIENTED_EDGE ( 'NONE', *, *, #27291, .F. ) ; +#14164 = ORIENTED_EDGE ( 'NONE', *, *, #9148, .T. ) ; +#14165 = VECTOR ( 'NONE', #31704, 1000.000000000000227 ) ; +#14166 = CARTESIAN_POINT ( 'NONE', ( -27.00166637643960854, 188.8391338125088907, 103.2661811242819141 ) ) ; +#14167 = DIRECTION ( 'NONE', ( -0.0006039748319385316970, -1.156831349449291921E-15, -0.9999998176071845934 ) ) ; +#14168 = DIRECTION ( 'NONE', ( 0.0005884949961216158097, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#14169 = ORIENTED_EDGE ( 'NONE', *, *, #14118, .F. ) ; +#14170 = LINE ( 'NONE', #1684, #4257 ) ; +#14171 = VERTEX_POINT ( 'NONE', #32678 ) ; +#14172 = EDGE_CURVE ( 'NONE', #30682, #26180, #38239, .T. ) ; +#14173 = CARTESIAN_POINT ( 'NONE', ( 25.86001714968000087, 120.6927307848000197, 90.40934820274000572 ) ) ; +#14174 = EDGE_CURVE ( 'NONE', #16794, #7173, #35709, .T. ) ; +#14175 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971558741 ) ) ; +#14176 = EDGE_CURVE ( 'NONE', #39055, #21097, #4656, .T. ) ; +#14177 = ADVANCED_FACE ( 'NONE', ( #7719 ), #38594, .F. ) ; +#14179 = FACE_OUTER_BOUND ( 'NONE', #29927, .T. ) ; +#14178 = CARTESIAN_POINT ( 'NONE', ( 20.48226435717378990, 207.6251565648111921, 76.64532538342577084 ) ) ; +#14180 = VERTEX_POINT ( 'NONE', #17114 ) ; +#14181 = ORIENTED_EDGE ( 'NONE', *, *, #22259, .F. ) ; +#14182 = ADVANCED_FACE ( 'NONE', ( #29611 ), #1676, .F. ) ; +#14183 = VECTOR ( 'NONE', #27709, 1000.000000000000227 ) ; +#14184 = CARTESIAN_POINT ( 'NONE', ( -36.20294578993510015, 191.8784110327004271, 104.4126546692563124 ) ) ; +#14185 = AXIS2_PLACEMENT_3D ( 'NONE', #11011, #20808, #14693 ) ; +#14186 = AXIS2_PLACEMENT_3D ( 'NONE', #23060, #35484, #38770 ) ; +#14187 = ORIENTED_EDGE ( 'NONE', *, *, #816, .T. ) ; +#14188 = CARTESIAN_POINT ( 'NONE', ( -35.58577006176208357, 114.4949262162575394, 87.28927720544345448 ) ) ; +#14189 = EDGE_CURVE ( 'NONE', #8395, #35627, #23078, .T. ) ; +#14190 = LINE ( 'NONE', #23572, #1772 ) ; +#14191 = CARTESIAN_POINT ( 'NONE', ( -25.86759374482710783, 189.1478801855697327, 105.9025369694237355 ) ) ; +#14192 = VERTEX_POINT ( 'NONE', #6922 ) ; +#14193 = ORIENTED_EDGE ( 'NONE', *, *, #32607, .F. ) ; +#14194 = CARTESIAN_POINT ( 'NONE', ( -55.13842001341838284, 70.21991383836160594, 291.5918461592676181 ) ) ; +#14195 = CARTESIAN_POINT ( 'NONE', ( 26.67362535667000145, 123.9118361340999996, 88.58630574830999649 ) ) ; +#14196 = ORIENTED_EDGE ( 'NONE', *, *, #6628, .T. ) ; +#14197 = CARTESIAN_POINT ( 'NONE', ( -35.47012669195299850, 192.2364783050030042, 106.9476611020870109 ) ) ; +#14198 = CARTESIAN_POINT ( 'NONE', ( -38.25678666646345505, 118.2563848851881261, 89.71134074324241681 ) ) ; +#14199 = ORIENTED_EDGE ( 'NONE', *, *, #13550, .F. ) ; +#14200 = CARTESIAN_POINT ( 'NONE', ( 2.897488390111000012, 190.8910838861999935, 106.6291555332999934 ) ) ; +#14201 = CARTESIAN_POINT ( 'NONE', ( -30.07323323487542410, 135.0982449750613057, 91.11183024367421979 ) ) ; +#14202 = CARTESIAN_POINT ( 'NONE', ( 6.034204648359921208, 177.7921235470974466, 100.6958268401488539 ) ) ; +#14203 = CARTESIAN_POINT ( 'NONE', ( 20.21154621427845655, 152.9536990292900782, 94.95285859969516196 ) ) ; +#14204 = CARTESIAN_POINT ( 'NONE', ( 32.66389061773956826, 141.7118122376935219, 282.5421777876526335 ) ) ; +#14205 = AXIS2_PLACEMENT_3D ( 'NONE', #19445, #6975, #37863 ) ; +#14206 = ORIENTED_EDGE ( 'NONE', *, *, #29260, .T. ) ; +#14207 = FACE_OUTER_BOUND ( 'NONE', #12373, .T. ) ; +#14208 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -1.540743955509788340E-33, -0.0006039748319384538513 ) ) ; +#14209 = ORIENTED_EDGE ( 'NONE', *, *, #33030, .T. ) ; +#14210 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#14211 = EDGE_CURVE ( 'NONE', #12603, #8692, #35107, .T. ) ; +#14212 = EDGE_CURVE ( 'NONE', #35056, #10693, #35110, .T. ) ; +#14214 = CARTESIAN_POINT ( 'NONE', ( 13.79955906167705315, 158.3019397583766192, 96.19147016730026678 ) ) ; +#14213 = DIRECTION ( 'NONE', ( -1.249000902737679666E-14, 0.9743700557921584071, 0.2249510932971565957 ) ) ; +#14215 = ORIENTED_EDGE ( 'NONE', *, *, #37836, .T. ) ; +#14216 = ORIENTED_EDGE ( 'NONE', *, *, #10574, .F. ) ; +#14217 = DIRECTION ( 'NONE', ( 0.6087614115774527823, 0.7729348350621608743, 0.1788331191968013101 ) ) ; +#14218 = LINE ( 'NONE', #4587, #23907 ) ; +#14219 = CARTESIAN_POINT ( 'NONE', ( -20.16649829641212577, 127.7037111234754008, 89.31880475177413814 ) ) ; +#14220 = CARTESIAN_POINT ( 'NONE', ( -13.49989043803929434, 124.0147166309723019, 91.09304410618094039 ) ) ; +#14221 = ORIENTED_EDGE ( 'NONE', *, *, #36480, .F. ) ; +#14222 = ORIENTED_EDGE ( 'NONE', *, *, #31106, .F. ) ; +#14223 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#14224 = ORIENTED_EDGE ( 'NONE', *, *, #11677, .F. ) ; +#14225 = ORIENTED_EDGE ( 'NONE', *, *, #16354, .T. ) ; +#14226 = DIRECTION ( 'NONE', ( -0.6075492010474002891, 0.7738441339353229198, 0.1790229724939113032 ) ) ; +#14227 = CARTESIAN_POINT ( 'NONE', ( 2.964187886207000133, 209.6236585254000317, 73.05669866528999989 ) ) ; +#14228 = CONICAL_SURFACE ( 'NONE', #37079, 2.502993756986731100, 0.7853981634153905933 ) ; +#14229 = VERTEX_POINT ( 'NONE', #3844 ) ; +#14230 = CARTESIAN_POINT ( 'NONE', ( 42.94254652958284879, 102.0785988256732679, 173.5067946477687144 ) ) ; +#14231 = DIRECTION ( 'NONE', ( 0.0004161288024536310341, -0.8480480897965216869, 0.5299191110247775116 ) ) ; +#14232 = CARTESIAN_POINT ( 'NONE', ( -36.19263021343000020, 191.7617955707000021, 104.2857773767999987 ) ) ; +#14233 = CARTESIAN_POINT ( 'NONE', ( 38.04191701154000071, 190.9293984182999964, 103.5603850786000066 ) ) ; +#14234 = CARTESIAN_POINT ( 'NONE', ( -15.49970618472456074, 126.6879451655382809, 89.42365126055415203 ) ) ; +#14235 = VECTOR ( 'NONE', #15279, 1000.000000000000114 ) ; +#14236 = ADVANCED_FACE ( 'NONE', ( #29006 ), #16909, .T. ) ; +#14237 = VERTEX_POINT ( 'NONE', #32088 ) ; +#14238 = LINE ( 'NONE', #20978, #2961 ) ; +#14239 = DIRECTION ( 'NONE', ( 0.0006039748319292907166, 1.314021223879979485E-14, 0.9999998176071844824 ) ) ; +#14240 = CARTESIAN_POINT ( 'NONE', ( 20.00000279695219874, 118.8155797008581374, 87.25566994753728522 ) ) ; +#14241 = EDGE_LOOP ( 'NONE', ( #29637, #6593, #11495, #6728 ) ) ; +#14242 = CARTESIAN_POINT ( 'NONE', ( 0.6175806947401220048, 188.6158791694291494, 103.1979573861220985 ) ) ; +#14243 = CARTESIAN_POINT ( 'NONE', ( 24.99841341575277553, 116.5768525021753561, 87.75250987812781034 ) ) ; +#14244 = CARTESIAN_POINT ( 'NONE', ( 20.16677047258863098, 191.4881498579996162, 104.0203231957113843 ) ) ; +#14245 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #40002, #11811, #8951, #9144 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14246 = CARTESIAN_POINT ( 'NONE', ( -14.22274084689574636, 128.8778062397453539, 177.5848030100378026 ) ) ; +#14247 = ORIENTED_EDGE ( 'NONE', *, *, #11647, .F. ) ; +#14248 = DIRECTION ( 'NONE', ( 0.0005884949961232421129, -0.2249510543439050270, 0.9743698870671265722 ) ) ; +#14249 = DIRECTION ( 'NONE', ( 0.0002393071182785211099, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#14250 = CARTESIAN_POINT ( 'NONE', ( 8.708510873816388553, 191.5259668330004104, 103.8649174644812661 ) ) ; +#14251 = ORIENTED_EDGE ( 'NONE', *, *, #12053, .T. ) ; +#14252 = DIRECTION ( 'NONE', ( -9.842052273231448302E-18, 0.9743043966640313469, 0.2252353050503801690 ) ) ; +#14253 = EDGE_LOOP ( 'NONE', ( #18335, #23584, #29046, #34500 ) ) ; +#14254 = VERTEX_POINT ( 'NONE', #13473 ) ; +#14255 = CARTESIAN_POINT ( 'NONE', ( -25.61303419248000068, 191.8414174858999957, 104.3130003953999960 ) ) ; +#14256 = CARTESIAN_POINT ( 'NONE', ( -6.273952199476604541, 148.6532986828639480, 94.48918149448384440 ) ) ; +#14257 = CARTESIAN_POINT ( 'NONE', ( 26.18467446761999895, 191.4585183799999868, 103.6969400202000031 ) ) ; +#14258 = CARTESIAN_POINT ( 'NONE', ( 5.704476631508000217, 115.9590670144843330, 152.9217693939943388 ) ) ; +#14259 = DIRECTION ( 'NONE', ( -0.0005884949961233675551, 0.2249510543439052490, -0.9743698870671265722 ) ) ; +#14260 = VERTEX_POINT ( 'NONE', #30428 ) ; +#14261 = AXIS2_PLACEMENT_3D ( 'NONE', #19654, #19452, #32347 ) ; +#14262 = EDGE_CURVE ( 'NONE', #23190, #18594, #39398, .T. ) ; +#14263 = EDGE_CURVE ( 'NONE', #25850, #28145, #11403, .T. ) ; +#14264 = VECTOR ( 'NONE', #38346, 1000.000000000000114 ) ; +#14265 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7151642779479941980, -0.6989564046112777262 ) ) ; +#14266 = CARTESIAN_POINT ( 'NONE', ( 20.61224087687466167, 176.1547247241071261, 100.3089964015452438 ) ) ; +#14267 = CARTESIAN_POINT ( 'NONE', ( 29.35770870545113809, 112.1779706540911974, 175.8381852828548801 ) ) ; +#14268 = ADVANCED_FACE ( 'NONE', ( #30216 ), #29752, .F. ) ; +#14269 = FACE_OUTER_BOUND ( 'NONE', #12184, .T. ) ; +#14270 = DIRECTION ( 'NONE', ( 0.0006039748549143392599, 0.000000000000000000, 0.9999998176071707157 ) ) ; +#14271 = CARTESIAN_POINT ( 'NONE', ( -5.667212792806153310, 130.0468365392308669, 92.34929107833154660 ) ) ; +#14272 = CARTESIAN_POINT ( 'NONE', ( 21.92247057211630690, 115.3137257461056322, 90.25454421631332025 ) ) ; +#14273 = ORIENTED_EDGE ( 'NONE', *, *, #38887, .F. ) ; +#14274 = CARTESIAN_POINT ( 'NONE', ( -5.676543322760370991, 181.0132184317505448, 104.5254537842582323 ) ) ; +#14275 = CARTESIAN_POINT ( 'NONE', ( 3.621429004694512788, 144.1998115149939679, 93.03134972452090778 ) ) ; +#14276 = CARTESIAN_POINT ( 'NONE', ( -31.13495665264160195, 135.1452985083338092, 90.87247663578949641 ) ) ; +#14277 = ORIENTED_EDGE ( 'NONE', *, *, #20637, .T. ) ; +#14278 = CARTESIAN_POINT ( 'NONE', ( 5.666638401078098575, 182.0642691150555663, 102.1955013913653545 ) ) ; +#14279 = ORIENTED_EDGE ( 'NONE', *, *, #40373, .T. ) ; +#14280 = VECTOR ( 'NONE', #8811, 1000.000000000000000 ) ; +#14281 = ADVANCED_FACE ( 'NONE', ( #26752 ), #21361, .F. ) ; +#14282 = LINE ( 'NONE', #11624, #24124 ) ; +#14283 = ORIENTED_EDGE ( 'NONE', *, *, #34317, .F. ) ; +#14284 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#14285 = AXIS2_PLACEMENT_3D ( 'NONE', #25572, #7334, #28825 ) ; +#14286 = CARTESIAN_POINT ( 'NONE', ( 12.35250447105000049, 123.2470639583000178, 152.4718672074000381 ) ) ; +#14287 = CONICAL_SURFACE ( 'NONE', #7092, 6.500002426223412400, 0.7853981633557588493 ) ; +#14288 = CARTESIAN_POINT ( 'NONE', ( 3.667815737293329548, 128.0237491601668012, 91.77307785500387638 ) ) ; +#14289 = CARTESIAN_POINT ( 'NONE', ( -12.63674275953259496, 130.7062907115098085, 90.10484016673494523 ) ) ; +#14290 = CARTESIAN_POINT ( 'NONE', ( 15.83342902163363242, 174.4759206640733282, 100.0953537165829772 ) ) ; +#14291 = EDGE_LOOP ( 'NONE', ( #34207, #30362, #14662, #26393 ) ) ; +#14292 = CYLINDRICAL_SURFACE ( 'NONE', #10894, 9.000000000000001776 ) ; +#14293 = CARTESIAN_POINT ( 'NONE', ( 12.63725345198346517, 181.8075844171357573, 101.7792460855116161 ) ) ; +#14294 = CARTESIAN_POINT ( 'NONE', ( 15.66824001305769443, 127.1447710819307275, 91.73395621462609029 ) ) ; +#14295 = EDGE_CURVE ( 'NONE', #26075, #4793, #18540, .T. ) ; +#14296 = CARTESIAN_POINT ( 'NONE', ( 62.95950931629634795, 77.27946979429611929, 297.5205190635956001 ) ) ; +#14297 = ORIENTED_EDGE ( 'NONE', *, *, #36454, .F. ) ; +#14298 = DIRECTION ( 'NONE', ( 0.0005884949961248158324, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#14299 = CARTESIAN_POINT ( 'NONE', ( 15.00166796934059299, 182.5876787558734975, 104.7054119478550547 ) ) ; +#14300 = CARTESIAN_POINT ( 'NONE', ( -14.29617623337722065, 129.3410249522306685, 92.25909571682996102 ) ) ; +#14301 = EDGE_CURVE ( 'NONE', #13582, #38246, #23890, .T. ) ; +#14302 = CARTESIAN_POINT ( 'NONE', ( 36.36947947310116547, 114.8200176383737414, 89.71357137054673103 ) ) ; +#14303 = CARTESIAN_POINT ( 'NONE', ( -21.21359846303053232, 183.2065877321888081, 103.1596643249062311 ) ) ; +#14304 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1123, #9950, #3783, #19524, #38151, #6647, #4177, #22623, #13605, #28945, #28745, #22020, #22225, #16258, #922, #35048, #16653, #29153 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999931721, 0.1874999999999952538, 0.2187499999999965583, 0.2499999999999978906, 0.4999999999999957812, 0.6249999999999951150, 0.6874999999999952260, 0.7187499999999952260, 0.7499999999999953371, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14305 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27361, #18102, #8530, #8327 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14306 = EDGE_CURVE ( 'NONE', #15784, #27638, #6888, .T. ) ; +#14307 = CARTESIAN_POINT ( 'NONE', ( 36.06237288317970524, 191.9759150222000130, 101.8996665707895204 ) ) ; +#14308 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #1628, #14120, #26597, #39039 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.591006494801850302, 3.611425299555533375 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999652563361538515, 0.9999652563361538515, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#14309 = EDGE_CURVE ( 'NONE', #23839, #29253, #37106, .T. ) ; +#14310 = CARTESIAN_POINT ( 'NONE', ( 12.31735976862525561, 136.6810573082978806, 94.28285972987136176 ) ) ; +#14311 = CONICAL_SURFACE ( 'NONE', #5812, 2.500000007006496716, 0.7853647137678984036 ) ; +#14312 = ADVANCED_FACE ( 'NONE', ( #1591 ), #34939, .T. ) ; +#14313 = FACE_OUTER_BOUND ( 'NONE', #5595, .T. ) ; +#14314 = CARTESIAN_POINT ( 'NONE', ( 38.54800172934000102, 119.2278403673000184, 90.41095816630999593 ) ) ; +#14315 = ORIENTED_EDGE ( 'NONE', *, *, #38013, .F. ) ; +#14316 = LINE ( 'NONE', #4895, #8739 ) ; +#14317 = CYLINDRICAL_SURFACE ( 'NONE', #11376, 5.999999999913002036 ) ; +#14318 = CARTESIAN_POINT ( 'NONE', ( -36.12795248578809293, 191.9248856836622394, 106.4372973041314339 ) ) ; +#14319 = CARTESIAN_POINT ( 'NONE', ( -18.92878511345999826, 153.5793303521000155, 96.66039321965999420 ) ) ; +#14320 = AXIS2_PLACEMENT_3D ( 'NONE', #18809, #19424, #25191 ) ; +#14321 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18250, #21754, #2135, #40330, #36464, #39935, #30336, #24632, #18445, #2919, #30751, #14605, #27088, #39521, #11943, #37078, #15406, #2741 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000073552, 0.1875000000000110467, 0.2187500000000071054, 0.2500000000000031641, 0.4999999999999666933, 0.6249999999999483746, 0.6874999999999465983, 0.7187499999999532596, 0.7499999999999598099, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14322 = CIRCLE ( 'NONE', #11052, 2.500000000078602902 ) ; +#14323 = CARTESIAN_POINT ( 'NONE', ( 37.28339173517426985, 124.9819308969460963, 93.36952625978587150 ) ) ; +#14324 = VERTEX_POINT ( 'NONE', #14887 ) ; +#14325 = VERTEX_POINT ( 'NONE', #35919 ) ; +#14326 = VERTEX_POINT ( 'NONE', #14480 ) ; +#14327 = CARTESIAN_POINT ( 'NONE', ( -23.36060660365039965, 177.5900848626628203, 100.8364999699883242 ) ) ; +#14328 = FACE_OUTER_BOUND ( 'NONE', #5541, .T. ) ; +#14329 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606773498981405, 136.6775772631814618, 180.9814965275718919 ) ) ; +#14330 = ORIENTED_EDGE ( 'NONE', *, *, #14913, .F. ) ; +#14331 = ORIENTED_EDGE ( 'NONE', *, *, #18499, .T. ) ; +#14332 = FACE_BOUND ( 'NONE', #21887, .T. ) ; +#14333 = CARTESIAN_POINT ( 'NONE', ( -38.51617849441122132, 161.8621938076236120, 192.1757404333372392 ) ) ; +#14334 = CARTESIAN_POINT ( 'NONE', ( -13.49694984184264079, 187.4841345813676128, 105.7733536678242530 ) ) ; +#14335 = CARTESIAN_POINT ( 'NONE', ( 16.58107005088550778, 121.6542341450989682, 177.3392501854816601 ) ) ; +#14336 = ORIENTED_EDGE ( 'NONE', *, *, #8050, .T. ) ; +#14337 = CARTESIAN_POINT ( 'NONE', ( 43.53522428377826259, 122.0090548114814766, 87.79422213383789142 ) ) ; +#14338 = ORIENTED_EDGE ( 'NONE', *, *, #29117, .F. ) ; +#14339 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#14340 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319383098692 ) ) ; +#14341 = CARTESIAN_POINT ( 'NONE', ( -32.57215250014812113, 175.3511933304038735, 100.1556091465108267 ) ) ; +#14342 = ORIENTED_EDGE ( 'NONE', *, *, #24602, .F. ) ; +#14343 = AXIS2_PLACEMENT_3D ( 'NONE', #33432, #40169, #12186 ) ; +#14344 = CARTESIAN_POINT ( 'NONE', ( -2.880684217277760251, 190.4460190246579998, 103.6193748697619981 ) ) ; +#14345 = CARTESIAN_POINT ( 'NONE', ( 38.54261875449868313, 119.6497881189073098, 87.27962667045721901 ) ) ; +#14346 = CARTESIAN_POINT ( 'NONE', ( 27.63271442396334621, 123.9176737634356869, 91.32379343171399455 ) ) ; +#14347 = EDGE_CURVE ( 'NONE', #34668, #19846, #1022, .T. ) ; +#14348 = AXIS2_PLACEMENT_3D ( 'NONE', #21556, #36670, #33996 ) ; +#14349 = ORIENTED_EDGE ( 'NONE', *, *, #18247, .T. ) ; +#14350 = CARTESIAN_POINT ( 'NONE', ( 0.5638615432932998495, 189.0000000000009095, 105.7369977312999936 ) ) ; +#14351 = ORIENTED_EDGE ( 'NONE', *, *, #24427, .F. ) ; +#14352 = ORIENTED_EDGE ( 'NONE', *, *, #5287, .T. ) ; +#14353 = AXIS2_PLACEMENT_3D ( 'NONE', #31966, #28886, #9683 ) ; +#14354 = EDGE_CURVE ( 'NONE', #35226, #5278, #7834, .T. ) ; +#14355 = EDGE_CURVE ( 'NONE', #1948, #5506, #11206, .T. ) ; +#14356 = VERTEX_POINT ( 'NONE', #5464 ) ; +#14357 = CARTESIAN_POINT ( 'NONE', ( 36.05503237417247675, 109.6131156919999938, 89.74600841171526611 ) ) ; +#14358 = ORIENTED_EDGE ( 'NONE', *, *, #29121, .F. ) ; +#14359 = CARTESIAN_POINT ( 'NONE', ( 20.55610212782154278, 211.7441870009438105, 73.54640939689545576 ) ) ; +#14360 = DIRECTION ( 'NONE', ( 0.0004161288024237092768, 0.5299192578742120130, 0.8480479980348188951 ) ) ; +#14361 = EDGE_CURVE ( 'NONE', #22046, #29247, #23685, .T. ) ; +#14362 = ORIENTED_EDGE ( 'NONE', *, *, #9036, .T. ) ; +#14363 = CARTESIAN_POINT ( 'NONE', ( 32.37049208148693680, 138.3096525682149718, 91.56466976714693828 ) ) ; +#14364 = ORIENTED_EDGE ( 'NONE', *, *, #37069, .T. ) ; +#14365 = CARTESIAN_POINT ( 'NONE', ( 26.07999776147000048, 121.7789252111000025, 90.65991193330999920 ) ) ; +#14366 = CARTESIAN_POINT ( 'NONE', ( 20.48231950984458649, 205.5677633305384120, 76.28703242847967658 ) ) ; +#14368 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319388572829 ) ) ; +#14367 = FACE_OUTER_BOUND ( 'NONE', #15182, .T. ) ; +#14369 = VERTEX_POINT ( 'NONE', #30013 ) ; +#14370 = CIRCLE ( 'NONE', #37224, 6.500000000014392043 ) ; +#14371 = VECTOR ( 'NONE', #6217, 1000.000000000000000 ) ; +#14372 = ORIENTED_EDGE ( 'NONE', *, *, #19769, .T. ) ; +#14373 = CARTESIAN_POINT ( 'NONE', ( -36.01285274962783234, 192.1029632286222011, 104.4278060014889178 ) ) ; +#14374 = AXIS2_PLACEMENT_3D ( 'NONE', #18745, #31246, #37577 ) ; +#14375 = VERTEX_POINT ( 'NONE', #2013 ) ; +#14376 = CARTESIAN_POINT ( 'NONE', ( 26.03373140117899709, 191.5260202047026041, 103.8544635878054976 ) ) ; +#14377 = DIRECTION ( 'NONE', ( 0.7075337269410274521, -4.361037875614716654E-15, 0.7066795774896423854 ) ) ; +#14378 = CARTESIAN_POINT ( 'NONE', ( -14.55306118018871508, 176.9194272080598296, 100.5067835523781667 ) ) ; +#14379 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971551247 ) ) ; +#14380 = ORIENTED_EDGE ( 'NONE', *, *, #21206, .T. ) ; +#14381 = ORIENTED_EDGE ( 'NONE', *, *, #4068, .T. ) ; +#14382 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8366, #33485, #8568, #36366 ), + .UNSPECIFIED., .F., .F. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.1808055686694189090, 1.570796326794853925 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8453711073098807427, 0.8453711073098807427, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#14383 = DIRECTION ( 'NONE', ( -0.0004161288024549092543, -0.5299192578742120130, -0.8480479980348188951 ) ) ; +#14384 = CARTESIAN_POINT ( 'NONE', ( 14.95238230675068891, 187.9053326462071425, 103.0252569047014504 ) ) ; +#14385 = ORIENTED_EDGE ( 'NONE', *, *, #30881, .F. ) ; +#14386 = CARTESIAN_POINT ( 'NONE', ( -35.64618537060330539, 191.6897546418510103, 106.9457646653179950 ) ) ; +#14387 = EDGE_CURVE ( 'NONE', #3120, #15609, #15090, .T. ) ; +#14388 = EDGE_CURVE ( 'NONE', #34191, #5671, #2501, .T. ) ; +#14389 = EDGE_CURVE ( 'NONE', #11374, #12730, #35616, .T. ) ; +#14390 = EDGE_CURVE ( 'NONE', #5203, #20831, #13211, .T. ) ; +#14391 = FACE_OUTER_BOUND ( 'NONE', #20534, .T. ) ; +#14392 = VERTEX_POINT ( 'NONE', #34666 ) ; +#14393 = AXIS2_PLACEMENT_3D ( 'NONE', #22736, #34760, #3299 ) ; +#14394 = DIRECTION ( 'NONE', ( -1.110223024594729071E-14, 0.9743700557921585181, 0.2249510932971564570 ) ) ; +#14395 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#14396 = FACE_OUTER_BOUND ( 'NONE', #30474, .T. ) ; +#14397 = EDGE_CURVE ( 'NONE', #6135, #7666, #38530, .T. ) ; +#14398 = AXIS2_PLACEMENT_3D ( 'NONE', #15139, #8398, #36182 ) ; +#14399 = EDGE_LOOP ( 'NONE', ( #5518, #23739, #668, #38843, #32105, #24506 ) ) ; +#14400 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#14401 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066409214, 128.0225132068638629, 91.77843135565319699 ) ) ; +#14402 = EDGE_CURVE ( 'NONE', #20118, #10469, #27863, .T. ) ; +#14403 = ORIENTED_EDGE ( 'NONE', *, *, #37024, .T. ) ; +#14404 = CARTESIAN_POINT ( 'NONE', ( 44.83246798001460576, 186.3081475081992551, 107.7694328794118377 ) ) ; +#14405 = CARTESIAN_POINT ( 'NONE', ( 13.55543936441898722, 147.3999836656304865, 96.75361515240540200 ) ) ; +#14406 = ORIENTED_EDGE ( 'NONE', *, *, #11923, .F. ) ; +#14407 = EDGE_CURVE ( 'NONE', #24100, #27561, #26906, .T. ) ; +#14408 = EDGE_LOOP ( 'NONE', ( #33160, #37458, #10954, #31436 ) ) ; +#14409 = CARTESIAN_POINT ( 'NONE', ( 38.60969634338000134, 118.5004358133784734, 89.66230393877533800 ) ) ; +#14410 = ORIENTED_EDGE ( 'NONE', *, *, #6165, .F. ) ; +#14411 = CARTESIAN_POINT ( 'NONE', ( 2.827185577763999813, 209.6732794012000056, 75.93458852445999696 ) ) ; +#14412 = CARTESIAN_POINT ( 'NONE', ( -39.69437836998564251, 161.5619712970498085, 197.5056430804474985 ) ) ; +#14413 = CARTESIAN_POINT ( 'NONE', ( 3.168110071474127043, 118.9434405806601802, 90.19017701310836799 ) ) ; +#14414 = CARTESIAN_POINT ( 'NONE', ( 12.63950535549863652, 177.3888402134530224, 100.9445866960912213 ) ) ; +#14415 = ORIENTED_EDGE ( 'NONE', *, *, #13335, .F. ) ; +#14416 = ORIENTED_EDGE ( 'NONE', *, *, #31818, .F. ) ; +#14417 = CARTESIAN_POINT ( 'NONE', ( -42.57436895466741333, 120.8400402992461409, 90.73486113234849881 ) ) ; +#14418 = ORIENTED_EDGE ( 'NONE', *, *, #28480, .F. ) ; +#14419 = ORIENTED_EDGE ( 'NONE', *, *, #33646, .T. ) ; +#14420 = LINE ( 'NONE', #39552, #38088 ) ; +#14421 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; +#14422 = CONICAL_SURFACE ( 'NONE', #6584, 5.999999999872287937, 0.7853981633778843729 ) ; +#14423 = FACE_OUTER_BOUND ( 'NONE', #34661, .T. ) ; +#14424 = CARTESIAN_POINT ( 'NONE', ( -2.954012481561790970, 209.1419323005786737, 76.14255792608456375 ) ) ; +#14425 = ORIENTED_EDGE ( 'NONE', *, *, #2265, .T. ) ; +#14426 = VECTOR ( 'NONE', #15668, 1000.000000000000000 ) ; +#14427 = ORIENTED_EDGE ( 'NONE', *, *, #23255, .F. ) ; +#14428 = CARTESIAN_POINT ( 'NONE', ( 12.64524319930002783, 177.7928828500099598, 100.6920447773197225 ) ) ; +#14429 = AXIS2_PLACEMENT_3D ( 'NONE', #21028, #17929, #30435 ) ; +#14430 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25481, #37932, #38327, #25688 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.8322218205202811525, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14431 = CARTESIAN_POINT ( 'NONE', ( 12.63809651561488856, 184.1270825474425408, 102.1512978314866871 ) ) ; +#14432 = CARTESIAN_POINT ( 'NONE', ( -35.87826735977000681, 191.4545805699000027, 103.7459785212000014 ) ) ; +#14433 = CARTESIAN_POINT ( 'NONE', ( 36.44204974789000318, 191.6821620213000017, 104.2306019315000043 ) ) ; +#14434 = VERTEX_POINT ( 'NONE', #37751 ) ; +#14435 = CARTESIAN_POINT ( 'NONE', ( -8.624838525067689332, 191.5260590501553395, 103.8754076631924761 ) ) ; +#14436 = FACE_OUTER_BOUND ( 'NONE', #39513, .T. ) ; +#14437 = ORIENTED_EDGE ( 'NONE', *, *, #9560, .F. ) ; +#14438 = LINE ( 'NONE', #21179, #6232 ) ; +#14439 = CARTESIAN_POINT ( 'NONE', ( -23.35287815472955941, 177.1132788188974132, 103.6357243926429135 ) ) ; +#14440 = ORIENTED_EDGE ( 'NONE', *, *, #21656, .T. ) ; +#14441 = CARTESIAN_POINT ( 'NONE', ( 0.6766601747610884177, 188.6125597266506873, 103.1971553497070317 ) ) ; +#14442 = PLANE ( 'NONE', #13607 ) ; +#14443 = EDGE_CURVE ( 'NONE', #15229, #24908, #30826, .T. ) ; +#14444 = ADVANCED_FACE ( 'NONE', ( #40410 ), #24913, .F. ) ; +#14445 = CARTESIAN_POINT ( 'NONE', ( -20.00029466087617180, 160.7280592933503556, 96.77210435901376684 ) ) ; +#14446 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.387778782212949593E-14 ) ) ; +#14447 = ORIENTED_EDGE ( 'NONE', *, *, #10626, .F. ) ; +#14448 = CARTESIAN_POINT ( 'NONE', ( -19.36440797352090470, 125.0913135789122634, 177.5037349333331917 ) ) ; +#14449 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#14450 = DIRECTION ( 'NONE', ( -0.7933530821293309776, -0.5932640870757666107, -0.1364866662427072774 ) ) ; +#14451 = PRODUCT_DEFINITION ( '', '', #37519, #36332 ) ; +#14452 = ORIENTED_EDGE ( 'NONE', *, *, #10344, .F. ) ; +#14453 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000092726, 182.4219699178716780, 101.7574819546388056 ) ) ; +#14454 = EDGE_LOOP ( 'NONE', ( #16657, #30962, #1229, #18429 ) ) ; +#14455 = ORIENTED_EDGE ( 'NONE', *, *, #1083, .F. ) ; +#14456 = CARTESIAN_POINT ( 'NONE', ( -16.85990575226742649, 148.9750591898919652, 176.9023370295861355 ) ) ; +#14457 = AXIS2_PLACEMENT_3D ( 'NONE', #25761, #28615, #6718 ) ; +#14458 = DIRECTION ( 'NONE', ( -0.7933533411653064249, -0.5931840316265241109, -0.1368326740407707076 ) ) ; +#14459 = CARTESIAN_POINT ( 'NONE', ( 25.89979282503000135, 191.5662133788000006, 103.9958839436000204 ) ) ; +#14460 = CARTESIAN_POINT ( 'NONE', ( -20.00659823406155624, 197.5803004199711097, 93.84897518597676935 ) ) ; +#14461 = VECTOR ( 'NONE', #15835, 1000.000000000000000 ) ; +#14462 = AXIS2_PLACEMENT_3D ( 'NONE', #24784, #2495, #40088 ) ; +#14463 = CARTESIAN_POINT ( 'NONE', ( 6.031425049375666703, 135.0095535936824263, 90.94154247174608940 ) ) ; +#14464 = ORIENTED_EDGE ( 'NONE', *, *, #898, .T. ) ; +#14465 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250902867, 132.4055461762854407, 92.79778151958552712 ) ) ; +#14466 = EDGE_CURVE ( 'NONE', #12388, #26352, #17416, .T. ) ; +#14467 = CARTESIAN_POINT ( 'NONE', ( 23.36209697621999126, 182.0666116861889066, 102.1853546028664397 ) ) ; +#14468 = CARTESIAN_POINT ( 'NONE', ( -25.92534507918878361, 117.3327747928809828, 87.28344255082397751 ) ) ; +#14469 = CARTESIAN_POINT ( 'NONE', ( -3.573670504831215400, 137.3406645800012313, 91.39957200407195614 ) ) ; +#14470 = FACE_OUTER_BOUND ( 'NONE', #18121, .T. ) ; +#14471 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971558463 ) ) ; +#14472 = CARTESIAN_POINT ( 'NONE', ( 27.38311190280685992, 155.9299021785007824, 179.7938373981314157 ) ) ; +#14473 = LINE ( 'NONE', #27377, #32412 ) ; +#14474 = ORIENTED_EDGE ( 'NONE', *, *, #23083, .T. ) ; +#14475 = ORIENTED_EDGE ( 'NONE', *, *, #18967, .T. ) ; +#14476 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319414569829 ) ) ; +#14477 = CARTESIAN_POINT ( 'NONE', ( 3.554793938553518107, 144.2181838125568447, 92.96728390614413229 ) ) ; +#14478 = CARTESIAN_POINT ( 'NONE', ( -32.42517106839203933, 136.5274910919899867, 91.19236025274476276 ) ) ; +#14479 = ORIENTED_EDGE ( 'NONE', *, *, #18019, .T. ) ; +#14480 = CARTESIAN_POINT ( 'NONE', ( -20.49970645903284705, 184.8492302318938698, 102.8542671896393301 ) ) ; +#14481 = CONICAL_SURFACE ( 'NONE', #22344, 4.999999999816541418, 0.7853981632964557313 ) ; +#14482 = VERTEX_POINT ( 'NONE', #18722 ) ; +#14483 = AXIS2_PLACEMENT_3D ( 'NONE', #30035, #29436, #36570 ) ; +#14484 = AXIS2_PLACEMENT_3D ( 'NONE', #24692, #31410, #9337 ) ; +#14485 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#14486 = ORIENTED_EDGE ( 'NONE', *, *, #9102, .F. ) ; +#14487 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 1.540743955509789367E-33, -0.0006039748319385908944 ) ) ; +#14488 = CARTESIAN_POINT ( 'NONE', ( 0.03687779169341001001, 7.827067153267001387E-13, 61.05847962042000887 ) ) ; +#14489 = CARTESIAN_POINT ( 'NONE', ( -35.94659742830589266, 112.4664344042326576, 89.78949559119494950 ) ) ; +#14490 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#14491 = EDGE_CURVE ( 'NONE', #6212, #17763, #37356, .T. ) ; +#14492 = CARTESIAN_POINT ( 'NONE', ( -12.19159238061602579, 125.0219911001496058, 178.7972028438273071 ) ) ; +#14493 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#14494 = ORIENTED_EDGE ( 'NONE', *, *, #3514, .T. ) ; +#14495 = ORIENTED_EDGE ( 'NONE', *, *, #37178, .F. ) ; +#14496 = DIRECTION ( 'NONE', ( 0.6337890847338583100, -0.7735059121120007042, 0.000000000000000000 ) ) ; +#14497 = FACE_OUTER_BOUND ( 'NONE', #29895, .T. ) ; +#14498 = CARTESIAN_POINT ( 'NONE', ( 9.337769825243999122, 176.9303572965000058, 103.3172116324000029 ) ) ; +#14499 = EDGE_LOOP ( 'NONE', ( #780, #766, #33447, #25657 ) ) ; +#14500 = CARTESIAN_POINT ( 'NONE', ( 16.45208125514326625, 152.1628593551957067, 181.3637068811612210 ) ) ; +#14501 = ORIENTED_EDGE ( 'NONE', *, *, #33859, .F. ) ; +#14502 = CARTESIAN_POINT ( 'NONE', ( -20.51208494570645513, 201.8037239448619573, 85.17910946014715989 ) ) ; +#14503 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#14504 = CARTESIAN_POINT ( 'NONE', ( -42.21450392588476319, 136.3064398602169263, 337.8725216998488463 ) ) ; +#14505 = CARTESIAN_POINT ( 'NONE', ( -14.42375247838731411, 129.4079016531295849, 92.44566340157058448 ) ) ; +#14506 = CARTESIAN_POINT ( 'NONE', ( -20.02016821360482268, 211.0854730039747267, 73.07052224373646254 ) ) ; +#14507 = CARTESIAN_POINT ( 'NONE', ( 14.30095350739092019, 209.7097330701937494, 73.04986666540851559 ) ) ; +#14508 = CARTESIAN_POINT ( 'NONE', ( 20.00007381421711372, 125.0896753410343507, 88.52014447053112178 ) ) ; +#14509 = VECTOR ( 'NONE', #13879, 1000.000000000000114 ) ; +#14510 = CARTESIAN_POINT ( 'NONE', ( -25.94414642037533625, 209.7102642087664321, 73.14014518873486281 ) ) ; +#14511 = AXIS2_PLACEMENT_3D ( 'NONE', #19441, #12929, #1238 ) ; +#14512 = CARTESIAN_POINT ( 'NONE', ( -2.454787986789333853, 158.3159520769750372, 101.3360438597573676 ) ) ; +#14513 = VECTOR ( 'NONE', #39198, 1000.000000000000000 ) ; +#14514 = CARTESIAN_POINT ( 'NONE', ( 37.53774977936000568, 118.7416573867000125, 87.12150836029999823 ) ) ; +#14515 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36759, #24517, #3210, #8974, #22044, #15300, #25119, #33684, #30641, #21450, #27785, #24723, #7478, #32444, #25725, #34875, #35466, #750, #13437, #28771 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999718836, 0.1874999999999578115, 0.2187499999999484024, 0.2343749999999451827, 0.2499999999999419353, 0.4999999999999288347, 0.6249999999999253930, 0.6874999999999236167, 0.7187499999999227285, 0.7343749999999260591, 0.7499999999999293898, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14516 = CARTESIAN_POINT ( 'NONE', ( -22.50035831641348949, 136.6787900224432235, 180.9762504730929891 ) ) ; +#14517 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552150381, 77.14301703112145958, 291.5584375788748162 ) ) ; +#14518 = ORIENTED_EDGE ( 'NONE', *, *, #38505, .T. ) ; +#14519 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988183502364, 156.3551877983796885, 95.75036263594044783 ) ) ; +#14520 = CARTESIAN_POINT ( 'NONE', ( -14.89128843831085192, 128.7610883624478788, 92.12556600355759429 ) ) ; +#14521 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#14522 = DIRECTION ( 'NONE', ( 1.396487634731935332E-14, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#14524 = VERTEX_POINT ( 'NONE', #6268 ) ; +#14523 = DIRECTION ( 'NONE', ( -0.0005884949961175196939, 0.2249510543439042221, -0.9743698870671267942 ) ) ; +#14525 = ORIENTED_EDGE ( 'NONE', *, *, #15875, .T. ) ; +#14526 = VERTEX_POINT ( 'NONE', #7266 ) ; +#14527 = CARTESIAN_POINT ( 'NONE', ( -2.243981616595559725, 189.3845921353988615, 103.3771571023711573 ) ) ; +#14528 = VERTEX_POINT ( 'NONE', #29367 ) ; +#14529 = CARTESIAN_POINT ( 'NONE', ( -23.35632100188561822, 177.7257551712265524, 100.7517216405086629 ) ) ; +#14530 = EDGE_CURVE ( 'NONE', #14135, #30803, #33878, .T. ) ; +#14531 = CARTESIAN_POINT ( 'NONE', ( 5.666344154467410910, 131.0223139869003148, 89.89838483048988849 ) ) ; +#14532 = CARTESIAN_POINT ( 'NONE', ( -43.33927092660995584, 121.3466802566939720, 90.52108273551040440 ) ) ; +#14533 = EDGE_LOOP ( 'NONE', ( #3202, #4007 ) ) ; +#14534 = CARTESIAN_POINT ( 'NONE', ( -76.10866181110002060, 155.9999951364999902, 97.25378303438999694 ) ) ; +#14535 = ADVANCED_FACE ( 'NONE', ( #35265 ), #38739, .F. ) ; +#14536 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2252353050503803633, 0.9743043966640312359 ) ) ; +#14537 = FACE_OUTER_BOUND ( 'NONE', #39367, .T. ) ; +#14538 = DIRECTION ( 'NONE', ( 0.0006039748319381690314, -1.159276051261448636E-15, 0.9999998176071845934 ) ) ; +#14539 = ORIENTED_EDGE ( 'NONE', *, *, #35578, .F. ) ; +#14540 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#14541 = VERTEX_POINT ( 'NONE', #19135 ) ; +#14542 = CARTESIAN_POINT ( 'NONE', ( -17.94609826154884402, 149.1879437481332502, 179.6906816993704581 ) ) ; +#14543 = EDGE_CURVE ( 'NONE', #2464, #40344, #19055, .T. ) ; +#14544 = AXIS2_PLACEMENT_3D ( 'NONE', #14897, #21235, #15498 ) ; +#14545 = ADVANCED_FACE ( 'NONE', ( #10756 ), #16467, .T. ) ; +#14546 = CARTESIAN_POINT ( 'NONE', ( 15.99998384348811875, 126.8035267017516787, 88.91816380576780432 ) ) ; +#14547 = CARTESIAN_POINT ( 'NONE', ( 25.60452841390158696, 177.7947404061257544, 100.6845902703070408 ) ) ; +#14548 = EDGE_CURVE ( 'NONE', #26442, #25364, #10562, .T. ) ; +#14549 = VECTOR ( 'NONE', #21494, 1000.000000000000227 ) ; +#14550 = ORIENTED_EDGE ( 'NONE', *, *, #1139, .F. ) ; +#14551 = DIRECTION ( 'NONE', ( -0.7933530821293314217, -0.5932640870757660556, -0.1364866662427072774 ) ) ; +#14552 = EDGE_CURVE ( 'NONE', #19871, #23412, #26301, .T. ) ; +#14553 = CONICAL_SURFACE ( 'NONE', #22404, 2.503104886457119260, 0.7853981634085609453 ) ; +#14554 = CARTESIAN_POINT ( 'NONE', ( 0.5749182425858000434, 188.7228409958999862, 103.3572403391000023 ) ) ; +#14555 = CARTESIAN_POINT ( 'NONE', ( 26.00790306097016469, 120.3826516281573049, 90.50865046224697608 ) ) ; +#14556 = EDGE_LOOP ( 'NONE', ( #31779, #10516, #30220, #8284, #4286, #12131 ) ) ; +#14557 = CARTESIAN_POINT ( 'NONE', ( 28.46561152637904257, 181.0177244442795654, 104.5058782010328855 ) ) ; +#14558 = EDGE_LOOP ( 'NONE', ( #36243, #31241, #3763, #1449 ) ) ; +#14559 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25125, #22049, #24324, #21456 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.740660174422384188, 5.205610502464788070 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9820660875108615517, 0.9820660875108615517, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#14560 = CARTESIAN_POINT ( 'NONE', ( 25.49063000826092562, 211.0902260967494897, 73.54299573436949800 ) ) ; +#14561 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30658, #11234, #8378, #5489, #17952, #40040, #26993, #14721, #11852, #21465, #17748, #36991, #23709, #11432, #18359, #23920 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000007494, 0.2500000000000014988, 0.5000000000000049960, 0.6250000000000067724, 0.6874999999999996669, 0.7187499999999961142, 0.7499999999999924505, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14562 = ORIENTED_EDGE ( 'NONE', *, *, #37470, .F. ) ; +#14563 = ORIENTED_EDGE ( 'NONE', *, *, #12318, .F. ) ; +#14564 = DIRECTION ( 'NONE', ( -0.0005884949961254435855, 0.2249510543439056098, -0.9743698870671265722 ) ) ; +#14565 = CARTESIAN_POINT ( 'NONE', ( 5.667983148730973753, 187.2950682031916472, 105.4557345104930022 ) ) ; +#14566 = LINE ( 'NONE', #16248, #19325 ) ; +#14567 = ORIENTED_EDGE ( 'NONE', *, *, #16356, .F. ) ; +#14568 = CARTESIAN_POINT ( 'NONE', ( 44.86430789981690026, 186.7819473042679022, 105.8267500767360758 ) ) ; +#14569 = CARTESIAN_POINT ( 'NONE', ( -5.670520111846581557, 181.9848756317858260, 102.0773479366436618 ) ) ; +#14570 = AXIS2_PLACEMENT_3D ( 'NONE', #32768, #33567, #39909 ) ; +#14571 = VERTEX_POINT ( 'NONE', #22434 ) ; +#14572 = CARTESIAN_POINT ( 'NONE', ( 25.96215568107999871, 121.3312454849999966, 90.55664172145999657 ) ) ; +#14573 = CARTESIAN_POINT ( 'NONE', ( 15.50029467954679596, 184.8540555714758966, 102.8336351796044426 ) ) ; +#14574 = CONICAL_SURFACE ( 'NONE', #8016, 6.500002405954553808, 0.7853981634096851572 ) ; +#14576 = DIRECTION ( 'NONE', ( -0.0004270746993317995526, -0.7071067811865993091, -0.7071066522152992251 ) ) ; +#14575 = CYLINDRICAL_SURFACE ( 'NONE', #34322, 2.000000000000000444 ) ; +#14577 = VERTEX_POINT ( 'NONE', #16272 ) ; +#14578 = AXIS2_PLACEMENT_3D ( 'NONE', #2565, #27322, #12171 ) ; +#14579 = EDGE_LOOP ( 'NONE', ( #18526, #1625, #29692, #18078 ) ) ; +#14580 = EDGE_CURVE ( 'NONE', #1633, #18145, #15658, .T. ) ; +#14581 = ORIENTED_EDGE ( 'NONE', *, *, #16319, .F. ) ; +#14582 = CARTESIAN_POINT ( 'NONE', ( 39.30108583578999770, 119.4692335736999951, 90.16757951597999465 ) ) ; +#14583 = CARTESIAN_POINT ( 'NONE', ( -36.00927514734391366, 116.0444906973774835, 87.28953299190300186 ) ) ; +#14584 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #97, #30786, #12559, #34423 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14585 = CARTESIAN_POINT ( 'NONE', ( -20.34678176212189982, 105.2139170220364974, 88.78007351195603292 ) ) ; +#14586 = DIRECTION ( 'NONE', ( 0.0005884949961292186690, -0.2249510543439060262, 0.9743698870671263501 ) ) ; +#14587 = EDGE_CURVE ( 'NONE', #35968, #17219, #4401, .T. ) ; +#14588 = ORIENTED_EDGE ( 'NONE', *, *, #30265, .T. ) ; +#14589 = ORIENTED_EDGE ( 'NONE', *, *, #9189, .F. ) ; +#14590 = CARTESIAN_POINT ( 'NONE', ( -10.03596943924101659, 167.8207392792327539, 101.4823675419857807 ) ) ; +#14591 = CARTESIAN_POINT ( 'NONE', ( 26.07427389743000035, 130.7251880588000006, 90.07403667762000055 ) ) ; +#14592 = EDGE_CURVE ( 'NONE', #24828, #39497, #16586, .T. ) ; +#14593 = CARTESIAN_POINT ( 'NONE', ( 27.24249485256000014, 124.7921279242000168, 88.96032778548000408 ) ) ; +#14594 = EDGE_CURVE ( 'NONE', #26903, #29957, #11482, .T. ) ; +#14595 = ORIENTED_EDGE ( 'NONE', *, *, #40184, .F. ) ; +#14596 = CARTESIAN_POINT ( 'NONE', ( 30.06790633150233205, 135.1102819760833142, 91.08386653316209447 ) ) ; +#14597 = AXIS2_PLACEMENT_3D ( 'NONE', #7611, #20075, #32952 ) ; +#14598 = VECTOR ( 'NONE', #4138, 1000.000000000000000 ) ; +#14599 = CARTESIAN_POINT ( 'NONE', ( -39.66922356035500741, 107.0867199669675358, 184.9165548509024006 ) ) ; +#14600 = ORIENTED_EDGE ( 'NONE', *, *, #17537, .T. ) ; +#14601 = CARTESIAN_POINT ( 'NONE', ( 5.667840232159853109, 130.6974365609393942, 90.10139097600442426 ) ) ; +#14602 = CIRCLE ( 'NONE', #15894, 4.999999999999990230 ) ; +#14603 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749094291, 179.1800746285969410, 103.5747911657857685 ) ) ; +#14604 = LINE ( 'NONE', #27087, #34595 ) ; +#14605 = CARTESIAN_POINT ( 'NONE', ( 3.799034111884631137, 146.0103245760286086, 93.35976675303339789 ) ) ; +#14606 = VERTEX_POINT ( 'NONE', #7463 ) ; +#14607 = CYLINDRICAL_SURFACE ( 'NONE', #1615, 2.000000000000014655 ) ; +#14608 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16560, #230, #34556, #6763 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14609 = CARTESIAN_POINT ( 'NONE', ( 22.99060780684998662, 213.5902260770751866, 73.54442216390444287 ) ) ; +#14610 = ORIENTED_EDGE ( 'NONE', *, *, #25899, .T. ) ; +#14611 = DIRECTION ( 'NONE', ( -0.0005884949961222158072, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#14613 = LINE ( 'NONE', #33402, #29851 ) ; +#14612 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#14614 = ORIENTED_EDGE ( 'NONE', *, *, #27450, .F. ) ; +#14615 = EDGE_LOOP ( 'NONE', ( #25409, #10746, #3957, #40296 ) ) ; +#14616 = VECTOR ( 'NONE', #35297, 1000.000000000000114 ) ; +#14617 = CARTESIAN_POINT ( 'NONE', ( 38.70058063102342771, 118.5858079959231901, 89.66270157713385913 ) ) ; +#14618 = ORIENTED_EDGE ( 'NONE', *, *, #4359, .T. ) ; +#14619 = EDGE_CURVE ( 'NONE', #6941, #22970, #37961, .T. ) ; +#14620 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858247, 183.1686750955933292, 104.5300206044594091 ) ) ; +#14621 = EDGE_CURVE ( 'NONE', #29487, #30923, #5375, .T. ) ; +#14622 = LINE ( 'NONE', #8280, #7566 ) ; +#14623 = CARTESIAN_POINT ( 'NONE', ( 16.81962279843222063, 125.7520086040206877, 179.0304986527600022 ) ) ; +#14624 = EDGE_CURVE ( 'NONE', #35118, #13652, #28760, .T. ) ; +#14625 = CARTESIAN_POINT ( 'NONE', ( 12.64524319930002783, 177.7928828500099598, 100.6920447773197225 ) ) ; +#14627 = EDGE_LOOP ( 'NONE', ( #29636, #32323, #29486, #12846, #27844, #7027, #32629 ) ) ; +#14626 = AXIS2_PLACEMENT_3D ( 'NONE', #31508, #3471, #7155 ) ; +#14628 = ORIENTED_EDGE ( 'NONE', *, *, #18022, .T. ) ; +#14629 = CARTESIAN_POINT ( 'NONE', ( -42.69001132698595313, 120.8765335464027686, 91.24842851203827365 ) ) ; +#14630 = ORIENTED_EDGE ( 'NONE', *, *, #30724, .T. ) ; +#14631 = ORIENTED_EDGE ( 'NONE', *, *, #37980, .F. ) ; +#14632 = DIRECTION ( 'NONE', ( -0.0005559617475465704339, 0.3907311284739450885, -0.9205046855654851479 ) ) ; +#14633 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825994489843006, 0.0005734119006650908101 ) ) ; +#14634 = AXIS2_PLACEMENT_3D ( 'NONE', #12926, #10053, #32132 ) ; +#14635 = EDGE_CURVE ( 'NONE', #13611, #36914, #7068, .T. ) ; +#14636 = CARTESIAN_POINT ( 'NONE', ( 3.045964837636964795, 205.1071438018522315, 76.10297588899729249 ) ) ; +#14637 = CARTESIAN_POINT ( 'NONE', ( 21.70887161542509247, 149.1053605161909559, 190.1067871781723966 ) ) ; +#14638 = VERTEX_POINT ( 'NONE', #39347 ) ; +#14639 = ORIENTED_EDGE ( 'NONE', *, *, #13647, .F. ) ; +#14640 = ORIENTED_EDGE ( 'NONE', *, *, #30419, .T. ) ; +#14641 = DIRECTION ( 'NONE', ( 0.7933533411653070910, -0.5930537057989941907, -0.1373964268091563690 ) ) ; +#14642 = CARTESIAN_POINT ( 'NONE', ( -36.04853124241000017, 191.6002292608999937, 104.0141960793000209 ) ) ; +#14643 = CARTESIAN_POINT ( 'NONE', ( 38.08169783580999734, 190.9297002386000202, 103.5605195629999997 ) ) ; +#14644 = CARTESIAN_POINT ( 'NONE', ( -26.00023137339078616, 120.7179891544659398, 87.50601697937879919 ) ) ; +#14645 = VERTEX_POINT ( 'NONE', #17261 ) ; +#14646 = EDGE_CURVE ( 'NONE', #30574, #32344, #34320, .T. ) ; +#14647 = ORIENTED_EDGE ( 'NONE', *, *, #5055, .F. ) ; +#14648 = CARTESIAN_POINT ( 'NONE', ( -21.70069623175950468, 176.1098200292445881, 103.0609967409726693 ) ) ; +#14649 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; +#14650 = ORIENTED_EDGE ( 'NONE', *, *, #35277, .T. ) ; +#14651 = CARTESIAN_POINT ( 'NONE', ( -20.51834749416153159, 208.5969270407305487, 75.82589319295023245 ) ) ; +#14652 = CARTESIAN_POINT ( 'NONE', ( -5.958856854636191969, 162.8886998924887166, 100.3412538487635857 ) ) ; +#14653 = CARTESIAN_POINT ( 'NONE', ( -15.51350684690919834, 125.3182505903097592, 88.59428848080469265 ) ) ; +#14654 = AXIS2_PLACEMENT_3D ( 'NONE', #13699, #26381, #33303 ) ; +#14655 = ORIENTED_EDGE ( 'NONE', *, *, #11597, .F. ) ; +#14656 = EDGE_CURVE ( 'NONE', #17766, #9823, #10215, .T. ) ; +#14657 = CARTESIAN_POINT ( 'NONE', ( -31.70384874264191311, 220.4002260771000294, 76.07765295995241672 ) ) ; +#14658 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971560406 ) ) ; +#14659 = CARTESIAN_POINT ( 'NONE', ( -15.99999411491280199, 138.1989450468032601, 91.56832761027415302 ) ) ; +#14660 = ORIENTED_EDGE ( 'NONE', *, *, #21141, .T. ) ; +#14661 = CARTESIAN_POINT ( 'NONE', ( 13.50147201673061481, 153.3583215346567670, 97.61608654020172082 ) ) ; +#14662 = ORIENTED_EDGE ( 'NONE', *, *, #31476, .T. ) ; +#14663 = ORIENTED_EDGE ( 'NONE', *, *, #5331, .F. ) ; +#14664 = CIRCLE ( 'NONE', #30326, 2.500000000022430502 ) ; +#14665 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265228896, 0.1368326740407719844 ) ) ; +#14666 = CARTESIAN_POINT ( 'NONE', ( 36.04796026513668039, 209.7096538831000032, 78.03673292965197561 ) ) ; +#14667 = CARTESIAN_POINT ( 'NONE', ( -25.51533646434189961, 211.0902259025884007, 73.57326538444725372 ) ) ; +#14668 = CARTESIAN_POINT ( 'NONE', ( 44.97133202873805402, 133.3536190811915958, 337.1387376220093302 ) ) ; +#14669 = FACE_OUTER_BOUND ( 'NONE', #23123, .T. ) ; +#14670 = VERTEX_POINT ( 'NONE', #11349 ) ; +#14671 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27498, #13137, #35175, #28276 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14672 = CARTESIAN_POINT ( 'NONE', ( -116.6809178989064293, 205.2853165843886245, 191.1682151682985307 ) ) ; +#14673 = LINE ( 'NONE', #35908, #4818 ) ; +#14674 = CARTESIAN_POINT ( 'NONE', ( -45.17838929977841644, 181.0906312430929574, 102.0014284585363669 ) ) ; +#14675 = EDGE_CURVE ( 'NONE', #5306, #39311, #32623, .T. ) ; +#14676 = CARTESIAN_POINT ( 'NONE', ( -38.46044104337040181, 118.4609804511839286, 89.70916240556151422 ) ) ; +#14677 = CARTESIAN_POINT ( 'NONE', ( 30.69859387782648596, 177.7369147060027217, 100.6681819028367073 ) ) ; +#14678 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265227786, -0.1368326740407718733 ) ) ; +#14679 = EDGE_CURVE ( 'NONE', #38924, #7297, #14770, .T. ) ; +#14680 = CARTESIAN_POINT ( 'NONE', ( 14.74085912557288403, 200.6198490733034987, 27.73455667519232293 ) ) ; +#14681 = ADVANCED_FACE ( 'NONE', ( #5205 ), #20755, .T. ) ; +#14682 = CARTESIAN_POINT ( 'NONE', ( -17.26247767858138005, 152.5342161776122225, 182.4800534808789791 ) ) ; +#14683 = CARTESIAN_POINT ( 'NONE', ( 20.23379851175398514, 116.9546646491199482, 90.25556413192329330 ) ) ; +#14684 = ORIENTED_EDGE ( 'NONE', *, *, #28156, .T. ) ; +#14685 = VECTOR ( 'NONE', #32901, 999.9999999999998863 ) ; +#14686 = AXIS2_PLACEMENT_3D ( 'NONE', #13047, #25527, #32256 ) ; +#14687 = CARTESIAN_POINT ( 'NONE', ( -19.99931527105535878, 118.1256151686936420, 90.27945241601419468 ) ) ; +#14688 = AXIS2_PLACEMENT_3D ( 'NONE', #11848, #8373, #8576 ) ; +#14689 = DIRECTION ( 'NONE', ( 0.0005559617642597537886, -0.3907311284892686643, 0.9205046855589705812 ) ) ; +#14690 = AXIS2_PLACEMENT_3D ( 'NONE', #11580, #35670, #23436 ) ; +#14691 = ADVANCED_FACE ( 'NONE', ( #24040 ), #32820, .F. ) ; +#14692 = EDGE_LOOP ( 'NONE', ( #39948, #38977, #19988, #21479 ) ) ; +#14693 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971535981 ) ) ; +#14694 = VECTOR ( 'NONE', #35852, 1000.000000000000227 ) ; +#14695 = EDGE_LOOP ( 'NONE', ( #22984, #23988, #36395, #37406 ) ) ; +#14696 = CARTESIAN_POINT ( 'NONE', ( -38.32031438860001060, 119.0223062448000064, 87.58457824427000560 ) ) ; +#14697 = EDGE_CURVE ( 'NONE', #2318, #8264, #4605, .T. ) ; +#14698 = CARTESIAN_POINT ( 'NONE', ( 25.49057710600703786, 211.4174709902825668, 73.54294251055145537 ) ) ; +#14699 = PLANE ( 'NONE', #14429 ) ; +#14700 = ORIENTED_EDGE ( 'NONE', *, *, #31507, .F. ) ; +#14701 = DIRECTION ( 'NONE', ( 1.868163743340544790E-15, 0.9743700557921586292, 0.2249510932971554855 ) ) ; +#14702 = FACE_OUTER_BOUND ( 'NONE', #3918, .T. ) ; +#14703 = CARTESIAN_POINT ( 'NONE', ( -40.70502761438000761, 217.7719116314000019, 75.83308940067001913 ) ) ; +#14704 = CARTESIAN_POINT ( 'NONE', ( -22.50072399476195528, 158.3009599602069954, 96.21317557253242114 ) ) ; +#14705 = CARTESIAN_POINT ( 'NONE', ( 39.79720373659698396, 141.5291680805872829, 284.4357792904225448 ) ) ; +#14706 = ORIENTED_EDGE ( 'NONE', *, *, #13520, .F. ) ; +#14707 = EDGE_CURVE ( 'NONE', #13769, #36287, #38269, .T. ) ; +#14708 = CARTESIAN_POINT ( 'NONE', ( 38.15196370523000269, 119.0569874929000207, 87.35187028091000627 ) ) ; +#14709 = LINE ( 'NONE', #27191, #8136 ) ; +#14710 = CARTESIAN_POINT ( 'NONE', ( 41.93030479274874978, 83.05956246986023928, 287.6687500667571840 ) ) ; +#14711 = CARTESIAN_POINT ( 'NONE', ( 28.46414028889297043, 128.4769340270111400, 89.81011889579673380 ) ) ; +#14712 = VERTEX_POINT ( 'NONE', #39153 ) ; +#14713 = DIRECTION ( 'NONE', ( 0.0005884949961262129353, -0.2249510543439086074, 0.9743698870671257950 ) ) ; +#14714 = PLANE ( 'NONE', #39519 ) ; +#14715 = AXIS2_PLACEMENT_3D ( 'NONE', #25081, #25279, #31403 ) ; +#14716 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#14717 = CARTESIAN_POINT ( 'NONE', ( -28.24856439448000245, 125.3059185480999957, 91.02595693825000467 ) ) ; +#14718 = CARTESIAN_POINT ( 'NONE', ( 3.047144816548554402, 209.7096538831000032, 78.05666459525210144 ) ) ; +#14719 = VECTOR ( 'NONE', #34763, 1000.000000000000114 ) ; +#14720 = AXIS2_PLACEMENT_3D ( 'NONE', #15060, #21605, #34048 ) ; +#14721 = CARTESIAN_POINT ( 'NONE', ( -25.28450265369502148, 213.0681446531329470, 73.07377528842077652 ) ) ; +#14722 = AXIS2_PLACEMENT_3D ( 'NONE', #28602, #22878, #16902 ) ; +#14723 = DIRECTION ( 'NONE', ( 0.6087611427424952648, 0.7731004630501231434, 0.1781166615410721132 ) ) ; +#14724 = CARTESIAN_POINT ( 'NONE', ( -36.54247293543086528, 78.99824749864018258, 288.8334071075194629 ) ) ; +#14725 = LINE ( 'NONE', #27205, #8632 ) ; +#14726 = CALENDAR_DATE ( 2025, 24, 6 ) ; +#14727 = CARTESIAN_POINT ( 'NONE', ( 26.77347080001853286, 123.5272686467274781, 88.15526736885951209 ) ) ; +#14728 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971544308 ) ) ; +#14729 = LINE ( 'NONE', #33508, #34213 ) ; +#14730 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825900929177606, 0.0005734119028281910212 ) ) ; +#14731 = CARTESIAN_POINT ( 'NONE', ( 35.93657474780000172, 112.8616927727999979, 87.62913976238999680 ) ) ; +#14732 = ADVANCED_FACE ( 'NONE', ( #5008 ), #6920, .T. ) ; +#14733 = ORIENTED_EDGE ( 'NONE', *, *, #34134, .T. ) ; +#14734 = CARTESIAN_POINT ( 'NONE', ( -22.50000098316691677, 138.1924791438345892, 91.56768502647121011 ) ) ; +#14735 = ORIENTED_EDGE ( 'NONE', *, *, #30055, .F. ) ; +#14736 = ORIENTED_EDGE ( 'NONE', *, *, #39531, .F. ) ; +#14737 = CARTESIAN_POINT ( 'NONE', ( -0.4376666143244844487, 188.6124751099401351, 103.1978086576974221 ) ) ; +#14738 = ORIENTED_EDGE ( 'NONE', *, *, #4027, .F. ) ; +#14739 = CARTESIAN_POINT ( 'NONE', ( -14.39900080767387358, 134.4949918206585551, 152.5558619512717371 ) ) ; +#14740 = CARTESIAN_POINT ( 'NONE', ( 16.54378305514588732, 151.9109168242012515, 184.2735515932985777 ) ) ; +#14741 = CARTESIAN_POINT ( 'NONE', ( -13.53688746037999913, 141.8439034424000056, 28.07991271570000080 ) ) ; +#14742 = EDGE_CURVE ( 'NONE', #31506, #7683, #2371, .T. ) ; +#14743 = ORIENTED_EDGE ( 'NONE', *, *, #2216, .T. ) ; +#14744 = VECTOR ( 'NONE', #3923, 1000.000000000000227 ) ; +#14745 = FACE_OUTER_BOUND ( 'NONE', #14825, .T. ) ; +#14746 = CARTESIAN_POINT ( 'NONE', ( 14.54953207236175139, 130.1535194663153447, 89.69244121379192336 ) ) ; +#14747 = AXIS2_PLACEMENT_3D ( 'NONE', #32948, #23157, #14778 ) ; +#14748 = AXIS2_PLACEMENT_3D ( 'NONE', #29526, #23396, #1721 ) ; +#14749 = CARTESIAN_POINT ( 'NONE', ( 21.44870230457277316, 181.8867687911781559, 104.7107509713525388 ) ) ; +#14750 = ORIENTED_EDGE ( 'NONE', *, *, #37276, .F. ) ; +#14751 = CONICAL_SURFACE ( 'NONE', #27163, 4.999999999930255790, 0.7853981633714466337 ) ; +#14752 = CARTESIAN_POINT ( 'NONE', ( 32.56861805024679768, 175.3596280205372011, 100.1182146692571138 ) ) ; +#14753 = CARTESIAN_POINT ( 'NONE', ( 3.484080676294788681, 187.1397425093524873, 102.8554330292374601 ) ) ; +#14754 = CONICAL_SURFACE ( 'NONE', #28458, 5.250000000064561689, 0.7853981633647640903 ) ; +#14755 = CARTESIAN_POINT ( 'NONE', ( -8.283690339216027709, 6.323265155852981323, 291.5635470766264348 ) ) ; +#14756 = CARTESIAN_POINT ( 'NONE', ( -12.64386474322367526, 181.0124094291204528, 104.5294403572958544 ) ) ; +#14757 = ORIENTED_EDGE ( 'NONE', *, *, #17142, .F. ) ; +#14758 = ADVANCED_FACE ( 'NONE', ( #20969 ), #7555, .T. ) ; +#14759 = CARTESIAN_POINT ( 'NONE', ( -28.51673990053000196, 187.2657903049000083, 103.0285994297999963 ) ) ; +#14760 = CARTESIAN_POINT ( 'NONE', ( 0.8619687770521999859, 188.7597673114000258, 103.3660920736000008 ) ) ; +#14761 = CARTESIAN_POINT ( 'NONE', ( 26.11627784374346106, 121.2164058409220786, 90.70107236864649281 ) ) ; +#14762 = ORIENTED_EDGE ( 'NONE', *, *, #5377, .F. ) ; +#14763 = EDGE_LOOP ( 'NONE', ( #25617, #16678, #30021, #15390 ) ) ; +#14764 = FACE_OUTER_BOUND ( 'NONE', #1949, .T. ) ; +#14765 = ORIENTED_EDGE ( 'NONE', *, *, #5944, .F. ) ; +#14766 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #18921, #15080 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14768 = EDGE_CURVE ( 'NONE', #16912, #12564, #13138, .T. ) ; +#14767 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16886, #7699, #11595, #17089 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999986321218314878 ), + .UNSPECIFIED. ) ; +#14769 = ORIENTED_EDGE ( 'NONE', *, *, #8155, .T. ) ; +#14770 = CIRCLE ( 'NONE', #25222, 2.000000000000011546 ) ; +#14771 = VERTEX_POINT ( 'NONE', #23632 ) ; +#14772 = CONICAL_SURFACE ( 'NONE', #18642, 4.999999999928862238, 0.7853981633813337249 ) ; +#14773 = CARTESIAN_POINT ( 'NONE', ( 23.36690039798400420, 177.7945729690129610, 100.6859215232942262 ) ) ; +#14774 = CARTESIAN_POINT ( 'NONE', ( -29.31840044800755862, 107.1313895729742853, 197.8236157141470812 ) ) ; +#14775 = AXIS2_PLACEMENT_3D ( 'NONE', #9786, #34692, #559 ) ; +#14776 = CARTESIAN_POINT ( 'NONE', ( -36.94217276719289345, 191.1469244249373958, 106.3510002446024174 ) ) ; +#14777 = EDGE_LOOP ( 'NONE', ( #28223, #23940, #31908, #6027 ) ) ; +#14778 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971539312 ) ) ; +#14779 = ORIENTED_EDGE ( 'NONE', *, *, #1126, .F. ) ; +#14780 = AXIS2_PLACEMENT_3D ( 'NONE', #12965, #19676, #6804 ) ; +#14781 = CARTESIAN_POINT ( 'NONE', ( 26.24278765071260011, 121.6914654643040166, 90.81416692690758907 ) ) ; +#14782 = CARTESIAN_POINT ( 'NONE', ( -35.96501400986333152, 191.5393548104552792, 103.8949329600032456 ) ) ; +#14783 = CONICAL_SURFACE ( 'NONE', #37617, 2.500000002031119717, 0.7853981634283228042 ) ; +#14784 = EDGE_CURVE ( 'NONE', #7826, #662, #20343, .T. ) ; +#14785 = EDGE_CURVE ( 'NONE', #29758, #12650, #34121, .T. ) ; +#14787 = LINE ( 'NONE', #20284, #12250 ) ; +#14786 = CARTESIAN_POINT ( 'NONE', ( 6.034364035348996680, 135.2945551047479853, 91.39763805309847555 ) ) ; +#14788 = VERTEX_POINT ( 'NONE', #10963 ) ; +#14789 = ORIENTED_EDGE ( 'NONE', *, *, #31023, .T. ) ; +#14790 = ORIENTED_EDGE ( 'NONE', *, *, #10674, .F. ) ; +#14791 = CARTESIAN_POINT ( 'NONE', ( -11.79198343374907054, 125.9681876107315333, 176.0676422622361770 ) ) ; +#14792 = CARTESIAN_POINT ( 'NONE', ( -32.37402305108282263, 174.4007230276914697, 99.93605550448263841 ) ) ; +#14793 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#14794 = CARTESIAN_POINT ( 'NONE', ( 6.035970131895862956, 136.6809175985756895, 94.28346487865485415 ) ) ; +#14795 = ORIENTED_EDGE ( 'NONE', *, *, #21131, .F. ) ; +#14796 = ORIENTED_EDGE ( 'NONE', *, *, #19430, .T. ) ; +#14797 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781609017, 0.0005734119022076547383 ) ) ; +#14798 = AXIS2_PLACEMENT_3D ( 'NONE', #5252, #24085, #11394 ) ; +#14799 = CARTESIAN_POINT ( 'NONE', ( -45.16400980236513618, 70.91888486856629470, 322.7789803297500839 ) ) ; +#14800 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #30955, #3129, #27300, #28099 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 2.390890780862696019, 2.519620269850888938 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9986195365718029127, 0.9986195365718029127, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#14801 = CARTESIAN_POINT ( 'NONE', ( 26.36788054911000145, 123.4245874620000052, 88.47400024127000506 ) ) ; +#14802 = ORIENTED_EDGE ( 'NONE', *, *, #23404, .F. ) ; +#14803 = ADVANCED_FACE ( 'NONE', ( #30171 ), #7878, .T. ) ; +#14804 = CARTESIAN_POINT ( 'NONE', ( -35.93471605327420093, 191.2065812678220311, 106.8934977285220072 ) ) ; +#14805 = AXIS2_PLACEMENT_3D ( 'NONE', #402, #15546, #6526 ) ; +#14806 = CARTESIAN_POINT ( 'NONE', ( 0.7417211779368000357, 188.7943872467999995, 105.8988894614000174 ) ) ; +#14807 = CARTESIAN_POINT ( 'NONE', ( -14.59022374134706901, 128.1503308081717876, 179.4782974412063936 ) ) ; +#14808 = CARTESIAN_POINT ( 'NONE', ( 13.50046316316999828, 187.7460073535528124, 103.5025028262052018 ) ) ; +#14809 = CARTESIAN_POINT ( 'NONE', ( -77.80920708077799475, 191.9373083000641316, 194.2502677903374604 ) ) ; +#14810 = ADVANCED_FACE ( 'NONE', ( #2166 ), #11541, .F. ) ; +#14811 = ORIENTED_EDGE ( 'NONE', *, *, #1202, .F. ) ; +#14812 = LINE ( 'NONE', #23199, #32954 ) ; +#14813 = DIRECTION ( 'NONE', ( 0.0006039748319388209621, -4.551467604553135559E-16, 0.9999998176071845934 ) ) ; +#14814 = EDGE_CURVE ( 'NONE', #31941, #1633, #37504, .T. ) ; +#14815 = ORIENTED_EDGE ( 'NONE', *, *, #15156, .F. ) ; +#14816 = CARTESIAN_POINT ( 'NONE', ( 25.99030105615392827, 209.7097546603872900, 73.04280869622928662 ) ) ; +#14817 = EDGE_LOOP ( 'NONE', ( #11324, #35988, #17629, #13356 ) ) ; +#14818 = ADVANCED_FACE ( 'NONE', ( #5833 ), #15241, .T. ) ; +#14819 = VECTOR ( 'NONE', #25802, 1000.000000000000000 ) ; +#14820 = ADVANCED_FACE ( 'NONE', ( #30983 ), #12558, .T. ) ; +#14821 = VECTOR ( 'NONE', #29805, 1000.000000000000114 ) ; +#14823 = CARTESIAN_POINT ( 'NONE', ( -42.29775297821973368, 68.10033796042301901, 322.1267884147291625 ) ) ; +#14822 = LINE ( 'NONE', #9082, #4370 ) ; +#14824 = EDGE_CURVE ( 'NONE', #2542, #17419, #40244, .T. ) ; +#14825 = EDGE_LOOP ( 'NONE', ( #37744, #38666, #31997, #28679 ) ) ; +#14826 = ORIENTED_EDGE ( 'NONE', *, *, #20794, .F. ) ; +#14827 = EDGE_CURVE ( 'NONE', #32124, #9285, #21969, .T. ) ; +#14828 = ORIENTED_EDGE ( 'NONE', *, *, #33734, .T. ) ; +#14830 = VECTOR ( 'NONE', #23380, 1000.000000000000114 ) ; +#14829 = DIRECTION ( 'NONE', ( -3.469446951953594073E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#14831 = PLANE ( 'NONE', #27867 ) ; +#14832 = CARTESIAN_POINT ( 'NONE', ( -37.22291683779299376, 185.3309949534769601, 105.5413495680464564 ) ) ; +#14833 = DIRECTION ( 'NONE', ( -0.0005884949961193586092, 0.2249510543439039167, -0.9743698870671270162 ) ) ; +#14834 = CARTESIAN_POINT ( 'NONE', ( 12.63911368426781223, 177.4999195067232449, 100.8751768350861795 ) ) ; +#14835 = ORIENTED_EDGE ( 'NONE', *, *, #33534, .F. ) ; +#14836 = ORIENTED_EDGE ( 'NONE', *, *, #29144, .T. ) ; +#14837 = DIRECTION ( 'NONE', ( -0.0005884949916165789496, 0.2249510543496076598, -0.9743698870658127342 ) ) ; +#14838 = ORIENTED_EDGE ( 'NONE', *, *, #20811, .F. ) ; +#14839 = ORIENTED_EDGE ( 'NONE', *, *, #24353, .F. ) ; +#14840 = CARTESIAN_POINT ( 'NONE', ( -19.32395937428486477, 125.1232359887470835, 178.1040707223516506 ) ) ; +#14841 = DIRECTION ( 'NONE', ( 0.0005559617638584173809, -0.3907311284892690528, 0.9205046855589706922 ) ) ; +#14842 = CARTESIAN_POINT ( 'NONE', ( 19.34464905661442913, 125.4224474659459361, 178.3484596968724247 ) ) ; +#14843 = ORIENTED_EDGE ( 'NONE', *, *, #16998, .T. ) ; +#14844 = ORIENTED_EDGE ( 'NONE', *, *, #7361, .F. ) ; +#14845 = DIRECTION ( 'NONE', ( -0.0006039748319386907495, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#14846 = CARTESIAN_POINT ( 'NONE', ( -35.57981409087999936, 192.4624458391000132, 104.0002278041999944 ) ) ; +#14847 = ORIENTED_EDGE ( 'NONE', *, *, #13441, .T. ) ; +#14848 = CARTESIAN_POINT ( 'NONE', ( -26.00107461933026443, 120.7512200989553151, 87.53535867504626822 ) ) ; +#14849 = ORIENTED_EDGE ( 'NONE', *, *, #23364, .F. ) ; +#14850 = DIRECTION ( 'NONE', ( -0.9999998268368034404, -0.0001323825955363455871, 0.0005734119039304815891 ) ) ; +#14851 = CARTESIAN_POINT ( 'NONE', ( 15.50176591790000025, 128.0783593493999888, 92.29169035091000239 ) ) ; +#14852 = ORIENTED_EDGE ( 'NONE', *, *, #15207, .F. ) ; +#14853 = CIRCLE ( 'NONE', #36408, 4.500000000071178619 ) ; +#14854 = FACE_OUTER_BOUND ( 'NONE', #30905, .T. ) ; +#14855 = CARTESIAN_POINT ( 'NONE', ( 3.806357625657792010, 174.7432254729364161, 102.7945264273639054 ) ) ; +#14856 = CARTESIAN_POINT ( 'NONE', ( -3.804637439536749266, 167.8806383395850048, 101.2168609214313193 ) ) ; +#14857 = EDGE_LOOP ( 'NONE', ( #5573, #40222, #9737, #39093, #24844, #7900, #40053, #25226, #28581, #10739, #19095, #9597, #31974 ) ) ; +#14858 = CARTESIAN_POINT ( 'NONE', ( -45.18925545272470856, 80.56898504508372127, 280.9798118546170258 ) ) ; +#14859 = CARTESIAN_POINT ( 'NONE', ( 41.02702155346852209, 188.5398332461408870, 107.5358668361008228 ) ) ; +#14860 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748612543, 179.1800746285557580, 103.5747911657685734 ) ) ; +#14861 = ADVANCED_FACE ( 'NONE', ( #2949 ), #1727, .T. ) ; +#14862 = VERTEX_POINT ( 'NONE', #15040 ) ; +#14863 = CARTESIAN_POINT ( 'NONE', ( 24.84150023435487142, 115.7113441437079899, 90.25278119554212708 ) ) ; +#14864 = ORIENTED_EDGE ( 'NONE', *, *, #17835, .F. ) ; +#14865 = FACE_OUTER_BOUND ( 'NONE', #34929, .T. ) ; +#14866 = CARTESIAN_POINT ( 'NONE', ( -35.45487758071271855, 209.7096534091000137, 76.07991848633032816 ) ) ; +#14867 = CARTESIAN_POINT ( 'NONE', ( -14.42530050483258286, 182.6237780248500258, 101.9947080626078559 ) ) ; +#14868 = EDGE_CURVE ( 'NONE', #4358, #1663, #18282, .T. ) ; +#14869 = CARTESIAN_POINT ( 'NONE', ( -35.43925701461602529, 191.9759150222000130, 101.9428517634920155 ) ) ; +#14870 = ORIENTED_EDGE ( 'NONE', *, *, #8255, .T. ) ; +#14871 = EDGE_CURVE ( 'NONE', #34014, #3655, #18037, .T. ) ; +#14872 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#14873 = CARTESIAN_POINT ( 'NONE', ( -6.045835231059395021, 134.9182589738620095, 90.80491324842614631 ) ) ; +#14874 = ADVANCED_FACE ( 'NONE', ( #28126 ), #8715, .F. ) ; +#14875 = CARTESIAN_POINT ( 'NONE', ( 38.08852185710932048, 146.1696274809962119, 280.9295141638872906 ) ) ; +#14876 = CARTESIAN_POINT ( 'NONE', ( -16.27844647523966159, 151.6576545058942997, 160.4643156198225427 ) ) ; +#14877 = AXIS2_PLACEMENT_3D ( 'NONE', #27449, #15731, #24768 ) ; +#14878 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319370571820 ) ) ; +#14879 = CARTESIAN_POINT ( 'NONE', ( 31.03325069022026383, 177.6068007423234008, 100.6379405975941097 ) ) ; +#14880 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; +#14881 = CARTESIAN_POINT ( 'NONE', ( 21.94280614663047047, 115.3059885538493177, 90.25453193413594022 ) ) ; +#14882 = EDGE_LOOP ( 'NONE', ( #37727, #22936, #19480, #26601 ) ) ; +#14883 = VERTEX_POINT ( 'NONE', #27934 ) ; +#14884 = CARTESIAN_POINT ( 'NONE', ( -2.935493006219376255, 190.8915656532114724, 106.8042233182557652 ) ) ; +#14885 = PLANE ( 'NONE', #6588 ) ; +#14886 = ORIENTED_EDGE ( 'NONE', *, *, #8263, .F. ) ; +#14887 = CARTESIAN_POINT ( 'NONE', ( -20.49853057565002601, 184.3993303303604705, 104.8029991440840973 ) ) ; +#14888 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921577410, 0.2249510932971590937 ) ) ; +#14889 = EDGE_LOOP ( 'NONE', ( #1607, #23367, #17522, #37102 ) ) ; +#14890 = DIRECTION ( 'NONE', ( -0.0005884949950231212505, 0.2249510543438350829, -0.9743698870671434475 ) ) ; +#14891 = CARTESIAN_POINT ( 'NONE', ( -5.668214785696392255, 130.7937963942969475, 90.04674115371072673 ) ) ; +#14892 = ORIENTED_EDGE ( 'NONE', *, *, #22210, .T. ) ; +#14893 = CARTESIAN_POINT ( 'NONE', ( -43.65360665174738841, 185.3905100451317765, 107.6115822775834374 ) ) ; +#14894 = CARTESIAN_POINT ( 'NONE', ( 75.24056455973224899, 196.4820008462166641, 189.1802437148639058 ) ) ; +#14895 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 2.710505431213761687E-20, -0.0006039748319346910192 ) ) ; +#14896 = CARTESIAN_POINT ( 'NONE', ( -1.458415330484564842, 144.9404864492794047, 129.0359332385724258 ) ) ; +#14897 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749387275, 132.8602140592439866, 90.82839891339261840 ) ) ; +#14898 = EDGE_LOOP ( 'NONE', ( #5460, #1077, #19635, #6055, #16790 ) ) ; +#14899 = CARTESIAN_POINT ( 'NONE', ( 39.73982121083000152, 119.6329988433000011, 87.90935942237000233 ) ) ; +#14900 = CARTESIAN_POINT ( 'NONE', ( -6.031620047117566052, 177.7903949882438042, 100.7027583919079063 ) ) ; +#14901 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; +#14902 = ADVANCED_FACE ( 'NONE', ( #3353 ), #18679, .T. ) ; +#14903 = EDGE_CURVE ( 'NONE', #27587, #29108, #2768, .T. ) ; +#14904 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#14905 = EDGE_CURVE ( 'NONE', #16249, #18466, #14161, .T. ) ; +#14906 = ORIENTED_EDGE ( 'NONE', *, *, #39270, .T. ) ; +#14907 = DIRECTION ( 'NONE', ( -0.0005884949961193429967, 0.2249510543439072197, -0.9743698870671261281 ) ) ; +#14908 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #7434, #4570 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14909 = CARTESIAN_POINT ( 'NONE', ( 22.34608376466076507, 115.6781728360633679, 89.75450174034121176 ) ) ; +#14910 = CARTESIAN_POINT ( 'NONE', ( 1.226896413245818884, 139.0230654261391692, 177.9317107752453921 ) ) ; +#14911 = DIRECTION ( 'NONE', ( 0.6087611434179127645, 0.7731004625452339019, 0.1781166614240815016 ) ) ; +#14912 = CARTESIAN_POINT ( 'NONE', ( -21.17604533225664554, 114.6186307098221846, 152.8157487814333422 ) ) ; +#14913 = EDGE_CURVE ( 'NONE', #37711, #25532, #19352, .T. ) ; +#14914 = CARTESIAN_POINT ( 'NONE', ( -12.63633097960429197, 127.9084167607413320, 92.27263726944957511 ) ) ; +#14915 = CARTESIAN_POINT ( 'NONE', ( 21.46568501808666696, 116.4032067661892569, 184.4826706400311025 ) ) ; +#14916 = CARTESIAN_POINT ( 'NONE', ( -25.66870877867046374, 209.7112358038351090, 73.41525054140304007 ) ) ; +#14917 = CARTESIAN_POINT ( 'NONE', ( 33.97342776401706743, 128.5679624385472266, 291.5380248361651638 ) ) ; +#14918 = EDGE_CURVE ( 'NONE', #28359, #36719, #21484, .T. ) ; +#14919 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319697021, 89.39970233729044935, 291.5295797804315612 ) ) ; +#14920 = CARTESIAN_POINT ( 'NONE', ( -6.035970131895957103, 136.6793194835712484, 94.29038707408911080 ) ) ; +#14921 = CARTESIAN_POINT ( 'NONE', ( 18.08289561727003658, 152.6324032069051384, 184.7487331658680887 ) ) ; +#14922 = CARTESIAN_POINT ( 'NONE', ( -27.01791081220863333, 113.9384843682444739, 176.2313260275029734 ) ) ; +#14923 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971547084 ) ) ; +#14925 = VERTEX_POINT ( 'NONE', #3152 ) ; +#14924 = CARTESIAN_POINT ( 'NONE', ( 37.28138085964135229, 124.9697182170792331, 93.49058584749309375 ) ) ; +#14926 = ORIENTED_EDGE ( 'NONE', *, *, #35704, .T. ) ; +#14927 = VERTEX_POINT ( 'NONE', #692 ) ; +#14929 = AXIS2_PLACEMENT_3D ( 'NONE', #19439, #4502, #3897 ) ; +#14928 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941776877568, 160.8896114957608177, 98.33667293300580070 ) ) ; +#14930 = ORIENTED_EDGE ( 'NONE', *, *, #1929, .F. ) ; +#14931 = LINE ( 'NONE', #14739, #10498 ) ; +#14932 = AXIS2_PLACEMENT_3D ( 'NONE', #31852, #19551, #12833 ) ; +#14933 = DIRECTION ( 'NONE', ( 0.5988974202702760374, -0.8008257488327958917, 0.000000000000000000 ) ) ; +#14934 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #40386, #24885, #31203, #22214 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.002537838772308321188, 0.007867325901353338855 ), + .UNSPECIFIED. ) ; +#14935 = CARTESIAN_POINT ( 'NONE', ( -19.99800679399352532, 151.2849267590962654, 97.67087031631508864 ) ) ; +#14936 = CONICAL_SURFACE ( 'NONE', #36553, 2.502994258127966720, 0.7853981633568209997 ) ; +#14937 = CONICAL_SURFACE ( 'NONE', #40368, 2.503080545183768546, 0.7853981633889626224 ) ; +#14938 = VERTEX_POINT ( 'NONE', #35220 ) ; +#14939 = CARTESIAN_POINT ( 'NONE', ( -5.662686464640452222, 188.3429660633563287, 103.1387990589197869 ) ) ; +#14940 = DIRECTION ( 'NONE', ( -0.0004161288024618653870, 0.8480480897819120401, -0.5299191110481576983 ) ) ; +#14941 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.271205363195980628E-14, -0.9999998176071845934 ) ) ; +#14942 = CARTESIAN_POINT ( 'NONE', ( 16.00176529486913424, 184.2900636920902002, 105.2688851223920778 ) ) ; +#14943 = ORIENTED_EDGE ( 'NONE', *, *, #27103, .T. ) ; +#14944 = CARTESIAN_POINT ( 'NONE', ( 17.25787011369294177, 152.4458873259683287, 182.8835471660145231 ) ) ; +#14945 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16968, #29468, #1443, #29668 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0001462318381979060247, 0.004088694087170433554 ), + .UNSPECIFIED. ) ; +#14946 = CARTESIAN_POINT ( 'NONE', ( 26.71688048470999988, 176.9326579885999990, 103.3072462416999997 ) ) ; +#14947 = CYLINDRICAL_SURFACE ( 'NONE', #7786, 16.50000000000000000 ) ; +#14948 = CARTESIAN_POINT ( 'NONE', ( -4.606085391967113196, 188.1124318115141989, 103.0848823474960625 ) ) ; +#14949 = CARTESIAN_POINT ( 'NONE', ( -22.62605270318119466, 214.0903621265957213, 76.07221691162195043 ) ) ; +#14950 = VERTEX_POINT ( 'NONE', #31794 ) ; +#14951 = CARTESIAN_POINT ( 'NONE', ( -27.81649859982000095, 186.9854473794999876, 103.4908046625999987 ) ) ; +#14952 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24676, #27944, #34045, #40374 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( -3.279828533275069060E-07, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#14953 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; +#14954 = CARTESIAN_POINT ( 'NONE', ( 37.71190864537933862, 212.3970730851055748, 73.53572712575454773 ) ) ; +#14955 = ORIENTED_EDGE ( 'NONE', *, *, #2214, .F. ) ; +#14956 = EDGE_CURVE ( 'NONE', #31137, #26517, #1462, .T. ) ; +#14957 = VERTEX_POINT ( 'NONE', #28517 ) ; +#14958 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#14959 = ADVANCED_FACE ( 'NONE', ( #10322 ), #22388, .T. ) ; +#14960 = ORIENTED_EDGE ( 'NONE', *, *, #7300, .T. ) ; +#14961 = VECTOR ( 'NONE', #7933, 1000.000000000000227 ) ; +#14962 = VECTOR ( 'NONE', #30449, 999.9999999999998863 ) ; +#14963 = VERTEX_POINT ( 'NONE', #38311 ) ; +#14964 = VECTOR ( 'NONE', #26037, 1000.000000000000000 ) ; +#14965 = ORIENTED_EDGE ( 'NONE', *, *, #4506, .F. ) ; +#14966 = CARTESIAN_POINT ( 'NONE', ( 23.36190162741788967, 177.7945445883550519, 100.6858769593398080 ) ) ; +#14967 = CONICAL_SURFACE ( 'NONE', #10390, 6.499999999957617014, 0.7853981634197665374 ) ; +#14968 = DIRECTION ( 'NONE', ( 0.7856007465113979960, 0.6187337610642678065, 0.000000000000000000 ) ) ; +#14969 = CARTESIAN_POINT ( 'NONE', ( 14.93318671104674777, 124.4798289405424612, 171.6828735292820625 ) ) ; +#14970 = ORIENTED_EDGE ( 'NONE', *, *, #17462, .T. ) ; +#14971 = CARTESIAN_POINT ( 'NONE', ( -30.44899543503618489, 184.9287465216532098, 105.4443919424699487 ) ) ; +#14972 = ORIENTED_EDGE ( 'NONE', *, *, #8310, .T. ) ; +#14973 = CARTESIAN_POINT ( 'NONE', ( 26.12685208517629931, 121.2579486302669949, 90.71245394277049456 ) ) ; +#14974 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#14976 = CARTESIAN_POINT ( 'NONE', ( 38.20283421333017060, 112.8208469135682037, 151.2502482518302145 ) ) ; +#14975 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319384230599 ) ) ; +#14977 = ORIENTED_EDGE ( 'NONE', *, *, #29558, .T. ) ; +#14978 = ADVANCED_FACE ( 'NONE', ( #29120 ), #1092, .T. ) ; +#14979 = DIRECTION ( 'NONE', ( 0.6087613186456907188, -0.7729176985478710682, -0.1789074850089337476 ) ) ; +#14980 = ORIENTED_EDGE ( 'NONE', *, *, #17243, .T. ) ; +#14981 = ORIENTED_EDGE ( 'NONE', *, *, #537, .T. ) ; +#14982 = CARTESIAN_POINT ( 'NONE', ( -28.53030869656295110, 124.6043131503039803, 91.51623810099293621 ) ) ; +#14983 = AXIS2_PLACEMENT_3D ( 'NONE', #5881, #30834, #17928 ) ; +#14984 = CARTESIAN_POINT ( 'NONE', ( 13.47462245814947934, 158.2310456470601423, 98.74105996008697161 ) ) ; +#14985 = CARTESIAN_POINT ( 'NONE', ( 45.36193107847550010, 123.6517040319592695, 91.25168146711183681 ) ) ; +#14986 = CARTESIAN_POINT ( 'NONE', ( 30.96384560852109047, 128.5897405105000360, 89.32150042245991983 ) ) ; +#14987 = CARTESIAN_POINT ( 'NONE', ( -15.49852918818087844, 160.1761146135337697, 99.20761364607615462 ) ) ; +#14988 = VERTEX_POINT ( 'NONE', #19690 ) ; +#14989 = AXIS2_PLACEMENT_3D ( 'NONE', #8262, #38514, #38708 ) ; +#14990 = EDGE_LOOP ( 'NONE', ( #35997, #25697, #1686, #28195, #3694, #32672 ) ) ; +#14991 = CIRCLE ( 'NONE', #13035, 5.999999999829195296 ) ; +#14992 = LINE ( 'NONE', #14194, #24675 ) ; +#14993 = VECTOR ( 'NONE', #32751, 1000.000000000000114 ) ; +#14994 = CARTESIAN_POINT ( 'NONE', ( 14.50494660459214202, 188.1403489822673407, 103.0797849509411606 ) ) ; +#14995 = ORIENTED_EDGE ( 'NONE', *, *, #3892, .F. ) ; +#14996 = CARTESIAN_POINT ( 'NONE', ( 35.80006985119368323, 209.7096538286036775, 75.78341165758600084 ) ) ; +#14997 = EDGE_CURVE ( 'NONE', #12942, #33829, #16095, .T. ) ; +#14998 = CARTESIAN_POINT ( 'NONE', ( 1.191689505327423015, 188.4327942350174396, 106.2411708578321736 ) ) ; +#14999 = EDGE_CURVE ( 'NONE', #28821, #29586, #38498, .T. ) ; +#15000 = CARTESIAN_POINT ( 'NONE', ( -20.51961669426007973, 208.8045157407349848, 73.66040143448114463 ) ) ; +#15001 = CARTESIAN_POINT ( 'NONE', ( -37.83635444431042316, 190.3639788717852923, 106.7036751988638912 ) ) ; +#15002 = CARTESIAN_POINT ( 'NONE', ( 20.50147081616042755, 137.9496117178372003, 94.05447709939286938 ) ) ; +#15003 = CARTESIAN_POINT ( 'NONE', ( 23.36337295639098599, 174.7961192000784649, 102.5594366671658833 ) ) ; +#15004 = ORIENTED_EDGE ( 'NONE', *, *, #1903, .T. ) ; +#15005 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319364164186 ) ) ; +#15006 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32464, #34699, #7299, #32268, #15905, #28794, #774, #25944, #32072, #13061, #25746, #13260, #25542, #28401 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 0.000000000000000000, 0.2499727892209989422, 0.4999454735151304119, 0.6249318156621461728, 0.7499181578092619649, 0.8124113288828697099, 0.8749044999562777258, 0.9373976710298355108, 0.9686442565666094628, 0.9842675493349863913, 0.9999740798740125447, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15007 = PLANE ( 'NONE', #16002 ) ; +#15008 = LINE ( 'NONE', #30340, #39783 ) ; +#15009 = AXIS2_PLACEMENT_3D ( 'NONE', #27240, #11885, #11267 ) ; +#15010 = AXIS2_PLACEMENT_3D ( 'NONE', #1703, #26657, #11306 ) ; +#15011 = ORIENTED_EDGE ( 'NONE', *, *, #17500, .T. ) ; +#15012 = CIRCLE ( 'NONE', #18899, 2.500000000000003997 ) ; +#15013 = VECTOR ( 'NONE', #25946, 1000.000000000000114 ) ; +#15014 = CARTESIAN_POINT ( 'NONE', ( 16.04677293489484668, 121.3099732125007364, 177.4328244646404187 ) ) ; +#15015 = ORIENTED_EDGE ( 'NONE', *, *, #14594, .T. ) ; +#15016 = CIRCLE ( 'NONE', #20887, 7.500000000039277914 ) ; +#15018 = CARTESIAN_POINT ( 'NONE', ( 36.11364262193256280, 191.5260145455536929, 103.8483746271915322 ) ) ; +#15017 = CARTESIAN_POINT ( 'NONE', ( 58.66975477332916711, 28.73766266558741478, 151.7693572141883749 ) ) ; +#15019 = EDGE_LOOP ( 'NONE', ( #13645, #428, #10104, #6375 ) ) ; +#15020 = ORIENTED_EDGE ( 'NONE', *, *, #13617, .F. ) ; +#15021 = EDGE_CURVE ( 'NONE', #40336, #23375, #30741, .T. ) ; +#15022 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6676, #19553, #38559, #4208, #22447, #32244, #10576, #23046, #9771, #19144, #3604 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998985256, 0.3749999999998269717, 0.4374999999997786215, 0.4687499999997544742, 0.4999999999997302713, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15023 = ORIENTED_EDGE ( 'NONE', *, *, #32765, .T. ) ; +#15024 = CARTESIAN_POINT ( 'NONE', ( -30.17967539261260868, 185.9478675171641271, 102.6005988726028590 ) ) ; +#15025 = CARTESIAN_POINT ( 'NONE', ( 36.04593084803799741, 218.5902260770999987, 76.03673379060180082 ) ) ; +#15026 = DIRECTION ( 'NONE', ( -3.965082230941001926E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; +#15027 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498896523, 179.0675991014397255, 104.0619761092555535 ) ) ; +#15028 = ORIENTED_EDGE ( 'NONE', *, *, #32127, .F. ) ; +#15029 = ORIENTED_EDGE ( 'NONE', *, *, #12133, .F. ) ; +#15030 = CARTESIAN_POINT ( 'NONE', ( -35.95473150033171095, 205.5673820438934172, 76.32193034924722497 ) ) ; +#15031 = VERTEX_POINT ( 'NONE', #34615 ) ; +#15032 = ORIENTED_EDGE ( 'NONE', *, *, #8213, .T. ) ; +#15033 = CARTESIAN_POINT ( 'NONE', ( 25.50832794966548889, 194.2771770616000140, 102.8828691709000083 ) ) ; +#15034 = FACE_OUTER_BOUND ( 'NONE', #39806, .T. ) ; +#15035 = CARTESIAN_POINT ( 'NONE', ( 23.49456796478292731, 134.9226066419677750, 90.78806929407819837 ) ) ; +#15036 = LINE ( 'NONE', #6218, #13121 ) ; +#15037 = ORIENTED_EDGE ( 'NONE', *, *, #31344, .F. ) ; +#15038 = EDGE_CURVE ( 'NONE', #25693, #33874, #24614, .T. ) ; +#15039 = VERTEX_POINT ( 'NONE', #19090 ) ; +#15040 = CARTESIAN_POINT ( 'NONE', ( 6.042240099596939196, 177.1173855813495948, 103.6190021212635770 ) ) ; +#15041 = CARTESIAN_POINT ( 'NONE', ( -36.32345314786999779, 191.9373732646000121, 104.5577068233999967 ) ) ; +#15042 = VERTEX_POINT ( 'NONE', #31585 ) ; +#15043 = CARTESIAN_POINT ( 'NONE', ( -26.09494683763999845, 122.9286295258000052, 88.39116117343999690 ) ) ; +#15044 = VECTOR ( 'NONE', #17936, 999.9999999999998863 ) ; +#15045 = EDGE_CURVE ( 'NONE', #15381, #10264, #3545, .T. ) ; +#15046 = ORIENTED_EDGE ( 'NONE', *, *, #26914, .T. ) ; +#15047 = CARTESIAN_POINT ( 'NONE', ( 22.78222448783905563, 147.4012051316053373, 96.74832440318435545 ) ) ; +#15048 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; +#15049 = VECTOR ( 'NONE', #5420, 1000.000000000000000 ) ; +#15050 = ORIENTED_EDGE ( 'NONE', *, *, #11114, .T. ) ; +#15051 = AXIS2_PLACEMENT_3D ( 'NONE', #3383, #18713, #18513 ) ; +#15052 = AXIS2_PLACEMENT_3D ( 'NONE', #9473, #15598, #21953 ) ; +#15053 = ADVANCED_FACE ( 'NONE', ( #6819 ), #30466, .T. ) ; +#15054 = FACE_OUTER_BOUND ( 'NONE', #11763, .T. ) ; +#15055 = EDGE_CURVE ( 'NONE', #11228, #2503, #452, .T. ) ; +#15056 = CARTESIAN_POINT ( 'NONE', ( 14.42549689688723902, 176.7813770855786970, 100.6284578791999849 ) ) ; +#15057 = EDGE_CURVE ( 'NONE', #27737, #14771, #37036, .T. ) ; +#15058 = CARTESIAN_POINT ( 'NONE', ( -19.36170877788639189, 125.9457204061172604, 176.2201754958151980 ) ) ; +#15059 = EDGE_CURVE ( 'NONE', #3485, #16249, #31687, .T. ) ; +#15060 = CARTESIAN_POINT ( 'NONE', ( 5.666638401079358900, 185.7962301796234783, 103.0570926492003423 ) ) ; +#15061 = LINE ( 'NONE', #34437, #5156 ) ; +#15062 = VERTEX_POINT ( 'NONE', #33762 ) ; +#15063 = CARTESIAN_POINT ( 'NONE', ( 23.00089693216080988, 115.1133509736824152, 90.25389292129368357 ) ) ; +#15064 = EDGE_LOOP ( 'NONE', ( #32281, #32194, #27485, #29146 ) ) ; +#15065 = ORIENTED_EDGE ( 'NONE', *, *, #32612, .T. ) ; +#15066 = CARTESIAN_POINT ( 'NONE', ( -39.67088391192145735, 107.0888282672084699, 184.9170418304496195 ) ) ; +#15067 = CARTESIAN_POINT ( 'NONE', ( -38.20994760263000245, 118.4557571329000041, 87.83717842695000400 ) ) ; +#15068 = CARTESIAN_POINT ( 'NONE', ( 38.73196185082999676, 118.4320966457000139, 89.50377527013000645 ) ) ; +#15069 = CARTESIAN_POINT ( 'NONE', ( -20.51882342812400850, 211.4177743922000730, 75.57082808996456436 ) ) ; +#15070 = CARTESIAN_POINT ( 'NONE', ( 6.033445973870449563, 135.2348759297800029, 91.30213210094883891 ) ) ; +#15071 = ORIENTED_EDGE ( 'NONE', *, *, #18846, .F. ) ; +#15072 = CARTESIAN_POINT ( 'NONE', ( 16.55946513390808406, 121.8573583107191780, 177.5776958584335148 ) ) ; +#15073 = AXIS2_PLACEMENT_3D ( 'NONE', #8098, #11363, #36514 ) ; +#15074 = EDGE_CURVE ( 'NONE', #19918, #15284, #23272, .T. ) ; +#15075 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319356122658 ) ) ; +#15076 = ORIENTED_EDGE ( 'NONE', *, *, #8257, .F. ) ; +#15077 = CARTESIAN_POINT ( 'NONE', ( 23.68479074153999875, 130.4250414353013241, 90.26276162061896002 ) ) ; +#15078 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36989, #8580, #18150, #8986, #16105, #12434, #12851, #557, #37383, #25328 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000945355, 0.3750000000001261768, 0.4375000000001419975, 0.5000000000001577627, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15079 = CARTESIAN_POINT ( 'NONE', ( 22.10845038464975332, 154.3881759508926734, 95.28288806961444379 ) ) ; +#15080 = CARTESIAN_POINT ( 'NONE', ( -28.70758035546699460, 163.1500623791996816, 99.90218165579484833 ) ) ; +#15081 = CARTESIAN_POINT ( 'NONE', ( -36.79864679810778227, 165.0248183764149701, 194.7126685882008985 ) ) ; +#15082 = DIRECTION ( 'NONE', ( -0.7856245185210576354, -0.6187035767623751958, 0.000000000000000000 ) ) ; +#15083 = CARTESIAN_POINT ( 'NONE', ( -1.208995885426419781, 135.1225269230298238, 180.6332618066155931 ) ) ; +#15084 = EDGE_LOOP ( 'NONE', ( #10816, #27491, #18224, #18371 ) ) ; +#15085 = ORIENTED_EDGE ( 'NONE', *, *, #29534, .T. ) ; +#15086 = CARTESIAN_POINT ( 'NONE', ( 1.240445527565428030, 189.1176099620038826, 105.7708271182180653 ) ) ; +#15087 = DIRECTION ( 'NONE', ( -0.5968393679911998539, -0.8023607473050168304, 0.000000000000000000 ) ) ; +#15088 = EDGE_CURVE ( 'NONE', #8503, #39173, #10880, .T. ) ; +#15089 = VERTEX_POINT ( 'NONE', #37636 ) ; +#15090 = LINE ( 'NONE', #31430, #10185 ) ; +#15091 = VERTEX_POINT ( 'NONE', #40096 ) ; +#15092 = CARTESIAN_POINT ( 'NONE', ( -38.99718989648000189, 120.0910792986999951, 87.40634461756999940 ) ) ; +#15093 = EDGE_CURVE ( 'NONE', #22, #24364, #24886, .T. ) ; +#15094 = CARTESIAN_POINT ( 'NONE', ( -5.668456030792887290, 130.7409932062415976, 90.07973636940788253 ) ) ; +#15095 = EDGE_LOOP ( 'NONE', ( #14706, #996, #14501 ) ) ; +#15096 = DIRECTION ( 'NONE', ( 0.0005667561018013857546, 0.5299192634445675232, 0.8480479072657912676 ) ) ; +#15097 = DIRECTION ( 'NONE', ( -0.0005734119072324083549, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#15098 = CARTESIAN_POINT ( 'NONE', ( -38.11718854129877343, 118.8155790694493561, 90.29079743518840928 ) ) ; +#15099 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #6798, #34794 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15100 = CARTESIAN_POINT ( 'NONE', ( 13.47343164508975377, 158.6809479346725595, 96.79232023565108989 ) ) ; +#15101 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988409597765, 161.7142231050778207, 96.98759364909003011 ) ) ; +#15102 = ORIENTED_EDGE ( 'NONE', *, *, #20051, .F. ) ; +#15103 = ADVANCED_FACE ( 'NONE', ( #22111 ), #34542, .F. ) ; +#15104 = ORIENTED_EDGE ( 'NONE', *, *, #21242, .F. ) ; +#15105 = CARTESIAN_POINT ( 'NONE', ( -20.68769432855515333, 105.5805168951702342, 87.28027914095393669 ) ) ; +#15106 = VECTOR ( 'NONE', #38571, 1000.000000000000114 ) ; +#15107 = CARTESIAN_POINT ( 'NONE', ( -12.63633098392225662, 174.6781851931449410, 103.0702648796800673 ) ) ; +#15108 = CARTESIAN_POINT ( 'NONE', ( 37.51815168729829963, 191.4396200122112077, 104.3353197794647826 ) ) ; +#15109 = CIRCLE ( 'NONE', #25562, 2.499999999988871124 ) ; +#15110 = CIRCLE ( 'NONE', #13778, 2.499999999999997335 ) ; +#15111 = CARTESIAN_POINT ( 'NONE', ( -15.94527957999837575, 152.8243907355866611, 181.6127031347539003 ) ) ; +#15112 = ORIENTED_EDGE ( 'NONE', *, *, #36359, .T. ) ; +#15113 = ORIENTED_EDGE ( 'NONE', *, *, #39774, .T. ) ; +#15114 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; +#15115 = CARTESIAN_POINT ( 'NONE', ( 12.31198009898977297, 134.9205818654068025, 90.79431936396761671 ) ) ; +#15116 = CARTESIAN_POINT ( 'NONE', ( -3.668404233967317740, 183.5617789224675676, 104.5994755554405486 ) ) ; +#15117 = LINE ( 'NONE', #12048, #11189 ) ; +#15118 = FACE_OUTER_BOUND ( 'NONE', #30760, .T. ) ; +#15119 = CARTESIAN_POINT ( 'NONE', ( -36.36397650069000065, 191.9049264267000012, 104.5553411748999935 ) ) ; +#15120 = CARTESIAN_POINT ( 'NONE', ( 14.94976271106517807, 136.0909262678420077, 93.97082019938331143 ) ) ; +#15121 = CARTESIAN_POINT ( 'NONE', ( -30.84019928186018689, 183.3517191563202005, 102.0016297752730168 ) ) ; +#15122 = CARTESIAN_POINT ( 'NONE', ( 7.997218435461875607, 131.0225853275861141, 89.89707245289747561 ) ) ; +#15123 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35359, #7365, #4297, #4501 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15124 = CARTESIAN_POINT ( 'NONE', ( -25.77483565525809084, 209.7107308647096033, 73.30925164553990214 ) ) ; +#15125 = CARTESIAN_POINT ( 'NONE', ( -0.02845919973435177830, 93.66652340833722690, 291.5585611238757906 ) ) ; +#15126 = CARTESIAN_POINT ( 'NONE', ( 38.12236789434999906, 118.6347812900000065, 87.56703225248999445 ) ) ; +#15127 = APPROVAL_STATUS ( 'not_yet_approved' ) ; +#15128 = CARTESIAN_POINT ( 'NONE', ( 4.214178076569004894, 182.1297273395886975, 101.6983387179820397 ) ) ; +#15129 = DIRECTION ( 'NONE', ( -0.0005884949961176016596, 0.2249510543439068588, -0.9743698870671261281 ) ) ; +#15130 = FACE_OUTER_BOUND ( 'NONE', #32814, .T. ) ; +#15131 = CYLINDRICAL_SURFACE ( 'NONE', #5158, 2.250000000000011102 ) ; +#15133 = ORIENTED_EDGE ( 'NONE', *, *, #31800, .F. ) ; +#15132 = CARTESIAN_POINT ( 'NONE', ( 36.46428275574999844, 191.4173107530999971, 106.4736958616000067 ) ) ; +#15134 = ORIENTED_EDGE ( 'NONE', *, *, #40094, .T. ) ; +#15135 = ORIENTED_EDGE ( 'NONE', *, *, #29907, .T. ) ; +#15136 = CYLINDRICAL_SURFACE ( 'NONE', #4919, 6.000000000000011546 ) ; +#15137 = VECTOR ( 'NONE', #30243, 1000.000000000000227 ) ; +#15138 = ORIENTED_EDGE ( 'NONE', *, *, #35872, .F. ) ; +#15139 = CARTESIAN_POINT ( 'NONE', ( 24.53499378586817414, 109.6131156702000027, 90.25296631807577796 ) ) ; +#15140 = ADVANCED_FACE ( 'NONE', ( #9242 ), #37511, .F. ) ; +#15141 = EDGE_CURVE ( 'NONE', #38935, #4337, #10033, .T. ) ; +#15142 = DIRECTION ( 'NONE', ( 0.0005884936524312223746, -0.2249510543440256249, 0.9743698870679101676 ) ) ; +#15143 = FACE_OUTER_BOUND ( 'NONE', #2638, .T. ) ; +#15144 = ADVANCED_FACE ( 'NONE', ( #9845 ), #23184, .F. ) ; +#15145 = EDGE_CURVE ( 'NONE', #4337, #27040, #2248, .T. ) ; +#15146 = ORIENTED_EDGE ( 'NONE', *, *, #15228, .F. ) ; +#15147 = CARTESIAN_POINT ( 'NONE', ( 14.01595022200380924, 135.4465979594034764, 93.65157854464966647 ) ) ; +#15148 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#15149 = CARTESIAN_POINT ( 'NONE', ( -13.35978900763059762, 130.9435614395062260, 89.89169326634505808 ) ) ; +#15150 = VERTEX_POINT ( 'NONE', #14919 ) ; +#15151 = EDGE_CURVE ( 'NONE', #27940, #34917, #22913, .T. ) ; +#15152 = CARTESIAN_POINT ( 'NONE', ( -42.54327191201071656, 120.9996688098205340, 92.62994261980294652 ) ) ; +#15153 = CARTESIAN_POINT ( 'NONE', ( 23.36439212065845794, 176.8044416301941055, 103.1046897219861904 ) ) ; +#15154 = CARTESIAN_POINT ( 'NONE', ( 37.06791829841335328, 117.4340048322533079, 90.24539674539980183 ) ) ; +#15155 = DIRECTION ( 'NONE', ( -0.0005884949961218734161, 0.2249510543439056931, -0.9743698870671265722 ) ) ; +#15156 = EDGE_CURVE ( 'NONE', #36682, #38732, #8174, .T. ) ; +#15157 = ORIENTED_EDGE ( 'NONE', *, *, #28165, .T. ) ; +#15158 = CARTESIAN_POINT ( 'NONE', ( -27.61276218341999922, 188.2939806148000059, 103.0017547080000071 ) ) ; +#15159 = CARTESIAN_POINT ( 'NONE', ( 1.315675836357660389, 189.1541845523380232, 103.7399269907329966 ) ) ; +#15160 = CARTESIAN_POINT ( 'NONE', ( 23.68617299094906059, 127.9139236766033179, 92.24878420086326969 ) ) ; +#15161 = VERTEX_POINT ( 'NONE', #33505 ) ; +#15162 = EDGE_LOOP ( 'NONE', ( #30602, #19530 ) ) ; +#15163 = CONICAL_SURFACE ( 'NONE', #4684, 2.503115222802204443, 0.7853981633873898804 ) ; +#15164 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; +#15165 = ORIENTED_EDGE ( 'NONE', *, *, #1410, .T. ) ; +#15166 = AXIS2_PLACEMENT_3D ( 'NONE', #1160, #34685, #3818 ) ; +#15167 = ADVANCED_FACE ( 'NONE', ( #39235 ), #39035, .F. ) ; +#15168 = CIRCLE ( 'NONE', #37339, 6.000000251127745265 ) ; +#15169 = CARTESIAN_POINT ( 'NONE', ( -17.26174088632014403, 121.9765816702171009, 174.4814081256518534 ) ) ; +#15170 = CARTESIAN_POINT ( 'NONE', ( -37.98654602637000011, 191.4670132987999978, 104.1597717548000190 ) ) ; +#15171 = CARTESIAN_POINT ( 'NONE', ( -20.01830659250219213, 205.5538814942069052, 75.24804808645014020 ) ) ; +#15172 = CARTESIAN_POINT ( 'NONE', ( -37.18901461366416328, 191.0654016131968262, 106.3408188258918727 ) ) ; +#15173 = ORIENTED_EDGE ( 'NONE', *, *, #2954, .T. ) ; +#15174 = CARTESIAN_POINT ( 'NONE', ( -21.44693882331385026, 135.7861819143374760, 91.01458761472625270 ) ) ; +#15175 = CARTESIAN_POINT ( 'NONE', ( -25.50129497783076715, 118.5814613607333285, 87.78316531807180922 ) ) ; +#15176 = CARTESIAN_POINT ( 'NONE', ( -1.914441492903718123, 189.6526805815070986, 105.9269172079772829 ) ) ; +#15177 = ORIENTED_EDGE ( 'NONE', *, *, #22986, .F. ) ; +#15178 = FACE_BOUND ( 'NONE', #28753, .T. ) ; +#15179 = CARTESIAN_POINT ( 'NONE', ( -35.85878617516480205, 191.6073043381418870, 103.9089155225263283 ) ) ; +#15181 = CARTESIAN_POINT ( 'NONE', ( -32.65040898612480191, 153.0051697192221241, 291.5764532040477093 ) ) ; +#15180 = CARTESIAN_POINT ( 'NONE', ( -23.00157826576616671, 118.1131156702000169, 87.27825658246501916 ) ) ; +#15182 = EDGE_LOOP ( 'NONE', ( #24150, #27740, #3268, #3865 ) ) ; +#15183 = EDGE_LOOP ( 'NONE', ( #19233, #23201, #19199, #25202, #35961 ) ) ; +#15184 = EDGE_CURVE ( 'NONE', #27979, #26904, #32708, .T. ) ; +#15185 = AXIS2_PLACEMENT_3D ( 'NONE', #28171, #8957, #12405 ) ; +#15186 = EDGE_CURVE ( 'NONE', #13948, #35226, #38972, .T. ) ; +#15187 = VERTEX_POINT ( 'NONE', #15518 ) ; +#15189 = VECTOR ( 'NONE', #6564, 1000.000000000000000 ) ; +#15188 = FACE_OUTER_BOUND ( 'NONE', #27600, .T. ) ; +#15190 = AXIS2_PLACEMENT_3D ( 'NONE', #29949, #39538, #8487 ) ; +#15191 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265228896, -0.1368326740407719011 ) ) ; +#15192 = CARTESIAN_POINT ( 'NONE', ( 29.66018523879016300, 130.7316300977390711, 89.81678206544971488 ) ) ; +#15193 = CARTESIAN_POINT ( 'NONE', ( -12.63917946761317879, 135.0411934724452010, 91.00683831463108220 ) ) ; +#15194 = ORIENTED_EDGE ( 'NONE', *, *, #20847, .T. ) ; +#15195 = EDGE_CURVE ( 'NONE', #9411, #38443, #30666, .T. ) ; +#15196 = EDGE_LOOP ( 'NONE', ( #18703, #10326, #9049, #12453, #23267, #29104, #5030, #11136, #14078, #34649, #2375, #27475 ) ) ; +#15197 = CARTESIAN_POINT ( 'NONE', ( 35.56284489036890051, 193.8169247291054376, 102.6814306727405750 ) ) ; +#15198 = CARTESIAN_POINT ( 'NONE', ( 13.76537810311827847, 124.4276589313617905, 178.6661833187116883 ) ) ; +#15199 = ADVANCED_FACE ( 'NONE', ( #37195 ), #6105, .T. ) ; +#15200 = ORIENTED_EDGE ( 'NONE', *, *, #14592, .T. ) ; +#15201 = CARTESIAN_POINT ( 'NONE', ( -36.06506250534999936, 191.3439698402999909, 106.7337090868000047 ) ) ; +#15202 = FACE_OUTER_BOUND ( 'NONE', #34447, .T. ) ; +#15203 = CARTESIAN_POINT ( 'NONE', ( 3.199984518777000631, 190.8630714974999876, 106.9328794001999938 ) ) ; +#15204 = EDGE_LOOP ( 'NONE', ( #39323, #17827, #30012, #22529 ) ) ; +#15205 = CARTESIAN_POINT ( 'NONE', ( 0.5641564930821999502, 188.3875164193000273, 106.2241891016000039 ) ) ; +#15206 = CARTESIAN_POINT ( 'NONE', ( 5.667442478653145876, 130.8359915337342727, 90.01481240614560875 ) ) ; +#15207 = EDGE_CURVE ( 'NONE', #31175, #36214, #15316, .T. ) ; +#15208 = CARTESIAN_POINT ( 'NONE', ( -46.35684242861079696, 110.7105035214231776, 151.9824889214679615 ) ) ; +#15209 = FACE_OUTER_BOUND ( 'NONE', #2996, .T. ) ; +#15210 = VECTOR ( 'NONE', #32555, 1000.000000000000114 ) ; +#15211 = ORIENTED_EDGE ( 'NONE', *, *, #20092, .F. ) ; +#15212 = VECTOR ( 'NONE', #24033, 1000.000000000000227 ) ; +#15213 = CARTESIAN_POINT ( 'NONE', ( -36.09769066460763298, 187.5602729729505711, 106.0553394373776115 ) ) ; +#15214 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391913256 ) ) ; +#15215 = CIRCLE ( 'NONE', #32175, 5.999999999651004501 ) ; +#15216 = ORIENTED_EDGE ( 'NONE', *, *, #35532, .T. ) ; +#15217 = CARTESIAN_POINT ( 'NONE', ( 30.17614589098232258, 126.7625099796061932, 88.90012650384656467 ) ) ; +#15218 = VERTEX_POINT ( 'NONE', #9389 ) ; +#15220 = CARTESIAN_POINT ( 'NONE', ( -44.88822238842725199, 179.5780855356435950, 137.0595526267623825 ) ) ; +#15219 = CARTESIAN_POINT ( 'NONE', ( -39.68697719330157270, 104.2905048274910058, 197.1740080326743794 ) ) ; +#15221 = ORIENTED_EDGE ( 'NONE', *, *, #37488, .T. ) ; +#15222 = ORIENTED_EDGE ( 'NONE', *, *, #170, .F. ) ; +#15223 = ORIENTED_EDGE ( 'NONE', *, *, #20245, .F. ) ; +#15224 = CARTESIAN_POINT ( 'NONE', ( 3.146407946422999924, 209.5134149454999886, 76.20363659513000698 ) ) ; +#15225 = CARTESIAN_POINT ( 'NONE', ( 2.564210731195382120, 191.0000001071945235, 106.3128016873806274 ) ) ; +#15226 = DIRECTION ( 'NONE', ( -2.530387804365254516E-14, -0.9743700557921585181, -0.2249510932971561239 ) ) ; +#15227 = DIRECTION ( 'NONE', ( -0.0005884949961254435855, 0.2249510543439056098, -0.9743698870671265722 ) ) ; +#15228 = EDGE_CURVE ( 'NONE', #31532, #8723, #6495, .T. ) ; +#15229 = VERTEX_POINT ( 'NONE', #33910 ) ; +#15230 = EDGE_CURVE ( 'NONE', #15773, #8079, #24540, .T. ) ; +#15231 = VERTEX_POINT ( 'NONE', #24744 ) ; +#15232 = ORIENTED_EDGE ( 'NONE', *, *, #13249, .F. ) ; +#15233 = VERTEX_POINT ( 'NONE', #28007 ) ; +#15234 = DIRECTION ( 'NONE', ( 0.0004270283471111629785, -0.7071067811866028618, 0.7071066522432896129 ) ) ; +#15235 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.110223024625155594E-14, -1.000000000000000000 ) ) ; +#15236 = CARTESIAN_POINT ( 'NONE', ( 8.046776635720599202, 151.4387294071806593, 94.61044745561473235 ) ) ; +#15237 = LINE ( 'NONE', #34419, #35879 ) ; +#15238 = AXIS2_PLACEMENT_3D ( 'NONE', #14718, #26581, #5083 ) ; +#15239 = ORIENTED_EDGE ( 'NONE', *, *, #33775, .F. ) ; +#15240 = ORIENTED_EDGE ( 'NONE', *, *, #38927, .T. ) ; +#15241 = CYLINDRICAL_SURFACE ( 'NONE', #12831, 10.00000000000000533 ) ; +#15242 = ADVANCED_FACE ( 'NONE', ( #176 ), #6943, .F. ) ; +#15243 = CYLINDRICAL_SURFACE ( 'NONE', #2200, 2.000000000000011546 ) ; +#15244 = DIRECTION ( 'NONE', ( 0.0005884981308560151671, -0.2249510543434312670, 0.9743698870653425548 ) ) ; +#15245 = AXIS2_PLACEMENT_3D ( 'NONE', #3993, #25908, #10559 ) ; +#15246 = VERTEX_POINT ( 'NONE', #21260 ) ; +#15247 = CARTESIAN_POINT ( 'NONE', ( -20.50037936456179821, 118.1134456052949560, 87.78011095654957785 ) ) ; +#15248 = ORIENTED_EDGE ( 'NONE', *, *, #22302, .F. ) ; +#15249 = VECTOR ( 'NONE', #39960, 1000.000000000000000 ) ; +#15250 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971571509 ) ) ; +#15251 = CARTESIAN_POINT ( 'NONE', ( -40.85601813336936061, 189.7480745836568303, 106.8731605699205574 ) ) ; +#15252 = VERTEX_POINT ( 'NONE', #5910 ) ; +#15253 = CARTESIAN_POINT ( 'NONE', ( -36.48898135731426606, 115.4643415116839975, 89.74914836252970929 ) ) ; +#15254 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20636, #4274, #20217, #35949 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15255 = CARTESIAN_POINT ( 'NONE', ( 46.37626369660664949, 72.18299133667814260, 291.5305338340516528 ) ) ; +#15256 = CARTESIAN_POINT ( 'NONE', ( -32.68154407215684643, 153.2594451684146293, 291.5782827689202463 ) ) ; +#15257 = CARTESIAN_POINT ( 'NONE', ( -37.54908091477015120, 212.5463744629944074, 73.41451618045002192 ) ) ; +#15258 = CARTESIAN_POINT ( 'NONE', ( -13.50000077688951450, 188.3420892684051751, 103.1432776901117307 ) ) ; +#15259 = ORIENTED_EDGE ( 'NONE', *, *, #3394, .F. ) ; +#15260 = CARTESIAN_POINT ( 'NONE', ( 21.98718844691312668, 129.2990422925554981, 92.22748880099159408 ) ) ; +#15261 = CARTESIAN_POINT ( 'NONE', ( -25.90158191252999842, 191.3557575943999893, 103.9673941423999963 ) ) ; +#15262 = DIRECTION ( 'NONE', ( -0.0006039748319382906789, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#15263 = FACE_OUTER_BOUND ( 'NONE', #6166, .T. ) ; +#15264 = DIRECTION ( 'NONE', ( -0.7075227810178683630, 0.1590644155802670434, -0.6885564799178420792 ) ) ; +#15265 = ORIENTED_EDGE ( 'NONE', *, *, #18131, .F. ) ; +#15266 = AXIS2_PLACEMENT_3D ( 'NONE', #14519, #33307, #27209 ) ; +#15267 = CARTESIAN_POINT ( 'NONE', ( 9.995029200524999879, 159.1892556871999886, 28.07991271570000080 ) ) ; +#15268 = ORIENTED_EDGE ( 'NONE', *, *, #37880, .T. ) ; +#15270 = ADVANCED_FACE ( 'NONE', ( #34305 ), #6299, .T. ) ; +#15269 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25281, #13001, #22611, #25484, #32011, #13594, #13202, #16644, #37935, #3971, #16444 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998275824, 0.3749999999997819522, 0.4374999999998048228, 0.4687499999997975508, 0.4999999999997902789, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15271 = CIRCLE ( 'NONE', #31587, 5.499999999543050855 ) ; +#15272 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#15273 = EDGE_CURVE ( 'NONE', #7173, #2217, #10240, .T. ) ; +#15274 = AXIS2_PLACEMENT_3D ( 'NONE', #19992, #31894, #13875 ) ; +#15275 = ORIENTED_EDGE ( 'NONE', *, *, #25439, .T. ) ; +#15276 = LINE ( 'NONE', #14876, #32306 ) ; +#15277 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555133 ) ) ; +#15278 = CARTESIAN_POINT ( 'NONE', ( -36.26459936063917411, 164.9566154569169782, 193.1834482597365366 ) ) ; +#15279 = DIRECTION ( 'NONE', ( -0.0003759422414365064615, 0.7826081567317987320, -0.6225145232717768096 ) ) ; +#15280 = EDGE_CURVE ( 'NONE', #16409, #4989, #40240, .T. ) ; +#15281 = DIRECTION ( 'NONE', ( -0.7933533411653052037, 0.5930537057989929695, 0.1373964268091736607 ) ) ; +#15282 = EDGE_CURVE ( 'NONE', #10977, #19860, #24381, .T. ) ; +#15283 = LINE ( 'NONE', #27970, #16058 ) ; +#15284 = VERTEX_POINT ( 'NONE', #37586 ) ; +#15285 = ADVANCED_FACE ( 'NONE', ( #34492 ), #27423, .T. ) ; +#15286 = CARTESIAN_POINT ( 'NONE', ( -20.50037936456179821, 118.1134456052949560, 87.78011095654957785 ) ) ; +#15287 = CARTESIAN_POINT ( 'NONE', ( -25.98970595316612631, 191.9759150222000130, 106.9371460002143692 ) ) ; +#15288 = VERTEX_POINT ( 'NONE', #27815 ) ; +#15289 = CARTESIAN_POINT ( 'NONE', ( 19.98170452206136005, 205.5539062507874917, 75.22380842103150655 ) ) ; +#15290 = ORIENTED_EDGE ( 'NONE', *, *, #15628, .T. ) ; +#15291 = CARTESIAN_POINT ( 'NONE', ( -26.00831778363330571, 205.1071295951813340, 76.12055741644476825 ) ) ; +#15292 = CARTESIAN_POINT ( 'NONE', ( -3.535851989103623971, 143.5328828484186943, 95.87118806634899215 ) ) ; +#15293 = ORIENTED_EDGE ( 'NONE', *, *, #14301, .T. ) ; +#15294 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; +#15295 = VECTOR ( 'NONE', #37874, 1000.000000000000227 ) ; +#15296 = AXIS2_PLACEMENT_3D ( 'NONE', #23874, #39593, #30408 ) ; +#15297 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 82.27946979429611929, 297.5967072516832559 ) ) ; +#15298 = CARTESIAN_POINT ( 'NONE', ( -26.12594029382999850, 191.4284810197000013, 107.0434483078000056 ) ) ; +#15299 = VECTOR ( 'NONE', #17574, 1000.000000000000227 ) ; +#15300 = CARTESIAN_POINT ( 'NONE', ( -24.01451938906670946, 115.2897724545006071, 90.28228900716538874 ) ) ; +#15301 = CARTESIAN_POINT ( 'NONE', ( 3.166264962546063710, 126.6495829448442407, 88.89036871524665173 ) ) ; +#15302 = ORIENTED_EDGE ( 'NONE', *, *, #22796, .F. ) ; +#15303 = CARTESIAN_POINT ( 'NONE', ( -41.93243227727202793, 132.0857236358559135, 291.5838700735885709 ) ) ; +#15304 = VECTOR ( 'NONE', #18241, 1000.000000000000000 ) ; +#15305 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989940797, 0.1373964268091564245 ) ) ; +#15306 = CARTESIAN_POINT ( 'NONE', ( 30.07038801303579234, 134.2481741983066854, 93.70730552177415973 ) ) ; +#15307 = CARTESIAN_POINT ( 'NONE', ( -46.23837296033245536, 124.7988103812620579, 91.22973473997339511 ) ) ; +#15308 = ORIENTED_EDGE ( 'NONE', *, *, #6673, .F. ) ; +#15309 = FACE_OUTER_BOUND ( 'NONE', #5948, .T. ) ; +#15310 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825947466614054, 0.0005734119017560097235 ) ) ; +#15311 = CARTESIAN_POINT ( 'NONE', ( 22.99138912207082441, 214.0899462551063266, 73.04463992848049259 ) ) ; +#15312 = CARTESIAN_POINT ( 'NONE', ( -27.14319524275719786, 187.2717417431980209, 105.4684560175520005 ) ) ; +#15313 = CIRCLE ( 'NONE', #36198, 5.499999999997797318 ) ; +#15314 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#15315 = ADVANCED_FACE ( 'NONE', ( #36788 ), #8791, .T. ) ; +#15316 = LINE ( 'NONE', #18557, #4315 ) ; +#15317 = AXIS2_PLACEMENT_3D ( 'NONE', #19797, #38810, #39226 ) ; +#15318 = AXIS2_PLACEMENT_3D ( 'NONE', #28869, #14953, #11476 ) ; +#15319 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971538202 ) ) ; +#15320 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700558022311276, -0.2249510932535267183 ) ) ; +#15321 = DIRECTION ( 'NONE', ( -0.6185863125140933505, -0.7857168535612664151, 0.000000000000000000 ) ) ; +#15322 = CARTESIAN_POINT ( 'NONE', ( 37.68865679123659618, 190.9605833865500415, 106.2965747328459969 ) ) ; +#15323 = AXIS2_PLACEMENT_3D ( 'NONE', #39645, #36174, #30465 ) ; +#15324 = ADVANCED_FACE ( 'NONE', ( #26683 ), #3039, .T. ) ; +#15325 = ADVANCED_FACE ( 'NONE', ( #22470 ), #25945, .F. ) ; +#15326 = ORIENTED_EDGE ( 'NONE', *, *, #14023, .T. ) ; +#15327 = CARTESIAN_POINT ( 'NONE', ( 36.64645721461000250, 191.6442232212000079, 106.2387314096999944 ) ) ; +#15328 = ORIENTED_EDGE ( 'NONE', *, *, #33032, .T. ) ; +#15329 = ORIENTED_EDGE ( 'NONE', *, *, #11343, .F. ) ; +#15330 = EDGE_CURVE ( 'NONE', #14524, #35793, #37782, .T. ) ; +#15331 = CARTESIAN_POINT ( 'NONE', ( -4.804068707279816053, 135.2091091625680406, 90.87130529227184184 ) ) ; +#15332 = ADVANCED_FACE ( 'NONE', ( #771 ), #3703, .T. ) ; +#15333 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971557076 ) ) ; +#15334 = DIRECTION ( 'NONE', ( -0.7933533411653069800, 0.5930537057989943017, 0.1373964268091564522 ) ) ; +#15335 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178582671909E-05, -0.0002331579774919533509 ) ) ; +#15336 = ORIENTED_EDGE ( 'NONE', *, *, #7917, .F. ) ; +#15337 = CARTESIAN_POINT ( 'NONE', ( 40.87847416758199870, 217.7719116157724670, 73.36714790239413730 ) ) ; +#15338 = CARTESIAN_POINT ( 'NONE', ( -28.70875734540877389, 163.5999644878620245, 97.95344188170561495 ) ) ; +#15339 = LINE ( 'NONE', #2680, #11193 ) ; +#15340 = FACE_OUTER_BOUND ( 'NONE', #19920, .T. ) ; +#15341 = ORIENTED_EDGE ( 'NONE', *, *, #19374, .F. ) ; +#15342 = LINE ( 'NONE', #8814, #16664 ) ; +#15343 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15564, #27264, #24397, #33962 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15344 = CARTESIAN_POINT ( 'NONE', ( 23.37116632637657077, 177.1196686977561399, 103.6090577849978445 ) ) ; +#15345 = CARTESIAN_POINT ( 'NONE', ( 0.5626164669235433902, 188.9999987160578598, 103.6843922204118940 ) ) ; +#15346 = CARTESIAN_POINT ( 'NONE', ( -43.30038974941377461, 190.4174923657541285, 106.7193308803196601 ) ) ; +#15347 = CARTESIAN_POINT ( 'NONE', ( -21.17491851070888131, 213.4894134887179575, 76.07132462503170700 ) ) ; +#15348 = AXIS2_PLACEMENT_3D ( 'NONE', #23658, #36104, #33043 ) ; +#15349 = ORIENTED_EDGE ( 'NONE', *, *, #21375, .T. ) ; +#15350 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825936697426862, 0.0005734119020020883800 ) ) ; +#15351 = CARTESIAN_POINT ( 'NONE', ( 1.767930770475999891, 189.4068743987000119, 103.8090290509999960 ) ) ; +#15352 = AXIS2_PLACEMENT_3D ( 'NONE', #40432, #13046, #35085 ) ; +#15353 = CIRCLE ( 'NONE', #6835, 1.749999999975493381 ) ; +#15354 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; +#15355 = CIRCLE ( 'NONE', #36233, 2.000000002746800565 ) ; +#15356 = EDGE_LOOP ( 'NONE', ( #2726, #1672, #20467, #8798 ) ) ; +#15357 = CARTESIAN_POINT ( 'NONE', ( 23.72254622402000024, 115.9590670144843330, 152.9217693939943388 ) ) ; +#15358 = VERTEX_POINT ( 'NONE', #16306 ) ; +#15359 = CARTESIAN_POINT ( 'NONE', ( -16.56450047176163309, 122.2697573860770319, 175.5880185216135203 ) ) ; +#15360 = EDGE_CURVE ( 'NONE', #32435, #18851, #19380, .T. ) ; +#15361 = DIRECTION ( 'NONE', ( 1.227022876780779975E-15, 0.9743700557917523986, 0.2249510932989154111 ) ) ; +#15362 = EDGE_CURVE ( 'NONE', #33884, #20941, #17041, .T. ) ; +#15363 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#15364 = CARTESIAN_POINT ( 'NONE', ( -35.93226012891999943, 192.4368824471000039, 104.9893856757999941 ) ) ; +#15365 = LINE ( 'NONE', #5130, #30015 ) ; +#15366 = CYLINDRICAL_SURFACE ( 'NONE', #27890, 2.000000000000011546 ) ; +#15367 = EDGE_CURVE ( 'NONE', #21152, #26196, #38194, .T. ) ; +#15368 = CARTESIAN_POINT ( 'NONE', ( -25.50131619893729962, 118.3473562840666773, 87.78314412258384891 ) ) ; +#15369 = DIRECTION ( 'NONE', ( -0.6087614810001786836, 0.7729390313185912076, 0.1788147452386050495 ) ) ; +#15370 = ORIENTED_EDGE ( 'NONE', *, *, #32934, .T. ) ; +#15371 = EDGE_CURVE ( 'NONE', #28855, #29199, #19460, .T. ) ; +#15372 = DIRECTION ( 'NONE', ( -0.0006039748319389028194, -1.385776189666588672E-14, -0.9999998176071847045 ) ) ; +#15373 = CARTESIAN_POINT ( 'NONE', ( 3.062676760987444347, 191.1124749746885811, 103.7728652716954514 ) ) ; +#15374 = DIRECTION ( 'NONE', ( 0.7933530821293330870, 0.5932640870757638352, 0.1364866662427067223 ) ) ; +#15376 = CARTESIAN_POINT ( 'NONE', ( 16.22208376845709310, 122.1533376337188628, 174.2257921326907422 ) ) ; +#15375 = CARTESIAN_POINT ( 'NONE', ( -25.50129508846853099, 118.1132512059233335, 87.78307593003776788 ) ) ; +#15377 = ORIENTED_EDGE ( 'NONE', *, *, #11530, .T. ) ; +#15378 = EDGE_CURVE ( 'NONE', #24997, #24826, #8060, .T. ) ; +#15379 = AXIS2_PLACEMENT_3D ( 'NONE', #10470, #16567, #29063 ) ; +#15380 = AXIS2_PLACEMENT_3D ( 'NONE', #14603, #1299, #26270 ) ; +#15381 = VERTEX_POINT ( 'NONE', #39136 ) ; +#15382 = CONICAL_SURFACE ( 'NONE', #22566, 47.99999999995237232, 0.7853981633972918486 ) ; +#15383 = CIRCLE ( 'NONE', #38227, 1.999999999955081931 ) ; +#15384 = EDGE_LOOP ( 'NONE', ( #37929, #26311, #26813, #30714 ) ) ; +#15385 = CARTESIAN_POINT ( 'NONE', ( 25.49934386937603392, 120.6644425437606287, 88.00825483662825377 ) ) ; +#15386 = CARTESIAN_POINT ( 'NONE', ( 13.47241245321180259, 158.0311791718573886, 98.86596480645644647 ) ) ; +#15387 = CARTESIAN_POINT ( 'NONE', ( -25.74963657374999926, 201.9934155195000187, 90.49394230229999891 ) ) ; +#15388 = DIRECTION ( 'NONE', ( 0.0005884949671858177161, -0.2249510543353067105, 0.9743698870691290814 ) ) ; +#15389 = LINE ( 'NONE', #37063, #38654 ) ; +#15390 = ORIENTED_EDGE ( 'NONE', *, *, #19791, .F. ) ; +#15391 = ORIENTED_EDGE ( 'NONE', *, *, #28657, .T. ) ; +#15392 = CARTESIAN_POINT ( 'NONE', ( 37.78687090636931600, 218.5902260770998282, 61.03567957051413373 ) ) ; +#15393 = PLANE ( 'NONE', #37334 ) ; +#15394 = ORIENTED_EDGE ( 'NONE', *, *, #13197, .T. ) ; +#15395 = CARTESIAN_POINT ( 'NONE', ( -36.51612232699000060, 191.1898310933999880, 106.5271947874000062 ) ) ; +#15396 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319389474885 ) ) ; +#15397 = CARTESIAN_POINT ( 'NONE', ( 15.95613733389899025, 121.8961617987971238, 174.4891947115541484 ) ) ; +#15398 = CONICAL_SURFACE ( 'NONE', #29849, 2.249999999963673503, 0.7853981633778843729 ) ; +#15399 = ORIENTED_EDGE ( 'NONE', *, *, #37158, .F. ) ; +#15400 = CARTESIAN_POINT ( 'NONE', ( 2.951980948709000074, 190.0921062097999936, 106.6158610948999979 ) ) ; +#15401 = AXIS2_PLACEMENT_3D ( 'NONE', #30920, #32, #12702 ) ; +#15402 = CARTESIAN_POINT ( 'NONE', ( 5.667875642759740984, 130.6721462434133230, 90.11719410458975688 ) ) ; +#15403 = AXIS2_PLACEMENT_3D ( 'NONE', #14869, #27151, #23866 ) ; +#15404 = LINE ( 'NONE', #15208, #12782 ) ; +#15405 = CARTESIAN_POINT ( 'NONE', ( -34.95487766943185193, 220.4002260771000294, 76.07961650006694754 ) ) ; +#15406 = CARTESIAN_POINT ( 'NONE', ( 3.535080169976978492, 144.6901993477816006, 93.05515119550676673 ) ) ; +#15407 = ADVANCED_FACE ( 'NONE', ( #1514 ), #8306, .F. ) ; +#15408 = AXIS2_PLACEMENT_3D ( 'NONE', #36803, #5921, #15334 ) ; +#15409 = EDGE_CURVE ( 'NONE', #37526, #16610, #1905, .T. ) ; +#15410 = EDGE_LOOP ( 'NONE', ( #39217, #21716, #37313, #16142 ) ) ; +#15411 = ADVANCED_FACE ( 'NONE', ( #36057 ), #20525, .T. ) ; +#15412 = EDGE_CURVE ( 'NONE', #20537, #33399, #30502, .T. ) ; +#15413 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999904787, 179.7376864901910949, 101.1595092801111377 ) ) ; +#15414 = CARTESIAN_POINT ( 'NONE', ( -20.41767204683837633, 127.1614620270025426, 91.67148453719821077 ) ) ; +#15415 = ORIENTED_EDGE ( 'NONE', *, *, #29519, .F. ) ; +#15416 = ADVANCED_FACE ( 'NONE', ( #26479 ), #2144, .T. ) ; +#15417 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3779, #16253, #35041, #7051 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15418 = CARTESIAN_POINT ( 'NONE', ( -5.669412827410644340, 187.7434695915656562, 103.5134950631828588 ) ) ; +#15419 = EDGE_LOOP ( 'NONE', ( #11559, #31376, #1444, #26570, #26908 ) ) ; +#15421 = DIRECTION ( 'NONE', ( -1.249000902695084964E-14, 0.9743700557921582961, 0.2249510932971567345 ) ) ; +#15420 = CARTESIAN_POINT ( 'NONE', ( 1.447658031000570666, 152.0519508845351595, 130.6788418773748219 ) ) ; +#15422 = ORIENTED_EDGE ( 'NONE', *, *, #37797, .T. ) ; +#15423 = EDGE_CURVE ( 'NONE', #25840, #8707, #37965, .T. ) ; +#15424 = EDGE_LOOP ( 'NONE', ( #18489, #38959, #10547, #710 ) ) ; +#15425 = CARTESIAN_POINT ( 'NONE', ( 25.49226348177107582, 205.5673819639667954, 76.28481786455526503 ) ) ; +#15426 = ORIENTED_EDGE ( 'NONE', *, *, #10299, .T. ) ; +#15427 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825916136676223, 0.0005734119024715054200 ) ) ; +#15428 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#15429 = ORIENTED_EDGE ( 'NONE', *, *, #13782, .T. ) ; +#15430 = AXIS2_PLACEMENT_3D ( 'NONE', #36591, #2052, #5502 ) ; +#15431 = ORIENTED_EDGE ( 'NONE', *, *, #27, .T. ) ; +#15432 = CIRCLE ( 'NONE', #20647, 2.499999999987245314 ) ; +#15433 = ORIENTED_EDGE ( 'NONE', *, *, #13023, .F. ) ; +#15434 = FACE_OUTER_BOUND ( 'NONE', #33649, .T. ) ; +#15435 = CARTESIAN_POINT ( 'NONE', ( 30.44899542203640408, 126.4319227165660635, 91.90255272003975051 ) ) ; +#15436 = CARTESIAN_POINT ( 'NONE', ( 13.50222385217858267, 187.3269060524752661, 105.5005337516834629 ) ) ; +#15437 = LINE ( 'NONE', #27931, #14371 ) ; +#15438 = VECTOR ( 'NONE', #25552, 1000.000000000000000 ) ; +#15439 = ORIENTED_EDGE ( 'NONE', *, *, #8357, .T. ) ; +#15440 = VERTEX_POINT ( 'NONE', #15219 ) ; +#15441 = CARTESIAN_POINT ( 'NONE', ( -5.669971430217174202, 123.9176819113750554, 91.14983607065533988 ) ) ; +#15442 = CIRCLE ( 'NONE', #20656, 47.49999999999543832 ) ; +#15443 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#15444 = DIRECTION ( 'NONE', ( -0.0004225984971752187952, 0.2247404086396479206, -0.9744185805571413672 ) ) ; +#15445 = CARTESIAN_POINT ( 'NONE', ( -28.44201500224999890, 125.3783906434000102, 88.78702912938001646 ) ) ; +#15446 = ORIENTED_EDGE ( 'NONE', *, *, #27956, .T. ) ; +#15447 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825822545, 158.2317141435470376, 98.73576230545255328 ) ) ; +#15448 = CARTESIAN_POINT ( 'NONE', ( -5.668571547462038396, 124.2905521228788785, 90.91684019217574075 ) ) ; +#15449 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#15450 = ORIENTED_EDGE ( 'NONE', *, *, #20147, .F. ) ; +#15451 = CARTESIAN_POINT ( 'NONE', ( 13.53825347476000118, 113.1227133813000023, 152.4718672074000381 ) ) ; +#15452 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930881478 ) ) ; +#15453 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -6.071530832037190021E-16, -0.0006039748319384735838 ) ) ; +#15454 = DIRECTION ( 'NONE', ( 0.5989082241854611910, -0.8008175873178838833, -0.0003617255600150170222 ) ) ; +#15455 = AXIS2_PLACEMENT_3D ( 'NONE', #33707, #5713, #2663 ) ; +#15456 = ORIENTED_EDGE ( 'NONE', *, *, #34677, .F. ) ; +#15457 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; +#15458 = EDGE_LOOP ( 'NONE', ( #27130, #19119, #38694, #9644 ) ) ; +#15459 = EDGE_CURVE ( 'NONE', #20244, #8209, #5808, .T. ) ; +#15460 = CARTESIAN_POINT ( 'NONE', ( 35.27885543649455258, 77.14301703111104302, 291.5372363905759130 ) ) ; +#15461 = AXIS2_PLACEMENT_3D ( 'NONE', #2357, #39749, #22531 ) ; +#15462 = LINE ( 'NONE', #5652, #5528 ) ; +#15463 = AXIS2_PLACEMENT_3D ( 'NONE', #4688, #4890, #7959 ) ; +#15464 = CARTESIAN_POINT ( 'NONE', ( 25.82535974979346705, 209.7094246239551012, 75.87624978972131373 ) ) ; +#15465 = CARTESIAN_POINT ( 'NONE', ( -35.81474217949671868, 108.6541353822862703, 168.9015064287443977 ) ) ; +#15466 = CARTESIAN_POINT ( 'NONE', ( 92.50187971282166188, 221.8453154663451699, 201.2060978135920379 ) ) ; +#15467 = ORIENTED_EDGE ( 'NONE', *, *, #26244, .F. ) ; +#15468 = AXIS2_PLACEMENT_3D ( 'NONE', #3842, #3439, #28412 ) ; +#15469 = CARTESIAN_POINT ( 'NONE', ( -38.01808904093999786, 118.9131641596000009, 90.45269863391999365 ) ) ; +#15470 = VERTEX_POINT ( 'NONE', #17654 ) ; +#15471 = CARTESIAN_POINT ( 'NONE', ( -5.668107805537519361, 126.1261160540004767, 91.85696217430825072 ) ) ; +#15472 = FACE_OUTER_BOUND ( 'NONE', #6660, .T. ) ; +#15473 = CARTESIAN_POINT ( 'NONE', ( 42.83487131658635860, 120.7910107177264081, 92.64688251868899727 ) ) ; +#15474 = CARTESIAN_POINT ( 'NONE', ( -22.50072399476195528, 158.3009599602069954, 96.21317557253242114 ) ) ; +#15475 = CARTESIAN_POINT ( 'NONE', ( 17.27193883265227825, 122.1565372283859290, 173.7595026853086324 ) ) ; +#15476 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6283, #18950, #18738, #31448, #31235, #12842, #3215 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 4 ), + ( 0.000000000000000000, 0.0002542678779985293731, 0.0005089035069198654618 ), + .UNSPECIFIED. ) ; +#15477 = CARTESIAN_POINT ( 'NONE', ( -37.09480771575991298, 117.6307073562036578, 90.29018917355014651 ) ) ; +#15478 = ORIENTED_EDGE ( 'NONE', *, *, #33140, .F. ) ; +#15479 = CARTESIAN_POINT ( 'NONE', ( -19.70055405364098533, 149.1723619494412389, 182.9474843209757751 ) ) ; +#15480 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971578725 ) ) ; +#15481 = EDGE_CURVE ( 'NONE', #11452, #25074, #14822, .T. ) ; +#15482 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#15483 = ORIENTED_EDGE ( 'NONE', *, *, #33577, .T. ) ; +#15484 = DIRECTION ( 'NONE', ( 0.0005884949961259295249, -0.2249510543438812127, 0.9743698870671321233 ) ) ; +#15485 = FACE_OUTER_BOUND ( 'NONE', #39577, .T. ) ; +#15486 = AXIS2_PLACEMENT_3D ( 'NONE', #13077, #16512, #26159 ) ; +#15487 = ORIENTED_EDGE ( 'NONE', *, *, #27905, .T. ) ; +#15488 = FACE_OUTER_BOUND ( 'NONE', #17124, .T. ) ; +#15489 = AXIS2_PLACEMENT_3D ( 'NONE', #19069, #15608, #15803 ) ; +#15490 = CARTESIAN_POINT ( 'NONE', ( -20.00111603559079398, 118.1131148921541438, 87.27965578728156970 ) ) ; +#15491 = CARTESIAN_POINT ( 'NONE', ( -3.738963458913685756, 143.5821509023425904, 95.67443424898375781 ) ) ; +#15492 = DIRECTION ( 'NONE', ( 0.6087614115774879764, 0.7729348350621345620, 0.1788331191967953704 ) ) ; +#15493 = ORIENTED_EDGE ( 'NONE', *, *, #6525, .F. ) ; +#15494 = CARTESIAN_POINT ( 'NONE', ( 37.96340688161021149, 191.0388337556233864, 103.7347927322450261 ) ) ; +#15495 = CARTESIAN_POINT ( 'NONE', ( 19.46094516130095542, 125.6747539604571813, 178.4426934156100231 ) ) ; +#15496 = CARTESIAN_POINT ( 'NONE', ( 16.19205324837119164, 122.0564273762022793, 174.6239568424747404 ) ) ; +#15497 = FACE_OUTER_BOUND ( 'NONE', #3095, .T. ) ; +#15498 = DIRECTION ( 'NONE', ( 1.982541115402070435E-15, 0.9743700557921585181, 0.2249510932971559851 ) ) ; +#15499 = ORIENTED_EDGE ( 'NONE', *, *, #11385, .T. ) ; +#15500 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555965 ) ) ; +#15501 = DIRECTION ( 'NONE', ( 0.6772915400549810450, 0.7357147339627989613, 0.000000000000000000 ) ) ; +#15502 = CARTESIAN_POINT ( 'NONE', ( 21.32710341636608220, 124.0031502495809121, 174.3449744221197761 ) ) ; +#15503 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27856, #34153, #6945, #19205, #25183, #34532, #22105, #3673, #16536, #34345 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15504 = CARTESIAN_POINT ( 'NONE', ( 76.10689632611000377, 156.0201458301999935, 97.16650080654000021 ) ) ; +#15505 = VERTEX_POINT ( 'NONE', #18264 ) ; +#15506 = EDGE_CURVE ( 'NONE', #31792, #22006, #36382, .T. ) ; +#15507 = ORIENTED_EDGE ( 'NONE', *, *, #27633, .T. ) ; +#15508 = CARTESIAN_POINT ( 'NONE', ( 30.44722912908971679, 185.6116624766144696, 102.4863628258041501 ) ) ; +#15509 = ADVANCED_FACE ( 'NONE', ( #39733 ), #18720, .F. ) ; +#15510 = CARTESIAN_POINT ( 'NONE', ( -41.91025164549390780, 121.8985265256900590, 90.89963868520955259 ) ) ; +#15511 = CARTESIAN_POINT ( 'NONE', ( 24.42207296340776779, 213.7301733865842266, 73.04375376229047845 ) ) ; +#15512 = CARTESIAN_POINT ( 'NONE', ( -36.05664063452000079, 191.5958398806000389, 104.0134324235999941 ) ) ; +#15513 = ORIENTED_EDGE ( 'NONE', *, *, #5968, .F. ) ; +#15514 = CARTESIAN_POINT ( 'NONE', ( -25.54062333385549621, 190.4808759212580185, 106.2083752500079896 ) ) ; +#15515 = EDGE_CURVE ( 'NONE', #5601, #14392, #17445, .T. ) ; +#15516 = AXIS2_PLACEMENT_3D ( 'NONE', #37050, #31877, #40302 ) ; +#15517 = CARTESIAN_POINT ( 'NONE', ( -19.70070278794882057, 149.4222755489676047, 181.8632635963006408 ) ) ; +#15518 = CARTESIAN_POINT ( 'NONE', ( -20.49970533410106910, 151.8550384231813553, 95.23695349207935124 ) ) ; +#15519 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -1.676366911644155200E-18, -0.0006039748319336982153 ) ) ; +#15520 = CARTESIAN_POINT ( 'NONE', ( 37.42082352723856076, 132.6200669550715929, 336.9739440566017379 ) ) ; +#15521 = CARTESIAN_POINT ( 'NONE', ( 38.08026479933000275, 190.5116989059000048, 106.5670812404000003 ) ) ; +#15522 = CARTESIAN_POINT ( 'NONE', ( 36.18932080103540017, 192.0081794014270145, 104.3591424689070095 ) ) ; +#15524 = ORIENTED_EDGE ( 'NONE', *, *, #34590, .T. ) ; +#15523 = CARTESIAN_POINT ( 'NONE', ( 36.65916486431000010, 191.2456250189000002, 106.4454339660999977 ) ) ; +#15525 = ORIENTED_EDGE ( 'NONE', *, *, #39994, .T. ) ; +#15526 = CARTESIAN_POINT ( 'NONE', ( 6.065957172925149798, 165.2216646702348726, 152.9217693117704755 ) ) ; +#15527 = EDGE_CURVE ( 'NONE', #24364, #11960, #40144, .T. ) ; +#15528 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4460, #1198, #26365, #31899, #7527, #35513 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.003386932291534215222, 0.5016934661457671529, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15529 = CARTESIAN_POINT ( 'NONE', ( -20.24433135671547745, 184.9057498690842749, 102.6049128384596543 ) ) ; +#15530 = CARTESIAN_POINT ( 'NONE', ( 41.04524146633079340, 217.7719116456999870, 73.53371387620883581 ) ) ; +#15531 = ORIENTED_EDGE ( 'NONE', *, *, #1987, .T. ) ; +#15532 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#15533 = DIRECTION ( 'NONE', ( 0.6088835872828582962, 0.7728434907583781044, 0.1788119568987562025 ) ) ; +#15534 = CARTESIAN_POINT ( 'NONE', ( -12.63633279611098637, 174.6788778987209696, 103.0672644427368141 ) ) ; +#15535 = DIRECTION ( 'NONE', ( -7.677760455955688654E-18, 1.000000000000000000, -1.271205131337280331E-14 ) ) ; +#15536 = VERTEX_POINT ( 'NONE', #33808 ) ; +#15537 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9687, #12534, #4694, #3932 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15538 = CARTESIAN_POINT ( 'NONE', ( -21.70206945121835673, 129.8649430144931216, 89.98981461717227148 ) ) ; +#15539 = CARTESIAN_POINT ( 'NONE', ( 25.50051830703121780, 120.2145355607603534, 89.95699753438390189 ) ) ; +#15540 = CARTESIAN_POINT ( 'NONE', ( 5.669237377567532654, 130.1643386382168330, 92.52843164004643484 ) ) ; +#15541 = CARTESIAN_POINT ( 'NONE', ( -13.36381811942701781, 134.9949716747269974, 90.82703762294032401 ) ) ; +#15542 = AXIS2_PLACEMENT_3D ( 'NONE', #17856, #30570, #21376 ) ; +#15543 = CARTESIAN_POINT ( 'NONE', ( -14.16977588484152939, 129.7240516297933368, 90.12378855087145268 ) ) ; +#15544 = ORIENTED_EDGE ( 'NONE', *, *, #10895, .F. ) ; +#15545 = EDGE_CURVE ( 'NONE', #7877, #14237, #21906, .T. ) ; +#15546 = DIRECTION ( 'NONE', ( -0.0004161288024513937829, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#15547 = CARTESIAN_POINT ( 'NONE', ( 1.804326061463000119, 188.9338856921999934, 103.2700435273000039 ) ) ; +#15548 = CARTESIAN_POINT ( 'NONE', ( -19.83814135548826840, 313.4886687833925407, 132.0394724468755214 ) ) ; +#15549 = EDGE_CURVE ( 'NONE', #32574, #19175, #12861, .T. ) ; +#15550 = VERTEX_POINT ( 'NONE', #24018 ) ; +#15551 = FACE_OUTER_BOUND ( 'NONE', #23093, .T. ) ; +#15552 = ORIENTED_EDGE ( 'NONE', *, *, #15481, .T. ) ; +#15553 = ADVANCED_FACE ( 'NONE', ( #33401 ), #9589, .F. ) ; +#15554 = ADVANCED_FACE ( 'NONE', ( #5397 ), #2545, .T. ) ; +#15555 = CARTESIAN_POINT ( 'NONE', ( 14.89305397814877452, 176.0596799000455803, 100.6326092481401133 ) ) ; +#15556 = EDGE_CURVE ( 'NONE', #27328, #26238, #40437, .T. ) ; +#15557 = CARTESIAN_POINT ( 'NONE', ( 28.46511207850870662, 181.6173849770507900, 104.1311689187607215 ) ) ; +#15558 = DIRECTION ( 'NONE', ( 0.0005884933334877639251, -0.2249510526608011762, 0.9743698874567060519 ) ) ; +#15559 = CARTESIAN_POINT ( 'NONE', ( 39.17918664236205473, 77.03152903297159071, 290.9156096052041676 ) ) ; +#15560 = DIRECTION ( 'NONE', ( -0.6087611434179115433, 0.7728348325624404547, 0.1792657018023851023 ) ) ; +#15561 = CARTESIAN_POINT ( 'NONE', ( -1.458415330454428505, 152.0517121853154379, 130.6798743964100993 ) ) ; +#15562 = DIRECTION ( 'NONE', ( 0.0005884949961244385300, -0.2249510543439064425, 0.9743698870671262391 ) ) ; +#15563 = ORIENTED_EDGE ( 'NONE', *, *, #39396, .T. ) ; +#15564 = CARTESIAN_POINT ( 'NONE', ( -21.44693681792356443, 182.5559435529752363, 101.8122371725110611 ) ) ; +#15565 = CARTESIAN_POINT ( 'NONE', ( -0.02993291085645299193, 92.27946995574508549, 297.5585631083172302 ) ) ; +#15566 = CIRCLE ( 'NONE', #18179, 2.499999999890851754 ) ; +#15568 = CARTESIAN_POINT ( 'NONE', ( 16.22228026661851175, 122.1117483434376538, 174.4064439747764652 ) ) ; +#15567 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#15569 = ADVANCED_FACE ( 'NONE', ( #12247 ), #3067, .T. ) ; +#15570 = ORIENTED_EDGE ( 'NONE', *, *, #24149, .F. ) ; +#15571 = EDGE_LOOP ( 'NONE', ( #29715, #30506, #33609 ) ) ; +#15572 = LINE ( 'NONE', #31131, #2832 ) ; +#15573 = CARTESIAN_POINT ( 'NONE', ( -2.437379602191326988, 196.1181861119999894, 103.6812116302992877 ) ) ; +#15574 = CARTESIAN_POINT ( 'NONE', ( -20.50069624036807880, 196.1175417876341385, 103.6936179443737842 ) ) ; +#15575 = CARTESIAN_POINT ( 'NONE', ( 30.94196180770107674, 128.9721955471032402, 89.40981035832403734 ) ) ; +#15576 = CARTESIAN_POINT ( 'NONE', ( -12.63986498321543372, 135.0215617510153834, 90.97542152242847635 ) ) ; +#15577 = ORIENTED_EDGE ( 'NONE', *, *, #8766, .T. ) ; +#15578 = CARTESIAN_POINT ( 'NONE', ( 16.57480312883150120, 122.4809640191215152, 174.7222864645349887 ) ) ; +#15579 = EDGE_CURVE ( 'NONE', #29855, #37711, #37189, .T. ) ; +#15580 = EDGE_LOOP ( 'NONE', ( #17172, #19422, #11930, #2093 ) ) ; +#15581 = LINE ( 'NONE', #18632, #25976 ) ; +#15582 = CARTESIAN_POINT ( 'NONE', ( 44.86764334808821530, 186.7951585210016390, 105.8297977827117506 ) ) ; +#15583 = VERTEX_POINT ( 'NONE', #18960 ) ; +#15584 = CONICAL_SURFACE ( 'NONE', #18832, 55.00273826250365516, 0.7853981633972993981 ) ; +#15585 = ADVANCED_FACE ( 'NONE', ( #21251 ), #7832, .F. ) ; +#15586 = DIRECTION ( 'NONE', ( 0.0002393071041605206672, 0.2255699564796173062, -0.9742269435125952004 ) ) ; +#15587 = CARTESIAN_POINT ( 'NONE', ( 1.149713694548329279, 188.6824523264095603, 103.2130056182572702 ) ) ; +#15588 = CARTESIAN_POINT ( 'NONE', ( -26.00862899788921823, 205.2974736693811622, 75.67203179090084575 ) ) ; +#15589 = CARTESIAN_POINT ( 'NONE', ( -8.473620765651141085, 161.4179317431856475, 97.43745832156695030 ) ) ; +#15590 = EDGE_CURVE ( 'NONE', #4758, #33189, #14584, .T. ) ; +#15591 = CIRCLE ( 'NONE', #22786, 5.500000000093046459 ) ; +#15592 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #15105, #2826 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15593 = ORIENTED_EDGE ( 'NONE', *, *, #26137, .F. ) ; +#15594 = CARTESIAN_POINT ( 'NONE', ( 3.056793808240038324, 190.5188190123237177, 106.7271838340357561 ) ) ; +#15595 = ORIENTED_EDGE ( 'NONE', *, *, #26685, .F. ) ; +#15596 = EDGE_CURVE ( 'NONE', #24048, #17766, #1760, .T. ) ; +#15597 = PLANE ( 'NONE', #13421 ) ; +#15598 = DIRECTION ( 'NONE', ( -0.7933533416835752972, 0.5930537051408127924, 0.1373964266575312121 ) ) ; +#15599 = CARTESIAN_POINT ( 'NONE', ( -26.13120584929999879, 120.3817185810000154, 90.67887808736001887 ) ) ; +#15600 = VERTEX_POINT ( 'NONE', #3546 ) ; +#15601 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26704, #33206, #1533, #5201 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0007245802958363142723, 0.001812217952646025948 ), + .UNSPECIFIED. ) ; +#15602 = CARTESIAN_POINT ( 'NONE', ( -1.458415330486092287, 152.0517121852905973, 130.6798743963483673 ) ) ; +#15603 = CARTESIAN_POINT ( 'NONE', ( 77.77238909525101462, 192.2324461921776617, 194.3567101486201238 ) ) ; +#15604 = VERTEX_POINT ( 'NONE', #9308 ) ; +#15605 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; +#15606 = VERTEX_POINT ( 'NONE', #18680 ) ; +#15608 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; +#15607 = CARTESIAN_POINT ( 'NONE', ( 36.16444667182974371, 192.0609968746609013, 104.3828606498395573 ) ) ; +#15609 = VERTEX_POINT ( 'NONE', #40164 ) ; +#15610 = AXIS2_PLACEMENT_3D ( 'NONE', #16475, #10370, #6467 ) ; +#15611 = DIRECTION ( 'NONE', ( 0.0005884951729871207987, -0.2249510544218079611, 0.9743698870490344888 ) ) ; +#15612 = EDGE_LOOP ( 'NONE', ( #35410, #4492, #4242, #9497, #25012, #17431, #36658, #24684 ) ) ; +#15613 = CARTESIAN_POINT ( 'NONE', ( 3.078223283673000132, 209.7348231832999943, 76.19194169975999387 ) ) ; +#15614 = AXIS2_PLACEMENT_3D ( 'NONE', #16436, #28928, #10335 ) ; +#15615 = AXIS2_PLACEMENT_3D ( 'NONE', #12747, #25238, #31562 ) ; +#15616 = CARTESIAN_POINT ( 'NONE', ( 20.25014673412999855, 123.8560256903000010, 88.49168292467001606 ) ) ; +#15617 = ORIENTED_EDGE ( 'NONE', *, *, #35326, .F. ) ; +#15618 = AXIS2_PLACEMENT_3D ( 'NONE', #14774, #30712, #14968 ) ; +#15619 = ORIENTED_EDGE ( 'NONE', *, *, #10280, .T. ) ; +#15620 = DIRECTION ( 'NONE', ( 0.0006039748319395907457, 1.314021223879979801E-14, 0.9999998176071847045 ) ) ; +#15621 = CARTESIAN_POINT ( 'NONE', ( 30.18434728222111829, 126.7045899472522308, 91.62356130930872666 ) ) ; +#15622 = CARTESIAN_POINT ( 'NONE', ( 13.50544439768758664, 187.6165333045301509, 105.9640318452364056 ) ) ; +#15623 = CARTESIAN_POINT ( 'NONE', ( 22.81270356676756350, 135.0716824376671923, 90.82289798865961927 ) ) ; +#15624 = CARTESIAN_POINT ( 'NONE', ( 36.07403909944999754, 192.3900100081999938, 104.3752709241999952 ) ) ; +#15625 = ORIENTED_EDGE ( 'NONE', *, *, #5427, .F. ) ; +#15626 = EDGE_CURVE ( 'NONE', #35766, #9326, #5677, .T. ) ; +#15627 = EDGE_LOOP ( 'NONE', ( #17926, #26751, #21961, #35768 ) ) ; +#15628 = EDGE_CURVE ( 'NONE', #8486, #36684, #12367, .T. ) ; +#15629 = VERTEX_POINT ( 'NONE', #34224 ) ; +#15630 = CARTESIAN_POINT ( 'NONE', ( 14.55129770294257341, 129.4786662571763998, 92.61555079168689986 ) ) ; +#15631 = ADVANCED_FACE ( 'NONE', ( #3354 ), #24666, .F. ) ; +#15632 = CARTESIAN_POINT ( 'NONE', ( 20.33495833690937005, 173.9218102917841691, 102.5304087197118434 ) ) ; +#15633 = CARTESIAN_POINT ( 'NONE', ( -3.668404236601097601, 185.3449489774860979, 105.0111528754605530 ) ) ; +#15634 = EDGE_CURVE ( 'NONE', #9657, #25568, #38963, .T. ) ; +#15635 = CARTESIAN_POINT ( 'NONE', ( -3.589080272436853125, 149.3464402607426962, 130.0539584787920830 ) ) ; +#15636 = ORIENTED_EDGE ( 'NONE', *, *, #9718, .T. ) ; +#15637 = LINE ( 'NONE', #28133, #31734 ) ; +#15638 = CARTESIAN_POINT ( 'NONE', ( -40.67088416478974011, 188.1990424077830255, 107.8411755427910776 ) ) ; +#15639 = EDGE_LOOP ( 'NONE', ( #34210, #38729, #9134, #20405 ) ) ; +#15640 = EDGE_CURVE ( 'NONE', #9595, #12555, #36035, .T. ) ; +#15641 = DIRECTION ( 'NONE', ( 0.0005884949961218503226, -0.2249510543439091348, 0.9743698870671257950 ) ) ; +#15642 = CARTESIAN_POINT ( 'NONE', ( -35.96311564216326673, 218.5902260770998282, 61.08022271437000938 ) ) ; +#15643 = EDGE_CURVE ( 'NONE', #1723, #30329, #21990, .T. ) ; +#15644 = CARTESIAN_POINT ( 'NONE', ( -37.40113477844868584, 212.8449769292228950, 73.08109343054711360 ) ) ; +#15645 = CARTESIAN_POINT ( 'NONE', ( 28.46284161542680025, 187.5721379928345129, 102.9401731420402939 ) ) ; +#15646 = ORIENTED_EDGE ( 'NONE', *, *, #35308, .F. ) ; +#15647 = PLANE ( 'NONE', #24310 ) ; +#15648 = ORIENTED_EDGE ( 'NONE', *, *, #27017, .F. ) ; +#15649 = CARTESIAN_POINT ( 'NONE', ( 41.76074418039778635, 76.52721947789308388, 288.1972846910081216 ) ) ; +#15650 = DIRECTION ( 'NONE', ( 0.7933533411653073131, 0.5931840316265226676, 0.1368326740407721509 ) ) ; +#15651 = AXIS2_PLACEMENT_3D ( 'NONE', #32309, #23309, #20016 ) ; +#15652 = CARTESIAN_POINT ( 'NONE', ( 37.90468641847999720, 118.3397859469999958, 90.10467778014999851 ) ) ; +#15653 = EDGE_CURVE ( 'NONE', #35446, #8079, #19092, .T. ) ; +#15654 = EDGE_LOOP ( 'NONE', ( #1705, #10448, #7736, #20031 ) ) ; +#15655 = CYLINDRICAL_SURFACE ( 'NONE', #29149, 4.999999999999990230 ) ; +#15656 = ORIENTED_EDGE ( 'NONE', *, *, #1354, .T. ) ; +#15657 = CARTESIAN_POINT ( 'NONE', ( 45.13396388906383550, 144.4285190563504386, 288.0543464848796020 ) ) ; +#15658 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #10365, #23228 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15659 = ORIENTED_EDGE ( 'NONE', *, *, #38163, .F. ) ; +#15660 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749389406, 179.6299767372367171, 101.6260513916640633 ) ) ; +#15661 = CARTESIAN_POINT ( 'NONE', ( -32.45585619719672366, 153.0051697192221241, 291.5781464590990026 ) ) ; +#15662 = DIRECTION ( 'NONE', ( 3.331154357219597397E-10, 0.9743700558672070411, 0.2249510929720852648 ) ) ; +#15663 = CARTESIAN_POINT ( 'NONE', ( -35.74514700973497128, 114.7698281653908481, 90.28937401230335524 ) ) ; +#15664 = ORIENTED_EDGE ( 'NONE', *, *, #23080, .T. ) ; +#15665 = ORIENTED_EDGE ( 'NONE', *, *, #28130, .T. ) ; +#15667 = AXIS2_PLACEMENT_3D ( 'NONE', #10423, #25566, #19995 ) ; +#15666 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#15668 = DIRECTION ( 'NONE', ( 0.6087614883550946931, -0.7730004026499607273, -0.1785492307423602321 ) ) ; +#15669 = AXIS2_PLACEMENT_3D ( 'NONE', #21817, #6063, #15277 ) ; +#15670 = ORIENTED_EDGE ( 'NONE', *, *, #22104, .F. ) ; +#15671 = CARTESIAN_POINT ( 'NONE', ( 19.98065423330452717, 207.8023024357342194, 73.39927846491143271 ) ) ; +#15672 = AXIS2_PLACEMENT_3D ( 'NONE', #34974, #37878, #25632 ) ; +#15673 = EDGE_CURVE ( 'NONE', #27579, #37550, #7243, .T. ) ; +#15674 = DIRECTION ( 'NONE', ( 0.7066905234128858515, 0.1590644159615968445, -0.6894106292284863935 ) ) ; +#15675 = ADVANCED_FACE ( 'NONE', ( #28319 ), #25260, .T. ) ; +#15676 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19628, #32126, #1024, #13514 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999992928140459814 ), + .UNSPECIFIED. ) ; +#15677 = ORIENTED_EDGE ( 'NONE', *, *, #35868, .F. ) ; +#15678 = CYLINDRICAL_SURFACE ( 'NONE', #37251, 2.000000000000011546 ) ; +#15679 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 92.27946979429643193, 322.5967026918627312 ) ) ; +#15680 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#15681 = ORIENTED_EDGE ( 'NONE', *, *, #10532, .F. ) ; +#15682 = CARTESIAN_POINT ( 'NONE', ( 28.21200539798000051, 125.5548472498000052, 89.13590720598000416 ) ) ; +#15683 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36124, #24083, #29602, #7711 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15684 = CARTESIAN_POINT ( 'NONE', ( -18.11101809600965140, 126.4107873866457368, 175.0113113579019739 ) ) ; +#15685 = CARTESIAN_POINT ( 'NONE', ( 17.27264158547648165, 121.9609240029174941, 174.6061468887760668 ) ) ; +#15686 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #40445, #24945, #16502, #1174 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.391724131716651547, 1.570796326794897446 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973295471489360686, 0.9973295471489360686, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#15687 = CARTESIAN_POINT ( 'NONE', ( -19.99994197501026250, 125.2902815941508408, 88.59048179173321103 ) ) ; +#15688 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319412346130 ) ) ; +#15689 = ORIENTED_EDGE ( 'NONE', *, *, #14530, .F. ) ; +#15690 = CARTESIAN_POINT ( 'NONE', ( -28.46004690425293404, 130.8179028617305732, 90.04286148709125825 ) ) ; +#15691 = FACE_OUTER_BOUND ( 'NONE', #30538, .T. ) ; +#15692 = CARTESIAN_POINT ( 'NONE', ( 36.75303272014377143, 191.6324003026956859, 104.3442794745380127 ) ) ; +#15693 = FACE_OUTER_BOUND ( 'NONE', #35427, .T. ) ; +#15694 = VERTEX_POINT ( 'NONE', #16026 ) ; +#15695 = CARTESIAN_POINT ( 'NONE', ( 38.56339867466881799, 119.0882710927012482, 90.25372335301064197 ) ) ; +#15696 = CARTESIAN_POINT ( 'NONE', ( 12.31576967456374838, 135.2953866561074676, 91.39403622019926843 ) ) ; +#15697 = CARTESIAN_POINT ( 'NONE', ( -19.44522556511200406, 148.1576261194917947, 181.5778736950635732 ) ) ; +#15698 = EDGE_CURVE ( 'NONE', #18185, #8486, #25463, .T. ) ; +#15699 = AXIS2_PLACEMENT_3D ( 'NONE', #25808, #15769, #10268 ) ; +#15700 = CARTESIAN_POINT ( 'NONE', ( -25.50061241622579544, 190.9799426753714613, 106.3218592287567077 ) ) ; +#15701 = EDGE_LOOP ( 'NONE', ( #31493, #21833, #17170, #2337 ) ) ; +#15702 = VECTOR ( 'NONE', #29754, 1000.000000000000114 ) ; +#15703 = FACE_OUTER_BOUND ( 'NONE', #59, .T. ) ; +#15704 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15435, #2363, #15621, #40352 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 5.340901054339369348E-08, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15705 = CIRCLE ( 'NONE', #39223, 2.000000001784958847 ) ; +#15706 = CARTESIAN_POINT ( 'NONE', ( -12.63886188339458094, 181.8545105071091257, 101.8741920870010347 ) ) ; +#15707 = DIRECTION ( 'NONE', ( 0.0004161288024487149904, -0.8480480898035930304, 0.5299191110134608973 ) ) ; +#15708 = ORIENTED_EDGE ( 'NONE', *, *, #20637, .F. ) ; +#15709 = LINE ( 'NONE', #12063, #34808 ) ; +#15710 = DIRECTION ( 'NONE', ( 0.0005884948869652768940, -0.2249510543002911367, 0.9743698870772616871 ) ) ; +#15711 = CARTESIAN_POINT ( 'NONE', ( 20.20768266840917704, 127.3886079643583571, 89.26371417184604695 ) ) ; +#15712 = CARTESIAN_POINT ( 'NONE', ( 36.36654477671010000, 191.7216060454559852, 106.4021762953440060 ) ) ; +#15713 = CARTESIAN_POINT ( 'NONE', ( 36.50285708549999697, 190.9865300476000129, 106.6685476356000066 ) ) ; +#15714 = EDGE_LOOP ( 'NONE', ( #35980, #19627, #14828, #35128 ) ) ; +#15715 = VERTEX_POINT ( 'NONE', #18283 ) ; +#15716 = ORIENTED_EDGE ( 'NONE', *, *, #34366, .T. ) ; +#15717 = CARTESIAN_POINT ( 'NONE', ( -3.841346491554074039, 136.1850729056500313, 91.09604285724341821 ) ) ; +#15718 = PLANE ( 'NONE', #38577 ) ; +#15719 = DIRECTION ( 'NONE', ( 0.0005884949961229807118, -0.2249510543439059429, 0.9743698870671263501 ) ) ; +#15720 = CARTESIAN_POINT ( 'NONE', ( 62.08695490598599775, 78.64495961329345164, 282.5210433287024898 ) ) ; +#15721 = EDGE_CURVE ( 'NONE', #5067, #25046, #26583, .T. ) ; +#15722 = EDGE_CURVE ( 'NONE', #10701, #29247, #18480, .T. ) ; +#15723 = EDGE_LOOP ( 'NONE', ( #5396, #24257, #34181, #20682 ) ) ; +#15724 = CARTESIAN_POINT ( 'NONE', ( -26.00148896606084037, 118.3501043404999962, 87.28357517440494462 ) ) ; +#15725 = VECTOR ( 'NONE', #7352, 1000.000000000000114 ) ; +#15726 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749387985, 132.8602140592423382, 90.82839891339965277 ) ) ; +#15727 = DIRECTION ( 'NONE', ( 7.930164461882003851E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; +#15728 = CARTESIAN_POINT ( 'NONE', ( -3.668404236352207359, 128.0226348367964988, 91.77725148510558029 ) ) ; +#15729 = VERTEX_POINT ( 'NONE', #27935 ) ; +#15730 = CARTESIAN_POINT ( 'NONE', ( -12.63780403360421545, 175.2412555344319856, 100.6313397257130617 ) ) ; +#15731 = DIRECTION ( 'NONE', ( -0.0005884949961263758909, 0.2249510543439055821, -0.9743698870671265722 ) ) ; +#15732 = ADVANCED_FACE ( 'NONE', ( #38695 ), #13377, .F. ) ; +#15733 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#15734 = CARTESIAN_POINT ( 'NONE', ( -15.83323561231152965, 184.9252659090778081, 102.5268986338905250 ) ) ; +#15735 = ORIENTED_EDGE ( 'NONE', *, *, #3561, .T. ) ; +#15736 = CARTESIAN_POINT ( 'NONE', ( 12.64071154648716799, 176.8676401789000749, 103.2142495390799866 ) ) ; +#15737 = CARTESIAN_POINT ( 'NONE', ( 2.549741881329860238, 190.9970219424760103, 104.2732579596220006 ) ) ; +#15738 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#15739 = ORIENTED_EDGE ( 'NONE', *, *, #20794, .T. ) ; +#15740 = ORIENTED_EDGE ( 'NONE', *, *, #25079, .F. ) ; +#15741 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930882562 ) ) ; +#15742 = ORIENTED_EDGE ( 'NONE', *, *, #18995, .T. ) ; +#15743 = CARTESIAN_POINT ( 'NONE', ( -40.78982053831894916, 220.4002260996649056, 73.41647350591635757 ) ) ; +#15744 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749096068, 179.1800746284886259, 103.5747911658217078 ) ) ; +#15745 = CARTESIAN_POINT ( 'NONE', ( 22.78191781013921968, 158.2317512751428126, 98.73560149028561739 ) ) ; +#15746 = CIRCLE ( 'NONE', #12481, 5.499999999997804423 ) ; +#15747 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2534, #12146, #39724, #24426 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.001265839647099397444 ), + .UNSPECIFIED. ) ; +#15748 = CARTESIAN_POINT ( 'NONE', ( 44.90072207509915359, 127.0650837324493523, 92.04000096660296037 ) ) ; +#15749 = VECTOR ( 'NONE', #6627, 1000.000000000000114 ) ; +#15750 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#15751 = CIRCLE ( 'NONE', #21649, 22.00000000001092815 ) ; +#15752 = DIRECTION ( 'NONE', ( 0.0005884949961232824453, -0.2249510543439075805, 0.9743698870671260170 ) ) ; +#15753 = CARTESIAN_POINT ( 'NONE', ( 44.05265128906093963, 113.3760414474945009, 85.80123528811637357 ) ) ; +#15754 = ORIENTED_EDGE ( 'NONE', *, *, #17414, .F. ) ; +#15755 = EDGE_CURVE ( 'NONE', #35358, #23147, #27274, .T. ) ; +#15756 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#15757 = CARTESIAN_POINT ( 'NONE', ( 25.50011543809205250, 118.8155664120999973, 94.25238413803072035 ) ) ; +#15758 = ORIENTED_EDGE ( 'NONE', *, *, #3750, .F. ) ; +#15759 = EDGE_LOOP ( 'NONE', ( #12697, #1, #17060, #38420 ) ) ; +#15760 = ADVANCED_FACE ( 'NONE', ( #3952 ), #23182, .F. ) ; +#15761 = ORIENTED_EDGE ( 'NONE', *, *, #7124, .F. ) ; +#15762 = CARTESIAN_POINT ( 'NONE', ( -20.33307505328456699, 118.8155084438010931, 87.61342193665612399 ) ) ; +#15763 = ADVANCED_FACE ( 'NONE', ( #886 ), #34814, .T. ) ; +#15764 = EDGE_CURVE ( 'NONE', #20447, #21013, #25273, .T. ) ; +#15765 = ORIENTED_EDGE ( 'NONE', *, *, #24427, .T. ) ; +#15766 = ADVANCED_FACE ( 'NONE', ( #1288 ), #31806, .F. ) ; +#15767 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971545696 ) ) ; +#15768 = CARTESIAN_POINT ( 'NONE', ( 38.86900528589750081, 119.2001525857115922, 87.69880077671245999 ) ) ; +#15769 = DIRECTION ( 'NONE', ( 0.0005884949961217107858, -0.2249510543439044441, 0.9743698870671267942 ) ) ; +#15770 = CARTESIAN_POINT ( 'NONE', ( 12.63580143090830887, 130.5208300941526147, 90.20832784594151121 ) ) ; +#15771 = LINE ( 'NONE', #34374, #39981 ) ; +#15772 = VERTEX_POINT ( 'NONE', #16425 ) ; +#15773 = VERTEX_POINT ( 'NONE', #22790 ) ; +#15774 = FACE_OUTER_BOUND ( 'NONE', #1889, .T. ) ; +#15775 = CIRCLE ( 'NONE', #27563, 2.249999999963659292 ) ; +#15776 = CARTESIAN_POINT ( 'NONE', ( 31.91041242450083004, 174.4868366864082532, 100.4302623719975571 ) ) ; +#15777 = CARTESIAN_POINT ( 'NONE', ( 15.95613733389899025, 121.8961617987971238, 174.4891947115541484 ) ) ; +#15778 = CONICAL_SURFACE ( 'NONE', #11212, 3.000000000033072212, 0.7853981634062642270 ) ; +#15779 = EDGE_LOOP ( 'NONE', ( #38437, #2382, #29744, #6367 ) ) ; +#15780 = FACE_OUTER_BOUND ( 'NONE', #32646, .T. ) ; +#15781 = AXIS2_PLACEMENT_3D ( 'NONE', #32261, #13845, #16700 ) ; +#15782 = CARTESIAN_POINT ( 'NONE', ( 2.621083284465321572, 189.6939337031247135, 103.4456358662860112 ) ) ; +#15783 = CARTESIAN_POINT ( 'NONE', ( -26.00146729410618107, 120.3902237924994836, 87.46289810595230563 ) ) ; +#15784 = VERTEX_POINT ( 'NONE', #19495 ) ; +#15785 = CARTESIAN_POINT ( 'NONE', ( -15.10713178427481651, 176.3794795624077096, 100.3824614381103828 ) ) ; +#15786 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251387457, 179.1753088543557624, 103.5954339978685965 ) ) ; +#15787 = ORIENTED_EDGE ( 'NONE', *, *, #6435, .T. ) ; +#15788 = ADVANCED_FACE ( 'NONE', ( #26457 ), #3754, .T. ) ; +#15789 = CARTESIAN_POINT ( 'NONE', ( -35.95668941153999754, 206.4002260771000010, 73.08022102180001411 ) ) ; +#15790 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36523, #24277, #34240, #36720 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15791 = CARTESIAN_POINT ( 'NONE', ( -35.95496198192999771, 218.5902260770999987, 74.58022025207000638 ) ) ; +#15792 = CARTESIAN_POINT ( 'NONE', ( 14.54953207236175139, 130.1535194663153447, 89.69244121379192336 ) ) ; +#15793 = ORIENTED_EDGE ( 'NONE', *, *, #23868, .T. ) ; +#15794 = CARTESIAN_POINT ( 'NONE', ( 2.444755512867411440, 189.2322982050264670, 106.4180782769317659 ) ) ; +#15795 = CARTESIAN_POINT ( 'NONE', ( -13.46754865746872376, 158.0276785376866826, 98.88143215986140433 ) ) ; +#15796 = CYLINDRICAL_SURFACE ( 'NONE', #14353, 4.999999999999990230 ) ; +#15797 = ORIENTED_EDGE ( 'NONE', *, *, #12578, .F. ) ; +#15798 = EDGE_CURVE ( 'NONE', #8915, #36967, #16774, .T. ) ; +#15799 = CARTESIAN_POINT ( 'NONE', ( 17.97063383950253623, 126.0060190202803625, 174.3181455802166795 ) ) ; +#15800 = CARTESIAN_POINT ( 'NONE', ( 41.44446280484381617, 121.0638739319363140, 90.65659975668269510 ) ) ; +#15801 = CIRCLE ( 'NONE', #30828, 2.000000000000011546 ) ; +#15803 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319411731388 ) ) ; +#15802 = CARTESIAN_POINT ( 'NONE', ( 36.40558664052492333, 191.8188463803718093, 104.3612499972096117 ) ) ; +#15804 = ORIENTED_EDGE ( 'NONE', *, *, #19025, .T. ) ; +#15805 = CIRCLE ( 'NONE', #30188, 2.499999999978018028 ) ; +#15806 = EDGE_CURVE ( 'NONE', #17411, #14103, #5042, .T. ) ; +#15807 = CARTESIAN_POINT ( 'NONE', ( 25.49092517336361041, 207.5918372323820904, 74.04845020794621746 ) ) ; +#15808 = AXIS2_PLACEMENT_3D ( 'NONE', #23167, #29912, #2106 ) ; +#15809 = EDGE_LOOP ( 'NONE', ( #24135, #29763, #27278, #25895 ) ) ; +#15810 = CARTESIAN_POINT ( 'NONE', ( 3.785823397764000564, 140.1660989325999935, 94.83286549423999645 ) ) ; +#15811 = EDGE_CURVE ( 'NONE', #18436, #34191, #27295, .T. ) ; +#15812 = CARTESIAN_POINT ( 'NONE', ( -22.49823186950551346, 173.8370468426015805, 102.8821234254057089 ) ) ; +#15813 = CARTESIAN_POINT ( 'NONE', ( 39.69446386203616584, 161.8153251821185563, 196.1471770628630793 ) ) ; +#15814 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; +#15815 = EDGE_LOOP ( 'NONE', ( #39036, #39967, #25381, #20199 ) ) ; +#15816 = EDGE_CURVE ( 'NONE', #37208, #21067, #2840, .T. ) ; +#15817 = VERTEX_POINT ( 'NONE', #22987 ) ; +#15818 = EDGE_CURVE ( 'NONE', #24578, #37440, #37054, .T. ) ; +#15819 = CARTESIAN_POINT ( 'NONE', ( 13.53487526333000091, 140.5899962463843167, 152.9217693939943388 ) ) ; +#15820 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 77.27946979429643193, 322.5967026918629017 ) ) ; +#15821 = CARTESIAN_POINT ( 'NONE', ( 23.08601424118414513, 134.9925771438349784, 90.80447001643439364 ) ) ; +#15822 = ORIENTED_EDGE ( 'NONE', *, *, #19408, .F. ) ; +#15823 = ORIENTED_EDGE ( 'NONE', *, *, #1302, .F. ) ; +#15824 = VERTEX_POINT ( 'NONE', #39107 ) ; +#15825 = CARTESIAN_POINT ( 'NONE', ( 34.29411924272742596, 218.5902260770999987, 73.03779129371588397 ) ) ; +#15826 = CARTESIAN_POINT ( 'NONE', ( 20.08486655242547414, 128.0648441155641990, 89.20688914988019746 ) ) ; +#15827 = CARTESIAN_POINT ( 'NONE', ( -28.35189984747000125, 125.4776471425000040, 88.98101198637000664 ) ) ; +#15828 = ORIENTED_EDGE ( 'NONE', *, *, #22113, .T. ) ; +#15829 = CARTESIAN_POINT ( 'NONE', ( 20.50039165879256942, 118.8156470718432729, 87.75541749211321019 ) ) ; +#15830 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#15831 = ORIENTED_EDGE ( 'NONE', *, *, #1026, .F. ) ; +#15832 = VECTOR ( 'NONE', #4133, 1000.000000000000114 ) ; +#15833 = CARTESIAN_POINT ( 'NONE', ( -36.99951977468094100, 116.5506918669546792, 89.73453862280433668 ) ) ; +#15834 = FACE_OUTER_BOUND ( 'NONE', #12546, .T. ) ; +#15835 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#15836 = VECTOR ( 'NONE', #35191, 1000.000000000000000 ) ; +#15837 = CARTESIAN_POINT ( 'NONE', ( 38.97204648811698036, 118.8228816124465368, 89.67376701884533929 ) ) ; +#15838 = CARTESIAN_POINT ( 'NONE', ( -3.169906973602109712, 126.7999172216492099, 88.92891361563410157 ) ) ; +#15839 = ORIENTED_EDGE ( 'NONE', *, *, #39532, .F. ) ; +#15840 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 1.376043959293782775E-15, -0.0006039748319377434820 ) ) ; +#15841 = VERTEX_POINT ( 'NONE', #32968 ) ; +#15842 = CARTESIAN_POINT ( 'NONE', ( 34.09746542872949249, 82.01624178880980764, 290.5639394685908314 ) ) ; +#15843 = CARTESIAN_POINT ( 'NONE', ( -38.01656497497999965, 118.6347820250999945, 87.61306182308000245 ) ) ; +#15844 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #2993, #15475, #40403, #18923 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.701183077854123038, 1.701264852836251729 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999994427375416, 0.9999999994427375416, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#15845 = CARTESIAN_POINT ( 'NONE', ( 29.05352371370200615, 110.6131156702000027, 87.25023669171606855 ) ) ; +#15846 = VERTEX_POINT ( 'NONE', #2322 ) ; +#15847 = FACE_OUTER_BOUND ( 'NONE', #29961, .T. ) ; +#15848 = ADVANCED_FACE ( 'NONE', ( #33579 ), #11722, .T. ) ; +#15849 = VERTEX_POINT ( 'NONE', #8033 ) ; +#15850 = EDGE_CURVE ( 'NONE', #21171, #35987, #11116, .T. ) ; +#15852 = EDGE_CURVE ( 'NONE', #39810, #36343, #39710, .T. ) ; +#15851 = CARTESIAN_POINT ( 'NONE', ( 25.18497250179792601, 116.8542503881588175, 89.75272387405183849 ) ) ; +#15853 = CARTESIAN_POINT ( 'NONE', ( 35.80546160733999983, 201.9934155195000187, 90.45676456543999677 ) ) ; +#15854 = EDGE_CURVE ( 'NONE', #25751, #2067, #10924, .T. ) ; +#15855 = EDGE_LOOP ( 'NONE', ( #22771, #16854, #34072, #13338 ) ) ; +#15856 = CARTESIAN_POINT ( 'NONE', ( -12.63810009328765815, 175.3544237672228121, 100.1411543447596983 ) ) ; +#15857 = CARTESIAN_POINT ( 'NONE', ( 28.70699186922535873, 163.1576631238072821, 99.86925946332931403 ) ) ; +#15858 = DIRECTION ( 'NONE', ( -5.551115123437337795E-15, 0.9743700557921585181, 0.2249510932971564292 ) ) ; +#15859 = CARTESIAN_POINT ( 'NONE', ( -39.70379676582250283, 165.1621345740199160, 181.9116255470079579 ) ) ; +#15860 = CARTESIAN_POINT ( 'NONE', ( -20.45296611704877776, 159.3209472110458762, 96.44741428446211273 ) ) ; +#15861 = AXIS2_PLACEMENT_3D ( 'NONE', #31177, #15620, #24455 ) ; +#15862 = CARTESIAN_POINT ( 'NONE', ( -12.59983791313500667, 115.9590670279657445, 152.9217693160060776 ) ) ; +#15863 = ORIENTED_EDGE ( 'NONE', *, *, #4734, .F. ) ; +#15864 = CARTESIAN_POINT ( 'NONE', ( -35.69245307692643365, 114.5537190934489189, 90.28934218648832655 ) ) ; +#15865 = ORIENTED_EDGE ( 'NONE', *, *, #7499, .F. ) ; +#15866 = ORIENTED_EDGE ( 'NONE', *, *, #37885, .F. ) ; +#15867 = EDGE_CURVE ( 'NONE', #9058, #35255, #14992, .T. ) ; +#15868 = CARTESIAN_POINT ( 'NONE', ( 30.09291612729013110, 103.6131156702000027, 152.4718672073996117 ) ) ; +#15869 = CARTESIAN_POINT ( 'NONE', ( 15.99970520780110483, 160.7332544674666508, 96.75156078672274873 ) ) ; +#15870 = ORIENTED_EDGE ( 'NONE', *, *, #25447, .F. ) ; +#15871 = CARTESIAN_POINT ( 'NONE', ( -14.89118547255141500, 175.5309352547254775, 102.9232378619308861 ) ) ; +#15872 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#15873 = ORIENTED_EDGE ( 'NONE', *, *, #13790, .F. ) ; +#15874 = CARTESIAN_POINT ( 'NONE', ( 23.31716640680999930, 201.2278123622999999, 28.07991271570000080 ) ) ; +#15875 = EDGE_CURVE ( 'NONE', #30846, #734, #11515, .T. ) ; +#15876 = CARTESIAN_POINT ( 'NONE', ( 77.76885812527426367, 193.5821525182410880, 188.5104908262173637 ) ) ; +#15877 = VERTEX_POINT ( 'NONE', #17428 ) ; +#15878 = CARTESIAN_POINT ( 'NONE', ( 28.11271033718000112, 125.4906462842000110, 89.12114495753000654 ) ) ; +#15879 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 164.9087802455859162, 182.8989377884010139 ) ) ; +#15880 = CARTESIAN_POINT ( 'NONE', ( 15.83512664620924326, 151.3287663793590809, 97.48834744810477559 ) ) ; +#15881 = CARTESIAN_POINT ( 'NONE', ( 30.07127365770511318, 176.8230753548089638, 103.1292432202702969 ) ) ; +#15882 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; +#15883 = EDGE_LOOP ( 'NONE', ( #28056, #22562, #6974, #3711 ) ) ; +#15884 = CARTESIAN_POINT ( 'NONE', ( 16.56026951762423494, 122.5141854615031178, 174.6306262266012084 ) ) ; +#15885 = LINE ( 'NONE', #28378, #29060 ) ; +#15886 = AXIS2_PLACEMENT_3D ( 'NONE', #8738, #9894, #22366 ) ; +#15887 = CARTESIAN_POINT ( 'NONE', ( 36.42433494591709575, 191.8057322581022390, 104.3592985921623750 ) ) ; +#15888 = CARTESIAN_POINT ( 'NONE', ( 12.63777575465211456, 130.2256679117907368, 92.62110684792574489 ) ) ; +#15889 = EDGE_LOOP ( 'NONE', ( #31986, #36304, #3330, #6353, #30883 ) ) ; +#15890 = VECTOR ( 'NONE', #37654, 1000.000000000000000 ) ; +#15891 = CARTESIAN_POINT ( 'NONE', ( 39.53379105069361543, 120.3902222971681368, 87.42331650858173475 ) ) ; +#15892 = CARTESIAN_POINT ( 'NONE', ( 19.32342759816472011, 148.9592218696507189, 180.9802330199531184 ) ) ; +#15893 = CARTESIAN_POINT ( 'NONE', ( -3.334876874488374998, 183.4854709603033598, 104.9237563252875844 ) ) ; +#15894 = AXIS2_PLACEMENT_3D ( 'NONE', #9660, #24817, #31536 ) ; +#15895 = CARTESIAN_POINT ( 'NONE', ( 43.53560975226982777, 121.3918131887250524, 90.46069063649885322 ) ) ; +#15896 = CARTESIAN_POINT ( 'NONE', ( -25.67411157019000001, 190.9010507822000022, 106.4782221023999966 ) ) ; +#15897 = ORIENTED_EDGE ( 'NONE', *, *, #3514, .F. ) ; +#15898 = EDGE_CURVE ( 'NONE', #10734, #32124, #1381, .T. ) ; +#15899 = ADVANCED_FACE ( 'NONE', ( #20921 ), #18087, .F. ) ; +#15900 = EDGE_CURVE ( 'NONE', #40361, #25177, #33125, .T. ) ; +#15901 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2233, #23293, #36569, #20620 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15902 = CARTESIAN_POINT ( 'NONE', ( -12.63924462906329005, 181.8109532889671698, 101.8044862477469081 ) ) ; +#15903 = CARTESIAN_POINT ( 'NONE', ( 0.06400980323497000579, 188.6937622364000049, 105.9808922080000002 ) ) ; +#15904 = CARTESIAN_POINT ( 'NONE', ( -2.770634212112902617, 196.4250215355508828, 103.8116555233700353 ) ) ; +#15905 = CARTESIAN_POINT ( 'NONE', ( -25.99372727560586682, 191.7362033397953383, 103.9228720321462447 ) ) ; +#15906 = EDGE_CURVE ( 'NONE', #8808, #19860, #28741, .T. ) ; +#15907 = DIRECTION ( 'NONE', ( -0.0005734119072288677843, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#15908 = CARTESIAN_POINT ( 'NONE', ( 36.36531231111000295, 191.8368571526999915, 104.3615859421999943 ) ) ; +#15909 = CARTESIAN_POINT ( 'NONE', ( 36.51615922305000339, 190.9752249994000124, 106.6662851373999956 ) ) ; +#15910 = VERTEX_POINT ( 'NONE', #21122 ) ; +#15911 = EDGE_CURVE ( 'NONE', #5671, #23621, #23384, .T. ) ; +#15912 = CARTESIAN_POINT ( 'NONE', ( -3.538821847849364488, 137.0364201774141577, 91.29240918044028774 ) ) ; +#15913 = VECTOR ( 'NONE', #2585, 999.9999999999998863 ) ; +#15914 = CARTESIAN_POINT ( 'NONE', ( -20.05040618438584943, 184.9463469738533661, 102.4150248276820179 ) ) ; +#15915 = VECTOR ( 'NONE', #38581, 1000.000000000000114 ) ; +#15916 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971556521 ) ) ; +#15917 = EDGE_LOOP ( 'NONE', ( #27061, #30121, #31333, #20648, #12703, #20192, #15975, #21193, #10001, #32225, #20736, #22613 ) ) ; +#15918 = CARTESIAN_POINT ( 'NONE', ( -14.78424370841450042, 128.6742020487672278, 91.93439134535178425 ) ) ; +#15919 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #13494, #30037, #25980, #16931 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 2.906772358712197857, 4.712388980384624837 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7462717963450520298, 0.7462717963450520298, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#15920 = CIRCLE ( 'NONE', #23763, 1.999999998088923370 ) ; +#15921 = ORIENTED_EDGE ( 'NONE', *, *, #39700, .F. ) ; +#15922 = DIRECTION ( 'NONE', ( 0.0005884949961247345172, -0.2249510543439062205, 0.9743698870671264611 ) ) ; +#15923 = CARTESIAN_POINT ( 'NONE', ( -3.169881662145332513, 128.5839160399947332, 89.34077473205128683 ) ) ; +#15924 = EDGE_LOOP ( 'NONE', ( #20190, #9314, #827, #1858 ) ) ; +#15925 = CARTESIAN_POINT ( 'NONE', ( 32.37225756566472512, 173.7344409119733086, 102.8220398834807980 ) ) ; +#15926 = CARTESIAN_POINT ( 'NONE', ( 23.38532237667366331, 214.0898681195277788, 76.04433488945258546 ) ) ; +#15927 = CARTESIAN_POINT ( 'NONE', ( 38.22623376675434059, 118.8155667128057615, 90.24469678293085906 ) ) ; +#15928 = CARTESIAN_POINT ( 'NONE', ( 13.50130427968899305, 124.2930898811154918, 90.90584795535438900 ) ) ; +#15929 = ORIENTED_EDGE ( 'NONE', *, *, #4359, .F. ) ; +#15930 = PLANE ( 'NONE', #14805 ) ; +#15931 = CARTESIAN_POINT ( 'NONE', ( 2.552808849906440081, 190.8272003400429924, 104.2221943813569851 ) ) ; +#15932 = LINE ( 'NONE', #15548, #7090 ) ; +#15933 = ORIENTED_EDGE ( 'NONE', *, *, #2308, .F. ) ; +#15934 = CYLINDRICAL_SURFACE ( 'NONE', #16575, 2.500000000000003997 ) ; +#15935 = VERTEX_POINT ( 'NONE', #33168 ) ; +#15936 = AXIS2_PLACEMENT_3D ( 'NONE', #39430, #26189, #10845 ) ; +#15937 = CARTESIAN_POINT ( 'NONE', ( 22.11776639833565028, 135.5859592220768945, 93.50780862338704935 ) ) ; +#15938 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10226, #35115, #993, #13486, #35324, #32489, #14289, #26975, #17122, #27186 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999997623568, 0.3749999999996778133, 0.4374999999997005729, 0.4999999999997233324, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#15939 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118071, 102.4385832782338071, 173.5892250900641045 ) ) ; +#15940 = AXIS2_PLACEMENT_3D ( 'NONE', #32300, #23100, #26776 ) ; +#15941 = AXIS2_PLACEMENT_3D ( 'NONE', #4009, #31439, #16086 ) ; +#15942 = LINE ( 'NONE', #6345, #1887 ) ; +#15943 = ADVANCED_FACE ( 'NONE', ( #26867 ), #23339, .T. ) ; +#15944 = CARTESIAN_POINT ( 'NONE', ( -14.31750948537055201, 182.2834106990709984, 101.7450119985854826 ) ) ; +#15945 = CIRCLE ( 'NONE', #19845, 1.749999999975493381 ) ; +#15946 = ADVANCED_FACE ( 'NONE', ( #17632 ), #32781, .F. ) ; +#15947 = CARTESIAN_POINT ( 'NONE', ( 1.226479719036516425, 136.3602109141136793, 175.2633797041700063 ) ) ; +#15948 = DIRECTION ( 'NONE', ( 0.6087614810001747978, -0.7729390313185978689, -0.1788147452385885350 ) ) ; +#15949 = LINE ( 'NONE', #19617, #364 ) ; +#15950 = CARTESIAN_POINT ( 'NONE', ( -36.34630485966000890, 190.6271491411999932, 106.9111579357000039 ) ) ; +#15951 = ORIENTED_EDGE ( 'NONE', *, *, #8780, .F. ) ; +#15952 = LINE ( 'NONE', #37242, #34190 ) ; +#15953 = CARTESIAN_POINT ( 'NONE', ( 19.71701219870257304, 124.6133069866743455, 177.2811646003819135 ) ) ; +#15954 = FACE_OUTER_BOUND ( 'NONE', #8215, .T. ) ; +#15955 = EDGE_CURVE ( 'NONE', #25569, #11781, #30122, .T. ) ; +#15956 = FACE_OUTER_BOUND ( 'NONE', #7751, .T. ) ; +#15957 = EDGE_LOOP ( 'NONE', ( #38083, #9398, #35849, #8714, #8407, #11847, #18069, #21225, #14474, #16371, #18455 ) ) ; +#15958 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #28827, #3863, #19195, #1206 ), + ( #3661, #34925, #16739, #10233 ), + ( #601, #13684, #38017, #29023 ), + ( #6733, #32104, #13291, #28628 ), + ( #1002, #406, #12896, #22704 ), + ( #38419, #25370, #16342, #35123 ), + ( #22301, #7137, #10430, #34730 ), + ( #37820, #4058, #10632, #16530 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.06155209981437000100, 0.000000000000000000, 0.3333252697642999918, 0.6666627199550000382, 1.000000000000000000, 1.082818155623000100 ), + ( 3.677872018049000041E-08, 1.000452713559000006 ), + .UNSPECIFIED. ) ; +#15959 = EDGE_LOOP ( 'NONE', ( #25478, #26213, #27659, #5967 ) ) ; +#15960 = CARTESIAN_POINT ( 'NONE', ( -43.95866919468323886, 185.6592565981171390, 107.3047072462908460 ) ) ; +#15961 = CARTESIAN_POINT ( 'NONE', ( 22.25124494035251388, 115.1832291781610564, 87.25434509765634061 ) ) ; +#15962 = CARTESIAN_POINT ( 'NONE', ( -6.037441369385219581, 175.2421293076922382, 100.6275549983384394 ) ) ; +#15963 = CARTESIAN_POINT ( 'NONE', ( -33.70586835455132046, 218.5902260770999987, 73.07886158226766327 ) ) ; +#15964 = ORIENTED_EDGE ( 'NONE', *, *, #19855, .T. ) ; +#15966 = EDGE_LOOP ( 'NONE', ( #952, #11342, #32459, #30495, #24437, #27927, #35004 ) ) ; +#15965 = CC_DESIGN_APPROVAL ( #25220, ( #26440 ) ) ; +#15967 = AXIS2_PLACEMENT_3D ( 'NONE', #36323, #20994, #4628 ) ; +#15968 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 77.27946979429631824, 312.5857197240631535 ) ) ; +#15969 = EDGE_CURVE ( 'NONE', #16187, #25826, #36453, .T. ) ; +#15970 = CARTESIAN_POINT ( 'NONE', ( 12.31470871943427348, 134.6455694126359219, 93.46769794297644296 ) ) ; +#15971 = CARTESIAN_POINT ( 'NONE', ( 0.04593741417267090121, 271.9029643395999187, 76.05847688452558941 ) ) ; +#15972 = LINE ( 'NONE', #3698, #33325 ) ; +#15973 = AXIS2_PLACEMENT_3D ( 'NONE', #30395, #24685, #20782 ) ; +#15974 = DIRECTION ( 'NONE', ( -0.0005884956407902205500, 0.2249510534665960237, -0.9743698872692800883 ) ) ; +#15975 = ORIENTED_EDGE ( 'NONE', *, *, #38563, .T. ) ; +#15976 = DIRECTION ( 'NONE', ( 3.885780586188055465E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#15977 = EDGE_LOOP ( 'NONE', ( #3581, #29864 ) ) ; +#15978 = ORIENTED_EDGE ( 'NONE', *, *, #33775, .T. ) ; +#15979 = CARTESIAN_POINT ( 'NONE', ( -23.65441916643283804, 115.6781806121213236, 89.78203721638622881 ) ) ; +#15980 = CONICAL_SURFACE ( 'NONE', #1620, 2.503080714863939793, 0.7853981633931875761 ) ; +#15981 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#15982 = DIRECTION ( 'NONE', ( 0.7933533411653069800, 0.5931840316265230006, 0.1368326740407719011 ) ) ; +#15983 = EDGE_LOOP ( 'NONE', ( #23220, #25773, #31233, #29651, #5421 ) ) ; +#15984 = CARTESIAN_POINT ( 'NONE', ( -2.941972109285600379, 190.8911159914279949, 103.7220337298560082 ) ) ; +#15985 = CARTESIAN_POINT ( 'NONE', ( 1.988498828323496115, 189.0590404400041393, 103.2994412454972633 ) ) ; +#15986 = CARTESIAN_POINT ( 'NONE', ( 38.51366257970000362, 191.2261826337999935, 104.0342813249999949 ) ) ; +#15987 = CARTESIAN_POINT ( 'NONE', ( -8.191411996002011975, 161.3204080351630978, 97.07267131671726190 ) ) ; +#15988 = ADVANCED_FACE ( 'NONE', ( #33377 ), #25303, .T. ) ; +#15989 = ORIENTED_EDGE ( 'NONE', *, *, #28293, .F. ) ; +#15990 = DIRECTION ( 'NONE', ( -4.163336342515006295E-15, 0.9743700557921587402, 0.2249510932971554300 ) ) ; +#15991 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#15992 = ORIENTED_EDGE ( 'NONE', *, *, #28452, .T. ) ; +#15993 = FACE_OUTER_BOUND ( 'NONE', #13737, .T. ) ; +#15994 = CARTESIAN_POINT ( 'NONE', ( 36.14465427956680088, 191.5051434224318712, 103.8435392573484961 ) ) ; +#15995 = CARTESIAN_POINT ( 'NONE', ( -26.13596305067000003, 119.9704139356000070, 90.58392378377000398 ) ) ; +#15996 = ORIENTED_EDGE ( 'NONE', *, *, #3839, .T. ) ; +#15997 = EDGE_CURVE ( 'NONE', #19279, #10234, #9647, .T. ) ; +#15998 = CARTESIAN_POINT ( 'NONE', ( 2.804985645282946471, 189.7674754617468409, 106.5414161346845816 ) ) ; +#15999 = ADVANCED_FACE ( 'NONE', ( #15774 ), #39922, .T. ) ; +#16000 = FACE_OUTER_BOUND ( 'NONE', #30097, .T. ) ; +#16001 = CARTESIAN_POINT ( 'NONE', ( 35.04524255441999259, 226.4002260770880355, 73.53733772517182388 ) ) ; +#16002 = AXIS2_PLACEMENT_3D ( 'NONE', #36880, #27512, #39937 ) ; +#16003 = AXIS2_PLACEMENT_3D ( 'NONE', #28192, #5695, #37570 ) ; +#16004 = ORIENTED_EDGE ( 'NONE', *, *, #29295, .T. ) ; +#16005 = CIRCLE ( 'NONE', #23286, 2.000000000000011546 ) ; +#16006 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989941907, -0.1373964268091565077 ) ) ; +#16007 = DIRECTION ( 'NONE', ( -0.0006039748319387576447, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#16008 = VECTOR ( 'NONE', #33922, 1000.000000000000000 ) ; +#16010 = FACE_OUTER_BOUND ( 'NONE', #19447, .T. ) ; +#16009 = CARTESIAN_POINT ( 'NONE', ( -20.49846059232846684, 118.8155328640159070, 89.78014971369738362 ) ) ; +#16011 = ORIENTED_EDGE ( 'NONE', *, *, #24549, .F. ) ; +#16012 = CARTESIAN_POINT ( 'NONE', ( 38.90297999749881797, 118.7655883057561965, 89.66942185881842420 ) ) ; +#16013 = VERTEX_POINT ( 'NONE', #2729 ) ; +#16014 = PLANE ( 'NONE', #29740 ) ; +#16015 = LINE ( 'NONE', #84, #15832 ) ; +#16016 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18090, #6383, #36517, #29790 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16017 = PLANE ( 'NONE', #37773 ) ; +#16018 = ORIENTED_EDGE ( 'NONE', *, *, #38660, .T. ) ; +#16019 = VERTEX_POINT ( 'NONE', #37264 ) ; +#16020 = CARTESIAN_POINT ( 'NONE', ( 22.78111302661506343, 158.5316860073367593, 97.43644165524102618 ) ) ; +#16021 = CARTESIAN_POINT ( 'NONE', ( 22.63655809249918605, 181.7690946929418487, 101.6039534401006392 ) ) ; +#16022 = CARTESIAN_POINT ( 'NONE', ( 35.56356469037133650, 192.3002554099812471, 103.8734939767707885 ) ) ; +#16023 = ORIENTED_EDGE ( 'NONE', *, *, #15590, .T. ) ; +#16024 = ORIENTED_EDGE ( 'NONE', *, *, #33674, .T. ) ; +#16025 = DIRECTION ( 'NONE', ( -0.7933310414247657372, -0.5931044597393388962, -0.1373060761554398823 ) ) ; +#16026 = CARTESIAN_POINT ( 'NONE', ( -42.86867325711791921, 121.2310159755540155, 90.74611056646313045 ) ) ; +#16027 = FACE_OUTER_BOUND ( 'NONE', #31584, .T. ) ; +#16028 = AXIS2_PLACEMENT_3D ( 'NONE', #2395, #21203, #17292 ) ; +#16029 = VERTEX_POINT ( 'NONE', #18829 ) ; +#16030 = VERTEX_POINT ( 'NONE', #9261 ) ; +#16031 = CARTESIAN_POINT ( 'NONE', ( 1.752039179668178903, 151.6655327357930219, 130.5892088565730091 ) ) ; +#16032 = ORIENTED_EDGE ( 'NONE', *, *, #34590, .F. ) ; +#16033 = VECTOR ( 'NONE', #17580, 1000.000000000000114 ) ; +#16034 = VECTOR ( 'NONE', #37165, 1000.000000000000000 ) ; +#16035 = AXIS2_PLACEMENT_3D ( 'NONE', #3057, #3253, #3447 ) ; +#16036 = ORIENTED_EDGE ( 'NONE', *, *, #27793, .T. ) ; +#16037 = CARTESIAN_POINT ( 'NONE', ( -15.99998595512920652, 185.9065961375156348, 102.5825112407314634 ) ) ; +#16038 = ORIENTED_EDGE ( 'NONE', *, *, #9085, .T. ) ; +#16039 = CARTESIAN_POINT ( 'NONE', ( -31.86340836050871417, 157.9239924182404877, 186.3985076549964788 ) ) ; +#16040 = EDGE_CURVE ( 'NONE', #28366, #37711, #16804, .T. ) ; +#16041 = CARTESIAN_POINT ( 'NONE', ( -2.554995790067999817, 191.0434702462999894, 106.4538185388999949 ) ) ; +#16042 = CARTESIAN_POINT ( 'NONE', ( 37.33701730692213516, 104.0256123824346446, 184.2143347311343859 ) ) ; +#16043 = VERTEX_POINT ( 'NONE', #40118 ) ; +#16044 = DIRECTION ( 'NONE', ( -0.0006039748319377451083, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#16046 = EDGE_CURVE ( 'NONE', #11449, #5782, #12129, .T. ) ; +#16045 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#16047 = EDGE_CURVE ( 'NONE', #37167, #7673, #9661, .T. ) ; +#16048 = LINE ( 'NONE', #910, #11427 ) ; +#16049 = CARTESIAN_POINT ( 'NONE', ( 19.46059643144436535, 126.3442427331793141, 175.5385488862945635 ) ) ; +#16050 = EDGE_CURVE ( 'NONE', #6998, #19028, #31837, .T. ) ; +#16051 = EDGE_CURVE ( 'NONE', #23911, #18328, #33773, .T. ) ; +#16052 = CARTESIAN_POINT ( 'NONE', ( 35.88952463556218930, 77.14301703112145958, 291.5368675616688279 ) ) ; +#16053 = VERTEX_POINT ( 'NONE', #24615 ) ; +#16054 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#16055 = ORIENTED_EDGE ( 'NONE', *, *, #38180, .F. ) ; +#16056 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28226, #18382, #21282, #9609 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16057 = CARTESIAN_POINT ( 'NONE', ( 22.68638433482282935, 158.3069331428809221, 96.18725556137884780 ) ) ; +#16058 = VECTOR ( 'NONE', #18715, 1000.000000000000000 ) ; +#16059 = AXIS2_PLACEMENT_3D ( 'NONE', #915, #26280, #10733 ) ; +#16060 = CARTESIAN_POINT ( 'NONE', ( -37.60586764323186060, 218.5902260770999987, 73.08121708413273154 ) ) ; +#16061 = ORIENTED_EDGE ( 'NONE', *, *, #18182, .T. ) ; +#16062 = CYLINDRICAL_SURFACE ( 'NONE', #11238, 30.00000000000001066 ) ; +#16063 = ORIENTED_EDGE ( 'NONE', *, *, #36774, .T. ) ; +#16065 = AXIS2_PLACEMENT_3D ( 'NONE', #15812, #19277, #9492 ) ; +#16064 = LINE ( 'NONE', #32021, #31032 ) ; +#16066 = CARTESIAN_POINT ( 'NONE', ( -26.06164500446789134, 121.6777288763670128, 87.76017847578864917 ) ) ; +#16067 = VECTOR ( 'NONE', #23999, 1000.000000000000000 ) ; +#16068 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16069 = VERTEX_POINT ( 'NONE', #34179 ) ; +#16070 = CARTESIAN_POINT ( 'NONE', ( 26.00081424259415641, 120.1020648120652510, 90.44388058125247198 ) ) ; +#16071 = ORIENTED_EDGE ( 'NONE', *, *, #30527, .T. ) ; +#16072 = ORIENTED_EDGE ( 'NONE', *, *, #21373, .F. ) ; +#16073 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250909262, 179.1753088544093657, 103.5954339977318739 ) ) ; +#16074 = ADVANCED_FACE ( 'NONE', ( #2908 ), #6376, .T. ) ; +#16075 = CYLINDRICAL_SURFACE ( 'NONE', #32632, 8.000000000000007105 ) ; +#16076 = ORIENTED_EDGE ( 'NONE', *, *, #15722, .F. ) ; +#16077 = CARTESIAN_POINT ( 'NONE', ( -25.50845318152657981, 205.7388967348897495, 75.91153402304078668 ) ) ; +#16078 = ORIENTED_EDGE ( 'NONE', *, *, #34002, .T. ) ; +#16079 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -0.000000000000000000, 0.0006039748319387908213 ) ) ; +#16080 = DIRECTION ( 'NONE', ( 0.0005884949961241158715, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16081 = DIRECTION ( 'NONE', ( 0.7075337269410153507, -2.187927502986928824E-15, 0.7066795774896545979 ) ) ; +#16082 = ORIENTED_EDGE ( 'NONE', *, *, #18430, .F. ) ; +#16083 = CARTESIAN_POINT ( 'NONE', ( 27.93899438949999947, 125.0366658260000037, 88.67409159612999758 ) ) ; +#16084 = ADVANCED_FACE ( 'NONE', ( #22137 ), #11605, .F. ) ; +#16085 = AXIS2_PLACEMENT_3D ( 'NONE', #15753, #15562, #21522 ) ; +#16086 = DIRECTION ( 'NONE', ( -7.115269692215706960E-15, 0.9743043966640313469, 0.2252353050503801690 ) ) ; +#16087 = CARTESIAN_POINT ( 'NONE', ( -20.00007258987272252, 169.9137872412887873, 98.89276590963629587 ) ) ; +#16088 = CARTESIAN_POINT ( 'NONE', ( 2.544461030880475594, 209.0000001909309901, 73.61327617014224245 ) ) ; +#16089 = CARTESIAN_POINT ( 'NONE', ( 20.49589212329804155, 159.2510479451992467, 96.40654468016703049 ) ) ; +#16090 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #23397, #22999, #7433, #19894 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.0004791655021827933257, 1.570796326795345532 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8048507809858619355, 0.8048507809858619355, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#16091 = VECTOR ( 'NONE', #8992, 1000.000000000000000 ) ; +#16092 = ORIENTED_EDGE ( 'NONE', *, *, #20062, .T. ) ; +#16093 = CARTESIAN_POINT ( 'NONE', ( 20.00171108015191024, 119.7153632178993377, 90.35824133875276232 ) ) ; +#16094 = EDGE_CURVE ( 'NONE', #36696, #21313, #10639, .T. ) ; +#16095 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25865, #19290, #28714, #13182 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16096 = DIRECTION ( 'NONE', ( 0.0005884949961209496759, -0.2249510543439030841, 0.9743698870671270162 ) ) ; +#16097 = CARTESIAN_POINT ( 'NONE', ( 25.49226348177107582, 205.5673819639667954, 76.28481786455526503 ) ) ; +#16098 = AXIS2_PLACEMENT_3D ( 'NONE', #1670, #13736, #1458 ) ; +#16099 = EDGE_CURVE ( 'NONE', #31534, #27880, #38991, .T. ) ; +#16100 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490314253413, 156.2427122711482070, 96.23754757943429183 ) ) ; +#16101 = CARTESIAN_POINT ( 'NONE', ( 38.47940687698435624, 119.0232181275810603, 90.24981979719966318 ) ) ; +#16102 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7512, #38995, #4443, #16897 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0008238168743097512266, 0.002797249353616942501 ), + .UNSPECIFIED. ) ; +#16103 = CARTESIAN_POINT ( 'NONE', ( -25.84447102352329750, 211.0902258593999932, 75.91014019561482939 ) ) ; +#16104 = LINE ( 'NONE', #31865, #35939 ) ; +#16105 = CARTESIAN_POINT ( 'NONE', ( 12.63850902179698998, 181.2597007827056643, 104.3624407909059784 ) ) ; +#16106 = ADVANCED_FACE ( 'NONE', ( #27888 ), #30936, .F. ) ; +#16107 = CARTESIAN_POINT ( 'NONE', ( -25.50638302354030174, 190.9262359218180052, 106.3111740386750057 ) ) ; +#16108 = VERTEX_POINT ( 'NONE', #28272 ) ; +#16109 = CARTESIAN_POINT ( 'NONE', ( -15.99974174651862313, 174.5231975350379514, 99.95452847233616467 ) ) ; +#16110 = CARTESIAN_POINT ( 'NONE', ( -16.17928014215196342, 122.0409702652264770, 178.1070844152368409 ) ) ; +#16111 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265226676, -0.1368326740407719011 ) ) ; +#16112 = CARTESIAN_POINT ( 'NONE', ( 2.545655555827734950, 209.1852808049790156, 75.59112338335545189 ) ) ; +#16113 = LINE ( 'NONE', #1173, #19150 ) ; +#16114 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38671, #35194, #19859, #35798 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 3.356945441522706129E-06, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16115 = CARTESIAN_POINT ( 'NONE', ( -13.46995280217765156, 158.2275496627099756, 98.75652669741377565 ) ) ; +#16116 = VECTOR ( 'NONE', #40235, 1000.000000000000000 ) ; +#16117 = CARTESIAN_POINT ( 'NONE', ( -8.622914549094021552, 190.8510648561669996, 106.7984846684352931 ) ) ; +#16118 = CARTESIAN_POINT ( 'NONE', ( 36.06383348468500571, 192.3733900160179928, 104.3179881943819822 ) ) ; +#16119 = VECTOR ( 'NONE', #4450, 1000.000000000000000 ) ; +#16120 = CARTESIAN_POINT ( 'NONE', ( -39.73142568412256992, 175.7232364642230777, 136.1664758066176830 ) ) ; +#16121 = ORIENTED_EDGE ( 'NONE', *, *, #22339, .T. ) ; +#16122 = FACE_OUTER_BOUND ( 'NONE', #37753, .T. ) ; +#16123 = PLANE ( 'NONE', #728 ) ; +#16124 = VECTOR ( 'NONE', #20296, 1000.000000000000114 ) ; +#16125 = CARTESIAN_POINT ( 'NONE', ( -35.93657501960694134, 192.7057386088000044, 106.3835760624021702 ) ) ; +#16126 = VERTEX_POINT ( 'NONE', #15197 ) ; +#16127 = CARTESIAN_POINT ( 'NONE', ( 19.99579756797234253, 191.9758059840616227, 101.9094256439181407 ) ) ; +#16128 = ORIENTED_EDGE ( 'NONE', *, *, #5210, .F. ) ; +#16129 = FACE_OUTER_BOUND ( 'NONE', #10433, .T. ) ; +#16130 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#16131 = CARTESIAN_POINT ( 'NONE', ( -36.31535185967262436, 190.8511613781771530, 106.8152324789805903 ) ) ; +#16132 = CARTESIAN_POINT ( 'NONE', ( -36.39991929748588717, 191.7382947397175599, 104.3966283125774623 ) ) ; +#16133 = EDGE_CURVE ( 'NONE', #6360, #33655, #15581, .T. ) ; +#16134 = CARTESIAN_POINT ( 'NONE', ( 17.27264158547648165, 121.9609240029174941, 174.6061468887760668 ) ) ; +#16135 = EDGE_CURVE ( 'NONE', #2293, #29235, #8336, .T. ) ; +#16137 = EDGE_CURVE ( 'NONE', #16794, #34336, #13599, .T. ) ; +#16136 = CARTESIAN_POINT ( 'NONE', ( 13.47462245814947934, 158.2310456470601423, 98.74105996008697161 ) ) ; +#16138 = CARTESIAN_POINT ( 'NONE', ( 13.81050778898542220, 149.9387330909817422, 180.4582364612731453 ) ) ; +#16139 = ADVANCED_FACE ( 'NONE', ( #7179 ), #32531, .F. ) ; +#16140 = CARTESIAN_POINT ( 'NONE', ( -30.06788429262541484, 177.0224639546494245, 103.4955571594761921 ) ) ; +#16141 = CARTESIAN_POINT ( 'NONE', ( -13.47112979352495543, 158.6774517721759139, 96.80778692315055878 ) ) ; +#16142 = ORIENTED_EDGE ( 'NONE', *, *, #10916, .F. ) ; +#16143 = ORIENTED_EDGE ( 'NONE', *, *, #21842, .F. ) ; +#16144 = LINE ( 'NONE', #596, #19994 ) ; +#16145 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971551802 ) ) ; +#16146 = EDGE_CURVE ( 'NONE', #11146, #9209, #37001, .T. ) ; +#16147 = AXIS2_PLACEMENT_3D ( 'NONE', #239, #37066, #24412 ) ; +#16148 = CARTESIAN_POINT ( 'NONE', ( -22.78280640698083559, 157.8259455793779864, 99.01153522024156928 ) ) ; +#16149 = EDGE_LOOP ( 'NONE', ( #17281, #28062, #9496, #25422 ) ) ; +#16150 = CYLINDRICAL_SURFACE ( 'NONE', #34208, 22.50000000000000000 ) ; +#16151 = VERTEX_POINT ( 'NONE', #34960 ) ; +#16152 = CIRCLE ( 'NONE', #27914, 40.00000000000073186 ) ; +#16153 = ADVANCED_FACE ( 'NONE', ( #842 ), #35167, .T. ) ; +#16154 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32926, #32735, #35986, #17584, #23745, #17378, #35773, #2274, #30085, #24162 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 7.859448383017418837E-15, 0.0004322186000195859384, 0.0008644372000313124953, 0.001296655800043038835, 0.001728874400054765392 ), + .UNSPECIFIED. ) ; +#16155 = CARTESIAN_POINT ( 'NONE', ( 19.99993950111425889, 196.1317665718410410, 104.7318359668413450 ) ) ; +#16156 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 166.8945455544008780, 183.3579980745095952 ) ) ; +#16157 = CARTESIAN_POINT ( 'NONE', ( 35.56356469037133650, 192.3002554099812471, 103.8734939767707885 ) ) ; +#16158 = FACE_OUTER_BOUND ( 'NONE', #13867, .T. ) ; +#16159 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 177.2126930573676304, 102.0942813187813982 ) ) ; +#16160 = EDGE_CURVE ( 'NONE', #13020, #12345, #35696, .T. ) ; +#16161 = CARTESIAN_POINT ( 'NONE', ( 20.48171464736319436, 206.1150451720382364, 75.33802399314664910 ) ) ; +#16162 = CARTESIAN_POINT ( 'NONE', ( 38.13598105415000106, 118.9081287641000131, 90.39876254777999520 ) ) ; +#16163 = ORIENTED_EDGE ( 'NONE', *, *, #34057, .T. ) ; +#16164 = CARTESIAN_POINT ( 'NONE', ( -28.53208073851174476, 125.2791694434640135, 88.59312828080875590 ) ) ; +#16165 = CARTESIAN_POINT ( 'NONE', ( 19.71680892478428859, 124.9569912405921883, 175.7901266015387023 ) ) ; +#16166 = CARTESIAN_POINT ( 'NONE', ( -45.16400980236513618, 70.91888486856629470, 322.7789803297500839 ) ) ; +#16167 = LINE ( 'NONE', #24599, #2981 ) ; +#16168 = ORIENTED_EDGE ( 'NONE', *, *, #18303, .T. ) ; +#16169 = EDGE_LOOP ( 'NONE', ( #24264, #17999, #14757, #14647 ) ) ; +#16170 = DIRECTION ( 'NONE', ( 0.0005884949961248158324, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16171 = AXIS2_PLACEMENT_3D ( 'NONE', #29014, #18992, #38412 ) ; +#16172 = CARTESIAN_POINT ( 'NONE', ( -30.05261220888372975, 126.8329673478291397, 91.51853052256073795 ) ) ; +#16173 = EDGE_LOOP ( 'NONE', ( #32067, #7131, #20492, #18659, #38634, #19688 ) ) ; +#16174 = ORIENTED_EDGE ( 'NONE', *, *, #25267, .T. ) ; +#16175 = CARTESIAN_POINT ( 'NONE', ( 35.55352078495887724, 112.9281706801280194, 87.24630913759760631 ) ) ; +#16176 = CARTESIAN_POINT ( 'NONE', ( -38.61757737722999906, 118.8204316123000126, 89.90765668362000440 ) ) ; +#16177 = FACE_OUTER_BOUND ( 'NONE', #18353, .T. ) ; +#16178 = FACE_OUTER_BOUND ( 'NONE', #33433, .T. ) ; +#16179 = ORIENTED_EDGE ( 'NONE', *, *, #36454, .T. ) ; +#16180 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319388799427 ) ) ; +#16181 = ORIENTED_EDGE ( 'NONE', *, *, #895, .F. ) ; +#16182 = EDGE_CURVE ( 'NONE', #36222, #38924, #31945, .T. ) ; +#16183 = CARTESIAN_POINT ( 'NONE', ( -25.43497462449660063, 117.4586649291000526, 89.78312114523609466 ) ) ; +#16184 = EDGE_CURVE ( 'NONE', #17805, #10259, #25412, .T. ) ; +#16185 = CARTESIAN_POINT ( 'NONE', ( -20.07947113715306386, 184.2548677810397635, 102.2036388924518207 ) ) ; +#16186 = CARTESIAN_POINT ( 'NONE', ( -22.63655565215235299, 130.9412805326379612, 89.89676961200316896 ) ) ; +#16187 = VERTEX_POINT ( 'NONE', #3907 ) ; +#16188 = CARTESIAN_POINT ( 'NONE', ( -2.771763471025999959, 190.8679547378000336, 103.8875947975000003 ) ) ; +#16189 = CARTESIAN_POINT ( 'NONE', ( 2.549069100720744441, 189.5938708632902774, 103.4225780300034643 ) ) ; +#16190 = DIRECTION ( 'NONE', ( -0.6087906217132950104, 0.7729786229956039367, 0.1785441886642067377 ) ) ; +#16191 = ORIENTED_EDGE ( 'NONE', *, *, #36359, .F. ) ; +#16192 = CARTESIAN_POINT ( 'NONE', ( 20.39650128425949305, 118.1111548655870536, 87.65155641249134533 ) ) ; +#16193 = LINE ( 'NONE', #25025, #34356 ) ; +#16194 = ORIENTED_EDGE ( 'NONE', *, *, #12359, .F. ) ; +#16195 = DIRECTION ( 'NONE', ( 0.7856246208753498994, 0.6187034467937467808, 0.000000000000000000 ) ) ; +#16196 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971545696 ) ) ; +#16197 = CARTESIAN_POINT ( 'NONE', ( -27.74595536588000400, 123.8455685898999974, 91.47954628734001403 ) ) ; +#16198 = CIRCLE ( 'NONE', #9038, 2.749999999927935423 ) ; +#16199 = VERTEX_POINT ( 'NONE', #38452 ) ; +#16200 = DIRECTION ( 'NONE', ( 0.0005884949672441799938, -0.2249510543775923299, 0.9743698870593667793 ) ) ; +#16201 = CARTESIAN_POINT ( 'NONE', ( -16.78807852584197491, 121.7176299279596208, 177.2134147146401233 ) ) ; +#16202 = CARTESIAN_POINT ( 'NONE', ( -19.99827944177191341, 118.8155627782461181, 90.27982142893266371 ) ) ; +#16203 = CARTESIAN_POINT ( 'NONE', ( -3.488613621442726576, 125.5688127946150985, 88.64487260003835445 ) ) ; +#16204 = EDGE_CURVE ( 'NONE', #37821, #26262, #14853, .T. ) ; +#16205 = VERTEX_POINT ( 'NONE', #443 ) ; +#16206 = CARTESIAN_POINT ( 'NONE', ( 26.00310484108860010, 120.1790658327160060, 90.46504372733748767 ) ) ; +#16207 = CARTESIAN_POINT ( 'NONE', ( 16.55946513390808406, 121.8573583107191780, 177.5776958584335148 ) ) ; +#16208 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16210 = CARTESIAN_POINT ( 'NONE', ( -13.49845036060215975, 187.8662283970866724, 103.4406284738125095 ) ) ; +#16209 = CARTESIAN_POINT ( 'NONE', ( -28.25571780481785567, 186.4543157461568228, 105.2821206686522686 ) ) ; +#16211 = DIRECTION ( 'NONE', ( -0.0005959779364584452156, -0.1621899515575390416, -0.9867593751386719569 ) ) ; +#16212 = ORIENTED_EDGE ( 'NONE', *, *, #3720, .F. ) ; +#16213 = CARTESIAN_POINT ( 'NONE', ( -30.04735478916544977, 185.8115295537965892, 102.7400937164344725 ) ) ; +#16214 = CARTESIAN_POINT ( 'NONE', ( -31.91217790952610756, 137.5486857473001407, 93.99357256101205849 ) ) ; +#16215 = FACE_OUTER_BOUND ( 'NONE', #25090, .T. ) ; +#16216 = CARTESIAN_POINT ( 'NONE', ( 28.64682496188636307, 225.5077044860236981, 75.54120257392457916 ) ) ; +#16217 = ORIENTED_EDGE ( 'NONE', *, *, #34449, .F. ) ; +#16218 = ORIENTED_EDGE ( 'NONE', *, *, #14624, .T. ) ; +#16219 = CARTESIAN_POINT ( 'NONE', ( 2.463364856792551905, 209.5677208948551993, 75.55701285043443249 ) ) ; +#16220 = AXIS2_PLACEMENT_3D ( 'NONE', #12312, #25007, #15191 ) ; +#16221 = CARTESIAN_POINT ( 'NONE', ( -46.70670256065962889, 123.1338644119410617, 91.82415844558849471 ) ) ; +#16222 = DIRECTION ( 'NONE', ( 0.6087611434178770153, 0.7731004625452604362, 0.1781166614240885793 ) ) ; +#16223 = CARTESIAN_POINT ( 'NONE', ( 35.98964030471999820, 192.0251590663000343, 104.2273425422000059 ) ) ; +#16224 = EDGE_LOOP ( 'NONE', ( #25598, #24977, #28242, #31855 ) ) ; +#16225 = EDGE_LOOP ( 'NONE', ( #16572, #22028, #27112, #25198 ) ) ; +#16226 = AXIS2_PLACEMENT_3D ( 'NONE', #26981, #5482, #23701 ) ; +#16227 = ORIENTED_EDGE ( 'NONE', *, *, #22104, .T. ) ; +#16228 = CARTESIAN_POINT ( 'NONE', ( 77.76885812527426367, 193.5821525182410880, 188.5104908262173637 ) ) ; +#16229 = EDGE_CURVE ( 'NONE', #21313, #11228, #12934, .T. ) ; +#16230 = CARTESIAN_POINT ( 'NONE', ( -23.36114798465503029, 134.5341053823447339, 93.55485419817190973 ) ) ; +#16231 = EDGE_CURVE ( 'NONE', #38615, #267, #29066, .T. ) ; +#16232 = FACE_OUTER_BOUND ( 'NONE', #40314, .T. ) ; +#16233 = ORIENTED_EDGE ( 'NONE', *, *, #8058, .F. ) ; +#16234 = ORIENTED_EDGE ( 'NONE', *, *, #9689, .T. ) ; +#16235 = LINE ( 'NONE', #13186, #21958 ) ; +#16236 = ORIENTED_EDGE ( 'NONE', *, *, #33627, .T. ) ; +#16237 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490291018744, 156.2427122711393395, 96.23754757947276062 ) ) ; +#16238 = ORIENTED_EDGE ( 'NONE', *, *, #21573, .T. ) ; +#16239 = CARTESIAN_POINT ( 'NONE', ( -13.82477833516488275, 124.3657273933217056, 88.37336118349627156 ) ) ; +#16240 = CARTESIAN_POINT ( 'NONE', ( -3.002001848952000174, 190.1395903318000080, 106.7780402845999959 ) ) ; +#16241 = LINE ( 'NONE', #38133, #29343 ) ; +#16242 = ORIENTED_EDGE ( 'NONE', *, *, #39861, .F. ) ; +#16243 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#16244 = CARTESIAN_POINT ( 'NONE', ( 13.49999902183750322, 160.7426630972690020, 96.75207176916120488 ) ) ; +#16245 = CARTESIAN_POINT ( 'NONE', ( 20.99968489185805964, 213.3366701443009106, 73.04582079892783497 ) ) ; +#16246 = FACE_OUTER_BOUND ( 'NONE', #37411, .T. ) ; +#16247 = AXIS2_PLACEMENT_3D ( 'NONE', #5928, #27832, #16130 ) ; +#16248 = CARTESIAN_POINT ( 'NONE', ( 30.44899456515794256, 126.4319216541827728, 91.90255247881687239 ) ) ; +#16249 = VERTEX_POINT ( 'NONE', #1241 ) ; +#16250 = CARTESIAN_POINT ( 'NONE', ( -46.39364199823201318, 124.7770151420462525, 91.05374585112593877 ) ) ; +#16251 = VECTOR ( 'NONE', #29935, 1000.000000000000227 ) ; +#16252 = VECTOR ( 'NONE', #21916, 1000.000000000000114 ) ; +#16253 = CARTESIAN_POINT ( 'NONE', ( -15.66646869924428032, 126.7256369811235714, 89.26140537028169319 ) ) ; +#16254 = CONICAL_SURFACE ( 'NONE', #8436, 4.999999999930198946, 0.7853981634432324332 ) ; +#16255 = DIRECTION ( 'NONE', ( 0.9999998268367997767, 0.0001323825946806684044, -0.0005734119104333256422 ) ) ; +#16256 = ORIENTED_EDGE ( 'NONE', *, *, #35730, .F. ) ; +#16257 = ORIENTED_EDGE ( 'NONE', *, *, #23630, .T. ) ; +#16258 = CARTESIAN_POINT ( 'NONE', ( 11.75690610893360422, 158.5518943791668676, 96.25041046018972679 ) ) ; +#16259 = EDGE_CURVE ( 'NONE', #12706, #27940, #34765, .T. ) ; +#16260 = CARTESIAN_POINT ( 'NONE', ( -38.38649509150999961, 190.6638049979000016, 106.5166526994999998 ) ) ; +#16261 = FACE_OUTER_BOUND ( 'NONE', #7364, .T. ) ; +#16262 = FACE_OUTER_BOUND ( 'NONE', #17116, .T. ) ; +#16263 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319356112900 ) ) ; +#16264 = VERTEX_POINT ( 'NONE', #25813 ) ; +#16265 = ORIENTED_EDGE ( 'NONE', *, *, #16359, .F. ) ; +#16266 = EDGE_LOOP ( 'NONE', ( #16461, #33026, #14970, #15, #8301, #36722, #33514, #6570, #32938 ) ) ; +#16267 = CARTESIAN_POINT ( 'NONE', ( -20.00006118649763209, 147.3680339623835209, 93.68765596609371471 ) ) ; +#16268 = EDGE_CURVE ( 'NONE', #11987, #22385, #21868, .T. ) ; +#16269 = CARTESIAN_POINT ( 'NONE', ( 36.05352243695642755, 118.8155670042997087, 87.24600886789973231 ) ) ; +#16270 = EDGE_LOOP ( 'NONE', ( #745, #21803, #24231, #15394, #19722 ) ) ; +#16271 = ORIENTED_EDGE ( 'NONE', *, *, #5847, .F. ) ; +#16272 = CARTESIAN_POINT ( 'NONE', ( 40.13009284222664519, 84.66001446739429070, 280.9279456820921723 ) ) ; +#16273 = EDGE_CURVE ( 'NONE', #30422, #39309, #4098, .T. ) ; +#16274 = CARTESIAN_POINT ( 'NONE', ( -38.57146445400000090, 119.0360826316999976, 90.16028290594999817 ) ) ; +#16275 = EDGE_CURVE ( 'NONE', #2569, #16955, #26214, .T. ) ; +#16276 = ORIENTED_EDGE ( 'NONE', *, *, #1179, .T. ) ; +#16277 = CARTESIAN_POINT ( 'NONE', ( 2.943104451508621544, 209.7096517725655644, 76.05672380837390278 ) ) ; +#16278 = EDGE_CURVE ( 'NONE', #6308, #17976, #33581, .T. ) ; +#16279 = AXIS2_PLACEMENT_3D ( 'NONE', #24051, #2377, #30791 ) ; +#16280 = ADVANCED_FACE ( 'NONE', ( #8617 ), #24038, .T. ) ; +#16281 = DIRECTION ( 'NONE', ( -0.7933533419755064431, 0.5930537050706157221, 0.1373964252748610115 ) ) ; +#16282 = VERTEX_POINT ( 'NONE', #39458 ) ; +#16283 = CARTESIAN_POINT ( 'NONE', ( 28.18055532800000051, 125.5349220596000066, 89.13115644789000669 ) ) ; +#16284 = AXIS2_PLACEMENT_3D ( 'NONE', #17545, #27199, #26990 ) ; +#16285 = CARTESIAN_POINT ( 'NONE', ( 25.02112415033897364, 129.9425189845125601, 92.71631651849574496 ) ) ; +#16286 = CARTESIAN_POINT ( 'NONE', ( 94.49328988966108511, 77.27448630901744764, 291.5014723559426670 ) ) ; +#16287 = CARTESIAN_POINT ( 'NONE', ( 23.68617301077875581, 136.6832543673160956, 94.27334322351919127 ) ) ; +#16288 = CIRCLE ( 'NONE', #29993, 4.500000000039500847 ) ; +#16289 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#16290 = ORIENTED_EDGE ( 'NONE', *, *, #9829, .T. ) ; +#16291 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 77.27946979429628982, 310.0857197240630967 ) ) ; +#16292 = CARTESIAN_POINT ( 'NONE', ( 1.086103810833373817, 189.0697198636973724, 103.7041996269950772 ) ) ; +#16293 = CARTESIAN_POINT ( 'NONE', ( -38.57146895724624613, 191.0388322217830250, 103.7810094805231387 ) ) ; +#16294 = CARTESIAN_POINT ( 'NONE', ( 12.63723266175987270, 130.1298785553014739, 92.46781221652395288 ) ) ; +#16295 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16296 = FACE_OUTER_BOUND ( 'NONE', #441, .T. ) ; +#16297 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319391458975 ) ) ; +#16298 = ADVANCED_FACE ( 'NONE', ( #39058 ), #23532, .T. ) ; +#16299 = CARTESIAN_POINT ( 'NONE', ( 45.36643772877659586, 116.4348306700458124, 122.4284095016645608 ) ) ; +#16300 = ORIENTED_EDGE ( 'NONE', *, *, #32495, .F. ) ; +#16301 = CARTESIAN_POINT ( 'NONE', ( 17.99794026751194309, 132.4103114830704442, 92.77714071222307268 ) ) ; +#16302 = CARTESIAN_POINT ( 'NONE', ( -19.44522627092439038, 148.1589718280038710, 181.5720362247187438 ) ) ; +#16303 = ORIENTED_EDGE ( 'NONE', *, *, #18563, .F. ) ; +#16304 = CARTESIAN_POINT ( 'NONE', ( -43.65360665174738841, 185.3905100451317765, 107.6115822775834374 ) ) ; +#16305 = VECTOR ( 'NONE', #19729, 1000.000000000000227 ) ; +#16306 = CARTESIAN_POINT ( 'NONE', ( -38.20405560931869360, 218.5902260770999987, 76.08157892187939808 ) ) ; +#16307 = CARTESIAN_POINT ( 'NONE', ( 20.81480888314487387, 116.8538579756977924, 87.75498164167572668 ) ) ; +#16308 = PLANE ( 'NONE', #19206 ) ; +#16309 = EDGE_CURVE ( 'NONE', #39281, #20371, #39017, .T. ) ; +#16310 = AXIS2_PLACEMENT_3D ( 'NONE', #7710, #29601, #20173 ) ; +#16311 = FACE_OUTER_BOUND ( 'NONE', #357, .T. ) ; +#16312 = CARTESIAN_POINT ( 'NONE', ( 36.06507820818748655, 192.5954166247090313, 106.3788509914820111 ) ) ; +#16313 = CONICAL_SURFACE ( 'NONE', #21565, 6.499999999924747307, 0.7853981633862021638 ) ; +#16314 = CARTESIAN_POINT ( 'NONE', ( 36.14095822016396653, 114.4249042674252763, 87.72551690086099541 ) ) ; +#16315 = CONICAL_SURFACE ( 'NONE', #39171, 2.500000339008657146, 0.7853981633778087668 ) ; +#16316 = CARTESIAN_POINT ( 'NONE', ( 35.43506417528000441, 192.9711071536000020, 106.9376191850000026 ) ) ; +#16317 = ORIENTED_EDGE ( 'NONE', *, *, #16853, .F. ) ; +#16318 = CARTESIAN_POINT ( 'NONE', ( 20.50028285398298777, 191.4126458000098978, 104.3447517631808097 ) ) ; +#16319 = EDGE_CURVE ( 'NONE', #14084, #28366, #39261, .T. ) ; +#16320 = DIRECTION ( 'NONE', ( 0.4303597330247870278, 0.7060138277436147636, -0.5624366410767025481 ) ) ; +#16321 = EDGE_CURVE ( 'NONE', #39083, #30155, #11438, .T. ) ; +#16322 = CARTESIAN_POINT ( 'NONE', ( 20.49369975149401668, 199.8820069588898320, 94.80039694518488602 ) ) ; +#16323 = ORIENTED_EDGE ( 'NONE', *, *, #39623, .T. ) ; +#16324 = CARTESIAN_POINT ( 'NONE', ( 24.86285456769096669, 182.2983400162870851, 101.7247947455283992 ) ) ; +#16325 = ADVANCED_FACE ( 'NONE', ( #36410 ), #28593, .T. ) ; +#16326 = VERTEX_POINT ( 'NONE', #23341 ) ; +#16327 = ADVANCED_FACE ( 'NONE', ( #36194 ), #10961, .F. ) ; +#16328 = CARTESIAN_POINT ( 'NONE', ( -5.663464557155529988, 131.0206703453534374, 89.90489628355439322 ) ) ; +#16329 = DIRECTION ( 'NONE', ( -0.7066905234128858515, -0.1590644159615968445, 0.6894106292284863935 ) ) ; +#16330 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023854076 ) ) ; +#16331 = CARTESIAN_POINT ( 'NONE', ( -23.35716082638948521, 130.0938126195854636, 92.43835990256307866 ) ) ; +#16332 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384538513 ) ) ; +#16333 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14659, #38759, #20777, #23857 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16334 = CARTESIAN_POINT ( 'NONE', ( -20.02002437005085511, 209.7095682957761085, 73.07054393135327075 ) ) ; +#16335 = ORIENTED_EDGE ( 'NONE', *, *, #29824, .T. ) ; +#16336 = CARTESIAN_POINT ( 'NONE', ( 39.76816811907257687, 175.4177889136913109, 159.9692080044317493 ) ) ; +#16337 = CONICAL_SURFACE ( 'NONE', #35907, 2.499999999965141662, 0.7853981634008656565 ) ; +#16338 = CARTESIAN_POINT ( 'NONE', ( -3.837388691982094091, 176.5591841211374629, 100.4171401915558306 ) ) ; +#16339 = CARTESIAN_POINT ( 'NONE', ( 5.668111417580466771, 183.4499515673966812, 105.0842738006407018 ) ) ; +#16340 = VECTOR ( 'NONE', #17457, 1000.000000000000000 ) ; +#16341 = AXIS2_PLACEMENT_3D ( 'NONE', #33289, #5487, #26779 ) ; +#16342 = CARTESIAN_POINT ( 'NONE', ( -36.29868172540000160, 191.6823464439000020, 104.2736944691999952 ) ) ; +#16343 = ORIENTED_EDGE ( 'NONE', *, *, #30497, .T. ) ; +#16344 = DIRECTION ( 'NONE', ( -0.1305262373691799260, -0.9659798014921964215, -0.2232620085624539286 ) ) ; +#16345 = ORIENTED_EDGE ( 'NONE', *, *, #26864, .T. ) ; +#16346 = CARTESIAN_POINT ( 'NONE', ( 3.847675889067868393, 147.9886445650915618, 129.7371189396918680 ) ) ; +#16347 = PLANE ( 'NONE', #9716 ) ; +#16348 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18859, #28497, #6596, #16209 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16349 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319417801836 ) ) ; +#16350 = CARTESIAN_POINT ( 'NONE', ( -37.29638110713771226, 178.8156383198445667, 136.8789424484697008 ) ) ; +#16351 = CARTESIAN_POINT ( 'NONE', ( 20.48073942642239942, 207.7074378936182768, 74.00492349107967982 ) ) ; +#16352 = CARTESIAN_POINT ( 'NONE', ( 38.50820439054000133, 118.5727785117999957, 89.80762991176000298 ) ) ; +#16353 = ORIENTED_EDGE ( 'NONE', *, *, #1089, .T. ) ; +#16354 = EDGE_CURVE ( 'NONE', #26865, #12152, #20669, .T. ) ; +#16355 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16356 = EDGE_CURVE ( 'NONE', #7827, #38615, #23954, .T. ) ; +#16357 = CARTESIAN_POINT ( 'NONE', ( -36.44242984183888723, 191.5061647249781061, 106.4038886115175728 ) ) ; +#16358 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 181.0156285263394125, 104.5149534146526236 ) ) ; +#16359 = EDGE_CURVE ( 'NONE', #26011, #16791, #35727, .T. ) ; +#16360 = CARTESIAN_POINT ( 'NONE', ( -20.50046838666520799, 193.8411600273693978, 103.5994668550054314 ) ) ; +#16361 = ORIENTED_EDGE ( 'NONE', *, *, #37118, .F. ) ; +#16362 = VERTEX_POINT ( 'NONE', #17582 ) ; +#16363 = VECTOR ( 'NONE', #1919, 1000.000000000000000 ) ; +#16364 = VECTOR ( 'NONE', #6548, 1000.000000000000227 ) ; +#16365 = ORIENTED_EDGE ( 'NONE', *, *, #14147, .T. ) ; +#16366 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555133 ) ) ; +#16367 = ADVANCED_FACE ( 'NONE', ( #29673 ), #29905, .F. ) ; +#16368 = CONICAL_SURFACE ( 'NONE', #37947, 6.000000401320364496, 0.7853981634158426761 ) ; +#16369 = VECTOR ( 'NONE', #30397, 1000.000000000000000 ) ; +#16370 = FACE_OUTER_BOUND ( 'NONE', #37428, .T. ) ; +#16371 = ORIENTED_EDGE ( 'NONE', *, *, #27813, .T. ) ; +#16372 = DIRECTION ( 'NONE', ( 0.7066903926851649809, 0.000000000000000000, -0.7075229246367126246 ) ) ; +#16373 = ADVANCED_FACE ( 'NONE', ( #30083 ), #38857, .F. ) ; +#16374 = CARTESIAN_POINT ( 'NONE', ( 34.28687154474416587, 218.5902260770998282, 61.03779348242591141 ) ) ; +#16375 = CARTESIAN_POINT ( 'NONE', ( 2.561557524529688212, 191.9759150222000130, 101.9199002238063372 ) ) ; +#16376 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#16377 = VERTEX_POINT ( 'NONE', #5739 ) ; +#16378 = CARTESIAN_POINT ( 'NONE', ( 16.57435211472781589, 122.8698034444475695, 173.0361124685911989 ) ) ; +#16379 = EDGE_LOOP ( 'NONE', ( #6565, #14247, #26650, #1526 ) ) ; +#16380 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498900431, 179.0675991014231556, 104.0619761093272899 ) ) ; +#16381 = CARTESIAN_POINT ( 'NONE', ( -21.68370027014267620, 130.4236040016583047, 89.77667904513492658 ) ) ; +#16382 = ADVANCED_FACE ( 'NONE', ( #8817 ), #18391, .T. ) ; +#16383 = EDGE_LOOP ( 'NONE', ( #7192, #158, #25146, #38537 ) ) ; +#16384 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250904998, 132.4055461762928019, 92.79778151953361487 ) ) ; +#16385 = PLANE ( 'NONE', #15318 ) ; +#16386 = CARTESIAN_POINT ( 'NONE', ( -20.49970532888763941, 191.4139234226054498, 104.3698659823340478 ) ) ; +#16387 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#16388 = VERTEX_POINT ( 'NONE', #36814 ) ; +#16389 = CIRCLE ( 'NONE', #19657, 47.50000000000088107 ) ; +#16390 = DIRECTION ( 'NONE', ( -0.6319268263561552690, -0.7750280550608716901, 0.000000000000000000 ) ) ; +#16391 = FACE_OUTER_BOUND ( 'NONE', #29228, .T. ) ; +#16392 = EDGE_LOOP ( 'NONE', ( #29256, #38089, #15173, #2266 ) ) ; +#16393 = AXIS2_PLACEMENT_3D ( 'NONE', #13586, #4766, #19891 ) ; +#16394 = VECTOR ( 'NONE', #9694, 999.9999999999997726 ) ; +#16395 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#16396 = CARTESIAN_POINT ( 'NONE', ( -25.65884129073699782, 194.1237596081920742, 102.8486509400222388 ) ) ; +#16397 = DIRECTION ( 'NONE', ( -0.7933533411653074241, -0.5931840316265230006, -0.1368326740407701525 ) ) ; +#16398 = EDGE_LOOP ( 'NONE', ( #20228, #4014, #26800, #21326 ) ) ; +#16399 = VECTOR ( 'NONE', #27841, 1000.000000000000114 ) ; +#16400 = DIRECTION ( 'NONE', ( 0.0005884949961242350253, -0.2249510543439066923, 0.9743698870671262391 ) ) ; +#16401 = LINE ( 'NONE', #6592, #28705 ) ; +#16402 = ORIENTED_EDGE ( 'NONE', *, *, #24485, .F. ) ; +#16403 = CARTESIAN_POINT ( 'NONE', ( 25.67102090886999832, 120.3907441056999943, 90.16869597336001618 ) ) ; +#16404 = EDGE_CURVE ( 'NONE', #34206, #5155, #18946, .T. ) ; +#16405 = CARTESIAN_POINT ( 'NONE', ( -15.67958464821357722, 153.2035578972894996, 95.03222041879267579 ) ) ; +#16406 = EDGE_CURVE ( 'NONE', #29855, #5612, #39872, .T. ) ; +#16408 = CARTESIAN_POINT ( 'NONE', ( 97.89458707257233527, 73.08085066759555559, 291.4994180576736085 ) ) ; +#16407 = LINE ( 'NONE', #7402, #23728 ) ; +#16409 = VERTEX_POINT ( 'NONE', #9614 ) ; +#16410 = CARTESIAN_POINT ( 'NONE', ( -29.91503390656419370, 185.6751918267468682, 102.8795885021705061 ) ) ; +#16411 = EDGE_CURVE ( 'NONE', #7887, #32617, #21692, .T. ) ; +#16412 = CARTESIAN_POINT ( 'NONE', ( -40.96777089817398121, 130.0214998612392208, 92.77440595303380633 ) ) ; +#16413 = EDGE_LOOP ( 'NONE', ( #17499, #31807, #5572, #28406 ) ) ; +#16414 = VECTOR ( 'NONE', #33985, 1000.000000000000114 ) ; +#16415 = ORIENTED_EDGE ( 'NONE', *, *, #13068, .T. ) ; +#16416 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#16417 = EDGE_CURVE ( 'NONE', #21067, #29513, #30490, .T. ) ; +#16418 = CARTESIAN_POINT ( 'NONE', ( 1.214432203236400998, 156.8167772888575655, 100.9862065159453124 ) ) ; +#16419 = LINE ( 'NONE', #10318, #37670 ) ; +#16420 = CARTESIAN_POINT ( 'NONE', ( 15.99970520780110483, 160.7332544674666508, 96.75156078672274873 ) ) ; +#16421 = ORIENTED_EDGE ( 'NONE', *, *, #15481, .F. ) ; +#16422 = ORIENTED_EDGE ( 'NONE', *, *, #37885, .T. ) ; +#16423 = ORIENTED_EDGE ( 'NONE', *, *, #1794, .F. ) ; +#16424 = CARTESIAN_POINT ( 'NONE', ( -42.83388826220544132, 121.9349074780233195, 87.82968285981074530 ) ) ; +#16425 = CARTESIAN_POINT ( 'NONE', ( 33.79411933395220302, 218.5902260770999987, 73.03809328116246036 ) ) ; +#16426 = FACE_OUTER_BOUND ( 'NONE', #5417, .T. ) ; +#16427 = EDGE_CURVE ( 'NONE', #43, #8699, #1876, .T. ) ; +#16428 = ORIENTED_EDGE ( 'NONE', *, *, #26911, .T. ) ; +#16429 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12231, #31229, #9565, #27596, #34280, #21230 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16430 = CARTESIAN_POINT ( 'NONE', ( 75.24056455973224899, 196.4820008462166641, 189.1802437148639058 ) ) ; +#16431 = ORIENTED_EDGE ( 'NONE', *, *, #28303, .T. ) ; +#16432 = DIRECTION ( 'NONE', ( -0.7933533416835752972, 0.5930537051408127924, 0.1373964266575312121 ) ) ; +#16433 = ORIENTED_EDGE ( 'NONE', *, *, #29730, .T. ) ; +#16434 = CARTESIAN_POINT ( 'NONE', ( -38.09104460848572415, 163.5977002183961986, 197.9766423606148180 ) ) ; +#16435 = CARTESIAN_POINT ( 'NONE', ( -3.067671275023999833, 190.9450925682999980, 106.9545067451000193 ) ) ; +#16436 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251386036, 132.4055461763500432, 92.79778151959344257 ) ) ; +#16437 = ORIENTED_EDGE ( 'NONE', *, *, #7424, .F. ) ; +#16438 = CARTESIAN_POINT ( 'NONE', ( 2.462157221798171314, 209.5677243469951634, 73.55701709285500556 ) ) ; +#16439 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22654, #23241, #13243, #16876, #4016, #35677 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16440 = CARTESIAN_POINT ( 'NONE', ( -24.26035614307613741, 115.9286812804331532, 87.78225227416257326 ) ) ; +#16441 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13496, #1210, #35526, #13689 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16442 = CIRCLE ( 'NONE', #38649, 6.000000000000007994 ) ; +#16443 = CARTESIAN_POINT ( 'NONE', ( 20.25283899970633783, 212.3189532007872344, 73.04627187513231945 ) ) ; +#16444 = CARTESIAN_POINT ( 'NONE', ( 13.50130427969020275, 124.2930898829833524, 90.90584795771297877 ) ) ; +#16445 = CONICAL_SURFACE ( 'NONE', #4719, 2.502994021815846182, 0.7853981633807167739 ) ; +#16446 = AXIS2_PLACEMENT_3D ( 'NONE', #30405, #33247, #17504 ) ; +#16447 = DIRECTION ( 'NONE', ( -0.9914446600486714889, 0.1270322995874082761, 0.03000468167652007440 ) ) ; +#16448 = VERTEX_POINT ( 'NONE', #17988 ) ; +#16449 = CARTESIAN_POINT ( 'NONE', ( 33.59566074061859098, 83.36374835074464329, 285.7734289287842557 ) ) ; +#16450 = ADVANCED_FACE ( 'NONE', ( #24366 ), #17468, .F. ) ; +#16451 = ADVANCED_FACE ( 'NONE', ( #40070 ), #29258, .F. ) ; +#16452 = CARTESIAN_POINT ( 'NONE', ( -36.47994717572999690, 115.7898166395000175, 89.87704453466000132 ) ) ; +#16453 = ORIENTED_EDGE ( 'NONE', *, *, #15997, .F. ) ; +#16454 = VERTEX_POINT ( 'NONE', #37219 ) ; +#16455 = CARTESIAN_POINT ( 'NONE', ( 37.59407280179000566, 112.0479120775361821, 151.0714151308390854 ) ) ; +#16456 = PLANE ( 'NONE', #31358 ) ; +#16457 = CARTESIAN_POINT ( 'NONE', ( 75.33446582941786573, 196.6730905574605970, 189.2244420380926329 ) ) ; +#16458 = EDGE_CURVE ( 'NONE', #23325, #8503, #18433, .T. ) ; +#16459 = ORIENTED_EDGE ( 'NONE', *, *, #9414, .T. ) ; +#16460 = FACE_BOUND ( 'NONE', #15196, .T. ) ; +#16461 = ORIENTED_EDGE ( 'NONE', *, *, #9642, .T. ) ; +#16462 = ORIENTED_EDGE ( 'NONE', *, *, #30793, .T. ) ; +#16463 = CARTESIAN_POINT ( 'NONE', ( 20.16681565195775150, 118.8156056749160001, 87.42222852412939460 ) ) ; +#16464 = DIRECTION ( 'NONE', ( -0.7933532970003733809, -0.5930762008556731413, -0.1372995488602876957 ) ) ; +#16465 = CARTESIAN_POINT ( 'NONE', ( -23.36190347369393194, 128.5832235793138523, 89.34972834851440382 ) ) ; +#16466 = VERTEX_POINT ( 'NONE', #15539 ) ; +#16467 = PLANE ( 'NONE', #12803 ) ; +#16468 = CARTESIAN_POINT ( 'NONE', ( 35.50063842825999672, 114.5394629846999948, 87.10535886572000663 ) ) ; +#16469 = CARTESIAN_POINT ( 'NONE', ( -38.52752199465000160, 119.2961657191000171, 90.46788514962000249 ) ) ; +#16470 = CARTESIAN_POINT ( 'NONE', ( -29.20104124294445214, 148.3921741051831873, 97.00850424916733061 ) ) ; +#16471 = VECTOR ( 'NONE', #34910, 1000.000000000000227 ) ; +#16472 = ADVANCED_FACE ( 'NONE', ( #2480 ), #3254, .T. ) ; +#16473 = VECTOR ( 'NONE', #30865, 1000.000000000000114 ) ; +#16474 = CARTESIAN_POINT ( 'NONE', ( -38.90591266646470103, 169.4072598844840627, 182.8931904839043625 ) ) ; +#16475 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749388340, 132.8602140592406045, 90.82839891340712768 ) ) ; +#16476 = CARTESIAN_POINT ( 'NONE', ( 21.23862774292054212, 136.3779700007411009, 91.12542899279699782 ) ) ; +#16477 = ORIENTED_EDGE ( 'NONE', *, *, #31340, .F. ) ; +#16478 = CARTESIAN_POINT ( 'NONE', ( 28.52619946403000029, 125.2833734473000078, 88.56110222834999490 ) ) ; +#16479 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700560425838653, -0.2249510922124452195 ) ) ; +#16480 = LINE ( 'NONE', #4206, #11665 ) ; +#16481 = CARTESIAN_POINT ( 'NONE', ( -35.62325547678683080, 209.7096871504523676, 73.24668633324121458 ) ) ; +#16482 = CARTESIAN_POINT ( 'NONE', ( -2.437027990547441014, 191.0000000396348128, 104.2633722229568605 ) ) ; +#16483 = ORIENTED_EDGE ( 'NONE', *, *, #22800, .T. ) ; +#16484 = DIRECTION ( 'NONE', ( -0.9999998176071912548, 1.116701431525940521E-11, 0.0006039748207718291517 ) ) ; +#16485 = CARTESIAN_POINT ( 'NONE', ( 0.7008280748616902978, 189.0047931960354219, 103.6853728373111920 ) ) ; +#16486 = CARTESIAN_POINT ( 'NONE', ( -0.7674275430754152749, 188.3856493364897347, 106.2245540265581241 ) ) ; +#16487 = EDGE_CURVE ( 'NONE', #4779, #24868, #39443, .T. ) ; +#16488 = CARTESIAN_POINT ( 'NONE', ( -16.56460962585015295, 151.5351474169435733, 184.4312778327909541 ) ) ; +#16489 = CARTESIAN_POINT ( 'NONE', ( -25.61308381689000058, 191.8269069694999871, 104.3105675431999941 ) ) ; +#16490 = DIRECTION ( 'NONE', ( -0.0001408415334274825802, 0.2249510912533641271, -0.9743700460849477052 ) ) ; +#16491 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16492 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16493 = VERTEX_POINT ( 'NONE', #4250 ) ; +#16494 = EDGE_CURVE ( 'NONE', #19286, #12627, #32159, .T. ) ; +#16495 = EDGE_CURVE ( 'NONE', #32173, #34620, #10013, .T. ) ; +#16496 = ADVANCED_FACE ( 'NONE', ( #12887 ), #13083, .F. ) ; +#16497 = LINE ( 'NONE', #4437, #3043 ) ; +#16498 = CIRCLE ( 'NONE', #12601, 51.90509898881904149 ) ; +#16499 = CARTESIAN_POINT ( 'NONE', ( -43.85192579621110553, 185.5794629365180413, 107.4090340691420664 ) ) ; +#16500 = ORIENTED_EDGE ( 'NONE', *, *, #5141, .F. ) ; +#16501 = LINE ( 'NONE', #19967, #14616 ) ; +#16502 = CARTESIAN_POINT ( 'NONE', ( -37.45249394195251824, 145.6179928404688724, 281.5041015744685637 ) ) ; +#16503 = CYLINDRICAL_SURFACE ( 'NONE', #26118, 2.000000000000014655 ) ; +#16504 = CARTESIAN_POINT ( 'NONE', ( 36.06383963597500752, 192.3117859303959847, 104.3281134044120080 ) ) ; +#16505 = CARTESIAN_POINT ( 'NONE', ( -13.46391575659845685, 154.4039982810205629, 95.30803284751881677 ) ) ; +#16506 = CARTESIAN_POINT ( 'NONE', ( 35.43188809533000239, 192.9169409211000072, 106.9485261150999946 ) ) ; +#16507 = ORIENTED_EDGE ( 'NONE', *, *, #10800, .T. ) ; +#16508 = CARTESIAN_POINT ( 'NONE', ( -2.913189425919000097, 209.5191065594000008, 76.06629948724000201 ) ) ; +#16509 = CARTESIAN_POINT ( 'NONE', ( -32.57214901757254211, 137.3507445002516079, 91.38251427481793598 ) ) ; +#16510 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; +#16511 = ORIENTED_EDGE ( 'NONE', *, *, #4660, .T. ) ; +#16512 = DIRECTION ( 'NONE', ( -0.0005884949961261437632, 0.2249510543439059151, -0.9743698870671263501 ) ) ; +#16513 = ORIENTED_EDGE ( 'NONE', *, *, #14871, .F. ) ; +#16514 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971580668 ) ) ; +#16515 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; +#16516 = CARTESIAN_POINT ( 'NONE', ( -36.81620286734185044, 191.5634815702392473, 104.3852644490423103 ) ) ; +#16517 = FACE_OUTER_BOUND ( 'NONE', #4385, .T. ) ; +#16518 = VECTOR ( 'NONE', #5149, 999.9999999999998863 ) ; +#16519 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14986, #18425, #15575, #36855, #30732, #6171, #37456, #8864, #21934, #39706, #5780, #2724, #15192, #30932, #3102, #28073, #22335, #34955, #25206, #35160 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999998899769, 0.1874999999998245848, 0.2187499999997803424, 0.2343749999997683797, 0.2499999999997563893, 0.4999999999998131495, 0.6249999999998484546, 0.6874999999998605560, 0.7187499999998683275, 0.7343749999998769873, 0.7499999999998856470, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16520 = CARTESIAN_POINT ( 'NONE', ( -35.98817295377529746, 191.5260130662397273, 103.8919236801626340 ) ) ; +#16521 = CARTESIAN_POINT ( 'NONE', ( 21.85768935794949996, 135.9059676768250711, 91.18714493273058963 ) ) ; +#16522 = ORIENTED_EDGE ( 'NONE', *, *, #5054, .F. ) ; +#16523 = EDGE_LOOP ( 'NONE', ( #37223, #27122, #18072, #13349 ) ) ; +#16524 = CARTESIAN_POINT ( 'NONE', ( 15.10764778216198323, 128.9370057249701063, 92.49016256005407399 ) ) ; +#16525 = VECTOR ( 'NONE', #4403, 999.9999999999998863 ) ; +#16526 = DIRECTION ( 'NONE', ( -0.7066903833891088338, -9.361005956066117864E-05, 0.7075229277292088836 ) ) ; +#16527 = CARTESIAN_POINT ( 'NONE', ( -18.61117187107760884, 125.1353300184083253, 178.8218272577300354 ) ) ; +#16528 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8591, #30464, #2458, #30250, #5715, #14116, #1626, #11443 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 4 ), + ( 1.040834085586084103E-17, 0.0002767357485092747566, 0.0005534714970185391049, 0.001106942994037067802 ), + .UNSPECIFIED. ) ; +#16529 = EDGE_CURVE ( 'NONE', #15062, #19831, #25783, .T. ) ; +#16530 = CARTESIAN_POINT ( 'NONE', ( -36.29419933191000069, 191.9582539845000042, 104.5583661083999942 ) ) ; +#16531 = ORIENTED_EDGE ( 'NONE', *, *, #34361, .T. ) ; +#16532 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#16533 = CARTESIAN_POINT ( 'NONE', ( 3.664993456856746601, 130.0812534783833030, 89.68233120885354026 ) ) ; +#16534 = EDGE_CURVE ( 'NONE', #19888, #20336, #22293, .T. ) ; +#16535 = CARTESIAN_POINT ( 'NONE', ( -20.89286847790088331, 136.3261294211067138, 91.13890976780785991 ) ) ; +#16536 = CARTESIAN_POINT ( 'NONE', ( 25.49176550122653850, 211.4176093050745067, 75.54327414409580399 ) ) ; +#16537 = EDGE_CURVE ( 'NONE', #36684, #1422, #40383, .T. ) ; +#16538 = EDGE_CURVE ( 'NONE', #9013, #29879, #2478, .T. ) ; +#16539 = DIRECTION ( 'NONE', ( 0.0005884949961195158185, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16540 = EDGE_CURVE ( 'NONE', #9057, #23733, #792, .T. ) ; +#16541 = FACE_OUTER_BOUND ( 'NONE', #32181, .T. ) ; +#16542 = CARTESIAN_POINT ( 'NONE', ( -2.836031461634000106, 208.9827885628999979, 73.23448830942000143 ) ) ; +#16543 = CARTESIAN_POINT ( 'NONE', ( 38.14662459809999717, 118.9171916317999944, 90.39768274928999858 ) ) ; +#16544 = VECTOR ( 'NONE', #34579, 1000.000000000000227 ) ; +#16545 = AXIS2_PLACEMENT_3D ( 'NONE', #16892, #10595, #1370 ) ; +#16546 = VERTEX_POINT ( 'NONE', #3449 ) ; +#16547 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#16548 = CARTESIAN_POINT ( 'NONE', ( 20.50176505208000322, 183.2870761629000071, 105.0346093865999961 ) ) ; +#16549 = DIRECTION ( 'NONE', ( 0.0004161288024805896127, -0.8480480897555470188, 0.5299191110903505031 ) ) ; +#16550 = AXIS2_PLACEMENT_3D ( 'NONE', #12108, #15372, #40098 ) ; +#16551 = CARTESIAN_POINT ( 'NONE', ( 44.73086057231283519, 108.4360122525000492, 169.8450455613742349 ) ) ; +#16552 = ORIENTED_EDGE ( 'NONE', *, *, #34489, .F. ) ; +#16553 = ORIENTED_EDGE ( 'NONE', *, *, #12885, .T. ) ; +#16554 = EDGE_LOOP ( 'NONE', ( #15032, #11045, #16092, #17659 ) ) ; +#16555 = LINE ( 'NONE', #4292, #39192 ) ; +#16556 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700562169599344, -0.2249510914571397902 ) ) ; +#16557 = CARTESIAN_POINT ( 'NONE', ( 5.667647268250993520, 124.2920528419670632, 90.91033987003989125 ) ) ; +#16558 = ORIENTED_EDGE ( 'NONE', *, *, #21797, .T. ) ; +#16559 = ORIENTED_EDGE ( 'NONE', *, *, #27304, .F. ) ; +#16560 = CARTESIAN_POINT ( 'NONE', ( 15.99999411728631671, 174.5114300543024513, 99.93239967722463746 ) ) ; +#16561 = CARTESIAN_POINT ( 'NONE', ( 12.31023268411626148, 134.2457138696073855, 93.71750156584897695 ) ) ; +#16562 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950931402, 137.3532831589782575, 178.0585834213011083 ) ) ; +#16563 = CARTESIAN_POINT ( 'NONE', ( -38.01370974153999782, 119.1992765896000037, 87.30104918352000709 ) ) ; +#16564 = CARTESIAN_POINT ( 'NONE', ( 12.63604222480166150, 130.6208451921540075, 90.14583135183596596 ) ) ; +#16565 = DIRECTION ( 'NONE', ( 0.0006039748319393677253, 3.488873499045632102E-19, 0.9999998176071845934 ) ) ; +#16566 = VERTEX_POINT ( 'NONE', #25763 ) ; +#16567 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#16568 = ORIENTED_EDGE ( 'NONE', *, *, #12054, .T. ) ; +#16569 = CARTESIAN_POINT ( 'NONE', ( 35.09291703857000044, 220.4002260771000010, 152.4718672074000381 ) ) ; +#16570 = CARTESIAN_POINT ( 'NONE', ( -26.00831778364999636, 205.1071295952009166, 76.12055741644040552 ) ) ; +#16571 = DIRECTION ( 'NONE', ( 0.0004161288024549962073, 0.5299192578740949955, 0.8480479980348919478 ) ) ; +#16572 = ORIENTED_EDGE ( 'NONE', *, *, #11701, .F. ) ; +#16573 = CARTESIAN_POINT ( 'NONE', ( 20.14888587518330354, 205.2606208450517329, 76.15744753280239365 ) ) ; +#16574 = CARTESIAN_POINT ( 'NONE', ( -8.048542123008331828, 160.5967930229313367, 99.81338747665230926 ) ) ; +#16575 = AXIS2_PLACEMENT_3D ( 'NONE', #6340, #22304, #9834 ) ; +#16576 = CIRCLE ( 'NONE', #39433, 6.500001098231858343 ) ; +#16577 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825829930067965, 0.0005734119044644985386 ) ) ; +#16578 = EDGE_CURVE ( 'NONE', #7841, #10482, #28618, .T. ) ; +#16579 = CONICAL_SURFACE ( 'NONE', #24483, 2.503093623396721146, 0.7853981633639495197 ) ; +#16580 = VERTEX_POINT ( 'NONE', #29225 ) ; +#16581 = CARTESIAN_POINT ( 'NONE', ( -25.50873731069575712, 209.2199388313156021, 75.57458662847975006 ) ) ; +#16582 = CARTESIAN_POINT ( 'NONE', ( 2.941278393888057341, 209.7096877029368613, 73.05672770647804271 ) ) ; +#16583 = ORIENTED_EDGE ( 'NONE', *, *, #27494, .T. ) ; +#16584 = EDGE_CURVE ( 'NONE', #15877, #31407, #28421, .T. ) ; +#16585 = FACE_OUTER_BOUND ( 'NONE', #25592, .T. ) ; +#16586 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28565, #38357, #29170, #13816, #1142, #35661, #26106, #25912, #16077, #6871 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16587 = ADVANCED_FACE ( 'NONE', ( #16517 ), #22725, .F. ) ; +#16588 = ORIENTED_EDGE ( 'NONE', *, *, #37749, .F. ) ; +#16589 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25018, #31341, #16573, #9466 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16590 = CARTESIAN_POINT ( 'NONE', ( 1.825277717689219870, 188.7045273156206520, 106.2966068932076240 ) ) ; +#16591 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18265, #27710, #22372, #24643, #9691, #34599, #30762, #2750, #6403, #18860 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.0004307675617671707360, 0.0008615351235343414720, 0.001292302685301512100, 0.001723070247068682944 ), + .UNSPECIFIED. ) ; +#16592 = CARTESIAN_POINT ( 'NONE', ( 28.25950385170297352, 125.5846682600628412, 89.14251585184922533 ) ) ; +#16593 = CARTESIAN_POINT ( 'NONE', ( -8.048542123480551425, 150.7617452742509556, 97.54278737913534769 ) ) ; +#16594 = EDGE_CURVE ( 'NONE', #36682, #34607, #7328, .T. ) ; +#16595 = VERTEX_POINT ( 'NONE', #396 ) ; +#16596 = VERTEX_POINT ( 'NONE', #20823 ) ; +#16597 = CARTESIAN_POINT ( 'NONE', ( 25.50429067071999967, 120.4343480257000039, 90.00774254085000337 ) ) ; +#16598 = LINE ( 'NONE', #19670, #22146 ) ; +#16599 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4044, #10409, #29001, #19776 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16601 = DIRECTION ( 'NONE', ( -0.0004270746993304995942, -0.7071067811865993091, -0.7071066522152992251 ) ) ; +#16600 = CARTESIAN_POINT ( 'NONE', ( -76.10777906862098519, 155.6625685549207105, 98.71533786495776042 ) ) ; +#16602 = FACE_OUTER_BOUND ( 'NONE', #31451, .T. ) ; +#16603 = CIRCLE ( 'NONE', #4203, 1.999999999983348431 ) ; +#16604 = AXIS2_PLACEMENT_3D ( 'NONE', #25367, #9022, #21505 ) ; +#16605 = ORIENTED_EDGE ( 'NONE', *, *, #36878, .T. ) ; +#16606 = CARTESIAN_POINT ( 'NONE', ( -35.44629553207012407, 109.6131156415000021, 90.28919351360151779 ) ) ; +#16607 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621345620, 0.1788331191967953704 ) ) ; +#16609 = ORIENTED_EDGE ( 'NONE', *, *, #9641, .T. ) ; +#16608 = VECTOR ( 'NONE', #36479, 1000.000000000000114 ) ; +#16610 = VERTEX_POINT ( 'NONE', #35718 ) ; +#16611 = CARTESIAN_POINT ( 'NONE', ( 2.623277854660710062, 209.6150308759818870, 75.72358690466917608 ) ) ; +#16612 = FACE_OUTER_BOUND ( 'NONE', #6020, .T. ) ; +#16613 = CARTESIAN_POINT ( 'NONE', ( -45.21698515504639460, 124.3314463512707846, 91.71916011353340537 ) ) ; +#16614 = LINE ( 'NONE', #10319, #26142 ) ; +#16615 = CARTESIAN_POINT ( 'NONE', ( 36.07326204741000453, 192.3427678687999958, 104.3838198541999986 ) ) ; +#16616 = ORIENTED_EDGE ( 'NONE', *, *, #5992, .F. ) ; +#16617 = VERTEX_POINT ( 'NONE', #33276 ) ; +#16618 = CARTESIAN_POINT ( 'NONE', ( -42.87041437821633139, 121.8978841230586170, 87.86525719409469559 ) ) ; +#16619 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498903273, 179.0675991014140607, 104.0619761093665971 ) ) ; +#16620 = LINE ( 'NONE', #3953, #2028 ) ; +#16621 = EDGE_LOOP ( 'NONE', ( #29357, #35243, #4747, #22785 ) ) ; +#16622 = ORIENTED_EDGE ( 'NONE', *, *, #27848, .T. ) ; +#16623 = PRODUCT ( 'MID360+\X2\76f8673a652f67b6\X0\6.24', 'MID360+\X2\76f8673a652f67b6\X0\6.24', '', ( #27422 ) ) ; +#16624 = FACE_OUTER_BOUND ( 'NONE', #30582, .T. ) ; +#16625 = ORIENTED_EDGE ( 'NONE', *, *, #9789, .F. ) ; +#16626 = EDGE_CURVE ( 'NONE', #13079, #29758, #5074, .T. ) ; +#16627 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5828, #39962, #20965, #5621 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16628 = EDGE_CURVE ( 'NONE', #37091, #23190, #7213, .T. ) ; +#16629 = VERTEX_POINT ( 'NONE', #11219 ) ; +#16630 = DIRECTION ( 'NONE', ( -0.0005884949961271457829, 0.2249510543439062482, -0.9743698870671264611 ) ) ; +#16631 = ORIENTED_EDGE ( 'NONE', *, *, #30279, .F. ) ; +#16632 = CARTESIAN_POINT ( 'NONE', ( -30.07200330635009067, 135.2897752519686776, 91.41834187752364471 ) ) ; +#16633 = AXIS2_PLACEMENT_3D ( 'NONE', #40382, #12385, #24883 ) ; +#16634 = CARTESIAN_POINT ( 'NONE', ( -0.3574740697902000219, 188.5380013795999901, 106.1066132219000053 ) ) ; +#16635 = CIRCLE ( 'NONE', #3586, 2.500000000031143088 ) ; +#16636 = AXIS2_PLACEMENT_3D ( 'NONE', #28776, #10183, #35079 ) ; +#16637 = LINE ( 'NONE', #39122, #27461 ) ; +#16638 = DIRECTION ( 'NONE', ( 0.6087614115774527823, 0.7729348350621608743, 0.1788331191968013101 ) ) ; +#16639 = EDGE_CURVE ( 'NONE', #21867, #1663, #26283, .T. ) ; +#16640 = ORIENTED_EDGE ( 'NONE', *, *, #3394, .T. ) ; +#16641 = AXIS2_PLACEMENT_3D ( 'NONE', #29105, #24141, #36594 ) ; +#16642 = FACE_OUTER_BOUND ( 'NONE', #30344, .T. ) ; +#16643 = CARTESIAN_POINT ( 'NONE', ( 17.33255171641533110, 121.2645175805946138, 177.4250592562015925 ) ) ; +#16644 = CARTESIAN_POINT ( 'NONE', ( 13.50019245297331949, 123.9864599348986616, 91.09745217655513727 ) ) ; +#16645 = EDGE_CURVE ( 'NONE', #27296, #38321, #2023, .T. ) ; +#16646 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825918840956979, 0.0005734119024144099241 ) ) ; +#16647 = ORIENTED_EDGE ( 'NONE', *, *, #33477, .F. ) ; +#16648 = CARTESIAN_POINT ( 'NONE', ( 23.65482006811145155, 115.6781945452533904, 89.75368254526981104 ) ) ; +#16649 = CARTESIAN_POINT ( 'NONE', ( -37.54611826410999953, 117.6150725292000061, 89.85907085683001583 ) ) ; +#16650 = EDGE_LOOP ( 'NONE', ( #15493, #31323, #342, #23998, #14789, #2675, #16840, #28340, #136, #23977, #17516 ) ) ; +#16651 = CARTESIAN_POINT ( 'NONE', ( -39.76913700811847718, 108.4405668372959468, 169.8253437122761795 ) ) ; +#16652 = ORIENTED_EDGE ( 'NONE', *, *, #12890, .T. ) ; +#16653 = CARTESIAN_POINT ( 'NONE', ( 12.93166457001120229, 158.3132409016616862, 96.19460342880938697 ) ) ; +#16654 = CARTESIAN_POINT ( 'NONE', ( 26.00081427186901095, 120.1020675870059762, 90.44387584870027297 ) ) ; +#16655 = CARTESIAN_POINT ( 'NONE', ( 2.730741220598960517, 190.9310047356335360, 106.4668625363826493 ) ) ; +#16656 = EDGE_LOOP ( 'NONE', ( #27976, #37872, #6961, #8267 ) ) ; +#16657 = ORIENTED_EDGE ( 'NONE', *, *, #12098, .T. ) ; +#16658 = FACE_BOUND ( 'NONE', #15917, .T. ) ; +#16659 = EDGE_LOOP ( 'NONE', ( #28363, #25461, #20325, #22795, #6827, #7579, #10161, #33354, #39179, #24971, #6745, #4741, #32749, #11692 ) ) ; +#16660 = CIRCLE ( 'NONE', #34293, 58.90509898902387675 ) ; +#16661 = ORIENTED_EDGE ( 'NONE', *, *, #10674, .T. ) ; +#16662 = VERTEX_POINT ( 'NONE', #1396 ) ; +#16663 = CARTESIAN_POINT ( 'NONE', ( -6.036394940235839002, 177.4973813401495875, 100.8859267458554854 ) ) ; +#16664 = VECTOR ( 'NONE', #36406, 1000.000000000000114 ) ; +#16665 = FACE_OUTER_BOUND ( 'NONE', #38317, .T. ) ; +#16666 = AXIS2_PLACEMENT_3D ( 'NONE', #24830, #9274, #34193 ) ; +#16667 = CIRCLE ( 'NONE', #39522, 48.00000000000002132 ) ; +#16668 = VERTEX_POINT ( 'NONE', #14288 ) ; +#16669 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#16670 = VECTOR ( 'NONE', #21398, 1000.000000000000114 ) ; +#16671 = CARTESIAN_POINT ( 'NONE', ( -6.036405711825560516, 134.8430548831865963, 93.35330002338830013 ) ) ; +#16672 = CARTESIAN_POINT ( 'NONE', ( 36.23883791301999935, 191.5582779153000104, 103.9620754990999956 ) ) ; +#16673 = LINE ( 'NONE', #19345, #21599 ) ; +#16674 = ORIENTED_EDGE ( 'NONE', *, *, #25214, .F. ) ; +#16675 = PLANE ( 'NONE', #22598 ) ; +#16676 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#16677 = FACE_OUTER_BOUND ( 'NONE', #33525, .T. ) ; +#16678 = ORIENTED_EDGE ( 'NONE', *, *, #37016, .F. ) ; +#16679 = LINE ( 'NONE', #33787, #25582 ) ; +#16680 = PLANE ( 'NONE', #34209 ) ; +#16681 = CARTESIAN_POINT ( 'NONE', ( 23.32645555946442073, 115.6131185450060030, 87.75350244859328086 ) ) ; +#16682 = EDGE_CURVE ( 'NONE', #39827, #9576, #37496, .T. ) ; +#16683 = EDGE_CURVE ( 'NONE', #13511, #16043, #19878, .T. ) ; +#16684 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455648501747, -31.54510897440487938, 136.4474729010642875 ) ) ; +#16685 = CARTESIAN_POINT ( 'NONE', ( -11.79202345736525892, 125.7774812735008254, 176.8918472601677365 ) ) ; +#16686 = ORIENTED_EDGE ( 'NONE', *, *, #1317, .T. ) ; +#16687 = CARTESIAN_POINT ( 'NONE', ( -42.38963504733576571, 73.00513959036860001, 297.5841473069626772 ) ) ; +#16688 = CARTESIAN_POINT ( 'NONE', ( -35.44810745648619132, 109.6131156741000154, 87.28919406056773767 ) ) ; +#16689 = CARTESIAN_POINT ( 'NONE', ( 36.40838257471642692, 191.8167960244688288, 104.3619212928119140 ) ) ; +#16690 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29589, #20165, #1779, #2193, #26734, #27149 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16691 = CARTESIAN_POINT ( 'NONE', ( 12.64033828019901939, 130.2859757627005877, 92.71761759901836797 ) ) ; +#16692 = CARTESIAN_POINT ( 'NONE', ( -25.35636387728000329, 191.7351922414000001, 104.5598766893999993 ) ) ; +#16693 = CONICAL_SURFACE ( 'NONE', #24556, 2.502999999887194349, 0.7853981633984101762 ) ; +#16694 = DIRECTION ( 'NONE', ( -0.1305262373691798983, 0.9659583596717404852, 0.2233547598295697878 ) ) ; +#16695 = CARTESIAN_POINT ( 'NONE', ( 21.00010498221761779, 176.2223731533329953, 100.4954345433673240 ) ) ; +#16696 = CARTESIAN_POINT ( 'NONE', ( 39.00044143696274546, 135.4860176042719786, 291.5349886458730566 ) ) ; +#16697 = CARTESIAN_POINT ( 'NONE', ( 26.71555981742730168, 123.8732672728377793, 90.80094690554606984 ) ) ; +#16698 = EDGE_LOOP ( 'NONE', ( #40054, #37536, #1713, #7627, #13823 ) ) ; +#16699 = VECTOR ( 'NONE', #25399, 1000.000000000000114 ) ; +#16700 = DIRECTION ( 'NONE', ( -0.5987319967475925875, -0.8009494341533932582, 0.000000000000000000 ) ) ; +#16701 = AXIS2_PLACEMENT_3D ( 'NONE', #16384, #12724, #651 ) ; +#16702 = CARTESIAN_POINT ( 'NONE', ( -15.87117416798851366, 146.8921292067080628, 179.7466459197605957 ) ) ; +#16703 = EDGE_CURVE ( 'NONE', #21152, #39877, #13876, .T. ) ; +#16704 = EDGE_LOOP ( 'NONE', ( #8285, #29475, #5924, #15664 ) ) ; +#16705 = LINE ( 'NONE', #10398, #15915 ) ; +#16706 = LINE ( 'NONE', #4229, #35507 ) ; +#16707 = CARTESIAN_POINT ( 'NONE', ( -76.10807331609903770, 155.7904255491852723, 98.23170401357633352 ) ) ; +#16708 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319401643971 ) ) ; +#16709 = CARTESIAN_POINT ( 'NONE', ( 16.55837427060546219, 127.1115566547025821, 154.7760191776372380 ) ) ; +#16710 = DIRECTION ( 'NONE', ( 0.0005884949961156549746, -0.2249510543439098842, 0.9743698870671255730 ) ) ; +#16711 = ORIENTED_EDGE ( 'NONE', *, *, #14172, .T. ) ; +#16712 = ORIENTED_EDGE ( 'NONE', *, *, #4545, .F. ) ; +#16713 = LINE ( 'NONE', #26550, #4090 ) ; +#16714 = CARTESIAN_POINT ( 'NONE', ( -2.850522251479513436, 209.7115537078749128, 76.06022745297526910 ) ) ; +#16715 = CARTESIAN_POINT ( 'NONE', ( 36.57174901144423274, 117.0762946090158607, 87.24569587203919241 ) ) ; +#16716 = LINE ( 'NONE', #38404, #15438 ) ; +#16717 = ORIENTED_EDGE ( 'NONE', *, *, #30225, .F. ) ; +#16718 = CARTESIAN_POINT ( 'NONE', ( 13.81047920904208226, 125.0581942443353114, 174.4028524411866954 ) ) ; +#16719 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927823695848, 0.0005734119022063523946 ) ) ; +#16720 = AXIS2_PLACEMENT_3D ( 'NONE', #19582, #25750, #28996 ) ; +#16721 = EDGE_LOOP ( 'NONE', ( #26602, #37447, #29893, #1564, #3493, #27843, #39102, #27913, #35542, #6491 ) ) ; +#16722 = VECTOR ( 'NONE', #28343, 1000.000000000000000 ) ; +#16723 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #235, #5781, #5976, #18231 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16724 = CARTESIAN_POINT ( 'NONE', ( -3.336611124200936640, 129.4601111755350189, 89.54315797652932929 ) ) ; +#16725 = ORIENTED_EDGE ( 'NONE', *, *, #38382, .F. ) ; +#16726 = CARTESIAN_POINT ( 'NONE', ( 36.43042111832376406, 191.6595748262901395, 106.3773235261021597 ) ) ; +#16727 = AXIS2_PLACEMENT_3D ( 'NONE', #22484, #18981, #37800 ) ; +#16728 = CARTESIAN_POINT ( 'NONE', ( -29.94810855088000423, 104.1131156701966916, 87.28587219915669948 ) ) ; +#16729 = AXIS2_PLACEMENT_3D ( 'NONE', #7945, #29229, #23291 ) ; +#16730 = ADVANCED_FACE ( 'NONE', ( #26565 ), #14228, .F. ) ; +#16731 = EDGE_CURVE ( 'NONE', #26863, #8041, #23693, .T. ) ; +#16732 = FACE_OUTER_BOUND ( 'NONE', #31390, .T. ) ; +#16733 = FACE_OUTER_BOUND ( 'NONE', #10412, .T. ) ; +#16734 = ORIENTED_EDGE ( 'NONE', *, *, #22302, .T. ) ; +#16735 = ORIENTED_EDGE ( 'NONE', *, *, #34133, .T. ) ; +#16736 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16737 = FACE_OUTER_BOUND ( 'NONE', #1305, .T. ) ; +#16738 = CARTESIAN_POINT ( 'NONE', ( 44.05294553655904366, 113.2635659203072578, 86.28842023171608844 ) ) ; +#16739 = CARTESIAN_POINT ( 'NONE', ( -37.92200784295000204, 191.3253432445999920, 104.2385424362999942 ) ) ; +#16740 = ORIENTED_EDGE ( 'NONE', *, *, #30703, .F. ) ; +#16741 = CARTESIAN_POINT ( 'NONE', ( 23.36018451437981369, 181.9417229093960771, 101.9854922266229664 ) ) ; +#16742 = LINE ( 'NONE', #7953, #26062 ) ; +#16743 = DIRECTION ( 'NONE', ( 0.7066905299392122197, 0.1591580245907027458, -0.6893890179736117396 ) ) ; +#16744 = AXIS2_PLACEMENT_3D ( 'NONE', #18604, #2886, #25188 ) ; +#16745 = CARTESIAN_POINT ( 'NONE', ( -18.59070810293174603, 148.9276284220111393, 180.2165354988448200 ) ) ; +#16746 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27050, #28738, #19711, #19515, #4379, #38715 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( -0.002794158215913641278, -0.0009957982206659000447, 0.0008025617745818411884 ), + .UNSPECIFIED. ) ; +#16747 = CONICAL_SURFACE ( 'NONE', #22008, 2.500000000044046544, 0.7853981634220001951 ) ; +#16748 = DIRECTION ( 'NONE', ( -0.0005884949961221202890, 0.2249510543439054433, -0.9743698870671265722 ) ) ; +#16749 = DIRECTION ( 'NONE', ( 0.0005884949961252946161, -0.2249510543439068866, 0.9743698870671261281 ) ) ; +#16750 = ADVANCED_FACE ( 'NONE', ( #36362 ), #4668, .T. ) ; +#16751 = CARTESIAN_POINT ( 'NONE', ( -3.090309791701999931, 208.8048984618000077, 73.00436043185000301 ) ) ; +#16752 = CARTESIAN_POINT ( 'NONE', ( 38.22486551803000765, 118.9813135233000025, 90.39832425324000553 ) ) ; +#16753 = ORIENTED_EDGE ( 'NONE', *, *, #2171, .T. ) ; +#16754 = VECTOR ( 'NONE', #36239, 1000.000000000000000 ) ; +#16755 = FACE_OUTER_BOUND ( 'NONE', #9707, .T. ) ; +#16756 = CARTESIAN_POINT ( 'NONE', ( -36.00791524158660195, 192.2004950762134854, 106.4370239608170010 ) ) ; +#16757 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319381693566 ) ) ; +#16758 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927787594355, 0.0005734119022079395582 ) ) ; +#16759 = ORIENTED_EDGE ( 'NONE', *, *, #5662, .T. ) ; +#16760 = EDGE_LOOP ( 'NONE', ( #17872, #23048, #16168, #34569 ) ) ; +#16761 = ORIENTED_EDGE ( 'NONE', *, *, #31507, .T. ) ; +#16762 = CARTESIAN_POINT ( 'NONE', ( -26.00869527696544381, 209.3199455192979315, 76.07456294362603444 ) ) ; +#16763 = EDGE_CURVE ( 'NONE', #27517, #15784, #26974, .T. ) ; +#16764 = CARTESIAN_POINT ( 'NONE', ( -42.83272783108322557, 107.4558756614410697, 150.2543767220365680 ) ) ; +#16765 = LINE ( 'NONE', #26607, #14819 ) ; +#16766 = ORIENTED_EDGE ( 'NONE', *, *, #22096, .T. ) ; +#16767 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -3.519737326604822600E-16, 0.0006039748319386522603 ) ) ; +#16768 = ADVANCED_FACE ( 'NONE', ( #39009 ), #20753, .T. ) ; +#16769 = CARTESIAN_POINT ( 'NONE', ( 20.00175897098971589, 118.8155681873422651, 90.25573236258343002 ) ) ; +#16770 = CARTESIAN_POINT ( 'NONE', ( -38.69784441830000077, 119.3720474567000025, 87.61528327729999432 ) ) ; +#16771 = FACE_OUTER_BOUND ( 'NONE', #7160, .T. ) ; +#16772 = VERTEX_POINT ( 'NONE', #17530 ) ; +#16773 = FACE_OUTER_BOUND ( 'NONE', #21341, .T. ) ; +#16774 = CIRCLE ( 'NONE', #12249, 2.000000002639695573 ) ; +#16775 = ORIENTED_EDGE ( 'NONE', *, *, #19168, .F. ) ; +#16776 = CARTESIAN_POINT ( 'NONE', ( 6.026693642215255053, 134.9199437178238838, 90.79804054718465522 ) ) ; +#16777 = CARTESIAN_POINT ( 'NONE', ( -45.26910127184291355, 115.3600147242497655, 130.2183997636157358 ) ) ; +#16778 = EDGE_CURVE ( 'NONE', #15784, #33558, #11023, .T. ) ; +#16779 = EDGE_CURVE ( 'NONE', #27307, #15773, #10622, .T. ) ; +#16780 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#16781 = AXIS2_PLACEMENT_3D ( 'NONE', #21365, #36681, #30560 ) ; +#16782 = CARTESIAN_POINT ( 'NONE', ( 46.20495712151593182, 125.4530955044509994, 88.75919419801047638 ) ) ; +#16783 = ADVANCED_FACE ( 'NONE', ( #7526 ), #32485, .F. ) ; +#16784 = ORIENTED_EDGE ( 'NONE', *, *, #15057, .F. ) ; +#16785 = CARTESIAN_POINT ( 'NONE', ( -1.677606480948000023, 188.9082371776000002, 103.2668395941000057 ) ) ; +#16786 = EDGE_CURVE ( 'NONE', #36559, #36424, #23308, .T. ) ; +#16787 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971551247 ) ) ; +#16788 = CARTESIAN_POINT ( 'NONE', ( 2.942644232360999812, 190.8797677718000045, 106.6729900079999993 ) ) ; +#16789 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19091, #15632, #28127, #7021 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16790 = ORIENTED_EDGE ( 'NONE', *, *, #12874, .T. ) ; +#16791 = VERTEX_POINT ( 'NONE', #24106 ) ; +#16792 = LINE ( 'NONE', #39275, #22480 ) ; +#16793 = CARTESIAN_POINT ( 'NONE', ( 19.98232544185748694, 209.7096131673859816, 76.04619115725449774 ) ) ; +#16794 = VERTEX_POINT ( 'NONE', #40217 ) ; +#16795 = EDGE_LOOP ( 'NONE', ( #13548, #19645, #35248, #26630 ) ) ; +#16796 = CARTESIAN_POINT ( 'NONE', ( -25.50111726777775090, 120.6553742016506874, 88.03695713991920968 ) ) ; +#16797 = EDGE_LOOP ( 'NONE', ( #2523, #13271, #2551, #37720 ) ) ; +#16798 = CARTESIAN_POINT ( 'NONE', ( -26.55624928970721399, 189.5398351624320128, 103.4276817862043885 ) ) ; +#16799 = CARTESIAN_POINT ( 'NONE', ( 8.708260088791295317, 196.5784692043456516, 103.8697732926175235 ) ) ; +#16800 = DIRECTION ( 'NONE', ( -0.0005734119072319287039, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#16801 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27290, #33992, #2530, #15000, #20722, #39931, #8877, #11317, #21350, #23798, #2738, #36254, #5170, #17639, #25772, #35331, #13492, #23098, #7537, #25575 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000420219, 0.1875000000000630329, 0.2187500000000735523, 0.2343750000000709710, 0.2500000000000683897, 0.5000000000000383027, 0.6250000000000253131, 0.6875000000000132117, 0.7187500000000069944, 0.7343750000000068834, 0.7500000000000066613, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16802 = ORIENTED_EDGE ( 'NONE', *, *, #26909, .T. ) ; +#16803 = CARTESIAN_POINT ( 'NONE', ( 25.66683533177824472, 120.1550886336836328, 90.09407280630837533 ) ) ; +#16804 = CIRCLE ( 'NONE', #20043, 2.499999999997815525 ) ; +#16805 = AXIS2_PLACEMENT_3D ( 'NONE', #17205, #27266, #18014 ) ; +#16807 = DIRECTION ( 'NONE', ( -0.9999998268367383814, -0.0001323827281007119180, 0.0005734119867657175469 ) ) ; +#16806 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16808 = LINE ( 'NONE', #3936, #2707 ) ; +#16809 = ORIENTED_EDGE ( 'NONE', *, *, #15527, .T. ) ; +#16810 = CARTESIAN_POINT ( 'NONE', ( -17.26178222639411430, 121.7713432978476220, 175.3684242141576703 ) ) ; +#16811 = CARTESIAN_POINT ( 'NONE', ( -27.19659902433550158, 110.6131156702000027, 89.78421081230766276 ) ) ; +#16812 = ORIENTED_EDGE ( 'NONE', *, *, #11253, .F. ) ; +#16813 = EDGE_LOOP ( 'NONE', ( #20550, #18354, #4026, #27437, #33406, #27549 ) ) ; +#16814 = CARTESIAN_POINT ( 'NONE', ( -37.02440097146959630, 118.0188495538648965, 87.29014610246385075 ) ) ; +#16815 = EDGE_CURVE ( 'NONE', #11960, #27919, #39364, .T. ) ; +#16816 = CARTESIAN_POINT ( 'NONE', ( -46.09612443885006883, 125.3278102177660429, 91.69387951472775455 ) ) ; +#16817 = DIRECTION ( 'NONE', ( -0.6983012566254244158, 0.000000000000000000, -0.7158039920225042207 ) ) ; +#16818 = EDGE_CURVE ( 'NONE', #16617, #19286, #33479, .T. ) ; +#16819 = ORIENTED_EDGE ( 'NONE', *, *, #2979, .T. ) ; +#16820 = EDGE_LOOP ( 'NONE', ( #8305, #12383, #24010, #10937 ) ) ; +#16821 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#16822 = CARTESIAN_POINT ( 'NONE', ( 22.50176647125079654, 173.8430425847558354, 102.8561530174562222 ) ) ; +#16823 = EDGE_CURVE ( 'NONE', #40349, #23375, #9709, .T. ) ; +#16824 = ORIENTED_EDGE ( 'NONE', *, *, #26589, .F. ) ; +#16825 = CARTESIAN_POINT ( 'NONE', ( -35.43127413710199392, 192.7876450715299939, 106.8815844585819974 ) ) ; +#16826 = AXIS2_PLACEMENT_3D ( 'NONE', #5112, #4508, #10873 ) ; +#16827 = LINE ( 'NONE', #29327, #30776 ) ; +#16828 = ORIENTED_EDGE ( 'NONE', *, *, #5291, .T. ) ; +#16829 = CARTESIAN_POINT ( 'NONE', ( 39.04990644688274415, 118.8856079855554668, 89.67794042206942606 ) ) ; +#16830 = AXIS2_PLACEMENT_3D ( 'NONE', #38535, #7453, #4389 ) ; +#16831 = CARTESIAN_POINT ( 'NONE', ( -44.77033340054011745, 105.5798858094823771, 174.2946625126398033 ) ) ; +#16832 = CARTESIAN_POINT ( 'NONE', ( -14.22265864990228401, 129.0629248693782074, 176.7848948385215806 ) ) ; +#16833 = CARTESIAN_POINT ( 'NONE', ( -35.45484958737997516, 205.1071295952006324, 76.12626288494027449 ) ) ; +#16834 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8057, #35636, #8269, #14000 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16835 = VERTEX_POINT ( 'NONE', #9167 ) ; +#16836 = DIRECTION ( 'NONE', ( -0.3756662126443757188, -0.7425674685094612038, 0.5544983781661413369 ) ) ; +#16837 = CARTESIAN_POINT ( 'NONE', ( 22.73844078587000084, 180.7017300104000128, 28.07991271570000080 ) ) ; +#16838 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#16839 = CARTESIAN_POINT ( 'NONE', ( -20.01839880255527149, 211.0884570636477520, 76.07059838194729195 ) ) ; +#16840 = ORIENTED_EDGE ( 'NONE', *, *, #2537, .T. ) ; +#16841 = CARTESIAN_POINT ( 'NONE', ( 32.08976031478660929, 77.14301703112181485, 318.8298887698903741 ) ) ; +#16842 = CARTESIAN_POINT ( 'NONE', ( -36.08315564226000305, 112.4034012541000038, 89.65458067341999993 ) ) ; +#16843 = EDGE_LOOP ( 'NONE', ( #11732, #13513, #36262, #16032 ) ) ; +#16844 = ORIENTED_EDGE ( 'NONE', *, *, #28476, .F. ) ; +#16845 = ADVANCED_FACE ( 'NONE', ( #24316 ), #18733, .T. ) ; +#16846 = CARTESIAN_POINT ( 'NONE', ( -30.11038580418999899, 151.9652147204000130, 28.07991271570000080 ) ) ; +#16847 = ADVANCED_FACE ( 'NONE', ( #24922 ), #36758, .F. ) ; +#16848 = AXIS2_PLACEMENT_3D ( 'NONE', #23145, #7589, #22949 ) ; +#16849 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16850 = ADVANCED_FACE ( 'NONE', ( #27597 ), #34550, .F. ) ; +#16851 = CARTESIAN_POINT ( 'NONE', ( -56.27298699561663398, 71.65331048429315786, 282.5958934331605406 ) ) ; +#16852 = ORIENTED_EDGE ( 'NONE', *, *, #24941, .T. ) ; +#16853 = EDGE_CURVE ( 'NONE', #29958, #9058, #34281, .T. ) ; +#16854 = ORIENTED_EDGE ( 'NONE', *, *, #36939, .T. ) ; +#16855 = DIRECTION ( 'NONE', ( 0.0005884949961212385073, -0.2249510543439022514, 0.9743698870671273493 ) ) ; +#16856 = VECTOR ( 'NONE', #3940, 1000.000000000000227 ) ; +#16857 = EDGE_LOOP ( 'NONE', ( #5313, #4924, #22974 ) ) ; +#16858 = ORIENTED_EDGE ( 'NONE', *, *, #10435, .T. ) ; +#16859 = CARTESIAN_POINT ( 'NONE', ( 1.918799663737837724, 189.5286487069128327, 105.8885755798531250 ) ) ; +#16860 = DIRECTION ( 'NONE', ( 0.0002393071182785538528, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#16861 = ORIENTED_EDGE ( 'NONE', *, *, #12326, .T. ) ; +#16862 = CARTESIAN_POINT ( 'NONE', ( 37.23485478980474994, 185.6815848316524011, 105.5773190055030142 ) ) ; +#16863 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 2.782262518445068689E-15, -0.0006039748319343033085 ) ) ; +#16864 = CARTESIAN_POINT ( 'NONE', ( 38.27239922564999830, 118.3969922751000041, 87.79417198072999895 ) ) ; +#16865 = CARTESIAN_POINT ( 'NONE', ( 36.33552280992999783, 191.7504287502000011, 104.2396449161000049 ) ) ; +#16866 = CARTESIAN_POINT ( 'NONE', ( 41.98377182996610202, 80.72020747014904885, 291.5331867890723743 ) ) ; +#16867 = ADVANCED_FACE ( 'NONE', ( #37759 ), #6675, .T. ) ; +#16868 = VERTEX_POINT ( 'NONE', #19143 ) ; +#16869 = CARTESIAN_POINT ( 'NONE', ( -23.35875116767058302, 176.9906340971583063, 103.4393502540127088 ) ) ; +#16870 = ORIENTED_EDGE ( 'NONE', *, *, #40140, .T. ) ; +#16871 = CARTESIAN_POINT ( 'NONE', ( -22.49823373578437113, 151.2926910092157868, 97.67409313451828723 ) ) ; +#16872 = CARTESIAN_POINT ( 'NONE', ( -35.95638742416511491, 209.7096535813600156, 73.58022093100927918 ) ) ; +#16873 = CARTESIAN_POINT ( 'NONE', ( 45.16919206690911892, 186.2581417638802463, 106.4094479429941060 ) ) ; +#16874 = VERTEX_POINT ( 'NONE', #9770 ) ; +#16875 = EDGE_CURVE ( 'NONE', #33874, #32027, #5104, .T. ) ; +#16876 = CARTESIAN_POINT ( 'NONE', ( -21.97178402990095236, 135.2954952222275153, 90.90161795910944420 ) ) ; +#16877 = AXIS2_PLACEMENT_3D ( 'NONE', #7980, #10866, #20241 ) ; +#16878 = CARTESIAN_POINT ( 'NONE', ( 0.8484015457715478048, 189.0205269402587760, 103.6908266210117660 ) ) ; +#16879 = CARTESIAN_POINT ( 'NONE', ( -15.99823486132897266, 118.9409032897876841, 90.20116722531848552 ) ) ; +#16880 = AXIS2_PLACEMENT_3D ( 'NONE', #30233, #27192, #29838 ) ; +#16881 = PLANE ( 'NONE', #37337 ) ; +#16882 = EDGE_LOOP ( 'NONE', ( #30781, #37962, #35383, #12734, #28830, #26947 ) ) ; +#16883 = CARTESIAN_POINT ( 'NONE', ( -26.12831152884999852, 191.8782704244000001, 103.7981124760000000 ) ) ; +#16884 = FACE_OUTER_BOUND ( 'NONE', #18275, .T. ) ; +#16885 = VECTOR ( 'NONE', #32406, 1000.000000000000114 ) ; +#16886 = CARTESIAN_POINT ( 'NONE', ( 38.15045221970718359, 118.4868570840783377, 87.66883015867043127 ) ) ; +#16887 = DIRECTION ( 'NONE', ( 0.0006039748319381496242, 1.231904546584163304E-14, 0.9999998176071845934 ) ) ; +#16888 = DIRECTION ( 'NONE', ( -0.6773442687123943928, -0.7356661890031861439, 0.000000000000000000 ) ) ; +#16889 = ORIENTED_EDGE ( 'NONE', *, *, #3084, .T. ) ; +#16890 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15644, #40377, #15257, #18690 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16891 = CARTESIAN_POINT ( 'NONE', ( 2.879966871558743868, 207.7152227517433403, 77.21019060626942121 ) ) ; +#16892 = CARTESIAN_POINT ( 'NONE', ( -76.10807331611901816, 155.7750440820818199, 98.22815292147127764 ) ) ; +#16893 = DIRECTION ( 'NONE', ( 0.9914448496618609719, 0.1271951731318045342, 0.02930013670514376375 ) ) ; +#16894 = CARTESIAN_POINT ( 'NONE', ( 36.45662811238000245, 191.0198550572999920, 106.6760028587000022 ) ) ; +#16895 = CARTESIAN_POINT ( 'NONE', ( 36.06506602550999929, 192.5926268146000098, 106.3586798020999993 ) ) ; +#16896 = EDGE_CURVE ( 'NONE', #31339, #11449, #8171, .T. ) ; +#16897 = CARTESIAN_POINT ( 'NONE', ( -16.15354643030308424, 152.0177870148501427, 180.9315030652959422 ) ) ; +#16898 = ADVANCED_FACE ( 'NONE', ( #28970 ), #7278, .F. ) ; +#16899 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825822545, 158.2317141435470376, 98.73576230545255328 ) ) ; +#16900 = ORIENTED_EDGE ( 'NONE', *, *, #10530, .T. ) ; +#16901 = CARTESIAN_POINT ( 'NONE', ( -5.669507493902576023, 181.2998697191823680, 104.3463240144063633 ) ) ; +#16903 = AXIS2_PLACEMENT_3D ( 'NONE', #17315, #29826, #29421 ) ; +#16902 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#16904 = CARTESIAN_POINT ( 'NONE', ( 35.55163102684422682, 113.4589874760156647, 87.24631199773988044 ) ) ; +#16905 = ADVANCED_FACE ( 'NONE', ( #25317 ), #37112, .F. ) ; +#16906 = AXIS2_PLACEMENT_3D ( 'NONE', #25684, #28534, #34633 ) ; +#16907 = LINE ( 'NONE', #24034, #13483 ) ; +#16908 = VERTEX_POINT ( 'NONE', #35274 ) ; +#16909 = PLANE ( 'NONE', #35031 ) ; +#16910 = CARTESIAN_POINT ( 'NONE', ( -45.39636767568900666, 130.6771924050837868, 92.41530714614147257 ) ) ; +#16911 = AXIS2_PLACEMENT_3D ( 'NONE', #8888, #18254, #30757 ) ; +#16912 = VERTEX_POINT ( 'NONE', #25517 ) ; +#16913 = ADVANCED_FACE ( 'NONE', ( #3603 ), #10177, .T. ) ; +#16914 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927790412197, -0.0005734119022076163575 ) ) ; +#16915 = CARTESIAN_POINT ( 'NONE', ( 23.77969838655435453, 115.1895133759981036, 87.25342195007469570 ) ) ; +#16916 = ORIENTED_EDGE ( 'NONE', *, *, #5442, .T. ) ; +#16917 = CARTESIAN_POINT ( 'NONE', ( 36.41030898367129964, 191.6852911315839663, 106.3796197328945965 ) ) ; +#16918 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19467, #3327, #25233, #25637, #25834, #16590, #37680, #15794, #28883, #9679, #15998, #25431, #38280, #2094, #13950, #4735, #8221, #17194, #1885, #29697 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), + ( 1.873882562120391099E-11, 0.0004916302229572380202, 0.0009832604271756500113, 0.001966520835612442335, 0.002458151039830843050, 0.002949781244049243332, 0.003441411448267643180, 0.003687226550376838767, 0.003810134101431441548, 0.003933041652486044329 ), + .UNSPECIFIED. ) ; +#16919 = CARTESIAN_POINT ( 'NONE', ( -35.44810745648619132, 109.6131156741000154, 87.28919406056773767 ) ) ; +#16920 = PLANE ( 'NONE', #5871 ) ; +#16921 = CARTESIAN_POINT ( 'NONE', ( 15.66686184794137127, 174.4404117407328840, 100.2583057336249368 ) ) ; +#16922 = ORIENTED_EDGE ( 'NONE', *, *, #28727, .F. ) ; +#16923 = EDGE_CURVE ( 'NONE', #4793, #38952, #33501, .T. ) ; +#16924 = CARTESIAN_POINT ( 'NONE', ( -13.49852954173680430, 158.2273469405900812, 98.75649715832007303 ) ) ; +#16925 = CARTESIAN_POINT ( 'NONE', ( -3.683314158571560082, 176.1742929228452113, 100.3281879834612909 ) ) ; +#16926 = CARTESIAN_POINT ( 'NONE', ( 20.94827535171210897, 136.6018947531004244, 91.17730147031002730 ) ) ; +#16927 = CARTESIAN_POINT ( 'NONE', ( 48.05258722404280292, 141.3314364184359420, 335.5134981609783154 ) ) ; +#16928 = ORIENTED_EDGE ( 'NONE', *, *, #12936, .F. ) ; +#16929 = ORIENTED_EDGE ( 'NONE', *, *, #9777, .F. ) ; +#16930 = ORIENTED_EDGE ( 'NONE', *, *, #21006, .F. ) ; +#16931 = CARTESIAN_POINT ( 'NONE', ( -21.69612205307337760, 152.4962460410746417, 197.7980205213018507 ) ) ; +#16932 = AXIS2_PLACEMENT_3D ( 'NONE', #12372, #5636, #18288 ) ; +#16933 = VECTOR ( 'NONE', #34807, 1000.000000000000114 ) ; +#16934 = CARTESIAN_POINT ( 'NONE', ( 38.22927031300470446, 118.1319447778811735, 89.66605183978815319 ) ) ; +#16935 = LINE ( 'NONE', #1009, #5824 ) ; +#16936 = CONICAL_SURFACE ( 'NONE', #27460, 2.499999999973934628, 0.7853981633778842619 ) ; +#16937 = AXIS2_PLACEMENT_3D ( 'NONE', #37401, #180, #18760 ) ; +#16938 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1457, #11275, #4728, #29284 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16939 = CIRCLE ( 'NONE', #3239, 9.000000000000008882 ) ; +#16940 = CARTESIAN_POINT ( 'NONE', ( 13.85658554640870932, 150.4134353348987929, 179.9607612626138007 ) ) ; +#16941 = CARTESIAN_POINT ( 'NONE', ( 25.41600307607999909, 190.8124423181000111, 106.1157579006000020 ) ) ; +#16942 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3409, #37173, #5886, #6474 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.003918820842042696796, 0.004627366295791773831 ), + .UNSPECIFIED. ) ; +#16943 = CARTESIAN_POINT ( 'NONE', ( -6.036122723735069862, 176.7409673271154702, 103.0261968760796378 ) ) ; +#16944 = CARTESIAN_POINT ( 'NONE', ( 38.30887535778000341, 118.7291051865999947, 90.10309265731001460 ) ) ; +#16945 = ORIENTED_EDGE ( 'NONE', *, *, #22437, .T. ) ; +#16946 = CARTESIAN_POINT ( 'NONE', ( 42.53291556922801675, 121.0577657085915035, 91.31834487752931295 ) ) ; +#16947 = CARTESIAN_POINT ( 'NONE', ( -28.26185612672702518, 125.5768230428473373, 89.17483656727264929 ) ) ; +#16948 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391911088 ) ) ; +#16949 = EDGE_CURVE ( 'NONE', #17966, #27038, #32243, .T. ) ; +#16950 = EDGE_CURVE ( 'NONE', #36191, #11452, #16480, .T. ) ; +#16951 = CARTESIAN_POINT ( 'NONE', ( -20.50065345750364898, 194.0643729098902384, 103.3282459304506773 ) ) ; +#16952 = VERTEX_POINT ( 'NONE', #35074 ) ; +#16953 = VERTEX_POINT ( 'NONE', #9972 ) ; +#16954 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #21675, #27820, #3041, #36999, #37402, #9800, #22274, #8999, #30869, #12648 ), + ( #12066, #37788, #21474, #31465, #34496, #34114, #25143, #18974, #15322, #18165 ), + ( #5718, #24544, #37590, #9591, #30671, #6109, #18565, #3237, #21865, #2667 ), + ( #12449, #22069, #3430, #33916, #28403, #9393, #376, #18368, #5914, #27621 ), + ( #40246, #12259, #181, #15908, #34312, #12863, #24749, #15712, #37201, #9197 ), + ( #31068, #6304, #15522, #28011, #40448, #24948, #18761, #31259, #776, #10797 ), + ( #6911, #38584, #38775, #4442, #7302, #35491, #13850, #7107, #22474, #10401 ), + ( #19767, #16504, #34897, #3832, #19382, #28993, #16895, #34701, #37992, #16312 ), + ( #19578, #16118, #31876, #10598, #28796, #22872, #23067, #569, #25947, #22677 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 4 ), + ( 4, 3, 3, 4 ), + ( 7.328236918486999764E-07, 0.2500013691263999749, 0.5000009923943999901, 0.6250008040283000499, 0.7500006156623000297, 0.8750004272963000096, 0.9999999999973999687 ), + ( 0.07073812993396939863, 0.07915448979703999799, 0.9207904761041000308, 0.9292068359671706856 ), + .UNSPECIFIED. ) ; +#16955 = VERTEX_POINT ( 'NONE', #22446 ) ; +#16956 = CARTESIAN_POINT ( 'NONE', ( -13.49987458194983425, 124.7394176591053423, 88.97259030931672896 ) ) ; +#16957 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34894, #9995, #10202, #16307, #19163, #565, #13060, #23063, #25541, #35488 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16958 = DIRECTION ( 'NONE', ( 0.0005884949961251158311, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#16959 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -0.000000000000000000, 0.0006039748319387908213 ) ) ; +#16960 = ORIENTED_EDGE ( 'NONE', *, *, #19991, .F. ) ; +#16961 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999905853, 179.7376864902958005, 101.1595092800906457 ) ) ; +#16962 = AXIS2_PLACEMENT_3D ( 'NONE', #27325, #24253, #14020 ) ; +#16963 = CARTESIAN_POINT ( 'NONE', ( -35.33451947138878069, 160.3133637736180219, 188.0241402224691569 ) ) ; +#16964 = CARTESIAN_POINT ( 'NONE', ( 44.88493990080282714, 186.3882837704542510, 107.4179575081553253 ) ) ; +#16965 = CARTESIAN_POINT ( 'NONE', ( -39.60525137617000269, 120.0401714335000207, 87.73240259396999363 ) ) ; +#16966 = CARTESIAN_POINT ( 'NONE', ( -26.01186646957073378, 210.6300580106999973, 73.07250685818237912 ) ) ; +#16967 = EDGE_LOOP ( 'NONE', ( #39253, #23884, #33969, #28917, #18325, #11727, #30874, #26358, #27570 ) ) ; +#16968 = CARTESIAN_POINT ( 'NONE', ( -37.31440426593247395, 172.2715631620466468, 165.0215178663606252 ) ) ; +#16969 = CIRCLE ( 'NONE', #16310, 2.499999999420936092 ) ; +#16970 = VERTEX_POINT ( 'NONE', #7080 ) ; +#16971 = CARTESIAN_POINT ( 'NONE', ( -46.25461004409986288, 125.6172549309450801, 93.81340741558051377 ) ) ; +#16972 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566790 ) ) ; +#16973 = CARTESIAN_POINT ( 'NONE', ( 43.07948244848589070, 114.2049668346823239, 142.4505081202680401 ) ) ; +#16974 = ORIENTED_EDGE ( 'NONE', *, *, #33366, .F. ) ; +#16975 = EDGE_CURVE ( 'NONE', #27038, #20569, #25117, .T. ) ; +#16976 = CARTESIAN_POINT ( 'NONE', ( -1.066424343056000090, 188.6647002756000120, 103.2102455249000030 ) ) ; +#16977 = DIRECTION ( 'NONE', ( 0.1782590667764302472, 0.3529010024509862120, -0.9185230468426391903 ) ) ; +#16978 = CARTESIAN_POINT ( 'NONE', ( 3.199984448537000592, 190.8479886215000079, 106.9296817209000068 ) ) ; +#16979 = ORIENTED_EDGE ( 'NONE', *, *, #3523, .F. ) ; +#16980 = CARTESIAN_POINT ( 'NONE', ( -24.54100696812323790, 121.5315340049588855, 173.9846402519010269 ) ) ; +#16981 = CARTESIAN_POINT ( 'NONE', ( 37.28972155214677997, 111.6142886700882713, 151.1857112732826636 ) ) ; +#16982 = EDGE_LOOP ( 'NONE', ( #4500, #2190, #3006, #32471, #8342, #10536 ) ) ; +#16983 = EDGE_CURVE ( 'NONE', #37750, #29048, #6703, .T. ) ; +#16984 = ORIENTED_EDGE ( 'NONE', *, *, #33448, .F. ) ; +#16985 = CARTESIAN_POINT ( 'NONE', ( -45.30255556275930928, 123.8777291761282129, 93.38906572069882372 ) ) ; +#16986 = ORIENTED_EDGE ( 'NONE', *, *, #32882, .T. ) ; +#16987 = CARTESIAN_POINT ( 'NONE', ( -28.34546150099999906, 186.5535928724000030, 105.4761456043000010 ) ) ; +#16988 = CARTESIAN_POINT ( 'NONE', ( -8.331143224077584009, 150.6641467966076391, 97.17832424337015595 ) ) ; +#16989 = AXIS2_PLACEMENT_3D ( 'NONE', #5429, #26718, #39570 ) ; +#16990 = EDGE_CURVE ( 'NONE', #1667, #28306, #6473, .T. ) ; +#16991 = CIRCLE ( 'NONE', #24871, 6.000000000067867489 ) ; +#16992 = CARTESIAN_POINT ( 'NONE', ( -5.670703162332638492, 181.9020850521579575, 101.9448554198169745 ) ) ; +#16993 = ORIENTED_EDGE ( 'NONE', *, *, #2845, .T. ) ; +#16994 = CARTESIAN_POINT ( 'NONE', ( 25.66721973961999836, 120.1770533424000007, 90.11923128508999525 ) ) ; +#16995 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28632, #18792, #15743, #12685 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#16996 = VECTOR ( 'NONE', #25710, 1000.000000000000000 ) ; +#16997 = DIRECTION ( 'NONE', ( 0.7933532411131102302, 0.5932638852154231701, 0.1364866195435442964 ) ) ; +#16998 = EDGE_CURVE ( 'NONE', #22653, #33715, #12301, .T. ) ; +#16999 = EDGE_CURVE ( 'NONE', #37463, #31691, #20120, .T. ) ; +#17001 = CARTESIAN_POINT ( 'NONE', ( -12.92992625491334735, 154.3966043506143251, 95.30599622086934630 ) ) ; +#17000 = CARTESIAN_POINT ( 'NONE', ( 25.49186599382388962, 210.6299066825333171, 75.54315863433498635 ) ) ; +#17002 = EDGE_CURVE ( 'NONE', #26903, #12880, #38367, .T. ) ; +#17003 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#17004 = ORIENTED_EDGE ( 'NONE', *, *, #29398, .F. ) ; +#17005 = CARTESIAN_POINT ( 'NONE', ( 25.91302100389999907, 181.8795946532999892, 101.8840615430000014 ) ) ; +#17006 = CARTESIAN_POINT ( 'NONE', ( 5.696483686681999892, 174.3879284816999871, 152.4718672074000381 ) ) ; +#17007 = EDGE_LOOP ( 'NONE', ( #38451, #25615, #6868, #30195 ) ) ; +#17008 = CARTESIAN_POINT ( 'NONE', ( 38.90081508490000317, 118.9029124540000026, 89.81098821378002128 ) ) ; +#17009 = CARTESIAN_POINT ( 'NONE', ( 75.31277094998291943, 196.2503230467754349, 191.1794474674156277 ) ) ; +#17010 = CARTESIAN_POINT ( 'NONE', ( 5.669394968218998798, 187.4866721514941048, 105.7623639025581213 ) ) ; +#17011 = DIRECTION ( 'NONE', ( 0.0004161288024376838296, -0.8480480898185422944, 0.5299191109895370344 ) ) ; +#17012 = ORIENTED_EDGE ( 'NONE', *, *, #39868, .F. ) ; +#17013 = ORIENTED_EDGE ( 'NONE', *, *, #25005, .F. ) ; +#17014 = CARTESIAN_POINT ( 'NONE', ( -23.36112933754671062, 134.4863425043212715, 93.58469975075284708 ) ) ; +#17015 = AXIS2_PLACEMENT_3D ( 'NONE', #8099, #13632, #14446 ) ; +#17016 = ORIENTED_EDGE ( 'NONE', *, *, #29462, .T. ) ; +#17017 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 77.27946979429628982, 310.0857197240630967 ) ) ; +#17018 = VECTOR ( 'NONE', #3755, 1000.000000000000000 ) ; +#17019 = ORIENTED_EDGE ( 'NONE', *, *, #21905, .F. ) ; +#17020 = CARTESIAN_POINT ( 'NONE', ( -12.63318022686153697, 177.7898047555129040, 100.7065638408787436 ) ) ; +#17021 = AXIS2_PLACEMENT_3D ( 'NONE', #35917, #17308, #15482 ) ; +#17022 = VECTOR ( 'NONE', #34909, 1000.000000000000114 ) ; +#17023 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825939415874888, 0.0005734119019403442589 ) ) ; +#17024 = ORIENTED_EDGE ( 'NONE', *, *, #4530, .F. ) ; +#17025 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; +#17026 = FACE_OUTER_BOUND ( 'NONE', #6002, .T. ) ; +#17027 = DIRECTION ( 'NONE', ( -0.0004161288024528938308, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#17028 = CARTESIAN_POINT ( 'NONE', ( 42.42192200091505327, 180.1607944338011862, 148.5017479457221441 ) ) ; +#17029 = EDGE_CURVE ( 'NONE', #24015, #14526, #26928, .T. ) ; +#17030 = ORIENTED_EDGE ( 'NONE', *, *, #32667, .T. ) ; +#17031 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#17032 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 6.705467647123323749E-18, 0.0006039748319385910029 ) ) ; +#17033 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22128, #13124, #34756, #9451 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.001817041690626580372, 0.003004561830990456345 ), + .UNSPECIFIED. ) ; +#17034 = CARTESIAN_POINT ( 'NONE', ( -29.44951657505878728, 160.9899919687744330, 187.1078845272746776 ) ) ; +#17035 = EDGE_CURVE ( 'NONE', #16388, #10860, #17144, .T. ) ; +#17036 = VERTEX_POINT ( 'NONE', #17483 ) ; +#17037 = EDGE_CURVE ( 'NONE', #34614, #15536, #14041, .T. ) ; +#17038 = CARTESIAN_POINT ( 'NONE', ( -76.10807331609906612, 155.7904255491920367, 98.23170401354687442 ) ) ; +#17039 = VECTOR ( 'NONE', #12464, 1000.000000000000114 ) ; +#17040 = ADVANCED_FACE ( 'NONE', ( #4811 ), #32440, .F. ) ; +#17042 = CARTESIAN_POINT ( 'NONE', ( -37.74902905047999724, 117.4606082276000052, 89.56629544742000348 ) ) ; +#17041 = LINE ( 'NONE', #25743, #6973 ) ; +#17043 = EDGE_CURVE ( 'NONE', #25569, #11123, #10992, .T. ) ; +#17044 = ORIENTED_EDGE ( 'NONE', *, *, #28931, .T. ) ; +#17045 = CARTESIAN_POINT ( 'NONE', ( -22.54486751829999847, 202.1123865979000129, 28.07991271570000080 ) ) ; +#17046 = ADVANCED_FACE ( 'NONE', ( #36307 ), #29786, .F. ) ; +#17047 = VECTOR ( 'NONE', #25032, 1000.000000000000000 ) ; +#17048 = ORIENTED_EDGE ( 'NONE', *, *, #22806, .T. ) ; +#17049 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17050 = CARTESIAN_POINT ( 'NONE', ( 37.24531140497809645, 191.0903604573513519, 106.2990387539292385 ) ) ; +#17051 = CARTESIAN_POINT ( 'NONE', ( -38.81604098509072998, 106.1964408357682856, 169.3067908620723472 ) ) ; +#17052 = FACE_OUTER_BOUND ( 'NONE', #31425, .T. ) ; +#17053 = ORIENTED_EDGE ( 'NONE', *, *, #29313, .T. ) ; +#17054 = ORIENTED_EDGE ( 'NONE', *, *, #28298, .F. ) ; +#17055 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606773498981405, 136.6775772631814618, 180.9814965275718919 ) ) ; +#17056 = ORIENTED_EDGE ( 'NONE', *, *, #12194, .F. ) ; +#17057 = VERTEX_POINT ( 'NONE', #39167 ) ; +#17058 = CARTESIAN_POINT ( 'NONE', ( 77.66065009075275327, 193.3992594998515244, 188.4681838635439419 ) ) ; +#17059 = CARTESIAN_POINT ( 'NONE', ( 2.838525112095999781, 209.4270098178000126, 73.22775551082000334 ) ) ; +#17060 = ORIENTED_EDGE ( 'NONE', *, *, #9188, .T. ) ; +#17061 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17062 = PLANE ( 'NONE', #36809 ) ; +#17063 = CARTESIAN_POINT ( 'NONE', ( -33.42986125250909168, 142.5729643372171722, 280.9723740511064989 ) ) ; +#17064 = CARTESIAN_POINT ( 'NONE', ( 37.75543887471000204, 191.1265769391000049, 103.8768853900000124 ) ) ; +#17065 = PLANE ( 'NONE', #29431 ) ; +#17066 = ORIENTED_EDGE ( 'NONE', *, *, #1269, .T. ) ; +#17067 = CARTESIAN_POINT ( 'NONE', ( 28.69329030557365101, 225.5077044868852170, 152.4737688808613711 ) ) ; +#17068 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971573729 ) ) ; +#17069 = ORIENTED_EDGE ( 'NONE', *, *, #25927, .T. ) ; +#17070 = FACE_OUTER_BOUND ( 'NONE', #27754, .T. ) ; +#17071 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825963514080415, 0.0005734119013848138109 ) ) ; +#17072 = AXIS2_PLACEMENT_3D ( 'NONE', #26015, #16571, #1243 ) ; +#17073 = CARTESIAN_POINT ( 'NONE', ( -14.29753829223670003, 176.6356860434633802, 100.7832211550218346 ) ) ; +#17074 = CARTESIAN_POINT ( 'NONE', ( -19.70071604027683065, 149.4445624503525778, 181.7665744593643637 ) ) ; +#17075 = VERTEX_POINT ( 'NONE', #10974 ) ; +#17076 = AXIS2_PLACEMENT_3D ( 'NONE', #16100, #19152, #22854 ) ; +#17077 = CARTESIAN_POINT ( 'NONE', ( 45.03701848846946376, 181.3762064645945600, 101.6707694279998293 ) ) ; +#17078 = AXIS2_PLACEMENT_3D ( 'NONE', #35692, #7706, #16111 ) ; +#17079 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567900 ) ) ; +#17080 = CARTESIAN_POINT ( 'NONE', ( -14.29593191187739087, 209.7096839136990809, 76.06713901443235670 ) ) ; +#17081 = EDGE_CURVE ( 'NONE', #8531, #24276, #30630, .T. ) ; +#17082 = EDGE_CURVE ( 'NONE', #5645, #40029, #12951, .T. ) ; +#17083 = ORIENTED_EDGE ( 'NONE', *, *, #30795, .T. ) ; +#17084 = CARTESIAN_POINT ( 'NONE', ( 37.28123020134204779, 185.8375337558694866, 106.4638125528461501 ) ) ; +#17085 = EDGE_LOOP ( 'NONE', ( #5939, #31621, #32806, #11896 ) ) ; +#17086 = EDGE_CURVE ( 'NONE', #32727, #20686, #7685, .T. ) ; +#17087 = CARTESIAN_POINT ( 'NONE', ( -26.13221451157999908, 191.7053700682999988, 103.7821650485000049 ) ) ; +#17088 = DIRECTION ( 'NONE', ( -0.0005884949961245386019, 0.2249510543439047772, -0.9743698870671267942 ) ) ; +#17089 = CARTESIAN_POINT ( 'NONE', ( 37.78115515336936880, 118.8155650090541968, 87.24496173037786662 ) ) ; +#17090 = EDGE_CURVE ( 'NONE', #921, #24745, #7056, .T. ) ; +#17091 = CARTESIAN_POINT ( 'NONE', ( 15.94070757266567995, 152.8237909711254190, 181.6389010276846818 ) ) ; +#17092 = LINE ( 'NONE', #35901, #28450 ) ; +#17093 = ORIENTED_EDGE ( 'NONE', *, *, #32442, .F. ) ; +#17094 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#17095 = ADVANCED_FACE ( 'NONE', ( #20559 ), #14442, .T. ) ; +#17096 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 4.622231866529367416E-33, -0.0006039748319394906738 ) ) ; +#17097 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749898865, 181.8223093628335221, 102.1321913515297126 ) ) ; +#17098 = CARTESIAN_POINT ( 'NONE', ( -2.955788759824745426, 209.1883112457904019, 73.08018916681729138 ) ) ; +#17099 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901141, 134.9773540767009763, 93.88293913757796361 ) ) ; +#17100 = CARTESIAN_POINT ( 'NONE', ( 32.44146722115601023, 176.1285443563099022, 100.2958076299900938 ) ) ; +#17101 = LINE ( 'NONE', #29409, #2162 ) ; +#17102 = CARTESIAN_POINT ( 'NONE', ( -5.666943510250832539, 130.1499721591725347, 92.51434240712107737 ) ) ; +#17103 = VECTOR ( 'NONE', #37026, 1000.000000000000114 ) ; +#17104 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498900431, 132.2978364233248953, 93.26432363101957890 ) ) ; +#17105 = ORIENTED_EDGE ( 'NONE', *, *, #37283, .T. ) ; +#17106 = VECTOR ( 'NONE', #25275, 999.9999999999998863 ) ; +#17107 = EDGE_CURVE ( 'NONE', #3220, #36851, #33028, .T. ) ; +#17108 = LINE ( 'NONE', #29607, #172 ) ; +#17109 = VECTOR ( 'NONE', #38529, 1000.000000000000114 ) ; +#17110 = CARTESIAN_POINT ( 'NONE', ( 17.18127995227040117, 121.6259304897876774, 177.7629839600756156 ) ) ; +#17111 = CARTESIAN_POINT ( 'NONE', ( 0.05451946023377000211, 104.1131156706999974, 90.26775191081999594 ) ) ; +#17112 = DIRECTION ( 'NONE', ( 0.0004161288024603425708, -0.8480480897887666680, 0.5299191110371879176 ) ) ; +#17113 = ORIENTED_EDGE ( 'NONE', *, *, #20320, .F. ) ; +#17114 = CARTESIAN_POINT ( 'NONE', ( 26.00894335418652048, 191.9759150222000130, 103.9057414310139080 ) ) ; +#17115 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564847 ) ) ; +#17116 = EDGE_LOOP ( 'NONE', ( #36207, #18274, #2412, #10060 ) ) ; +#17117 = LINE ( 'NONE', #35923, #14961 ) ; +#17118 = ORIENTED_EDGE ( 'NONE', *, *, #37738, .T. ) ; +#17119 = LINE ( 'NONE', #36356, #13798 ) ; +#17120 = DIRECTION ( 'NONE', ( -0.0005884949961191883894, 0.2249510543439073307, -0.9743698870671261281 ) ) ; +#17121 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#17122 = CARTESIAN_POINT ( 'NONE', ( -12.63510598152721975, 130.9323451246731338, 89.96358487428598494 ) ) ; +#17123 = LINE ( 'NONE', #23092, #8654 ) ; +#17124 = EDGE_LOOP ( 'NONE', ( #4302, #25641, #16323, #33110, #21378, #7907, #20884, #4705 ) ) ; +#17125 = PLANE ( 'NONE', #1653 ) ; +#17126 = CARTESIAN_POINT ( 'NONE', ( 12.63703436142900216, 181.9093167050804709, 101.9420519965222240 ) ) ; +#17127 = CIRCLE ( 'NONE', #34129, 2.000000001304274910 ) ; +#17128 = CARTESIAN_POINT ( 'NONE', ( 37.42082352723856076, 132.6200669550715929, 336.9739440566017379 ) ) ; +#17129 = EDGE_CURVE ( 'NONE', #26262, #6484, #2310, .T. ) ; +#17131 = ORIENTED_EDGE ( 'NONE', *, *, #16584, .T. ) ; +#17130 = EDGE_CURVE ( 'NONE', #30603, #16668, #10353, .T. ) ; +#17132 = CARTESIAN_POINT ( 'NONE', ( 17.02597799957154834, 152.4294734933178290, 182.1650376563844702 ) ) ; +#17133 = ADVANCED_FACE ( 'NONE', ( #29575 ), #21457, .F. ) ; +#17134 = ORIENTED_EDGE ( 'NONE', *, *, #37539, .T. ) ; +#17135 = AXIS2_PLACEMENT_3D ( 'NONE', #37156, #36958, #9350 ) ; +#17136 = CARTESIAN_POINT ( 'NONE', ( 42.83487131658636571, 120.7910107177263797, 92.64688251868901148 ) ) ; +#17137 = EDGE_CURVE ( 'NONE', #24276, #629, #7648, .T. ) ; +#17138 = CARTESIAN_POINT ( 'NONE', ( 37.39185766581847759, 191.0442970149452151, 103.7363911818666509 ) ) ; +#17139 = CARTESIAN_POINT ( 'NONE', ( 16.16729401867695515, 152.0078996042194603, 180.9416867539977716 ) ) ; +#17140 = CONICAL_SURFACE ( 'NONE', #31527, 2.502999398265778108, 0.7853981633749954616 ) ; +#17141 = FACE_OUTER_BOUND ( 'NONE', #32158, .T. ) ; +#17142 = EDGE_CURVE ( 'NONE', #36832, #28131, #16198, .T. ) ; +#17143 = CARTESIAN_POINT ( 'NONE', ( 18.58912714118548237, 148.0271172827300177, 184.1229846802908128 ) ) ; +#17144 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #19944, #35884, #26119, #7889 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.1325196467246753107, 1.704150287259436958 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8045411634788308675, 0.8045411634788308675, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#17145 = CARTESIAN_POINT ( 'NONE', ( 25.49183423580130636, 211.0903769678246817, 75.54322026927223988 ) ) ; +#17146 = EDGE_CURVE ( 'NONE', #28366, #29855, #20839, .T. ) ; +#17147 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8971, #21446, #40215, #37168 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17148 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; +#17149 = CARTESIAN_POINT ( 'NONE', ( 20.48049177332755733, 208.4149586973334181, 73.73637375758902124 ) ) ; +#17150 = CARTESIAN_POINT ( 'NONE', ( 26.55314565214595035, 123.1309328123378606, 88.06389908587492243 ) ) ; +#17151 = ORIENTED_EDGE ( 'NONE', *, *, #29307, .F. ) ; +#17152 = DIRECTION ( 'NONE', ( 0.9999998160276427628, 6.024061281570464090E-07, -0.0006065841390484965311 ) ) ; +#17153 = LINE ( 'NONE', #17960, #4851 ) ; +#17154 = CARTESIAN_POINT ( 'NONE', ( -25.26021706816886692, 117.1739734221355889, 170.8214860574283591 ) ) ; +#17155 = FACE_OUTER_BOUND ( 'NONE', #8363, .T. ) ; +#17156 = EDGE_CURVE ( 'NONE', #25599, #20440, #37468, .T. ) ; +#17157 = ORIENTED_EDGE ( 'NONE', *, *, #10299, .F. ) ; +#17158 = EDGE_LOOP ( 'NONE', ( #28316, #28110, #13806, #25776 ) ) ; +#17159 = ORIENTED_EDGE ( 'NONE', *, *, #38303, .F. ) ; +#17160 = CARTESIAN_POINT ( 'NONE', ( 36.04796026473877646, 209.7096538831000032, 78.03673292964222696 ) ) ; +#17161 = CIRCLE ( 'NONE', #21781, 58.90509898151368873 ) ; +#17162 = CARTESIAN_POINT ( 'NONE', ( 22.31312662366504540, 116.2335386298891393, 182.3227435278615474 ) ) ; +#17163 = CARTESIAN_POINT ( 'NONE', ( -0.4543644820471367529, 208.9999999999988916, 75.55877896301241492 ) ) ; +#17164 = VERTEX_POINT ( 'NONE', #19049 ) ; +#17165 = AXIS2_PLACEMENT_3D ( 'NONE', #26905, #8080, #4598 ) ; +#17166 = ORIENTED_EDGE ( 'NONE', *, *, #19723, .F. ) ; +#17167 = CARTESIAN_POINT ( 'NONE', ( -13.83106602394250650, 188.3420923983079547, 103.1434753385557741 ) ) ; +#17168 = VECTOR ( 'NONE', #14632, 1000.000000000000000 ) ; +#17169 = CARTESIAN_POINT ( 'NONE', ( -35.83070930321999725, 112.8598257618999980, 87.67250422460000436 ) ) ; +#17170 = ORIENTED_EDGE ( 'NONE', *, *, #88, .F. ) ; +#17171 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17172 = ORIENTED_EDGE ( 'NONE', *, *, #17830, .T. ) ; +#17173 = DIRECTION ( 'NONE', ( -0.0006039748319380815363, -1.388651635424563573E-14, -0.9999998176071845934 ) ) ; +#17174 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319383098692 ) ) ; +#17175 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15024, #16213, #16410, #34409 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17176 = CARTESIAN_POINT ( 'NONE', ( 0.04442747709263908384, 271.9029643395999756, 73.55847734050897202 ) ) ; +#17177 = CARTESIAN_POINT ( 'NONE', ( 12.31706371121084231, 136.7942246724338702, 93.79267811176558212 ) ) ; +#17178 = ORIENTED_EDGE ( 'NONE', *, *, #28476, .T. ) ; +#17179 = CARTESIAN_POINT ( 'NONE', ( -19.99998967951139051, 191.8246488541593919, 103.9335226341060263 ) ) ; +#17180 = CARTESIAN_POINT ( 'NONE', ( -8.331143220612540645, 160.8442841037902724, 99.52859455750945017 ) ) ; +#17181 = CARTESIAN_POINT ( 'NONE', ( 28.53094770716555217, 124.6122665164779164, 91.48361085109841895 ) ) ; +#17182 = EDGE_CURVE ( 'NONE', #16030, #7007, #9627, .T. ) ; +#17183 = EDGE_LOOP ( 'NONE', ( #30369, #33269, #29093, #3218 ) ) ; +#17184 = CARTESIAN_POINT ( 'NONE', ( -2.390862647930000140, 209.5043720128000189, 75.55992074799000591 ) ) ; +#17185 = CARTESIAN_POINT ( 'NONE', ( -24.86160776171564990, 213.4882199952567419, 76.07240447855350851 ) ) ; +#17186 = ADVANCED_FACE ( 'NONE', ( #21946 ), #6381, .T. ) ; +#17187 = ORIENTED_EDGE ( 'NONE', *, *, #1536, .F. ) ; +#17188 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33193, #33410, #39543, #1945, #30158, #8490, #1737, #17050, #4995, #23414, #26898, #11143, #29549, #38939, #1522 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998973599, 0.3749999999998370748, 0.4374999999998115952, 0.4687499999997922773, 0.4843749999997982725, 0.4999999999998042677, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17189 = VERTEX_POINT ( 'NONE', #37073 ) ; +#17190 = VECTOR ( 'NONE', #19378, 1000.000000000000114 ) ; +#17191 = ORIENTED_EDGE ( 'NONE', *, *, #34859, .T. ) ; +#17192 = CARTESIAN_POINT ( 'NONE', ( 44.69319351362821635, 71.37631305377094293, 322.8294081051816420 ) ) ; +#17193 = ORIENTED_EDGE ( 'NONE', *, *, #9520, .T. ) ; +#17194 = CARTESIAN_POINT ( 'NONE', ( 3.063265537705500918, 190.7705380642428565, 106.7728354309631840 ) ) ; +#17195 = VECTOR ( 'NONE', #33162, 1000.000000000000114 ) ; +#17196 = LINE ( 'NONE', #7603, #2982 ) ; +#17197 = FACE_OUTER_BOUND ( 'NONE', #19783, .T. ) ; +#17198 = AXIS2_PLACEMENT_3D ( 'NONE', #22241, #28365, #34667 ) ; +#17199 = ORIENTED_EDGE ( 'NONE', *, *, #13565, .T. ) ; +#17200 = CARTESIAN_POINT ( 'NONE', ( -23.01844285970464909, 211.0902260919000355, 76.07552203529617429 ) ) ; +#17201 = VERTEX_POINT ( 'NONE', #3314 ) ; +#17202 = CARTESIAN_POINT ( 'NONE', ( 27.30158521878999878, 124.4440410757000137, 90.93222334034000198 ) ) ; +#17203 = PLANE ( 'NONE', #20850 ) ; +#17205 = CARTESIAN_POINT ( 'NONE', ( 5.666342389540173663, 185.9093800082626160, 102.5669869859405026 ) ) ; +#17204 = DIRECTION ( 'NONE', ( -0.0005884952009901332510, 0.2249510543175750887, -0.9743698870730815864 ) ) ; +#17206 = ORIENTED_EDGE ( 'NONE', *, *, #35841, .T. ) ; +#17207 = EDGE_CURVE ( 'NONE', #33874, #8706, #9468, .T. ) ; +#17208 = CYLINDRICAL_SURFACE ( 'NONE', #28243, 2.000000000000000000 ) ; +#17209 = EDGE_LOOP ( 'NONE', ( #32512, #12500, #7115, #34578, #27822, #10603, #23936, #16477 ) ) ; +#17210 = CARTESIAN_POINT ( 'NONE', ( -36.17271632336002085, 191.9052612783726772, 104.4154311915522015 ) ) ; +#17211 = ORIENTED_EDGE ( 'NONE', *, *, #22899, .F. ) ; +#17212 = DIRECTION ( 'NONE', ( -0.0005884949671858177161, 0.2249510543353067105, -0.9743698870691290814 ) ) ; +#17213 = LINE ( 'NONE', #8027, #18646 ) ; +#17214 = DIRECTION ( 'NONE', ( 0.6087614115774561130, 0.7729348350580500515, 0.1788331192145569681 ) ) ; +#17215 = DIRECTION ( 'NONE', ( 0.0002393071041605207214, 0.2255699564796172785, -0.9742269435125953114 ) ) ; +#17216 = CARTESIAN_POINT ( 'NONE', ( 36.11983317218000167, 191.5127010687999984, 103.8373663176000008 ) ) ; +#17217 = VECTOR ( 'NONE', #40081, 1000.000000000000000 ) ; +#17218 = ORIENTED_EDGE ( 'NONE', *, *, #38173, .F. ) ; +#17219 = VERTEX_POINT ( 'NONE', #21551 ) ; +#17220 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #28559, #526, #25501, #9957 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.570796326794893449, 1.750577995572639267 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973083591495172096, 0.9973083591495172096, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#17221 = DIRECTION ( 'NONE', ( -0.5988681445390194868, 0.8008476418498040594, 0.000000000000000000 ) ) ; +#17222 = ORIENTED_EDGE ( 'NONE', *, *, #1224, .F. ) ; +#17223 = AXIS2_PLACEMENT_3D ( 'NONE', #32329, #29266, #13718 ) ; +#17224 = CARTESIAN_POINT ( 'NONE', ( -35.46848709283599987, 192.2361886390060306, 106.9493674620740080 ) ) ; +#17225 = VERTEX_POINT ( 'NONE', #15783 ) ; +#17226 = ADVANCED_FACE ( 'NONE', ( #22352 ), #12941, .T. ) ; +#17227 = CARTESIAN_POINT ( 'NONE', ( 3.069762736230476907, 190.8498496381319569, 106.7968308444213648 ) ) ; +#17228 = EDGE_CURVE ( 'NONE', #34253, #16448, #17417, .T. ) ; +#17229 = ORIENTED_EDGE ( 'NONE', *, *, #19003, .F. ) ; +#17230 = FACE_OUTER_BOUND ( 'NONE', #10296, .T. ) ; +#17231 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772234801672, 136.6775772631780796, 180.9814965275865575 ) ) ; +#17232 = CARTESIAN_POINT ( 'NONE', ( 9.583319590155999990, 124.5551187389999939, 88.65952379800000926 ) ) ; +#17233 = LINE ( 'NONE', #7642, #13033 ) ; +#17234 = ORIENTED_EDGE ( 'NONE', *, *, #13296, .F. ) ; +#17235 = CARTESIAN_POINT ( 'NONE', ( -15.94446068766880487, 121.2107412334159591, 177.4020268254936923 ) ) ; +#17236 = LINE ( 'NONE', #26679, #2562 ) ; +#17237 = AXIS2_PLACEMENT_3D ( 'NONE', #2285, #21508, #33948 ) ; +#17238 = VECTOR ( 'NONE', #35120, 1000.000000000000000 ) ; +#17239 = EDGE_LOOP ( 'NONE', ( #14839, #23696, #15076 ) ) ; +#17240 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#17241 = DIRECTION ( 'NONE', ( 0.0005884949907373547388, -0.2249510543438368870, 0.9743698870671455570 ) ) ; +#17242 = ORIENTED_EDGE ( 'NONE', *, *, #37892, .F. ) ; +#17243 = EDGE_CURVE ( 'NONE', #20872, #17425, #31543, .T. ) ; +#17244 = CARTESIAN_POINT ( 'NONE', ( -6.028075236889769428, 177.1156665047246008, 103.6258451396837899 ) ) ; +#17245 = ORIENTED_EDGE ( 'NONE', *, *, #22614, .T. ) ; +#17246 = CARTESIAN_POINT ( 'NONE', ( 91.24547840862865655, 222.8067606030032550, 201.4280517774668624 ) ) ; +#17247 = CARTESIAN_POINT ( 'NONE', ( -20.33310178517772826, 127.6671047516186377, 89.48154071701799239 ) ) ; +#17248 = LINE ( 'NONE', #16851, #10995 ) ; +#17249 = ORIENTED_EDGE ( 'NONE', *, *, #27108, .T. ) ; +#17250 = ORIENTED_EDGE ( 'NONE', *, *, #8596, .T. ) ; +#17251 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265228896, -0.1368326740407719011 ) ) ; +#17252 = ORIENTED_EDGE ( 'NONE', *, *, #39501, .F. ) ; +#17253 = EDGE_LOOP ( 'NONE', ( #1181, #40154, #27958, #3739 ) ) ; +#17254 = ORIENTED_EDGE ( 'NONE', *, *, #26823, .F. ) ; +#17255 = CARTESIAN_POINT ( 'NONE', ( 20.00182604067493131, 190.8514159882993511, 106.7812686061269716 ) ) ; +#17256 = CARTESIAN_POINT ( 'NONE', ( 28.64561701362920942, 225.5077044868850180, 73.54120293868254521 ) ) ; +#17257 = CARTESIAN_POINT ( 'NONE', ( -2.851222922393109815, 209.7096616640929199, 76.06022722140575354 ) ) ; +#17258 = ORIENTED_EDGE ( 'NONE', *, *, #10743, .F. ) ; +#17259 = EDGE_CURVE ( 'NONE', #13129, #14154, #30944, .T. ) ; +#17260 = ORIENTED_EDGE ( 'NONE', *, *, #11684, .F. ) ; +#17261 = CARTESIAN_POINT ( 'NONE', ( 18.98780079260364317, 148.3242069017240681, 184.1917624428014904 ) ) ; +#17262 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#17263 = CARTESIAN_POINT ( 'NONE', ( -35.71142153204999659, 191.5606522780000205, 103.7690409172000017 ) ) ; +#17264 = CARTESIAN_POINT ( 'NONE', ( 36.61401666729999960, 191.8263800043999936, 104.5069429764999995 ) ) ; +#17265 = CARTESIAN_POINT ( 'NONE', ( -25.66782949977000428, 120.7016921406000023, 87.87645205366999335 ) ) ; +#17266 = AXIS2_PLACEMENT_3D ( 'NONE', #17290, #10987, #11186 ) ; +#17267 = ADVANCED_FACE ( 'NONE', ( #30742 ), #2736, .T. ) ; +#17268 = LINE ( 'NONE', #1970, #29099 ) ; +#17269 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921576300, -0.2249510932971598709 ) ) ; +#17270 = VERTEX_POINT ( 'NONE', #15397 ) ; +#17271 = VECTOR ( 'NONE', #27147, 1000.000000000000000 ) ; +#17272 = VECTOR ( 'NONE', #24521, 1000.000000000000114 ) ; +#17273 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17809, #18217, #30304, #8018 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17274 = DIRECTION ( 'NONE', ( -0.0005884949961246157971, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#17275 = DIRECTION ( 'NONE', ( -0.0006039748319382907873, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#17276 = VECTOR ( 'NONE', #35645, 1000.000000000000000 ) ; +#17277 = ADVANCED_FACE ( 'NONE', ( #6186 ), #13050, .F. ) ; +#17278 = CARTESIAN_POINT ( 'NONE', ( 20.50038014672672304, 194.9390793442601364, 105.3094855762004727 ) ) ; +#17279 = ADVANCED_FACE ( 'NONE', ( #7187 ), #34480, .F. ) ; +#17280 = FACE_OUTER_BOUND ( 'NONE', #30193, .T. ) ; +#17281 = ORIENTED_EDGE ( 'NONE', *, *, #22437, .F. ) ; +#17282 = CARTESIAN_POINT ( 'NONE', ( 20.00001350029910085, 189.3408603011638718, 103.3536401978308419 ) ) ; +#17283 = ADVANCED_FACE ( 'NONE', ( #25622 ), #653, .T. ) ; +#17284 = CARTESIAN_POINT ( 'NONE', ( 2.560074644014078693, 190.8728800184543104, 104.2237589072057773 ) ) ; +#17285 = CARTESIAN_POINT ( 'NONE', ( 32.50505481319044065, 136.7246762262726918, 91.19866780689935126 ) ) ; +#17286 = ORIENTED_EDGE ( 'NONE', *, *, #39255, .T. ) ; +#17287 = CARTESIAN_POINT ( 'NONE', ( 20.48008986686174282, 210.6299648728911222, 73.54684484258879706 ) ) ; +#17288 = ORIENTED_EDGE ( 'NONE', *, *, #23113, .F. ) ; +#17289 = CARTESIAN_POINT ( 'NONE', ( -25.61801701081000360, 191.6082135239000195, 104.2857596666000006 ) ) ; +#17290 = CARTESIAN_POINT ( 'NONE', ( 5.668111471659128320, 185.2331518488130655, 105.4960524095502734 ) ) ; +#17291 = CARTESIAN_POINT ( 'NONE', ( -25.45534549256436918, 211.7447000708251608, 73.57353581660497355 ) ) ; +#17292 = DIRECTION ( 'NONE', ( 1.804112415037046094E-14, 0.9743700557921584071, 0.2249510932971567900 ) ) ; +#17293 = ORIENTED_EDGE ( 'NONE', *, *, #28500, .F. ) ; +#17294 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#17295 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265227786, 0.1368326740407719844 ) ) ; +#17296 = EDGE_CURVE ( 'NONE', #24799, #39067, #20017, .T. ) ; +#17297 = VECTOR ( 'NONE', #24157, 1000.000000000000114 ) ; +#17298 = AXIS2_PLACEMENT_3D ( 'NONE', #10724, #36462, #14394 ) ; +#17299 = CARTESIAN_POINT ( 'NONE', ( -35.94008004079000074, 192.5552285418999929, 104.9676488416999973 ) ) ; +#17301 = CARTESIAN_POINT ( 'NONE', ( -16.88747875106462715, 122.0414632028714124, 175.0198840672369442 ) ) ; +#17300 = CIRCLE ( 'NONE', #24624, 2.249999999984611421 ) ; +#17302 = DIRECTION ( 'NONE', ( -0.0005884949961260158274, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#17303 = DIRECTION ( 'NONE', ( 0.0002265441438622214161, -0.9034129951719994667, 0.4287713946056891934 ) ) ; +#17304 = CARTESIAN_POINT ( 'NONE', ( -5.664830602385754865, 130.2917189741279458, 92.74118313415932846 ) ) ; +#17305 = CARTESIAN_POINT ( 'NONE', ( -38.39791937170240743, 118.8574915090185726, 87.72183780368946771 ) ) ; +#17306 = ORIENTED_EDGE ( 'NONE', *, *, #40206, .F. ) ; +#17307 = CARTESIAN_POINT ( 'NONE', ( 3.647052574382751544, 144.1925529306576266, 93.05594058926581624 ) ) ; +#17308 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; +#17309 = EDGE_CURVE ( 'NONE', #18814, #33719, #23389, .T. ) ; +#17310 = ORIENTED_EDGE ( 'NONE', *, *, #2081, .T. ) ; +#17311 = CARTESIAN_POINT ( 'NONE', ( 5.665019113453634958, 181.9430578531224967, 102.0015240401697554 ) ) ; +#17312 = VERTEX_POINT ( 'NONE', #28673 ) ; +#17313 = EDGE_CURVE ( 'NONE', #18192, #33506, #29604, .T. ) ; +#17314 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082099409, 3.782957827463197881E-12, 297.5876476292049801 ) ) ; +#17315 = CARTESIAN_POINT ( 'NONE', ( -61.84220049570050293, 78.72323700374754196, 282.5958934331605406 ) ) ; +#17316 = FACE_OUTER_BOUND ( 'NONE', #20679, .T. ) ; +#17317 = ORIENTED_EDGE ( 'NONE', *, *, #11912, .F. ) ; +#17318 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#17319 = ADVANCED_FACE ( 'NONE', ( #3914 ), #10073, .T. ) ; +#17320 = AXIS2_PLACEMENT_3D ( 'NONE', #23472, #4850, #27382 ) ; +#17321 = CARTESIAN_POINT ( 'NONE', ( 20.50029382537679723, 138.3995138256450446, 92.10573732898133414 ) ) ; +#17322 = CARTESIAN_POINT ( 'NONE', ( 3.064505435595261229, 190.8915653482034998, 106.8005998850467222 ) ) ; +#17323 = CONICAL_SURFACE ( 'NONE', #29123, 6.499999999885919699, 0.7853981633843651888 ) ; +#17324 = CARTESIAN_POINT ( 'NONE', ( 29.37618521805934080, 109.9008702326019886, 185.6692766672719017 ) ) ; +#17325 = CARTESIAN_POINT ( 'NONE', ( 30.01965015980229978, 186.1545558735057853, 102.6119579121506433 ) ) ; +#17326 = EDGE_CURVE ( 'NONE', #26196, #29062, #22550, .T. ) ; +#17327 = VERTEX_POINT ( 'NONE', #35178 ) ; +#17328 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421897730, 184.2914807614346273, 105.2707223254774931 ) ) ; +#17329 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#17330 = AXIS2_PLACEMENT_3D ( 'NONE', #13640, #6893, #35286 ) ; +#17331 = CARTESIAN_POINT ( 'NONE', ( 8.471855298021594649, 160.9702727382075125, 99.37648202509593887 ) ) ; +#17332 = CARTESIAN_POINT ( 'NONE', ( -28.47344760044883216, 181.6851202344923308, 101.6154648382260035 ) ) ; +#17333 = AXIS2_PLACEMENT_3D ( 'NONE', #33024, #5016, #17479 ) ; +#17334 = ORIENTED_EDGE ( 'NONE', *, *, #33070, .F. ) ; +#17335 = CARTESIAN_POINT ( 'NONE', ( 23.35635955975471134, 181.6919812636757285, 101.5857449861623110 ) ) ; +#17336 = CARTESIAN_POINT ( 'NONE', ( -43.60275574284717237, 120.4180340293254972, 91.53716516524805513 ) ) ; +#17337 = CARTESIAN_POINT ( 'NONE', ( 6.034635603964243700, 134.5587005980779622, 93.52506117850155931 ) ) ; +#17338 = FACE_OUTER_BOUND ( 'NONE', #35535, .T. ) ; +#17339 = CARTESIAN_POINT ( 'NONE', ( 31.91158940776717046, 137.5571349200599798, 93.95697525044668907 ) ) ; +#17340 = CARTESIAN_POINT ( 'NONE', ( -15.49970618479461137, 184.8500655517521807, 102.8514372352811108 ) ) ; +#17341 = CARTESIAN_POINT ( 'NONE', ( 20.50147089296921266, 119.8278772667796090, 89.87074392140300461 ) ) ; +#17342 = CARTESIAN_POINT ( 'NONE', ( 23.68587876377409529, 136.7957297058827351, 93.78615909692494768 ) ) ; +#17343 = CARTESIAN_POINT ( 'NONE', ( 28.13101631667413471, 125.0359381400565582, 88.50275130584401495 ) ) ; +#17344 = ORIENTED_EDGE ( 'NONE', *, *, #27154, .T. ) ; +#17345 = FACE_OUTER_BOUND ( 'NONE', #18717, .T. ) ; +#17346 = CARTESIAN_POINT ( 'NONE', ( 26.00076108762728211, 119.7153706401760758, 90.35460073770548206 ) ) ; +#17347 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15425, #21368, #37294, #27920, #5814, #15807, #12346, #9292, #12543, #9489 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17348 = CARTESIAN_POINT ( 'NONE', ( -91.29662383756267729, 223.8160270898476085, 197.5110405146249946 ) ) ; +#17349 = CARTESIAN_POINT ( 'NONE', ( 26.03550245107076933, 190.8511564191358900, 106.7775725292634945 ) ) ; +#17350 = CONICAL_SURFACE ( 'NONE', #19982, 2.499999999930474281, 0.7853981634269987522 ) ; +#17351 = CARTESIAN_POINT ( 'NONE', ( -38.34602178450000309, 118.5791799481999931, 89.90303731784000263 ) ) ; +#17352 = AXIS2_PLACEMENT_3D ( 'NONE', #18209, #30713, #2706 ) ; +#17353 = ORIENTED_EDGE ( 'NONE', *, *, #7492, .F. ) ; +#17354 = ORIENTED_EDGE ( 'NONE', *, *, #21206, .F. ) ; +#17355 = ORIENTED_EDGE ( 'NONE', *, *, #558, .T. ) ; +#17356 = CARTESIAN_POINT ( 'NONE', ( -23.35851273695973873, 177.6602557452652036, 100.7926513040667658 ) ) ; +#17357 = EDGE_CURVE ( 'NONE', #34643, #9107, #20054, .T. ) ; +#17358 = VECTOR ( 'NONE', #10317, 1000.000000000000114 ) ; +#17359 = EDGE_CURVE ( 'NONE', #14963, #29005, #20790, .T. ) ; +#17360 = CARTESIAN_POINT ( 'NONE', ( 26.32033074026975328, 114.4659742150060282, 176.3663696116665278 ) ) ; +#17361 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #3036, #12445 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17362 = DIRECTION ( 'NONE', ( -0.0005884949961254158299, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#17363 = EDGE_CURVE ( 'NONE', #21843, #29784, #34009, .T. ) ; +#17364 = AXIS2_PLACEMENT_3D ( 'NONE', #24371, #11682, #2872 ) ; +#17365 = EDGE_CURVE ( 'NONE', #10264, #6338, #31753, .T. ) ; +#17366 = ORIENTED_EDGE ( 'NONE', *, *, #9414, .F. ) ; +#17367 = FACE_BOUND ( 'NONE', #39977, .T. ) ; +#17368 = CARTESIAN_POINT ( 'NONE', ( -37.56657168646712108, 112.0458133426950695, 151.1389157892933781 ) ) ; +#17369 = CARTESIAN_POINT ( 'NONE', ( -36.09521837964000213, 112.8619364219999994, 87.93783553672000153 ) ) ; +#17370 = ORIENTED_EDGE ( 'NONE', *, *, #34490, .T. ) ; +#17371 = EDGE_CURVE ( 'NONE', #38213, #16794, #32078, .T. ) ; +#17372 = CARTESIAN_POINT ( 'NONE', ( -31.74259674813110266, 153.0051697192226641, 334.9416436895348284 ) ) ; +#17373 = ORIENTED_EDGE ( 'NONE', *, *, #34426, .F. ) ; +#17374 = DIRECTION ( 'NONE', ( -0.0005884949961236305826, 0.2249510543439055266, -0.9743698870671265722 ) ) ; +#17375 = CARTESIAN_POINT ( 'NONE', ( 20.33743256209849903, 184.3692938640446073, 104.9398584957469751 ) ) ; +#17376 = LINE ( 'NONE', #14755, #2586 ) ; +#17377 = CARTESIAN_POINT ( 'NONE', ( -3.255230332982838704, 186.5475403829457548, 102.7227827455729852 ) ) ; +#17378 = CARTESIAN_POINT ( 'NONE', ( -19.31467031021941949, 148.4018994673661780, 183.4532939704609760 ) ) ; +#17379 = EDGE_LOOP ( 'NONE', ( #11424, #29437, #25894, #27378 ) ) ; +#17380 = EDGE_CURVE ( 'NONE', #29108, #39755, #33857, .T. ) ; +#17381 = VERTEX_POINT ( 'NONE', #26625 ) ; +#17382 = CARTESIAN_POINT ( 'NONE', ( -2.470687046066000647, 189.8752689345000135, 103.6418612018999994 ) ) ; +#17383 = CARTESIAN_POINT ( 'NONE', ( 1.159933842655000102, 188.9561970069999859, 103.5493244023000017 ) ) ; +#17384 = DIRECTION ( 'NONE', ( 0.0006039748319371906473, -0.000000000000000000, 0.9999998176071844824 ) ) ; +#17385 = CARTESIAN_POINT ( 'NONE', ( 26.90851097252234325, 123.0590747987910589, 91.12600760642735054 ) ) ; +#17386 = VECTOR ( 'NONE', #20639, 1000.000000000000114 ) ; +#17387 = ORIENTED_EDGE ( 'NONE', *, *, #3840, .F. ) ; +#17388 = CARTESIAN_POINT ( 'NONE', ( 31.91041241775748105, 138.0070370287062644, 92.00823547631698318 ) ) ; +#17389 = VECTOR ( 'NONE', #521, 999.9999999999998863 ) ; +#17390 = ORIENTED_EDGE ( 'NONE', *, *, #25068, .T. ) ; +#17391 = ORIENTED_EDGE ( 'NONE', *, *, #13399, .T. ) ; +#17392 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #6092, #37571, #31046, #161 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.442085121493781097, 1.442120204651619719 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999998974310467, 0.9999999998974310467, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#17393 = AXIS2_PLACEMENT_3D ( 'NONE', #14310, #29852, #7747 ) ; +#17394 = EDGE_CURVE ( 'NONE', #8036, #20595, #6443, .T. ) ; +#17395 = AXIS2_PLACEMENT_3D ( 'NONE', #28678, #6384, #18843 ) ; +#17396 = ORIENTED_EDGE ( 'NONE', *, *, #17657, .F. ) ; +#17397 = DIRECTION ( 'NONE', ( 0.0005884965786932929224, -0.2255194605963585786, 0.9742384854665229188 ) ) ; +#17398 = ORIENTED_EDGE ( 'NONE', *, *, #10528, .F. ) ; +#17399 = CONICAL_SURFACE ( 'NONE', #36922, 2.503156890187742345, 0.7853981634156100844 ) ; +#17400 = CARTESIAN_POINT ( 'NONE', ( -27.84411046026790615, 187.9073204487185933, 103.0515638343963190 ) ) ; +#17401 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385318054 ) ) ; +#17402 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858958, 190.9636369981938913, 106.3296296870415887 ) ) ; +#17403 = CARTESIAN_POINT ( 'NONE', ( 22.50216366289214065, 153.7345681062837457, 98.21065990825610470 ) ) ; +#17404 = ORIENTED_EDGE ( 'NONE', *, *, #24059, .T. ) ; +#17405 = FACE_OUTER_BOUND ( 'NONE', #23971, .T. ) ; +#17406 = EDGE_LOOP ( 'NONE', ( #13219, #31765, #11573, #12316 ) ) ; +#17407 = CARTESIAN_POINT ( 'NONE', ( 26.06239804790540049, 120.9051242772579968, 90.63100925411518460 ) ) ; +#17408 = CARTESIAN_POINT ( 'NONE', ( -23.34599098040433063, 213.5902373340899487, 75.57257973203529389 ) ) ; +#17410 = CARTESIAN_POINT ( 'NONE', ( -42.64607636366788057, 189.6955224779507034, 106.3355408767127130 ) ) ; +#17409 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17411 = VERTEX_POINT ( 'NONE', #14954 ) ; +#17412 = EDGE_LOOP ( 'NONE', ( #35922, #38034, #957 ) ) ; +#17413 = AXIS2_PLACEMENT_3D ( 'NONE', #13979, #7628, #19291 ) ; +#17414 = EDGE_CURVE ( 'NONE', #16580, #10957, #6132, .T. ) ; +#17415 = EDGE_CURVE ( 'NONE', #19816, #35304, #30038, .T. ) ; +#17416 = CIRCLE ( 'NONE', #5607, 4.999999999999990230 ) ; +#17417 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #58, #454, #18438, #18638 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17418 = AXIS2_PLACEMENT_3D ( 'NONE', #12539, #12962, #15421 ) ; +#17419 = VERTEX_POINT ( 'NONE', #29686 ) ; +#17420 = CARTESIAN_POINT ( 'NONE', ( 38.71212993358000176, 119.3468886729999952, 90.42738107078000098 ) ) ; +#17421 = CARTESIAN_POINT ( 'NONE', ( -35.64769754903084475, 114.8291202300115117, 87.28931460809403120 ) ) ; +#17422 = DIRECTION ( 'NONE', ( -0.0002267487151011638629, -0.6230052038431761474, -0.7822176580526309930 ) ) ; +#17423 = CARTESIAN_POINT ( 'NONE', ( -21.44517147737999707, 135.1113278520462586, 93.93769420648519031 ) ) ; +#17424 = FACE_OUTER_BOUND ( 'NONE', #24139, .T. ) ; +#17425 = VERTEX_POINT ( 'NONE', #39065 ) ; +#17426 = EDGE_LOOP ( 'NONE', ( #16437, #9896, #36624, #27033 ) ) ; +#17427 = VERTEX_POINT ( 'NONE', #11076 ) ; +#17428 = CARTESIAN_POINT ( 'NONE', ( -37.20408499829227367, 178.1325612192622430, 136.7211859319445466 ) ) ; +#17429 = CARTESIAN_POINT ( 'NONE', ( 26.51446272604999876, 123.3842700242000063, 88.29346878733001347 ) ) ; +#17430 = ORIENTED_EDGE ( 'NONE', *, *, #20375, .T. ) ; +#17431 = ORIENTED_EDGE ( 'NONE', *, *, #11530, .F. ) ; +#17432 = DIRECTION ( 'NONE', ( -6.245004513516517373E-15, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#17433 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17434 = EDGE_LOOP ( 'NONE', ( #23653, #15439, #12002, #39375 ) ) ; +#17435 = CARTESIAN_POINT ( 'NONE', ( 39.30807791769741044, 119.0864935850325992, 89.70193021882299433 ) ) ; +#17436 = EDGE_CURVE ( 'NONE', #31729, #2793, #35992, .T. ) ; +#17437 = CARTESIAN_POINT ( 'NONE', ( 21.29537473037836293, 122.9345409059655196, 152.1198303650941170 ) ) ; +#17438 = CARTESIAN_POINT ( 'NONE', ( 20.45288617049414270, 153.3893259209510234, 95.05328524723617534 ) ) ; +#17439 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17440 = ORIENTED_EDGE ( 'NONE', *, *, #20606, .F. ) ; +#17441 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.271205363195980628E-14, -0.9999998176071845934 ) ) ; +#17442 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#17443 = VECTOR ( 'NONE', #33, 1000.000000000000114 ) ; +#17444 = FACE_OUTER_BOUND ( 'NONE', #7409, .T. ) ; +#17445 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30761, #11749, #37089, #8483 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17446 = EDGE_LOOP ( 'NONE', ( #18268, #26668, #2163, #31102 ) ) ; +#17447 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999894129, 179.7376864901495992, 101.1595092802908198 ) ) ; +#17448 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13563, #35000, #38100, #28903 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17450 = LINE ( 'NONE', #14823, #21363 ) ; +#17449 = CARTESIAN_POINT ( 'NONE', ( 13.48868993473300826, 135.2035988320031095, 90.85898476414814695 ) ) ; +#17451 = ORIENTED_EDGE ( 'NONE', *, *, #2632, .T. ) ; +#17452 = ORIENTED_EDGE ( 'NONE', *, *, #22384, .F. ) ; +#17453 = CARTESIAN_POINT ( 'NONE', ( -37.28640831843555503, 117.9292370818984352, 123.9370462788764087 ) ) ; +#17454 = CARTESIAN_POINT ( 'NONE', ( 38.60142841442970507, 118.4926359200404846, 89.66235211310707598 ) ) ; +#17455 = ORIENTED_EDGE ( 'NONE', *, *, #1784, .F. ) ; +#17456 = CARTESIAN_POINT ( 'NONE', ( 2.579967698511000052, 209.6022726829999954, 75.67849517673001003 ) ) ; +#17457 = DIRECTION ( 'NONE', ( -0.7933535325932937754, 0.5931614258681804364, 0.1369295263402624530 ) ) ; +#17458 = APPLICATION_CONTEXT ( 'configuration controlled 3d designs of mechanical parts and assemblies' ) ; +#17459 = DIRECTION ( 'NONE', ( -0.7857167650892391553, 0.6185862428610305885, 0.0004745532376930882562 ) ) ; +#17460 = EDGE_CURVE ( 'NONE', #13095, #33101, #30550, .T. ) ; +#17461 = ORIENTED_EDGE ( 'NONE', *, *, #34539, .F. ) ; +#17462 = EDGE_CURVE ( 'NONE', #10098, #22830, #259, .T. ) ; +#17463 = ORIENTED_EDGE ( 'NONE', *, *, #17740, .F. ) ; +#17464 = CARTESIAN_POINT ( 'NONE', ( 10.03449820175319118, 168.3857740907195364, 99.03493333412644972 ) ) ; +#17465 = ORIENTED_EDGE ( 'NONE', *, *, #23015, .T. ) ; +#17466 = VERTEX_POINT ( 'NONE', #11273 ) ; +#17467 = DIRECTION ( 'NONE', ( 0.0005884949961234757585, -0.2249510543439061094, 0.9743698870671263501 ) ) ; +#17468 = CONICAL_SURFACE ( 'NONE', #33798, 2.503080714863939793, 0.7853981633931875761 ) ; +#17469 = CARTESIAN_POINT ( 'NONE', ( -1.762796036306197633, 151.6652447677196847, 130.5904578367407396 ) ) ; +#17470 = CARTESIAN_POINT ( 'NONE', ( -18.98879854313464577, 125.4558735758789538, 175.9382205149915706 ) ) ; +#17471 = CARTESIAN_POINT ( 'NONE', ( -35.82451515115999996, 192.4421462047999967, 104.2777259915000059 ) ) ; +#17472 = DIRECTION ( 'NONE', ( -0.5605692862037908730, 0.2602880237709958022, 0.7861375325261872327 ) ) ; +#17473 = ORIENTED_EDGE ( 'NONE', *, *, #12252, .F. ) ; +#17474 = CARTESIAN_POINT ( 'NONE', ( -26.00065299636052529, 120.7346046267106203, 87.52068782721254081 ) ) ; +#17475 = VECTOR ( 'NONE', #17459, 1000.000000000000227 ) ; +#17476 = CARTESIAN_POINT ( 'NONE', ( -31.84898476996059813, 157.9423125112969331, 186.4027463543498584 ) ) ; +#17477 = ORIENTED_EDGE ( 'NONE', *, *, #17137, .T. ) ; +#17478 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; +#17479 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971575949 ) ) ; +#17480 = CARTESIAN_POINT ( 'NONE', ( -23.35829001585551978, 177.0054919146453756, 103.4631273769316806 ) ) ; +#17481 = VERTEX_POINT ( 'NONE', #11892 ) ; +#17482 = CARTESIAN_POINT ( 'NONE', ( 37.78115515336936880, 118.8155650090541968, 87.24496173037786662 ) ) ; +#17483 = CARTESIAN_POINT ( 'NONE', ( 14.78600926606004862, 175.8977815190944796, 100.7663474239818839 ) ) ; +#17484 = CARTESIAN_POINT ( 'NONE', ( 20.50072654596022304, 194.3039055573108840, 105.7669459458108037 ) ) ; +#17485 = CARTESIAN_POINT ( 'NONE', ( 44.87321850267542800, 186.3681360267014782, 107.6486605579196123 ) ) ; +#17486 = ORIENTED_EDGE ( 'NONE', *, *, #3678, .F. ) ; +#17487 = CARTESIAN_POINT ( 'NONE', ( -19.40198027091592081, 124.9165765156423760, 177.8474014814652264 ) ) ; +#17488 = EDGE_CURVE ( 'NONE', #17201, #16019, #22729, .T. ) ; +#17489 = FACE_OUTER_BOUND ( 'NONE', #34554, .T. ) ; +#17490 = CARTESIAN_POINT ( 'NONE', ( 20.25161797161999999, 123.2936480544000091, 90.92760764233000259 ) ) ; +#17491 = EDGE_LOOP ( 'NONE', ( #6870, #21520, #26822, #38946 ) ) ; +#17492 = CARTESIAN_POINT ( 'NONE', ( 59.75594728261907562, 246.2738964432155342, 199.3192736266051668 ) ) ; +#17493 = ORIENTED_EDGE ( 'NONE', *, *, #29300, .F. ) ; +#17494 = CARTESIAN_POINT ( 'NONE', ( 13.50029502672948389, 174.4049036335025562, 100.4224658841498297 ) ) ; +#17495 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#17496 = FACE_OUTER_BOUND ( 'NONE', #35644, .T. ) ; +#17497 = CARTESIAN_POINT ( 'NONE', ( -20.01777344647963730, 205.1071326358727163, 76.11698016271346035 ) ) ; +#17498 = CARTESIAN_POINT ( 'NONE', ( -28.26067782467530520, 125.1269179218217857, 91.12357580992288320 ) ) ; +#17499 = ORIENTED_EDGE ( 'NONE', *, *, #13568, .F. ) ; +#17500 = EDGE_CURVE ( 'NONE', #6589, #7826, #13457, .T. ) ; +#17501 = VECTOR ( 'NONE', #13436, 1000.000000000000000 ) ; +#17502 = CARTESIAN_POINT ( 'NONE', ( -30.69659838596064461, 110.6131156702000027, 89.78632472421946886 ) ) ; +#17503 = ADVANCED_FACE ( 'NONE', ( #21300 ), #8828, .T. ) ; +#17504 = DIRECTION ( 'NONE', ( -0.0006039748319387582953, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#17505 = CARTESIAN_POINT ( 'NONE', ( 12.63245678305150044, 181.0156363297572000, 104.5149566212380989 ) ) ; +#17506 = CARTESIAN_POINT ( 'NONE', ( -17.08814518252571091, 121.9278384327233624, 175.1946533361529532 ) ) ; +#17507 = CARTESIAN_POINT ( 'NONE', ( 22.34217513307632785, 154.4094372266218613, 95.28765545888695954 ) ) ; +#17508 = CARTESIAN_POINT ( 'NONE', ( 23.36219596639283225, 175.2460213084726206, 100.6106968941989663 ) ) ; +#17509 = DIRECTION ( 'NONE', ( 0.0006039748319392990953, 2.305558552177526877E-15, 0.9999998176071847045 ) ) ; +#17510 = EDGE_CURVE ( 'NONE', #22903, #19279, #20158, .T. ) ; +#17511 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#17512 = EDGE_CURVE ( 'NONE', #19373, #28309, #9227, .T. ) ; +#17513 = FACE_OUTER_BOUND ( 'NONE', #31217, .T. ) ; +#17514 = ORIENTED_EDGE ( 'NONE', *, *, #30095, .F. ) ; +#17515 = EDGE_CURVE ( 'NONE', #288, #18050, #28429, .T. ) ; +#17516 = ORIENTED_EDGE ( 'NONE', *, *, #4353, .T. ) ; +#17517 = CARTESIAN_POINT ( 'NONE', ( 3.417962904437000127, 184.3981819701000120, 105.0448705359000030 ) ) ; +#17518 = EDGE_CURVE ( 'NONE', #7059, #2798, #13, .T. ) ; +#17519 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#17520 = ORIENTED_EDGE ( 'NONE', *, *, #38163, .T. ) ; +#17521 = CARTESIAN_POINT ( 'NONE', ( 2.564210731195382120, 191.0000001071945235, 106.3128016873806274 ) ) ; +#17522 = ORIENTED_EDGE ( 'NONE', *, *, #38927, .F. ) ; +#17523 = AXIS2_PLACEMENT_3D ( 'NONE', #11259, #36403, #14536 ) ; +#17524 = DIRECTION ( 'NONE', ( -0.0005884949961243157984, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#17525 = CARTESIAN_POINT ( 'NONE', ( 36.05539628129138663, 119.7153741857807745, 90.34852886392080507 ) ) ; +#17526 = VERTEX_POINT ( 'NONE', #37624 ) ; +#17527 = CARTESIAN_POINT ( 'NONE', ( -42.33056243206983282, 103.5691829158648716, 168.6985699702358090 ) ) ; +#17528 = CONICAL_SURFACE ( 'NONE', #25420, 2.503022984658444638, 0.7853981634305220449 ) ; +#17529 = CARTESIAN_POINT ( 'NONE', ( 20.33353033788438680, 138.4388794944718200, 91.94387688982007489 ) ) ; +#17530 = CARTESIAN_POINT ( 'NONE', ( -45.38224234400345125, 124.4312361121064896, 88.40754498314288412 ) ) ; +#17531 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319387907129 ) ) ; +#17532 = VECTOR ( 'NONE', #18795, 1000.000000000000227 ) ; +#17533 = CARTESIAN_POINT ( 'NONE', ( -22.78329764787637046, 154.4034317766920310, 95.31352365236099899 ) ) ; +#17534 = ORIENTED_EDGE ( 'NONE', *, *, #39528, .F. ) ; +#17535 = ORIENTED_EDGE ( 'NONE', *, *, #17371, .T. ) ; +#17536 = CARTESIAN_POINT ( 'NONE', ( 39.93170777403999949, 119.7458890212000142, 87.93590199493999648 ) ) ; +#17537 = EDGE_CURVE ( 'NONE', #22589, #13086, #12977, .T. ) ; +#17538 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17539 = EDGE_LOOP ( 'NONE', ( #35823, #23086, #28470, #8801 ) ) ; +#17540 = CARTESIAN_POINT ( 'NONE', ( -25.07217336826253273, 181.6855096711613839, 101.6134976257350644 ) ) ; +#17541 = ORIENTED_EDGE ( 'NONE', *, *, #25161, .T. ) ; +#17542 = DIRECTION ( 'NONE', ( -0.6087613505914957202, 0.7729391287514063569, 0.1788147680451337707 ) ) ; +#17543 = PLANE ( 'NONE', #10164 ) ; +#17544 = FACE_OUTER_BOUND ( 'NONE', #29011, .T. ) ; +#17545 = CARTESIAN_POINT ( 'NONE', ( 3.416491666947000017, 184.9605596060000039, 102.6089458181999987 ) ) ; +#17546 = CARTESIAN_POINT ( 'NONE', ( 14.74285125918311756, 136.4206760581051867, 93.70497248843004456 ) ) ; +#17547 = ADVANCED_FACE ( 'NONE', ( #24775 ), #18838, .F. ) ; +#17548 = CARTESIAN_POINT ( 'NONE', ( 44.30515803278058229, 188.2843354219114929, 106.1739411498338939 ) ) ; +#17549 = CARTESIAN_POINT ( 'NONE', ( 6.037042346762936162, 176.9423404431283871, 103.3389806385386294 ) ) ; +#17550 = VECTOR ( 'NONE', #986, 1000.000000000000000 ) ; +#17551 = EDGE_CURVE ( 'NONE', #40142, #31711, #27847, .T. ) ; +#17552 = CARTESIAN_POINT ( 'NONE', ( 38.31600023055000293, 118.4557739757999997, 87.79094888852999645 ) ) ; +#17553 = CARTESIAN_POINT ( 'NONE', ( 20.48050040959321549, 208.3867791706507546, 73.74492918753165327 ) ) ; +#17554 = CARTESIAN_POINT ( 'NONE', ( 38.62452218546999916, 119.2816704622000117, 90.41603517917999966 ) ) ; +#17555 = ORIENTED_EDGE ( 'NONE', *, *, #25896, .T. ) ; +#17556 = EDGE_CURVE ( 'NONE', #32811, #13604, #27647, .T. ) ; +#17557 = DIRECTION ( 'NONE', ( -1.734723476052543855E-15, 0.9743700557921586292, 0.2249510932971556243 ) ) ; +#17558 = CARTESIAN_POINT ( 'NONE', ( -20.49954538792513148, 118.3474577000311143, 87.78002983709943408 ) ) ; +#17559 = FACE_OUTER_BOUND ( 'NONE', #26870, .T. ) ; +#17560 = CARTESIAN_POINT ( 'NONE', ( -20.15539790843522283, 117.1470949619612583, 87.27995764731555539 ) ) ; +#17561 = VECTOR ( 'NONE', #40245, 1000.000000000000114 ) ; +#17562 = EDGE_CURVE ( 'NONE', #32051, #31339, #12678, .T. ) ; +#17563 = AXIS2_PLACEMENT_3D ( 'NONE', #2881, #39481, #33552 ) ; +#17564 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 108.4362817545589905, 169.8438797714867405 ) ) ; +#17565 = ORIENTED_EDGE ( 'NONE', *, *, #14071, .F. ) ; +#17566 = ORIENTED_EDGE ( 'NONE', *, *, #7046, .F. ) ; +#17567 = EDGE_CURVE ( 'NONE', #13870, #24015, #37850, .T. ) ; +#17568 = CARTESIAN_POINT ( 'NONE', ( -2.852240684793061476, 190.4446136019508344, 103.6222497587798870 ) ) ; +#17569 = ORIENTED_EDGE ( 'NONE', *, *, #19327, .T. ) ; +#17570 = CARTESIAN_POINT ( 'NONE', ( 30.06438278973887535, 134.2480451416175811, 93.70732421818068758 ) ) ; +#17571 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6370, #18822, #25205, #31326 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17572 = DIRECTION ( 'NONE', ( -0.0005884949961296528920, 0.2249510543439046939, -0.9743698870671267942 ) ) ; +#17573 = ORIENTED_EDGE ( 'NONE', *, *, #38301, .F. ) ; +#17574 = DIRECTION ( 'NONE', ( -0.0004161288024723274501, 0.8480480897761999426, -0.5299191110572988306 ) ) ; +#17575 = CARTESIAN_POINT ( 'NONE', ( -37.04044279746617008, 161.2612793056356963, 189.7402396365586696 ) ) ; +#17576 = CARTESIAN_POINT ( 'NONE', ( -25.60336619595795327, 134.9156435395334199, 90.81609673312185294 ) ) ; +#17577 = FACE_OUTER_BOUND ( 'NONE', #34090, .T. ) ; +#17578 = CARTESIAN_POINT ( 'NONE', ( -37.78603381399999961, 118.7643818931999959, 87.39034903127999598 ) ) ; +#17579 = VERTEX_POINT ( 'NONE', #9023 ) ; +#17580 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#17581 = DIRECTION ( 'NONE', ( -0.0005884941996571894972, 0.2249510543439501575, -0.9743698870675971957 ) ) ; +#17582 = CARTESIAN_POINT ( 'NONE', ( 20.50147081773584290, 151.4111479308915023, 97.16231817868397513 ) ) ; +#17583 = CARTESIAN_POINT ( 'NONE', ( 39.72066837979766518, 175.7297623423441166, 136.1382466769391897 ) ) ; +#17584 = CARTESIAN_POINT ( 'NONE', ( -19.42613131718963260, 148.7783707801748392, 183.2662285685778443 ) ) ; +#17585 = ORIENTED_EDGE ( 'NONE', *, *, #23125, .T. ) ; +#17586 = ORIENTED_EDGE ( 'NONE', *, *, #38338, .T. ) ; +#17587 = VECTOR ( 'NONE', #7473, 1000.000000000000227 ) ; +#17588 = CARTESIAN_POINT ( 'NONE', ( -19.33043961327094706, 148.7913001523307912, 183.3364864566283359 ) ) ; +#17589 = CARTESIAN_POINT ( 'NONE', ( 39.01469539726659264, 120.0482035829021328, 87.34466845720035622 ) ) ; +#17590 = CARTESIAN_POINT ( 'NONE', ( -36.24924816598951338, 190.9038461227203243, 106.8273557833577456 ) ) ; +#17591 = VECTOR ( 'NONE', #40130, 1000.000000000000227 ) ; +#17592 = AXIS2_PLACEMENT_3D ( 'NONE', #29527, #14395, #26469 ) ; +#17593 = ORIENTED_EDGE ( 'NONE', *, *, #8961, .F. ) ; +#17594 = CARTESIAN_POINT ( 'NONE', ( -22.49999922076347758, 151.9675441756866690, 94.75098345857672655 ) ) ; +#17595 = ORIENTED_EDGE ( 'NONE', *, *, #5668, .F. ) ; +#17596 = CARTESIAN_POINT ( 'NONE', ( 25.49065798218091672, 210.6301881023333635, 73.54305791159129058 ) ) ; +#17597 = EDGE_CURVE ( 'NONE', #16772, #30360, #15932, .T. ) ; +#17598 = ADVANCED_FACE ( 'NONE', ( #5943 ), #18398, .T. ) ; +#17599 = ORIENTED_EDGE ( 'NONE', *, *, #6350, .F. ) ; +#17600 = ADVANCED_FACE ( 'NONE', ( #12289 ), #21486, .F. ) ; +#17601 = ORIENTED_EDGE ( 'NONE', *, *, #39414, .T. ) ; +#17602 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17603 = CARTESIAN_POINT ( 'NONE', ( 19.98059076253610300, 209.7097557544199162, 73.04669817794425057 ) ) ; +#17604 = CARTESIAN_POINT ( 'NONE', ( -25.65829064362023004, 196.2716043697412545, 103.7603564967673861 ) ) ; +#17605 = ORIENTED_EDGE ( 'NONE', *, *, #9556, .F. ) ; +#17606 = CARTESIAN_POINT ( 'NONE', ( 46.07851895380935048, 185.2520563475989661, 105.4728131717084949 ) ) ; +#17607 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#17608 = ORIENTED_EDGE ( 'NONE', *, *, #31520, .T. ) ; +#17609 = ADVANCED_FACE ( 'NONE', ( #10023 ), #29021, .T. ) ; +#17610 = CARTESIAN_POINT ( 'NONE', ( 25.69394431265000023, 120.7465094597000075, 90.25074256333999756 ) ) ; +#17611 = CARTESIAN_POINT ( 'NONE', ( 35.48442776063147619, 88.13433118093483642, 282.5337480928039895 ) ) ; +#17613 = DIRECTION ( 'NONE', ( -0.0006039748319388572829, -3.099784637799882324E-15, -0.9999998176071847045 ) ) ; +#17612 = LINE ( 'NONE', #2103, #32382 ) ; +#17614 = ORIENTED_EDGE ( 'NONE', *, *, #20811, .T. ) ; +#17615 = EDGE_CURVE ( 'NONE', #1820, #11064, #20760, .T. ) ; +#17616 = CONICAL_SURFACE ( 'NONE', #12406, 2.503000006865153448, 0.7853981633739405277 ) ; +#17617 = AXIS2_PLACEMENT_3D ( 'NONE', #18625, #24203, #12124 ) ; +#17618 = ORIENTED_EDGE ( 'NONE', *, *, #2515, .T. ) ; +#17619 = AXIS2_PLACEMENT_3D ( 'NONE', #5664, #12397, #15858 ) ; +#17620 = CARTESIAN_POINT ( 'NONE', ( -25.83516676602354778, 119.7245759509484913, 87.30912072347993558 ) ) ; +#17621 = AXIS2_PLACEMENT_3D ( 'NONE', #761, #6894, #10191 ) ; +#17622 = VERTEX_POINT ( 'NONE', #1000 ) ; +#17623 = CARTESIAN_POINT ( 'NONE', ( 39.25497886610000364, 118.8953424551000211, 89.53045808048000254 ) ) ; +#17624 = FACE_OUTER_BOUND ( 'NONE', #5811, .T. ) ; +#17625 = EDGE_CURVE ( 'NONE', #15629, #29127, #4679, .T. ) ; +#17626 = LINE ( 'NONE', #2316, #12873 ) ; +#17627 = CARTESIAN_POINT ( 'NONE', ( -22.78227175507932500, 153.4787728439779357, 97.83686093391889926 ) ) ; +#17628 = CARTESIAN_POINT ( 'NONE', ( 36.12366260232001025, 191.5066187523999872, 103.8330160090000049 ) ) ; +#17629 = ORIENTED_EDGE ( 'NONE', *, *, #23571, .T. ) ; +#17630 = ORIENTED_EDGE ( 'NONE', *, *, #33646, .F. ) ; +#17631 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048994616, 134.2394347309202658, 93.74516030699426494 ) ) ; +#17632 = FACE_OUTER_BOUND ( 'NONE', #21452, .T. ) ; +#17633 = CARTESIAN_POINT ( 'NONE', ( 15.87308592176477795, 186.6781958245231010, 102.7413939128299489 ) ) ; +#17634 = ORIENTED_EDGE ( 'NONE', *, *, #31154, .F. ) ; +#17635 = ORIENTED_EDGE ( 'NONE', *, *, #39262, .F. ) ; +#17636 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; +#17637 = CARTESIAN_POINT ( 'NONE', ( 41.09291594421311089, 217.7719116457018060, 152.4682433584083867 ) ) ; +#17638 = ORIENTED_EDGE ( 'NONE', *, *, #39310, .T. ) ; +#17639 = CARTESIAN_POINT ( 'NONE', ( -20.51848692360195514, 206.3589432834550905, 75.06605631655357058 ) ) ; +#17640 = CIRCLE ( 'NONE', #22896, 7.999999999999992895 ) ; +#17641 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971541255 ) ) ; +#17642 = DIRECTION ( 'NONE', ( 0.0005884949961162573573, -0.2249510543439059151, 0.9743698870671263501 ) ) ; +#17643 = CARTESIAN_POINT ( 'NONE', ( -21.82845864282945669, 129.2731355035732292, 92.07692058346603403 ) ) ; +#17644 = VECTOR ( 'NONE', #36279, 999.9999999999998863 ) ; +#17645 = ORIENTED_EDGE ( 'NONE', *, *, #35580, .F. ) ; +#17646 = AXIS2_PLACEMENT_3D ( 'NONE', #35241, #310, #3568 ) ; +#17647 = ADVANCED_FACE ( 'NONE', ( #29231 ), #31708, .T. ) ; +#17648 = EDGE_CURVE ( 'NONE', #27876, #25693, #13491, .T. ) ; +#17649 = DIRECTION ( 'NONE', ( -0.7072735235945706300, -0.6508952239913728954, -0.2758615054829884894 ) ) ; +#17650 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#17651 = ORIENTED_EDGE ( 'NONE', *, *, #15141, .F. ) ; +#17652 = ADVANCED_FACE ( 'NONE', ( #38016 ), #3658, .T. ) ; +#17653 = CARTESIAN_POINT ( 'NONE', ( 39.53379105069361543, 120.3902222971681368, 87.42331650858173475 ) ) ; +#17655 = FACE_OUTER_BOUND ( 'NONE', #15714, .T. ) ; +#17654 = CARTESIAN_POINT ( 'NONE', ( 15.50029467790899496, 185.7974155947267718, 103.0514270424844483 ) ) ; +#17656 = ORIENTED_EDGE ( 'NONE', *, *, #11723, .F. ) ; +#17657 = EDGE_CURVE ( 'NONE', #13026, #31750, #22300, .T. ) ; +#17658 = ORIENTED_EDGE ( 'NONE', *, *, #31666, .F. ) ; +#17659 = ORIENTED_EDGE ( 'NONE', *, *, #35817, .F. ) ; +#17660 = CARTESIAN_POINT ( 'NONE', ( 19.99995599910763389, 165.3414092450989301, 97.81287038969479397 ) ) ; +#17661 = CARTESIAN_POINT ( 'NONE', ( 2.562619485644860973, 196.1181876864285698, 103.6781880485148406 ) ) ; +#17662 = DIRECTION ( 'NONE', ( 0.0004716571195295989473, 0.6225146315353430326, 0.7826080187833355239 ) ) ; +#17663 = EDGE_LOOP ( 'NONE', ( #2864, #13679, #33424, #27547 ) ) ; +#17664 = ORIENTED_EDGE ( 'NONE', *, *, #34361, .F. ) ; +#17665 = CARTESIAN_POINT ( 'NONE', ( -13.50000077923899688, 138.1929969155733318, 91.56544231107801579 ) ) ; +#17666 = VERTEX_POINT ( 'NONE', #35121 ) ; +#17667 = ORIENTED_EDGE ( 'NONE', *, *, #36868, .F. ) ; +#17668 = DIRECTION ( 'NONE', ( -0.7865509479255973213, -0.6175253892086901564, 0.000000000000000000 ) ) ; +#17669 = EDGE_CURVE ( 'NONE', #4296, #13220, #15591, .T. ) ; +#17670 = AXIS2_PLACEMENT_3D ( 'NONE', #23116, #25793, #26389 ) ; +#17671 = CARTESIAN_POINT ( 'NONE', ( -24.02278420256503111, 115.4960067055939277, 202.0650339681855883 ) ) ; +#17672 = ORIENTED_EDGE ( 'NONE', *, *, #22297, .T. ) ; +#17673 = AXIS2_PLACEMENT_3D ( 'NONE', #10752, #13224, #932 ) ; +#17674 = ORIENTED_EDGE ( 'NONE', *, *, #24198, .T. ) ; +#17675 = CARTESIAN_POINT ( 'NONE', ( -20.49711472948942870, 211.0904275233606313, 75.59256565440196596 ) ) ; +#17676 = AXIS2_PLACEMENT_3D ( 'NONE', #39207, #19782, #11015 ) ; +#17677 = CARTESIAN_POINT ( 'NONE', ( -35.75587340871999942, 191.8338532855999858, 104.0497549258000021 ) ) ; +#17678 = CARTESIAN_POINT ( 'NONE', ( 36.67500110392000323, 191.3369781904000320, 103.9170611561000186 ) ) ; +#17679 = CARTESIAN_POINT ( 'NONE', ( -25.50102279335000333, 120.6643622512000036, 88.03908242295000264 ) ) ; +#17680 = ORIENTED_EDGE ( 'NONE', *, *, #17556, .F. ) ; +#17681 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17682 = CARTESIAN_POINT ( 'NONE', ( -35.94780537806226306, 113.8881156701999942, 87.78949595635012315 ) ) ; +#17683 = VERTEX_POINT ( 'NONE', #1205 ) ; +#17684 = CARTESIAN_POINT ( 'NONE', ( -37.67574118798827243, 118.8155645602721222, 87.29053938956874958 ) ) ; +#17685 = DIRECTION ( 'NONE', ( -0.6087116037913344879, 0.7730376917437173923, 0.1785578633197842380 ) ) ; +#17686 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #24888, #37341 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17687 = DIRECTION ( 'NONE', ( 0.0005559617913757295945, -0.3907311284892698300, 0.9205046855589537058 ) ) ; +#17688 = CARTESIAN_POINT ( 'NONE', ( -3.931607349826474529, 167.9092076435330512, 101.0933002075414038 ) ) ; +#17689 = VERTEX_POINT ( 'NONE', #34923 ) ; +#17690 = CARTESIAN_POINT ( 'NONE', ( -24.42746480248682062, 109.6131156702000027, 87.78253795971667728 ) ) ; +#17691 = CARTESIAN_POINT ( 'NONE', ( 2.242171634080408094, 189.9138756023754127, 103.9471229047883014 ) ) ; +#17692 = CARTESIAN_POINT ( 'NONE', ( 30.06443600138266703, 134.9229365128052507, 90.78414315763292564 ) ) ; +#17693 = ORIENTED_EDGE ( 'NONE', *, *, #39270, .F. ) ; +#17694 = CARTESIAN_POINT ( 'NONE', ( 20.48015056202373074, 210.1700361193774143, 73.54651103472254192 ) ) ; +#17695 = ORIENTED_EDGE ( 'NONE', *, *, #28235, .F. ) ; +#17696 = ORIENTED_EDGE ( 'NONE', *, *, #34963, .T. ) ; +#17697 = EDGE_CURVE ( 'NONE', #23821, #38370, #32500, .T. ) ; +#17698 = CARTESIAN_POINT ( 'NONE', ( -42.43581683406742400, 94.00600134306105815, 291.5841741052475413 ) ) ; +#17699 = AXIS2_PLACEMENT_3D ( 'NONE', #2475, #15535, #18774 ) ; +#17700 = ADVANCED_FACE ( 'NONE', ( #13091 ), #17528, .F. ) ; +#17701 = DIRECTION ( 'NONE', ( -0.6087614115774886425, 0.7730004600455401276, 0.1785492440296710948 ) ) ; +#17702 = CARTESIAN_POINT ( 'NONE', ( 25.88353131012999953, 191.8571809995999899, 104.0322739423999963 ) ) ; +#17703 = AXIS2_PLACEMENT_3D ( 'NONE', #32497, #31709, #4468 ) ; +#17704 = CIRCLE ( 'NONE', #18346, 6.000000651512662486 ) ; +#17705 = CARTESIAN_POINT ( 'NONE', ( 16.77614372998638359, 152.4482931959673806, 181.9616063807505384 ) ) ; +#17706 = DIRECTION ( 'NONE', ( 0.0005884950603321816021, -0.2249510543244929717, 0.9743698870715694627 ) ) ; +#17707 = VERTEX_POINT ( 'NONE', #19194 ) ; +#17708 = EDGE_CURVE ( 'NONE', #6620, #35941, #26173, .T. ) ; +#17709 = DIRECTION ( 'NONE', ( -0.0004161288024302700009, 0.8480480898291783420, -0.5299191109725157611 ) ) ; +#17710 = CARTESIAN_POINT ( 'NONE', ( 43.14456005852381537, 112.6780295318855565, 129.4537069268840526 ) ) ; +#17711 = LINE ( 'NONE', #8335, #28404 ) ; +#17712 = CARTESIAN_POINT ( 'NONE', ( 19.71684765030295949, 124.8915327974199130, 176.0741111412129385 ) ) ; +#17713 = DIRECTION ( 'NONE', ( 0.0005884949961256158652, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17714 = CARTESIAN_POINT ( 'NONE', ( -20.89282324149344561, 183.0959377177359215, 101.9365769416837253 ) ) ; +#17715 = CARTESIAN_POINT ( 'NONE', ( -22.54148966027999990, 174.6477734297156985, 27.63001052910568944 ) ) ; +#17716 = CARTESIAN_POINT ( 'NONE', ( 20.28520147395606799, 116.8369336581640709, 90.25553308582213674 ) ) ; +#17717 = EDGE_LOOP ( 'NONE', ( #34414, #23767, #13187, #7471 ) ) ; +#17718 = CARTESIAN_POINT ( 'NONE', ( 4.034499242067735025, 144.1016867008426061, 93.43213283160849869 ) ) ; +#17719 = ADVANCED_FACE ( 'NONE', ( #19405 ), #2527, .F. ) ; +#17720 = CARTESIAN_POINT ( 'NONE', ( -42.83981852382991917, 113.7604137494400476, 123.0507168651698038 ) ) ; +#17721 = ORIENTED_EDGE ( 'NONE', *, *, #27067, .T. ) ; +#17722 = CARTESIAN_POINT ( 'NONE', ( -35.95473150033847531, 205.5673820439000110, 76.32193034924999608 ) ) ; +#17723 = ORIENTED_EDGE ( 'NONE', *, *, #12203, .T. ) ; +#17724 = CARTESIAN_POINT ( 'NONE', ( -38.20553841305000020, 119.1510546080999973, 87.44536496121999392 ) ) ; +#17725 = AXIS2_PLACEMENT_3D ( 'NONE', #24789, #37238, #34157 ) ; +#17726 = CARTESIAN_POINT ( 'NONE', ( -16.17179426088062044, 151.9775549948883508, 184.4787338324457835 ) ) ; +#17727 = EDGE_LOOP ( 'NONE', ( #38698, #13924, #19227, #1899 ) ) ; +#17728 = CARTESIAN_POINT ( 'NONE', ( 35.82807448362839864, 191.6307925291198160, 106.8885444632594499 ) ) ; +#17729 = EDGE_CURVE ( 'NONE', #7664, #23325, #25385, .T. ) ; +#17730 = PLANE ( 'NONE', #19173 ) ; +#17731 = CARTESIAN_POINT ( 'NONE', ( 13.46612284730906950, 158.3062971533392158, 96.19268454968825210 ) ) ; +#17732 = CARTESIAN_POINT ( 'NONE', ( -12.63555412105795561, 130.0309333250218629, 92.32931262750892643 ) ) ; +#17733 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; +#17734 = CARTESIAN_POINT ( 'NONE', ( 39.82491996314075777, 141.3585264024648609, 285.0163987782322579 ) ) ; +#17735 = ORIENTED_EDGE ( 'NONE', *, *, #8930, .F. ) ; +#17736 = CARTESIAN_POINT ( 'NONE', ( 39.45067306616000025, 120.1726932226000031, 87.49420585638002024 ) ) ; +#17737 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#17738 = DIRECTION ( 'NONE', ( -4.163336342262541617E-15, 0.9743700557921591843, 0.2249510932971534871 ) ) ; +#17739 = CARTESIAN_POINT ( 'NONE', ( 16.23201905896638308, 152.0606143167149185, 181.0564827348360382 ) ) ; +#17740 = EDGE_CURVE ( 'NONE', #2098, #35411, #12016, .T. ) ; +#17741 = VERTEX_POINT ( 'NONE', #39221 ) ; +#17742 = CARTESIAN_POINT ( 'NONE', ( 3.334680759033842534, 127.9501515180691769, 92.09838694450060359 ) ) ; +#17743 = ADVANCED_FACE ( 'NONE', ( #29632 ), #39015, .F. ) ; +#17744 = CARTESIAN_POINT ( 'NONE', ( -43.00608122665288136, 121.0191425024765550, 90.97016640535348131 ) ) ; +#17746 = EDGE_CURVE ( 'NONE', #38838, #133, #26056, .T. ) ; +#17745 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927789280832, 0.0005734119022080210902 ) ) ; +#17747 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323826020982455905, 0.0005734119000540774001 ) ) ; +#17748 = CARTESIAN_POINT ( 'NONE', ( -25.71417928276665421, 212.4116159412069464, 73.07403480233796245 ) ) ; +#17749 = ADVANCED_FACE ( 'NONE', ( #26772 ), #38806, .T. ) ; +#17750 = AXIS2_PLACEMENT_3D ( 'NONE', #5526, #15155, #17991 ) ; +#17751 = DIRECTION ( 'NONE', ( -0.0005884949961206531466, 0.2249510543439048327, -0.9743698870671267942 ) ) ; +#17752 = AXIS2_PLACEMENT_3D ( 'NONE', #34637, #22408, #34439 ) ; +#17753 = CARTESIAN_POINT ( 'NONE', ( 6.037027004990604517, 176.9341431689030060, 103.3258622659047461 ) ) ; +#17754 = AXIS2_PLACEMENT_3D ( 'NONE', #6060, #2984, #18709 ) ; +#17755 = CARTESIAN_POINT ( 'NONE', ( 38.13590145119999875, 118.2511992291999974, 87.79762229201999446 ) ) ; +#17756 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; +#17757 = CARTESIAN_POINT ( 'NONE', ( 26.07108133293812813, 121.6493863964714279, 87.72214823715854948 ) ) ; +#17758 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#17759 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#17760 = CARTESIAN_POINT ( 'NONE', ( -23.00006628334871550, 115.6131129681876359, 89.78164257609942922 ) ) ; +#17761 = DIRECTION ( 'NONE', ( 0.0005884949961232180437, -0.2249510543439044996, 0.9743698870671267942 ) ) ; +#17762 = LINE ( 'NONE', #30064, #31108 ) ; +#17763 = VERTEX_POINT ( 'NONE', #36153 ) ; +#17764 = ORIENTED_EDGE ( 'NONE', *, *, #17515, .F. ) ; +#17765 = CARTESIAN_POINT ( 'NONE', ( -1.448782306007865506, 188.8264521967578844, 103.2478200403819955 ) ) ; +#17766 = VERTEX_POINT ( 'NONE', #26371 ) ; +#17767 = CARTESIAN_POINT ( 'NONE', ( -23.36047527027495363, 177.3840784139692346, 100.9652270349779997 ) ) ; +#17768 = CARTESIAN_POINT ( 'NONE', ( -6.037299711038997430, 177.1908694379475264, 101.0774571039573999 ) ) ; +#17769 = CARTESIAN_POINT ( 'NONE', ( -48.00106611543790081, 61.15928328279096604, 291.5875353763605062 ) ) ; +#17770 = ORIENTED_EDGE ( 'NONE', *, *, #36059, .T. ) ; +#17771 = CARTESIAN_POINT ( 'NONE', ( -39.41254998849999680, 119.8270850916999990, 90.55892179784000007 ) ) ; +#17772 = DIRECTION ( 'NONE', ( -0.7933533411653341805, 0.5930537057989598848, 0.1373964268091485141 ) ) ; +#17773 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749096068, 179.1800746285871355, 103.5747911658281168 ) ) ; +#17774 = CARTESIAN_POINT ( 'NONE', ( -35.30169115038999905, 112.8556044416999953, 87.14184160035000559 ) ) ; +#17775 = ORIENTED_EDGE ( 'NONE', *, *, #17313, .F. ) ; +#17776 = DIRECTION ( 'NONE', ( -0.0006039748319391913256, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#17777 = ORIENTED_EDGE ( 'NONE', *, *, #38058, .F. ) ; +#17778 = LINE ( 'NONE', #39666, #8745 ) ; +#17779 = DIRECTION ( 'NONE', ( -0.0006039748319383107366, -1.234791622901071989E-14, -0.9999998176071845934 ) ) ; +#17780 = AXIS2_PLACEMENT_3D ( 'NONE', #27379, #36543, #20596 ) ; +#17781 = CARTESIAN_POINT ( 'NONE', ( 36.04389107617218002, 115.3860002890582734, 90.24601523218206012 ) ) ; +#17782 = CARTESIAN_POINT ( 'NONE', ( -12.63842163636918059, 181.1849447922443233, 104.4215566640188086 ) ) ; +#17783 = ORIENTED_EDGE ( 'NONE', *, *, #5719, .F. ) ; +#17784 = EDGE_CURVE ( 'NONE', #3379, #34917, #15901, .T. ) ; +#17785 = CARTESIAN_POINT ( 'NONE', ( -28.54477463726000508, 187.2491079767000031, 103.0247649423999974 ) ) ; +#17786 = VECTOR ( 'NONE', #13896, 1000.000000000000227 ) ; +#17787 = CARTESIAN_POINT ( 'NONE', ( 0.7115303131630320577, 189.0187413740609941, 103.6993385983880245 ) ) ; +#17788 = CARTESIAN_POINT ( 'NONE', ( -35.97303847993521941, 191.1967732357732075, 106.8821304174405782 ) ) ; +#17789 = ADVANCED_FACE ( 'NONE', ( #33488 ), #33084, .T. ) ; +#17790 = ORIENTED_EDGE ( 'NONE', *, *, #19466, .F. ) ; +#17791 = CARTESIAN_POINT ( 'NONE', ( 30.05503346856145086, 103.6131156702632410, 89.74963226087875512 ) ) ; +#17792 = VERTEX_POINT ( 'NONE', #20830 ) ; +#17793 = EDGE_CURVE ( 'NONE', #13780, #7212, #8430, .T. ) ; +#17794 = EDGE_CURVE ( 'NONE', #17966, #16874, #32693, .T. ) ; +#17795 = EDGE_CURVE ( 'NONE', #20168, #37805, #29433, .T. ) ; +#17796 = ORIENTED_EDGE ( 'NONE', *, *, #11114, .F. ) ; +#17797 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23079, #39003, #29218, #26755 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17798 = ORIENTED_EDGE ( 'NONE', *, *, #3498, .T. ) ; +#17799 = CARTESIAN_POINT ( 'NONE', ( -35.95698934392000012, 192.3172225881000372, 105.8170796091999932 ) ) ; +#17800 = DIRECTION ( 'NONE', ( 0.7856637149787880636, -0.6186538021912818541, 0.000000000000000000 ) ) ; +#17801 = CARTESIAN_POINT ( 'NONE', ( -31.91335489949009130, 137.9985878559502623, 92.04483278691883186 ) ) ; +#17802 = ORIENTED_EDGE ( 'NONE', *, *, #32091, .T. ) ; +#17803 = CARTESIAN_POINT ( 'NONE', ( -22.49852798328017300, 151.4051665355240459, 97.18690819472567455 ) ) ; +#17804 = CONICAL_SURFACE ( 'NONE', #39997, 4.999999999923872451, 0.7853981633990386735 ) ; +#17805 = VERTEX_POINT ( 'NONE', #1402 ) ; +#17806 = CARTESIAN_POINT ( 'NONE', ( 28.35073491905000154, 124.9606733549999973, 91.22198593361000007 ) ) ; +#17807 = CARTESIAN_POINT ( 'NONE', ( -35.92212000658612681, 191.5653759301798686, 103.9005706184658067 ) ) ; +#17808 = VECTOR ( 'NONE', #36076, 1000.000000000000227 ) ; +#17810 = CARTESIAN_POINT ( 'NONE', ( 37.49119510912425568, 212.8449757119041408, 76.03586094040831256 ) ) ; +#17809 = CARTESIAN_POINT ( 'NONE', ( -25.51533646434189961, 211.0902259025884007, 73.57326538444725372 ) ) ; +#17811 = EDGE_LOOP ( 'NONE', ( #16303, #14206, #10103, #39867 ) ) ; +#17812 = VECTOR ( 'NONE', #12762, 1000.000000000000000 ) ; +#17813 = ADVANCED_FACE ( 'NONE', ( #10831 ), #7738, .T. ) ; +#17814 = ORIENTED_EDGE ( 'NONE', *, *, #38173, .T. ) ; +#17815 = ORIENTED_EDGE ( 'NONE', *, *, #14543, .T. ) ; +#17816 = CARTESIAN_POINT ( 'NONE', ( 39.44669341952000252, 119.3098229202999931, 89.86714104326999575 ) ) ; +#17817 = CARTESIAN_POINT ( 'NONE', ( -13.46442671968396709, 158.3027909046028583, 96.20813345690331175 ) ) ; +#17818 = CARTESIAN_POINT ( 'NONE', ( 14.31450538706609521, 182.2837619838007583, 101.7278000795456308 ) ) ; +#17819 = LINE ( 'NONE', #14585, #31821 ) ; +#17820 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672665709, 158.2308735878961556, 98.74100402060588522 ) ) ; +#17821 = ORIENTED_EDGE ( 'NONE', *, *, #5815, .T. ) ; +#17822 = ORIENTED_EDGE ( 'NONE', *, *, #19502, .F. ) ; +#17823 = EDGE_CURVE ( 'NONE', #5875, #32498, #5949, .T. ) ; +#17824 = ORIENTED_EDGE ( 'NONE', *, *, #34713, .T. ) ; +#17825 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 5.029100215316657124E-18, 0.0006039748319386160479 ) ) ; +#17826 = CARTESIAN_POINT ( 'NONE', ( 27.28348237275000088, 124.2320809166999993, 88.31760212342000216 ) ) ; +#17827 = ORIENTED_EDGE ( 'NONE', *, *, #9508, .T. ) ; +#17828 = EDGE_CURVE ( 'NONE', #19997, #5617, #1221, .T. ) ; +#17829 = CARTESIAN_POINT ( 'NONE', ( -3.859508698811262128, 144.1403424298719074, 93.26310401271429384 ) ) ; +#17830 = EDGE_CURVE ( 'NONE', #39132, #14925, #32578, .T. ) ; +#17831 = ORIENTED_EDGE ( 'NONE', *, *, #11295, .F. ) ; +#17832 = AXIS2_PLACEMENT_3D ( 'NONE', #32569, #4346, #36236 ) ; +#17833 = CARTESIAN_POINT ( 'NONE', ( 1.106619553340999929, 188.8408486938999999, 105.9110459091999985 ) ) ; +#17834 = LINE ( 'NONE', #37075, #2056 ) ; +#17835 = EDGE_CURVE ( 'NONE', #22597, #19682, #10565, .T. ) ; +#17836 = CONICAL_SURFACE ( 'NONE', #36150, 22.50000000000898837, 0.7853981633973132759 ) ; +#17837 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#17838 = CARTESIAN_POINT ( 'NONE', ( -82.79477499249559003, 72.19295329727926003, 166.5670822259618262 ) ) ; +#17839 = VERTEX_POINT ( 'NONE', #17331 ) ; +#17840 = CARTESIAN_POINT ( 'NONE', ( 25.75023662782000500, 199.6921533858000259, 89.48600966998000672 ) ) ; +#17841 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34684, #35080, #550, #32060 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17842 = DIRECTION ( 'NONE', ( -0.7933533411653076461, 0.5930537057989941907, 0.1373964268091527330 ) ) ; +#17843 = ORIENTED_EDGE ( 'NONE', *, *, #4633, .F. ) ; +#17844 = CARTESIAN_POINT ( 'NONE', ( 29.91189702434756370, 126.8852189367780170, 89.27071757938477958 ) ) ; +#17845 = ORIENTED_EDGE ( 'NONE', *, *, #32753, .F. ) ; +#17847 = CARTESIAN_POINT ( 'NONE', ( -35.38988506213597418, 77.14301703112144537, 290.1978808180363671 ) ) ; +#17846 = DIRECTION ( 'NONE', ( 0.9999998268371397270, 0.0001323824647179528205, -0.0005734113476489175907 ) ) ; +#17848 = ORIENTED_EDGE ( 'NONE', *, *, #11301, .T. ) ; +#17849 = ORIENTED_EDGE ( 'NONE', *, *, #35017, .T. ) ; +#17850 = CONICAL_SURFACE ( 'NONE', #30288, 2.499997363466079037, 0.7853981633710050980 ) ; +#17851 = AXIS2_PLACEMENT_3D ( 'NONE', #18561, #28400, #27617 ) ; +#17852 = ORIENTED_EDGE ( 'NONE', *, *, #36604, .T. ) ; +#17853 = CARTESIAN_POINT ( 'NONE', ( 2.408274994265000579, 208.8706265008999878, 75.56874651716999836 ) ) ; +#17854 = CARTESIAN_POINT ( 'NONE', ( -25.99978576141418429, 118.1122949349609286, 90.28348809642494643 ) ) ; +#17855 = CARTESIAN_POINT ( 'NONE', ( -15.94527486429822538, 152.8203387458500231, 181.6302711725483050 ) ) ; +#17856 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066635700, 183.5616063994668536, 104.6006436764798195 ) ) ; +#17858 = ORIENTED_EDGE ( 'NONE', *, *, #16584, .F. ) ; +#17857 = AXIS2_PLACEMENT_3D ( 'NONE', #2713, #28251, #6546 ) ; +#17859 = CARTESIAN_POINT ( 'NONE', ( -37.20408499807465574, 178.1325612194088421, 136.7211859319782263 ) ) ; +#17860 = EDGE_LOOP ( 'NONE', ( #733, #5146, #10025, #35211 ) ) ; +#17861 = ORIENTED_EDGE ( 'NONE', *, *, #24383, .F. ) ; +#17862 = CARTESIAN_POINT ( 'NONE', ( -23.36013443158915237, 136.6763330450122567, 94.30332275863374036 ) ) ; +#17863 = AXIS2_PLACEMENT_3D ( 'NONE', #22083, #15922, #24962 ) ; +#17864 = CARTESIAN_POINT ( 'NONE', ( 25.99199080364422443, 211.0901596425212574, 76.04279652306830428 ) ) ; +#17865 = CARTESIAN_POINT ( 'NONE', ( -13.54341419034824945, 127.9461742602649679, 176.4876677107182843 ) ) ; +#17866 = CARTESIAN_POINT ( 'NONE', ( 19.39390165059181825, 124.9043552653802180, 177.8552826716125139 ) ) ; +#17867 = CARTESIAN_POINT ( 'NONE', ( 35.90076804576000313, 192.3671129742999995, 104.2031949967000202 ) ) ; +#17868 = ORIENTED_EDGE ( 'NONE', *, *, #38672, .T. ) ; +#17869 = ADVANCED_FACE ( 'NONE', ( #13885 ), #39074, .T. ) ; +#17870 = ORIENTED_EDGE ( 'NONE', *, *, #1354, .F. ) ; +#17871 = EDGE_CURVE ( 'NONE', #38693, #24898, #14559, .T. ) ; +#17872 = ORIENTED_EDGE ( 'NONE', *, *, #31153, .T. ) ; +#17873 = CARTESIAN_POINT ( 'NONE', ( 3.991644188892757406, 184.7664131289848228, 28.08339314683390242 ) ) ; +#17874 = EDGE_CURVE ( 'NONE', #3122, #11256, #17392, .T. ) ; +#17875 = CARTESIAN_POINT ( 'NONE', ( -35.89350200887000142, 191.4464572824000186, 103.7438032780000015 ) ) ; +#17876 = EDGE_LOOP ( 'NONE', ( #26502, #5700, #1103, #36707, #2571, #2570, #34030, #1464, #19589, #459 ) ) ; +#17877 = CARTESIAN_POINT ( 'NONE', ( -25.66781978934000108, 120.6928363009999998, 87.87473006517001295 ) ) ; +#17878 = EDGE_LOOP ( 'NONE', ( #99, #11348, #6816, #14600, #14906 ) ) ; +#17879 = VERTEX_POINT ( 'NONE', #30849 ) ; +#17880 = DIRECTION ( 'NONE', ( 0.0004161288024604291444, 0.5299192578603125758, 0.8480479980435040588 ) ) ; +#17881 = CARTESIAN_POINT ( 'NONE', ( -40.86425246474745165, 188.5523987672290218, 107.5827897523195560 ) ) ; +#17882 = ORIENTED_EDGE ( 'NONE', *, *, #21090, .F. ) ; +#17883 = EDGE_CURVE ( 'NONE', #12644, #36762, #9174, .T. ) ; +#17884 = CARTESIAN_POINT ( 'NONE', ( 1.993517670461378399, 189.0625354601347397, 103.3002451033650431 ) ) ; +#17885 = CARTESIAN_POINT ( 'NONE', ( 20.50081714887910778, 194.1061032057583873, 105.8792863328844902 ) ) ; +#17886 = CARTESIAN_POINT ( 'NONE', ( 38.68874437559378521, 119.1826339606430878, 90.26160218306198146 ) ) ; +#17887 = VECTOR ( 'NONE', #36635, 1000.000000000000227 ) ; +#17888 = ORIENTED_EDGE ( 'NONE', *, *, #13597, .T. ) ; +#17890 = EDGE_CURVE ( 'NONE', #25001, #31188, #31236, .T. ) ; +#17889 = CARTESIAN_POINT ( 'NONE', ( 12.31735795870903161, 134.2458240057509329, 93.71748532227019268 ) ) ; +#17891 = CARTESIAN_POINT ( 'NONE', ( 2.346033262188341961, 190.0750585238097585, 103.9936005391582654 ) ) ; +#17892 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14445, #26315, #11581, #11172 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17893 = AXIS2_PLACEMENT_3D ( 'NONE', #37823, #15741, #10235 ) ; +#17894 = CIRCLE ( 'NONE', #21190, 2.500000000002172040 ) ; +#17895 = CARTESIAN_POINT ( 'NONE', ( 20.50124949713573841, 118.1127836709285077, 89.08883525397649805 ) ) ; +#17896 = VERTEX_POINT ( 'NONE', #15306 ) ; +#17897 = CARTESIAN_POINT ( 'NONE', ( 26.00056762447263026, 118.1139028608674408, 90.25209678512123901 ) ) ; +#17898 = ORIENTED_EDGE ( 'NONE', *, *, #31991, .F. ) ; +#17899 = AXIS2_PLACEMENT_3D ( 'NONE', #22272, #37990, #6700 ) ; +#17900 = CARTESIAN_POINT ( 'NONE', ( -44.96472012149743591, 114.9735949632774634, 130.1287737409121235 ) ) ; +#17901 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251392786, 179.1753088543749755, 103.5954339977854346 ) ) ; +#17902 = CARTESIAN_POINT ( 'NONE', ( -26.00146729408999491, 120.3902237924986451, 87.46289810595591518 ) ) ; +#17903 = CARTESIAN_POINT ( 'NONE', ( -29.53010039065708270, 181.9152030469051624, 101.6691925721778347 ) ) ; +#17904 = DIRECTION ( 'NONE', ( -0.7933530821293308666, -0.5932640870757669438, -0.1364866662427074440 ) ) ; +#17905 = ORIENTED_EDGE ( 'NONE', *, *, #19954, .T. ) ; +#17906 = FACE_OUTER_BOUND ( 'NONE', #11551, .T. ) ; +#17907 = DIRECTION ( 'NONE', ( -8.673617379883985182E-16, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#17908 = FACE_OUTER_BOUND ( 'NONE', #12330, .T. ) ; +#17909 = CARTESIAN_POINT ( 'NONE', ( 75.24056455973224899, 196.4820008462166641, 189.1802437148639058 ) ) ; +#17910 = CARTESIAN_POINT ( 'NONE', ( 19.71699054648574645, 124.6499361933662158, 177.1222525964093109 ) ) ; +#17911 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#17912 = DIRECTION ( 'NONE', ( -0.4305589114774804327, -0.3870810988319002277, -0.8153448636463075383 ) ) ; +#17913 = DIRECTION ( 'NONE', ( -0.6087616187692346248, 0.7730003051580285334, 0.1785492081725818803 ) ) ; +#17914 = DIRECTION ( 'NONE', ( -0.0004161288024432313669, 0.8480480898092180864, -0.5299191110044590980 ) ) ; +#17915 = ORIENTED_EDGE ( 'NONE', *, *, #20373, .F. ) ; +#17916 = VECTOR ( 'NONE', #8939, 1000.000000000000227 ) ; +#17917 = CARTESIAN_POINT ( 'NONE', ( 3.534327104360340588, 144.2236672556986434, 92.94748474794259607 ) ) ; +#17918 = CIRCLE ( 'NONE', #19869, 2.000000000014617640 ) ; +#17919 = CARTESIAN_POINT ( 'NONE', ( -17.34531841520229634, 127.5687170461390565, 172.4105396402263466 ) ) ; +#17920 = VECTOR ( 'NONE', #16977, 1000.000000000000114 ) ; +#17921 = ORIENTED_EDGE ( 'NONE', *, *, #9784, .T. ) ; +#17922 = CARTESIAN_POINT ( 'NONE', ( 5.661755184049897416, 181.7278491563756972, 101.6571205978850969 ) ) ; +#17923 = ADVANCED_FACE ( 'NONE', ( #18542 ), #6284, .T. ) ; +#17924 = VECTOR ( 'NONE', #14217, 1000.000000000000114 ) ; +#17925 = EDGE_CURVE ( 'NONE', #8275, #7741, #27792, .T. ) ; +#17926 = ORIENTED_EDGE ( 'NONE', *, *, #40376, .F. ) ; +#17927 = CARTESIAN_POINT ( 'NONE', ( -38.48370105922000306, 119.6611731044000067, 87.34165442331999429 ) ) ; +#17928 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#17929 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; +#17930 = ORIENTED_EDGE ( 'NONE', *, *, #39117, .T. ) ; +#17931 = CARTESIAN_POINT ( 'NONE', ( -44.72305387772779284, 186.4890408525310477, 106.4986220546478819 ) ) ; +#17932 = APPROVAL ( #12253, '未' ) ; +#17933 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16535, #22708, #32305, #4270, #38618, #29240 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#17934 = CARTESIAN_POINT ( 'NONE', ( 35.04524255441999259, 226.4002260770880355, 73.53733772517182388 ) ) ; +#17935 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#17936 = DIRECTION ( 'NONE', ( 0.0005559617456005168726, -0.3907311285063747031, 0.9205046855517208249 ) ) ; +#17937 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971554578 ) ) ; +#17938 = VERTEX_POINT ( 'NONE', #15502 ) ; +#17939 = CARTESIAN_POINT ( 'NONE', ( 37.96662911696999743, 119.2513318047000013, 87.13126180806000320 ) ) ; +#17940 = FACE_OUTER_BOUND ( 'NONE', #33475, .T. ) ; +#17941 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#17942 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; +#17943 = EDGE_LOOP ( 'NONE', ( #5015, #24919, #37679, #32136 ) ) ; +#17944 = VERTEX_POINT ( 'NONE', #37181 ) ; +#17945 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971555410 ) ) ; +#17946 = FACE_OUTER_BOUND ( 'NONE', #37675, .T. ) ; +#17947 = VECTOR ( 'NONE', #37335, 1000.000000000000000 ) ; +#17948 = CARTESIAN_POINT ( 'NONE', ( -23.00078011532012212, 115.1133396198523968, 87.28167119284988473 ) ) ; +#17949 = ADVANCED_FACE ( 'NONE', ( #3017 ), #27994, .F. ) ; +#17950 = CARTESIAN_POINT ( 'NONE', ( -16.99952089899032615, 137.4668171152774221, 177.5674675513082263 ) ) ; +#17951 = CIRCLE ( 'NONE', #31029, 2.499999999921701299 ) ; +#17952 = CARTESIAN_POINT ( 'NONE', ( -23.97850471017942198, 213.9398281896897629, 73.07298649838843119 ) ) ; +#17953 = FACE_OUTER_BOUND ( 'NONE', #20269, .T. ) ; +#17954 = VECTOR ( 'NONE', #20650, 1000.000000000000114 ) ; +#17955 = FACE_OUTER_BOUND ( 'NONE', #8627, .T. ) ; +#17956 = DIRECTION ( 'NONE', ( 0.6087614810001747978, -0.7729390313185939831, -0.1788147452386057157 ) ) ; +#17957 = CARTESIAN_POINT ( 'NONE', ( 27.16245655375060153, 124.0804297401828364, 88.28273975555136133 ) ) ; +#17958 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; +#17959 = CARTESIAN_POINT ( 'NONE', ( 14.78500024124773304, 129.1259577792816629, 89.96821972116190125 ) ) ; +#17960 = CARTESIAN_POINT ( 'NONE', ( -5.669730063300002065, 182.0627683766816176, 102.2020018021338927 ) ) ; +#17961 = CARTESIAN_POINT ( 'NONE', ( -19.28798288393075921, 116.9568857464341960, 189.5000423914045484 ) ) ; +#17962 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 1.676366911794336136E-18, 0.0006039748319371601813 ) ) ; +#17964 = ORIENTED_EDGE ( 'NONE', *, *, #14402, .F. ) ; +#17963 = CARTESIAN_POINT ( 'NONE', ( -20.49983153468760833, 192.4566819323742948, 104.3904707837865402 ) ) ; +#17965 = ORIENTED_EDGE ( 'NONE', *, *, #7806, .T. ) ; +#17966 = VERTEX_POINT ( 'NONE', #12428 ) ; +#17967 = ORIENTED_EDGE ( 'NONE', *, *, #39255, .F. ) ; +#17968 = CARTESIAN_POINT ( 'NONE', ( -39.61054748937312553, 129.5177821288435780, 336.3042500576304974 ) ) ; +#17969 = ORIENTED_EDGE ( 'NONE', *, *, #6026, .F. ) ; +#17970 = CARTESIAN_POINT ( 'NONE', ( 20.50147082588080139, 126.8719997938822530, 91.49700837604584081 ) ) ; +#17971 = DIRECTION ( 'NONE', ( -0.7933308265452445607, -0.5932923437231208963, -0.1364932032467742196 ) ) ; +#17972 = CARTESIAN_POINT ( 'NONE', ( -22.78469271946612196, 158.3009118758265004, 96.21332883968871386 ) ) ; +#17973 = ADVANCED_FACE ( 'NONE', ( #24931 ), #7755, .T. ) ; +#17974 = EDGE_CURVE ( 'NONE', #8481, #6206, #27169, .T. ) ; +#17975 = CONICAL_SURFACE ( 'NONE', #10820, 59.40509992922268623, 0.7853981633972876297 ) ; +#17976 = VERTEX_POINT ( 'NONE', #10184 ) ; +#17977 = AXIS2_PLACEMENT_3D ( 'NONE', #11948, #9077, #9478 ) ; +#17978 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 67.27946979429633245, 315.0857197240632672 ) ) ; +#17979 = CARTESIAN_POINT ( 'NONE', ( -13.49836187949013322, 187.2925309095741113, 105.4667247238223524 ) ) ; +#17980 = AXIS2_PLACEMENT_3D ( 'NONE', #5957, #15752, #34158 ) ; +#17981 = AXIS2_PLACEMENT_3D ( 'NONE', #34394, #18847, #1059 ) ; +#17982 = CARTESIAN_POINT ( 'NONE', ( -12.63793204807002901, 135.2920832194301397, 91.40834497133602099 ) ) ; +#17983 = ORIENTED_EDGE ( 'NONE', *, *, #37072, .T. ) ; +#17984 = CONICAL_SURFACE ( 'NONE', #368, 4.999999999982041032, 0.7853981634251984145 ) ; +#17985 = ADVANCED_FACE ( 'NONE', ( #31859 ), #31449, .F. ) ; +#17986 = CARTESIAN_POINT ( 'NONE', ( -63.18208837076905127, 82.27946979429619034, 302.5967063397189349 ) ) ; +#17987 = LINE ( 'NONE', #6722, #13956 ) ; +#17988 = CARTESIAN_POINT ( 'NONE', ( 13.47463546662201317, 153.3581425397641453, 97.61606142177900836 ) ) ; +#17989 = VECTOR ( 'NONE', #3854, 1000.000000000000227 ) ; +#17990 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#17991 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971555133 ) ) ; +#17992 = VERTEX_POINT ( 'NONE', #22656 ) ; +#17993 = EDGE_LOOP ( 'NONE', ( #14362, #2620, #3051, #9833 ) ) ; +#17994 = CARTESIAN_POINT ( 'NONE', ( -25.88211498805000232, 191.5534218900999974, 104.0168860973000022 ) ) ; +#17995 = CARTESIAN_POINT ( 'NONE', ( 0.7245737304257999778, 188.8838344680000034, 103.5294067165000058 ) ) ; +#17996 = CARTESIAN_POINT ( 'NONE', ( -35.43627711891984688, 192.7868339519407357, 106.8766537076977698 ) ) ; +#17997 = ORIENTED_EDGE ( 'NONE', *, *, #10567, .T. ) ; +#17998 = CARTESIAN_POINT ( 'NONE', ( -26.01100183241918984, 209.7097224523000136, 73.07421407572023497 ) ) ; +#17999 = ORIENTED_EDGE ( 'NONE', *, *, #23807, .T. ) ; +#18000 = VERTEX_POINT ( 'NONE', #16097 ) ; +#18001 = ORIENTED_EDGE ( 'NONE', *, *, #16321, .F. ) ; +#18002 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; +#18003 = AXIS2_PLACEMENT_3D ( 'NONE', #29657, #26798, #23722 ) ; +#18004 = CARTESIAN_POINT ( 'NONE', ( -37.98512463470000000, 190.9255745234999893, 106.5168391131000050 ) ) ; +#18005 = DIRECTION ( 'NONE', ( 0.0005884949961228996135, -0.2249510543439057764, 0.9743698870671265722 ) ) ; +#18006 = CARTESIAN_POINT ( 'NONE', ( -37.83658322688275888, 190.9636381155321203, 106.3289620680116343 ) ) ; +#18007 = ORIENTED_EDGE ( 'NONE', *, *, #7822, .T. ) ; +#18008 = CARTESIAN_POINT ( 'NONE', ( 46.07702524554187562, 185.2597197907774955, 105.4745833194638607 ) ) ; +#18009 = LINE ( 'NONE', #18211, #10731 ) ; +#18010 = EDGE_LOOP ( 'NONE', ( #11512, #31985 ) ) ; +#18011 = CARTESIAN_POINT ( 'NONE', ( -13.49953887075311698, 187.7424330182009840, 103.5179849509054435 ) ) ; +#18012 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971573451 ) ) ; +#18014 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971570121 ) ) ; +#18013 = CARTESIAN_POINT ( 'NONE', ( -22.82606489386816406, 174.8555096703654499, 26.73020617941470078 ) ) ; +#18015 = VERTEX_POINT ( 'NONE', #28584 ) ; +#18016 = ORIENTED_EDGE ( 'NONE', *, *, #38066, .T. ) ; +#18017 = CARTESIAN_POINT ( 'NONE', ( 20.10465118437221577, 117.3133951571205813, 87.25564158649584101 ) ) ; +#18018 = CARTESIAN_POINT ( 'NONE', ( -4.037441716910447731, 175.2423114651814160, 100.6263891030057778 ) ) ; +#18019 = EDGE_CURVE ( 'NONE', #8699, #28523, #13443, .T. ) ; +#18020 = EDGE_CURVE ( 'NONE', #37463, #36542, #17841, .T. ) ; +#18021 = EDGE_LOOP ( 'NONE', ( #4493, #28258, #2488, #10458 ) ) ; +#18022 = EDGE_CURVE ( 'NONE', #40344, #18640, #1270, .T. ) ; +#18023 = CARTESIAN_POINT ( 'NONE', ( -13.46665720407698430, 158.4276779027484281, 96.40801793781008655 ) ) ; +#18024 = EDGE_CURVE ( 'NONE', #14927, #19402, #8087, .T. ) ; +#18025 = CARTESIAN_POINT ( 'NONE', ( 42.33252156615733952, 171.7659273071258497, 184.4847811977609524 ) ) ; +#18026 = DIRECTION ( 'NONE', ( -0.7933532411131102302, -0.5932638852154231701, -0.1364866195435442964 ) ) ; +#18027 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#18028 = LINE ( 'NONE', #47, #6041 ) ; +#18029 = ORIENTED_EDGE ( 'NONE', *, *, #15145, .T. ) ; +#18030 = ORIENTED_EDGE ( 'NONE', *, *, #16999, .T. ) ; +#18031 = AXIS2_PLACEMENT_3D ( 'NONE', #285, #2572, #40163 ) ; +#18032 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18033 = AXIS2_PLACEMENT_3D ( 'NONE', #11863, #11246, #24347 ) ; +#18034 = CARTESIAN_POINT ( 'NONE', ( 26.18543207681999974, 122.7183532277000069, 88.13992845963001344 ) ) ; +#18035 = ORIENTED_EDGE ( 'NONE', *, *, #9933, .F. ) ; +#18036 = CARTESIAN_POINT ( 'NONE', ( -25.49122390263418936, 191.6804084528734791, 104.4219781743341287 ) ) ; +#18037 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39968, #30784, #96, #15441, #27542, #36911, #25059, #8918, #24864, #6418, #11976 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000002099987, 0.3750000000002899903, 0.4375000000003124168, 0.4687500000003236300, 0.5000000000003348433, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18038 = CARTESIAN_POINT ( 'NONE', ( -12.63563964607691759, 177.7898056417149917, 100.7065655309022532 ) ) ; +#18039 = VECTOR ( 'NONE', #14841, 1000.000000000000000 ) ; +#18040 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34428, #22596, #13581, #32195 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18041 = CONICAL_SURFACE ( 'NONE', #32420, 7.999999999839934262, 0.7853981633973153853 ) ; +#18042 = CARTESIAN_POINT ( 'NONE', ( 0.7706342105979004931, 188.3655401650390218, 106.2398045854893525 ) ) ; +#18043 = DIRECTION ( 'NONE', ( 0.0006039748319385852566, 1.189165140469103041E-14, 0.9999998176071845934 ) ) ; +#18044 = FACE_BOUND ( 'NONE', #18463, .T. ) ; +#18045 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#18046 = LINE ( 'NONE', #33796, #17591 ) ; +#18047 = ORIENTED_EDGE ( 'NONE', *, *, #30599, .T. ) ; +#18048 = FACE_OUTER_BOUND ( 'NONE', #20807, .T. ) ; +#18049 = DIRECTION ( 'NONE', ( 0.1627648957830039600, -0.3422987685252318890, 0.9253859420624767074 ) ) ; +#18050 = VERTEX_POINT ( 'NONE', #38565 ) ; +#18051 = EDGE_CURVE ( 'NONE', #39751, #34948, #39796, .T. ) ; +#18052 = AXIS2_PLACEMENT_3D ( 'NONE', #31183, #27733, #40365 ) ; +#18053 = CARTESIAN_POINT ( 'NONE', ( 41.39749877257511201, 121.2433985891848067, 87.61916177723681187 ) ) ; +#18054 = ORIENTED_EDGE ( 'NONE', *, *, #5523, .F. ) ; +#18055 = VECTOR ( 'NONE', #37849, 1000.000000000000000 ) ; +#18056 = AXIS2_PLACEMENT_3D ( 'NONE', #14512, #27418, #39838 ) ; +#18058 = FACE_OUTER_BOUND ( 'NONE', #4852, .T. ) ; +#18057 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921596284, -0.2249510932971514610 ) ) ; +#18059 = ORIENTED_EDGE ( 'NONE', *, *, #635, .T. ) ; +#18061 = ORIENTED_EDGE ( 'NONE', *, *, #768, .F. ) ; +#18060 = EDGE_CURVE ( 'NONE', #16952, #33548, #6887, .T. ) ; +#18062 = ORIENTED_EDGE ( 'NONE', *, *, #21338, .F. ) ; +#18064 = AXIS2_PLACEMENT_3D ( 'NONE', #32963, #5568, #24202 ) ; +#18063 = CARTESIAN_POINT ( 'NONE', ( 2.668862736158999827, 209.0672528707999902, 75.76277278460999298 ) ) ; +#18065 = EDGE_CURVE ( 'NONE', #17839, #25158, #7792, .T. ) ; +#18066 = DIRECTION ( 'NONE', ( -0.9914447795421099663, -0.1272537940605282525, -0.02904687618140097335 ) ) ; +#18067 = CARTESIAN_POINT ( 'NONE', ( 12.64072830267882530, 177.6453042594414455, 100.7843295571792197 ) ) ; +#18068 = ORIENTED_EDGE ( 'NONE', *, *, #29131, .F. ) ; +#18069 = ORIENTED_EDGE ( 'NONE', *, *, #7136, .T. ) ; +#18070 = CARTESIAN_POINT ( 'NONE', ( -19.46385842112644582, 125.8687678076213530, 177.6217747046812008 ) ) ; +#18071 = ORIENTED_EDGE ( 'NONE', *, *, #2590, .T. ) ; +#18072 = ORIENTED_EDGE ( 'NONE', *, *, #32790, .T. ) ; +#18073 = EDGE_CURVE ( 'NONE', #20440, #29484, #7286, .T. ) ; +#18074 = LINE ( 'NONE', #15033, #23704 ) ; +#18075 = DIRECTION ( 'NONE', ( 0.0005734119072255677982, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#18076 = CARTESIAN_POINT ( 'NONE', ( -28.55676206495941827, 225.5077044902725163, 73.57575174230528603 ) ) ; +#18077 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; +#18078 = ORIENTED_EDGE ( 'NONE', *, *, #10110, .F. ) ; +#18079 = ORIENTED_EDGE ( 'NONE', *, *, #13926, .T. ) ; +#18080 = CARTESIAN_POINT ( 'NONE', ( -15.49823494792000034, 136.5125476982000237, 94.25759973750000142 ) ) ; +#18081 = CARTESIAN_POINT ( 'NONE', ( -35.88663413247999756, 191.4497865545999957, 103.7448652294000055 ) ) ; +#18082 = CARTESIAN_POINT ( 'NONE', ( -25.83455595018638462, 120.6939522944666834, 87.68857576906727047 ) ) ; +#18083 = VERTEX_POINT ( 'NONE', #28379 ) ; +#18084 = ORIENTED_EDGE ( 'NONE', *, *, #12836, .T. ) ; +#18085 = CARTESIAN_POINT ( 'NONE', ( 40.29675614866165745, 187.8287955346809213, 108.1243603913822824 ) ) ; +#18086 = ORIENTED_EDGE ( 'NONE', *, *, #8450, .T. ) ; +#18087 = CONICAL_SURFACE ( 'NONE', #27270, 2.250000000041454840, 0.7853981633778843729 ) ; +#18088 = DIRECTION ( 'NONE', ( 0.0005884949961251158311, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18089 = LINE ( 'NONE', #15256, #33350 ) ; +#18090 = CARTESIAN_POINT ( 'NONE', ( -3.669581230397975791, 128.4724600144964484, 89.82849395191713882 ) ) ; +#18091 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26868, #32969, #1916, #11519, #17633, #20716, #1712, #33582, #23997, #2522, #4967, #14384, #33169, #5161, #14994, #39308, #19742, #2124, #36455, #8462 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999858169, 0.1874999999999787392, 0.2187499999999648337, 0.2343749999999583111, 0.2499999999999517886, 0.5000000000000051070, 0.6250000000000329736, 0.6875000000000407452, 0.7187500000000440759, 0.7343750000000410783, 0.7500000000000380806, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18092 = DIRECTION ( 'NONE', ( -0.7856007919586942556, -0.6187337033602360314, 0.000000000000000000 ) ) ; +#18093 = CARTESIAN_POINT ( 'NONE', ( 38.51513381718999796, 190.6638049979000016, 106.4702060427000134 ) ) ; +#18094 = ORIENTED_EDGE ( 'NONE', *, *, #17002, .T. ) ; +#18095 = LINE ( 'NONE', #37331, #12542 ) ; +#18096 = ORIENTED_EDGE ( 'NONE', *, *, #15818, .F. ) ; +#18097 = EDGE_LOOP ( 'NONE', ( #13809, #31683, #32352, #12071 ) ) ; +#18098 = DIRECTION ( 'NONE', ( 6.071532165918790121E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#18099 = CARTESIAN_POINT ( 'NONE', ( 36.40558664052492333, 191.8188463803718093, 104.3612499972096117 ) ) ; +#18100 = CARTESIAN_POINT ( 'NONE', ( 36.95307372573000038, 117.6087066819000029, 90.39852571456000874 ) ) ; +#18101 = CARTESIAN_POINT ( 'NONE', ( -25.50117313778553552, 120.2777482655987598, 87.94978106212539615 ) ) ; +#18102 = CARTESIAN_POINT ( 'NONE', ( 39.06361167813316371, 191.1637310494582209, 103.9340057247245142 ) ) ; +#18103 = EDGE_CURVE ( 'NONE', #12599, #36135, #13245, .T. ) ; +#18104 = EDGE_LOOP ( 'NONE', ( #26984, #4253, #40155, #3781 ) ) ; +#18105 = EDGE_CURVE ( 'NONE', #33829, #21029, #30191, .T. ) ; +#18106 = EDGE_CURVE ( 'NONE', #23623, #8275, #20362, .T. ) ; +#18107 = EDGE_CURVE ( 'NONE', #12780, #21071, #16333, .T. ) ; +#18108 = CARTESIAN_POINT ( 'NONE', ( -6.038082992467953325, 135.2621705534379544, 91.35529203372260554 ) ) ; +#18109 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14935, #8404, #27440, #33117 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18110 = CARTESIAN_POINT ( 'NONE', ( 20.49349609279370199, 198.0405739724999989, 94.02009863521665523 ) ) ; +#18111 = VERTEX_POINT ( 'NONE', #11587 ) ; +#18112 = LINE ( 'NONE', #15077, #25144 ) ; +#18113 = ADVANCED_FACE ( 'NONE', ( #1351 ), #35474, .F. ) ; +#18114 = VECTOR ( 'NONE', #591, 1000.000000000000114 ) ; +#18115 = CARTESIAN_POINT ( 'NONE', ( -20.56299248376943112, 183.8327314439351028, 104.6722249315171638 ) ) ; +#18116 = CARTESIAN_POINT ( 'NONE', ( 26.00894374567046441, 191.9425530329557716, 103.9054621679136261 ) ) ; +#18117 = CARTESIAN_POINT ( 'NONE', ( -30.17966072969699454, 126.7544990129442795, 88.93473033871077860 ) ) ; +#18118 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#18119 = CARTESIAN_POINT ( 'NONE', ( 45.51092638067240870, 130.6862150259999282, 92.36248445504377003 ) ) ; +#18120 = AXIS2_PLACEMENT_3D ( 'NONE', #7108, #40102, #28994 ) ; +#18121 = EDGE_LOOP ( 'NONE', ( #37092, #13311, #32416, #14618, #22036, #5540, #38653 ) ) ; +#18122 = ORIENTED_EDGE ( 'NONE', *, *, #8121, .T. ) ; +#18123 = EDGE_CURVE ( 'NONE', #25286, #31100, #29522, .T. ) ; +#18124 = CARTESIAN_POINT ( 'NONE', ( -40.45487666628986290, 217.7719115803249963, 76.08293836134893695 ) ) ; +#18125 = CARTESIAN_POINT ( 'NONE', ( -19.30112294124457861, 148.8672454922145221, 180.8685255073344536 ) ) ; +#18126 = CARTESIAN_POINT ( 'NONE', ( -31.03678255265001695, 135.1035752748423420, 90.86278477189215153 ) ) ; +#18127 = ORIENTED_EDGE ( 'NONE', *, *, #33952, .F. ) ; +#18128 = CARTESIAN_POINT ( 'NONE', ( 34.28793556153255651, 83.33961454349231701, 284.1689683552120300 ) ) ; +#18129 = ORIENTED_EDGE ( 'NONE', *, *, #32571, .F. ) ; +#18130 = CARTESIAN_POINT ( 'NONE', ( -38.77968390195999859, 119.6789568014999929, 87.49970845907000694 ) ) ; +#18131 = EDGE_CURVE ( 'NONE', #6653, #23984, #25130, .T. ) ; +#18132 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058949670, 130.4211554272716000, 90.27959376792703949 ) ) ; +#18133 = CARTESIAN_POINT ( 'NONE', ( -45.30371984282656683, 124.3227729409930618, 91.46136974178456569 ) ) ; +#18134 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5202, #17257, #23832, #29767, #35659, #1959, #38951, #30168, #14424 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 1, 1, 4 ), + ( 0.000000000000000000, 2.226407581420605065E-05, 0.3333477931941779548, 0.6666747780319307592, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18135 = CARTESIAN_POINT ( 'NONE', ( 20.50411903179698214, 118.8156364820424358, 94.25541735824513978 ) ) ; +#18136 = CARTESIAN_POINT ( 'NONE', ( -25.89534614573000226, 190.7439020952000135, 106.6581656403000125 ) ) ; +#18137 = CARTESIAN_POINT ( 'NONE', ( -3.537737212824113353, 144.2088358181959222, 92.94829169108382416 ) ) ; +#18138 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921591843, -0.2249510932971537092 ) ) ; +#18139 = ORIENTED_EDGE ( 'NONE', *, *, #12626, .F. ) ; +#18140 = DIRECTION ( 'NONE', ( -2.508512021221107617E-14, 0.9743700558021061164, 0.2249510932540687291 ) ) ; +#18141 = CARTESIAN_POINT ( 'NONE', ( 20.94615154526903567, 129.3425601203839221, 89.50137061379278691 ) ) ; +#18142 = CARTESIAN_POINT ( 'NONE', ( 36.70606526514563228, 191.6516938454589933, 104.3454524653553932 ) ) ; +#18143 = AXIS2_PLACEMENT_3D ( 'NONE', #25825, #13733, #4514 ) ; +#18144 = CARTESIAN_POINT ( 'NONE', ( 20.16690163351599452, 151.9417136388183849, 94.89044178777534455 ) ) ; +#18145 = VERTEX_POINT ( 'NONE', #39176 ) ; +#18146 = CARTESIAN_POINT ( 'NONE', ( 15.50147165555466522, 173.9550007109359342, 102.3699975152791239 ) ) ; +#18147 = CARTESIAN_POINT ( 'NONE', ( -1.212288473603901240, 143.4871526178525869, 158.5698567282870499 ) ) ; +#18148 = AXIS2_PLACEMENT_3D ( 'NONE', #20798, #33253, #2206 ) ; +#18149 = DIRECTION ( 'NONE', ( -1.363824338041664219E-09, 0.9743700554850293072, 0.2249510946274785039 ) ) ; +#18150 = CARTESIAN_POINT ( 'NONE', ( 12.63701685433996680, 181.1288752993226865, 104.4441903665902203 ) ) ; +#18151 = CARTESIAN_POINT ( 'NONE', ( -14.16859886990510731, 176.0439122282943458, 102.8701808096547126 ) ) ; +#18152 = CARTESIAN_POINT ( 'NONE', ( -30.88168004888737883, 183.4793843894118766, 102.0311286754261744 ) ) ; +#18153 = EDGE_CURVE ( 'NONE', #18185, #29835, #36314, .T. ) ; +#18154 = ADVANCED_FACE ( 'NONE', ( #11178 ), #25448, .T. ) ; +#18155 = ADVANCED_FACE ( 'NONE', ( #23652 ), #7694, .T. ) ; +#18156 = CARTESIAN_POINT ( 'NONE', ( -39.04919065169610803, 128.3857842691216149, 92.39561240981451817 ) ) ; +#18157 = CARTESIAN_POINT ( 'NONE', ( -39.75024793617362917, 128.4756217986020488, 92.41677646255658374 ) ) ; +#18158 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; +#18159 = CARTESIAN_POINT ( 'NONE', ( -9.337769825243999122, 177.4902628103000097, 100.8919948495999961 ) ) ; +#18160 = LINE ( 'NONE', #5714, #16473 ) ; +#18161 = CARTESIAN_POINT ( 'NONE', ( -20.25935325476000060, 199.6921202901999948, 89.51379066862999423 ) ) ; +#18162 = CYLINDRICAL_SURFACE ( 'NONE', #36863, 6.000000000154989799 ) ; +#18163 = EDGE_CURVE ( 'NONE', #2967, #7231, #6549, .T. ) ; +#18164 = CARTESIAN_POINT ( 'NONE', ( -20.51998460911297784, 211.0905570173818546, 73.57089872868714053 ) ) ; +#18165 = CARTESIAN_POINT ( 'NONE', ( 37.68866078465489267, 190.9590569619750511, 106.3031863550690019 ) ) ; +#18166 = EDGE_LOOP ( 'NONE', ( #8393, #37433, #24847, #14225 ) ) ; +#18168 = ORIENTED_EDGE ( 'NONE', *, *, #11073, .T. ) ; +#18167 = CARTESIAN_POINT ( 'NONE', ( 36.09993383802999745, 190.9634858167000004, 106.9436247654000027 ) ) ; +#18169 = VERTEX_POINT ( 'NONE', #20567 ) ; +#18170 = ORIENTED_EDGE ( 'NONE', *, *, #29901, .F. ) ; +#18171 = VERTEX_POINT ( 'NONE', #33232 ) ; +#18172 = ADVANCED_FACE ( 'NONE', ( #5029 ), #4623, .T. ) ; +#18174 = CIRCLE ( 'NONE', #26686, 5.499999999940946793 ) ; +#18173 = CARTESIAN_POINT ( 'NONE', ( -15.74838202838000178, 167.0072215012000072, 101.0414262103000027 ) ) ; +#18175 = ORIENTED_EDGE ( 'NONE', *, *, #31890, .F. ) ; +#18176 = CARTESIAN_POINT ( 'NONE', ( 22.78193024034099423, 147.5136806587757405, 96.26113945965757068 ) ) ; +#18177 = VECTOR ( 'NONE', #25368, 1000.000000000000227 ) ; +#18178 = CARTESIAN_POINT ( 'NONE', ( 33.79593125845812551, 218.5902260770999987, 76.03809273391679824 ) ) ; +#18179 = AXIS2_PLACEMENT_3D ( 'NONE', #28506, #3142, #3535 ) ; +#18180 = ORIENTED_EDGE ( 'NONE', *, *, #8059, .T. ) ; +#18181 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; +#18182 = EDGE_CURVE ( 'NONE', #10098, #15694, #29985, .T. ) ; +#18183 = CARTESIAN_POINT ( 'NONE', ( -28.46737701140906651, 128.5818728498977634, 89.35557899873234078 ) ) ; +#18184 = CARTESIAN_POINT ( 'NONE', ( 17.33070710942128301, 121.2635828526781268, 177.4224744102505440 ) ) ; +#18185 = VERTEX_POINT ( 'NONE', #39371 ) ; +#18186 = CARTESIAN_POINT ( 'NONE', ( 17.25783335673383689, 152.2632692426403196, 183.6728012514050477 ) ) ; +#18187 = CARTESIAN_POINT ( 'NONE', ( 23.36549494770271806, 177.0154873188169233, 103.4424326537949383 ) ) ; +#18188 = PLANE ( 'NONE', #23876 ) ; +#18189 = FACE_OUTER_BOUND ( 'NONE', #5857, .T. ) ; +#18190 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173123658, 184.8502840662089568, 102.8502797338132382 ) ) ; +#18191 = ORIENTED_EDGE ( 'NONE', *, *, #21975, .T. ) ; +#18192 = VERTEX_POINT ( 'NONE', #38974 ) ; +#18193 = DIRECTION ( 'NONE', ( 0.0005884949961244984864, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18194 = CARTESIAN_POINT ( 'NONE', ( 0.5624177495529000259, 188.7437975896999944, 103.3623115639999952 ) ) ; +#18195 = DIRECTION ( 'NONE', ( 0.0006039748319385831966, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#18196 = ORIENTED_EDGE ( 'NONE', *, *, #28156, .F. ) ; +#18197 = ORIENTED_EDGE ( 'NONE', *, *, #4361, .F. ) ; +#18198 = CARTESIAN_POINT ( 'NONE', ( -3.936101898023678825, 136.7687160347144584, 93.89934258040432269 ) ) ; +#18199 = ORIENTED_EDGE ( 'NONE', *, *, #36870, .F. ) ; +#18200 = AXIS2_PLACEMENT_3D ( 'NONE', #23893, #30219, #14082 ) ; +#18201 = AXIS2_PLACEMENT_3D ( 'NONE', #19703, #12570, #18897 ) ; +#18202 = CARTESIAN_POINT ( 'NONE', ( 38.59086485963890567, 79.69179921679354095, 285.2955982571226059 ) ) ; +#18203 = AXIS2_PLACEMENT_3D ( 'NONE', #36272, #24016, #17240 ) ; +#18204 = ADVANCED_FACE ( 'NONE', ( #10980 ), #23446, .T. ) ; +#18205 = EDGE_CURVE ( 'NONE', #12793, #12043, #7570, .T. ) ; +#18206 = CARTESIAN_POINT ( 'NONE', ( -37.05700344865999796, 191.3523728055000106, 104.9609275802999946 ) ) ; +#18207 = AXIS2_PLACEMENT_3D ( 'NONE', #6001, #11538, #30552 ) ; +#18208 = CARTESIAN_POINT ( 'NONE', ( 21.78519456296580259, 199.9748479675050987, 27.79156831217387946 ) ) ; +#18209 = CARTESIAN_POINT ( 'NONE', ( -25.74982265071000143, 119.9604208062000055, 90.18585507400999290 ) ) ; +#18210 = ORIENTED_EDGE ( 'NONE', *, *, #8836, .T. ) ; +#18211 = CARTESIAN_POINT ( 'NONE', ( 0.05270753573795999847, 118.8155666110999960, 87.26775245800000391 ) ) ; +#18212 = CARTESIAN_POINT ( 'NONE', ( -1.330569699202522216, 189.2108882306625333, 105.7992439180508910 ) ) ; +#18213 = ORIENTED_EDGE ( 'NONE', *, *, #29998, .T. ) ; +#18214 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30619, #17507, #15079, #27575, #40000, #12012, #8126, #20587, #32400, #20507, #32205, #17438, #7845, #39317, #14203, #13989, #23800, #35425, #32589, #1722 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000036082, 0.1875000000000047462, 0.2187500000000066613, 0.2343750000000089095, 0.2500000000000111577, 0.5000000000001214584, 0.6250000000001766365, 0.6875000000002058353, 0.7187500000002121636, 0.7343750000002163825, 0.7500000000002206013, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18215 = FACE_OUTER_BOUND ( 'NONE', #5052, .T. ) ; +#18216 = EDGE_CURVE ( 'NONE', #30903, #9305, #24782, .T. ) ; +#18218 = CARTESIAN_POINT ( 'NONE', ( -21.44693882331385026, 135.7861819143374760, 91.01458761472625270 ) ) ; +#18217 = CARTESIAN_POINT ( 'NONE', ( -25.51021417979479011, 210.6319001491000051, 73.57355354290324101 ) ) ; +#18219 = EDGE_LOOP ( 'NONE', ( #11340, #1891, #32240, #40331, #37921, #3132, #27453, #9735, #23686, #13738, #10350, #20895 ) ) ; +#18220 = ORIENTED_EDGE ( 'NONE', *, *, #4238, .F. ) ; +#18221 = FACE_OUTER_BOUND ( 'NONE', #36319, .T. ) ; +#18222 = VERTEX_POINT ( 'NONE', #33443 ) ; +#18223 = CARTESIAN_POINT ( 'NONE', ( 20.15491921390506391, 117.1565408753359065, 87.25561122586560714 ) ) ; +#18224 = ORIENTED_EDGE ( 'NONE', *, *, #8062, .F. ) ; +#18225 = CARTESIAN_POINT ( 'NONE', ( 28.25950385170297352, 125.5846682600628412, 89.14251585184922533 ) ) ; +#18226 = AXIS2_PLACEMENT_3D ( 'NONE', #17176, #4921, #11472 ) ; +#18227 = CARTESIAN_POINT ( 'NONE', ( 12.63088349563799184, 181.6904995670203391, 101.5918601121804556 ) ) ; +#18228 = FACE_OUTER_BOUND ( 'NONE', #35859, .T. ) ; +#18229 = CARTESIAN_POINT ( 'NONE', ( -29.78212383378786399, 185.3139029630853258, 103.9934530775901038 ) ) ; +#18230 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#18231 = CARTESIAN_POINT ( 'NONE', ( 25.50046716662595969, 119.8278461341035523, 89.86771791572004986 ) ) ; +#18232 = ORIENTED_EDGE ( 'NONE', *, *, #39386, .T. ) ; +#18233 = AXIS2_PLACEMENT_3D ( 'NONE', #3921, #22558, #254 ) ; +#18234 = ORIENTED_EDGE ( 'NONE', *, *, #5990, .T. ) ; +#18235 = CARTESIAN_POINT ( 'NONE', ( -23.36013623391100325, 183.4467887557270842, 105.0979734400102217 ) ) ; +#18236 = AXIS2_PLACEMENT_3D ( 'NONE', #24014, #36467, #9283 ) ; +#18237 = DIRECTION ( 'NONE', ( -0.0005884949961221956410, 0.2249510543439041110, -0.9743698870671267942 ) ) ; +#18238 = ORIENTED_EDGE ( 'NONE', *, *, #11597, .T. ) ; +#18239 = ORIENTED_EDGE ( 'NONE', *, *, #23820, .F. ) ; +#18240 = CARTESIAN_POINT ( 'NONE', ( -36.18295178273969981, 190.9538016885580021, 106.8410015666040067 ) ) ; +#18241 = DIRECTION ( 'NONE', ( -0.7072759766252744162, -0.1592272936566939134, 0.6887723585071698906 ) ) ; +#18242 = EDGE_CURVE ( 'NONE', #15233, #14883, #38462, .T. ) ; +#18243 = PERSON ( '未', '未', '未', ('未'), ('未'), ('未') ) ; +#18244 = ORIENTED_EDGE ( 'NONE', *, *, #4685, .F. ) ; +#18245 = CARTESIAN_POINT ( 'NONE', ( 0.5639603665540000588, 188.7958495505000087, 105.8993863219999980 ) ) ; +#18246 = CARTESIAN_POINT ( 'NONE', ( 24.95681190508087965, 159.0107988627873397, 180.5054692823873097 ) ) ; +#18247 = EDGE_CURVE ( 'NONE', #604, #32344, #18493, .T. ) ; +#18248 = CARTESIAN_POINT ( 'NONE', ( -23.01874678158921839, 213.5902083388722303, 75.57231541044464507 ) ) ; +#18249 = DIRECTION ( 'NONE', ( -0.0009686424652863183989, 0.2252351993847905853, -0.9743039395844954598 ) ) ; +#18250 = CARTESIAN_POINT ( 'NONE', ( 5.957091414655063311, 149.1468224720344438, 94.08258114083251655 ) ) ; +#18251 = ORIENTED_EDGE ( 'NONE', *, *, #39861, .T. ) ; +#18252 = ADVANCED_FACE ( 'NONE', ( #31000 ), #5434, .F. ) ; +#18253 = CARTESIAN_POINT ( 'NONE', ( -19.99925998143469030, 118.3555979054333278, 90.27986389109715049 ) ) ; +#18254 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#18255 = EDGE_CURVE ( 'NONE', #11405, #33023, #26568, .T. ) ; +#18256 = VECTOR ( 'NONE', #17531, 1000.000000000000227 ) ; +#18257 = AXIS2_PLACEMENT_3D ( 'NONE', #5367, #32776, #39507 ) ; +#18258 = ORIENTED_EDGE ( 'NONE', *, *, #7407, .T. ) ; +#18259 = CIRCLE ( 'NONE', #643, 2.000000000000011546 ) ; +#18260 = VECTOR ( 'NONE', #32664, 1000.000000000000114 ) ; +#18261 = CARTESIAN_POINT ( 'NONE', ( -20.50275215376747440, 191.9757880780653068, 104.4368574122889299 ) ) ; +#18262 = EDGE_LOOP ( 'NONE', ( #13372, #35347, #25996, #22395 ) ) ; +#18263 = AXIS2_PLACEMENT_3D ( 'NONE', #14307, #25983, #23104 ) ; +#18265 = CARTESIAN_POINT ( 'NONE', ( -17.26183737405610330, 121.4975388230068916, 176.5517749385022057 ) ) ; +#18264 = CARTESIAN_POINT ( 'NONE', ( 37.08917536360815603, 153.0051697192222093, 297.5361440970456215 ) ) ; +#18266 = ORIENTED_EDGE ( 'NONE', *, *, #121, .T. ) ; +#18267 = VERTEX_POINT ( 'NONE', #2966 ) ; +#18268 = ORIENTED_EDGE ( 'NONE', *, *, #5990, .F. ) ; +#18269 = DIRECTION ( 'NONE', ( 0.0001408404318097916858, -0.2249510911089059872, 0.9743700461184576778 ) ) ; +#18270 = CARTESIAN_POINT ( 'NONE', ( 39.71730849539001440, 182.4927982134933302, 106.8443253198619374 ) ) ; +#18271 = CARTESIAN_POINT ( 'NONE', ( 12.64359260118063233, 177.7305216002704071, 100.7310784416387435 ) ) ; +#18272 = ORIENTED_EDGE ( 'NONE', *, *, #36883, .F. ) ; +#18273 = EDGE_LOOP ( 'NONE', ( #10755, #2926, #17514, #19484 ) ) ; +#18274 = ORIENTED_EDGE ( 'NONE', *, *, #13425, .F. ) ; +#18275 = EDGE_LOOP ( 'NONE', ( #8642, #26609, #30687, #3158 ) ) ; +#18276 = DIRECTION ( 'NONE', ( 0.4115636185179725182, -0.6942467237022525994, 0.5904548031315189904 ) ) ; +#18277 = LINE ( 'NONE', #24858, #31555 ) ; +#18278 = FACE_OUTER_BOUND ( 'NONE', #3759, .T. ) ; +#18279 = DIRECTION ( 'NONE', ( 0.0004161288024640698410, -0.8480480897796375261, 0.5299191110517978975 ) ) ; +#18280 = ORIENTED_EDGE ( 'NONE', *, *, #33115, .F. ) ; +#18281 = ORIENTED_EDGE ( 'NONE', *, *, #15282, .F. ) ; +#18282 = LINE ( 'NONE', #24664, #5644 ) ; +#18283 = CARTESIAN_POINT ( 'NONE', ( -2.953326078673281341, 207.8686482947572074, 77.27881662714202093 ) ) ; +#18284 = CARTESIAN_POINT ( 'NONE', ( -27.30234400592999933, 124.8861144825999929, 89.01493418404001545 ) ) ; +#18285 = VECTOR ( 'NONE', #8043, 1000.000000000000227 ) ; +#18286 = ORIENTED_EDGE ( 'NONE', *, *, #33864, .F. ) ; +#18287 = CARTESIAN_POINT ( 'NONE', ( -25.76810376906509958, 158.0179022077391835, 180.2634769281190188 ) ) ; +#18288 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825934671853956, 0.0005734119020480080283 ) ) ; +#18289 = AXIS2_PLACEMENT_3D ( 'NONE', #16375, #13127, #19032 ) ; +#18290 = ORIENTED_EDGE ( 'NONE', *, *, #39389, .F. ) ; +#18292 = EDGE_CURVE ( 'NONE', #21029, #24812, #24189, .T. ) ; +#18291 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18367, #5093, #24132, #27620 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18293 = AXIS2_PLACEMENT_3D ( 'NONE', #4897, #17761, #23719 ) ; +#18294 = AXIS2_PLACEMENT_3D ( 'NONE', #15791, #22155, #253 ) ; +#18295 = CARTESIAN_POINT ( 'NONE', ( 4.035676231532755232, 174.7936433537611265, 102.5705385171684298 ) ) ; +#18296 = CARTESIAN_POINT ( 'NONE', ( -35.95638742416511491, 209.7096535813600156, 73.58022093100927918 ) ) ; +#18297 = EDGE_CURVE ( 'NONE', #1155, #349, #18868, .T. ) ; +#18298 = CARTESIAN_POINT ( 'NONE', ( 28.46384604140093799, 128.5894095540980402, 89.32293395218094645 ) ) ; +#18299 = CARTESIAN_POINT ( 'NONE', ( 20.50100932471902482, 118.1127835883590365, 89.75563873136169946 ) ) ; +#18300 = ORIENTED_EDGE ( 'NONE', *, *, #2537, .F. ) ; +#18301 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319377623471 ) ) ; +#18302 = LINE ( 'NONE', #12198, #13357 ) ; +#18303 = EDGE_CURVE ( 'NONE', #11263, #3990, #37328, .T. ) ; +#18304 = CARTESIAN_POINT ( 'NONE', ( 72.09533725057714548, 197.6701254222500097, 173.3705209015881792 ) ) ; +#18305 = CARTESIAN_POINT ( 'NONE', ( 35.92881332601000111, 113.0022062185000067, 89.86214737193999724 ) ) ; +#18306 = EDGE_CURVE ( 'NONE', #31197, #22792, #35795, .T. ) ; +#18307 = ADVANCED_FACE ( 'NONE', ( #27746 ), #2784, .T. ) ; +#18308 = LINE ( 'NONE', #37888, #23088 ) ; +#18309 = VERTEX_POINT ( 'NONE', #21802 ) ; +#18310 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; +#18311 = ORIENTED_EDGE ( 'NONE', *, *, #17156, .T. ) ; +#18312 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; +#18313 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25085, #37533, #34444, #6439 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18314 = CARTESIAN_POINT ( 'NONE', ( -6.038848507788371123, 135.1370730830105060, 91.15509477705727193 ) ) ; +#18315 = CIRCLE ( 'NONE', #17015, 1.999999997936985352 ) ; +#18316 = AXIS2_PLACEMENT_3D ( 'NONE', #34745, #6749, #3685 ) ; +#18317 = ORIENTED_EDGE ( 'NONE', *, *, #4964, .T. ) ; +#18318 = CARTESIAN_POINT ( 'NONE', ( 76.10748482110098223, 155.7951947758797644, 98.14087069364011029 ) ) ; +#18319 = AXIS2_PLACEMENT_3D ( 'NONE', #7863, #20531, #32808 ) ; +#18320 = LINE ( 'NONE', #25097, #7175 ) ; +#18321 = AXIS2_PLACEMENT_3D ( 'NONE', #14794, #18230, #3103 ) ; +#18322 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18323 = DIRECTION ( 'NONE', ( 0.0005884949961254158299, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18324 = EDGE_LOOP ( 'NONE', ( #20601, #14092, #29316, #30588 ) ) ; +#18325 = ORIENTED_EDGE ( 'NONE', *, *, #16529, .T. ) ; +#18326 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; +#18327 = CARTESIAN_POINT ( 'NONE', ( 26.00069066973446041, 119.1180911281959283, 90.25207238698713752 ) ) ; +#18328 = VERTEX_POINT ( 'NONE', #34238 ) ; +#18329 = CARTESIAN_POINT ( 'NONE', ( 30.06907743352446261, 134.5412604939639039, 93.52416550224677394 ) ) ; +#18330 = CARTESIAN_POINT ( 'NONE', ( -22.21857727096708146, 115.1893093715653151, 90.28120430312861799 ) ) ; +#18331 = ORIENTED_EDGE ( 'NONE', *, *, #19411, .F. ) ; +#18332 = CARTESIAN_POINT ( 'NONE', ( -17.26183737405610330, 121.4975388230068916, 176.5517749385022057 ) ) ; +#18333 = CYLINDRICAL_SURFACE ( 'NONE', #1687, 10.00000000000000000 ) ; +#18334 = CARTESIAN_POINT ( 'NONE', ( -12.19159238061602579, 125.0219911001496058, 178.7972028438273071 ) ) ; +#18335 = ORIENTED_EDGE ( 'NONE', *, *, #24566, .T. ) ; +#18336 = CARTESIAN_POINT ( 'NONE', ( -44.18930552168288273, 185.9402243567042206, 107.0564869194947022 ) ) ; +#18337 = EDGE_CURVE ( 'NONE', #34206, #9250, #9041, .T. ) ; +#18338 = ADVANCED_FACE ( 'NONE', ( #20988 ), #28049, .F. ) ; +#18339 = PLANE ( 'NONE', #914 ) ; +#18340 = CARTESIAN_POINT ( 'NONE', ( -25.86594528267000470, 191.2406205388000160, 106.7635301985999945 ) ) ; +#18341 = CARTESIAN_POINT ( 'NONE', ( 42.83909609183046996, 114.0261269511795632, 121.8710131578908573 ) ) ; +#18342 = CARTESIAN_POINT ( 'NONE', ( 3.326570984746394011, 125.9446392491717290, 88.72752278887659827 ) ) ; +#18343 = VERTEX_POINT ( 'NONE', #36520 ) ; +#18344 = PLANE ( 'NONE', #4328 ) ; +#18345 = ADVANCED_FACE ( 'NONE', ( #2385 ), #11794, .F. ) ; +#18346 = AXIS2_PLACEMENT_3D ( 'NONE', #5286, #27413, #5704 ) ; +#18347 = CARTESIAN_POINT ( 'NONE', ( 37.26954635975619823, 164.8944657675721999, 196.8584033196613916 ) ) ; +#18348 = CARTESIAN_POINT ( 'NONE', ( 36.66457562586903407, 191.6705100315085986, 104.3467321929502702 ) ) ; +#18349 = EDGE_CURVE ( 'NONE', #27237, #33399, #19218, .T. ) ; +#18350 = VECTOR ( 'NONE', #14072, 1000.000000000000000 ) ; +#18351 = VECTOR ( 'NONE', #15492, 1000.000000000000114 ) ; +#18352 = CARTESIAN_POINT ( 'NONE', ( -17.26216147564933223, 152.2838680029373677, 183.5655880739604981 ) ) ; +#18353 = EDGE_LOOP ( 'NONE', ( #21616, #8075, #8477, #4930 ) ) ; +#18354 = ORIENTED_EDGE ( 'NONE', *, *, #17081, .F. ) ; +#18355 = CARTESIAN_POINT ( 'NONE', ( -28.70816885920003614, 148.6529082553554417, 95.52894535674428766 ) ) ; +#18356 = CARTESIAN_POINT ( 'NONE', ( -41.96574953104487093, 121.8296678666196442, 91.00834655609098434 ) ) ; +#18357 = CARTESIAN_POINT ( 'NONE', ( -21.58773827856433769, 112.4042505803195411, 201.3497749872312568 ) ) ; +#18358 = EDGE_CURVE ( 'NONE', #17526, #22377, #31927, .T. ) ; +#18359 = CARTESIAN_POINT ( 'NONE', ( -26.01483129551610674, 211.4946636794494736, 73.07421638861994495 ) ) ; +#18360 = CARTESIAN_POINT ( 'NONE', ( -37.17303481993481284, 80.33007150473585511, 286.7096455229116714 ) ) ; +#18361 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#18362 = APPROVAL_ROLE ( '' ) ; +#18363 = CARTESIAN_POINT ( 'NONE', ( 20.50145491254044927, 188.7781080962309375, 105.7891785871605492 ) ) ; +#18364 = ORIENTED_EDGE ( 'NONE', *, *, #12493, .T. ) ; +#18365 = LINE ( 'NONE', #34698, #7417 ) ; +#18366 = DIRECTION ( 'NONE', ( 0.0005884949961216829218, -0.2249510543439096899, 0.9743698870671256840 ) ) ; +#18367 = CARTESIAN_POINT ( 'NONE', ( -26.00624846271685442, 190.8511609718977127, 106.8090059743847178 ) ) ; +#18368 = CARTESIAN_POINT ( 'NONE', ( 36.67803576733449944, 191.3746321016990066, 106.3708854744160135 ) ) ; +#18370 = ORIENTED_EDGE ( 'NONE', *, *, #34798, .T. ) ; +#18369 = CARTESIAN_POINT ( 'NONE', ( 36.82689161663000021, 191.4975675794999859, 106.2211857680000122 ) ) ; +#18371 = ORIENTED_EDGE ( 'NONE', *, *, #40253, .F. ) ; +#18372 = ORIENTED_EDGE ( 'NONE', *, *, #40320, .F. ) ; +#18373 = ORIENTED_EDGE ( 'NONE', *, *, #13506, .T. ) ; +#18374 = CIRCLE ( 'NONE', #32746, 2.499999999945713647 ) ; +#18375 = CARTESIAN_POINT ( 'NONE', ( -93.54594160988693829, 221.9633383074385051, 197.0821917869895969 ) ) ; +#18376 = AXIS2_PLACEMENT_3D ( 'NONE', #16301, #1167, #10592 ) ; +#18377 = CARTESIAN_POINT ( 'NONE', ( 20.13818639815300671, 126.7931285923730655, 91.85207892258530649 ) ) ; +#18378 = DIRECTION ( 'NONE', ( 0.0005884949961259158639, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18379 = ORIENTED_EDGE ( 'NONE', *, *, #11828, .F. ) ; +#18380 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18381 = CARTESIAN_POINT ( 'NONE', ( 45.67081843470916880, 116.8212980865162507, 122.5178260610734355 ) ) ; +#18382 = CARTESIAN_POINT ( 'NONE', ( 37.63773291092297768, 212.5463736527291303, 73.36910522896195630 ) ) ; +#18383 = CARTESIAN_POINT ( 'NONE', ( -20.89113403792100598, 128.9341314247968455, 92.51124259315015763 ) ) ; +#18384 = LINE ( 'NONE', #30886, #34105 ) ; +#18385 = EDGE_CURVE ( 'NONE', #28271, #282, #15061, .T. ) ; +#18386 = VERTEX_POINT ( 'NONE', #22406 ) ; +#18387 = CARTESIAN_POINT ( 'NONE', ( -15.49970617573983311, 151.8558896894846839, 95.23413014739874427 ) ) ; +#18388 = ADVANCED_FACE ( 'NONE', ( #13194 ), #34826, .F. ) ; +#18390 = EDGE_CURVE ( 'NONE', #27737, #11249, #3653, .T. ) ; +#18389 = CARTESIAN_POINT ( 'NONE', ( -75.39632045840481567, 196.1406929364112273, 190.0907134300437633 ) ) ; +#18391 = PLANE ( 'NONE', #4434 ) ; +#18392 = EDGE_CURVE ( 'NONE', #34227, #7229, #22910, .T. ) ; +#18393 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18394 = DIRECTION ( 'NONE', ( 6.071532165918790121E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#18395 = ORIENTED_EDGE ( 'NONE', *, *, #37612, .F. ) ; +#18396 = CARTESIAN_POINT ( 'NONE', ( -25.91300670584000088, 191.0997758704000091, 103.9121724043999961 ) ) ; +#18397 = CARTESIAN_POINT ( 'NONE', ( 2.302058793142580218, 189.9851746974860305, 103.9779396045330060 ) ) ; +#18398 = PLANE ( 'NONE', #5789 ) ; +#18399 = EDGE_CURVE ( 'NONE', #30625, #24414, #31302, .T. ) ; +#18400 = ORIENTED_EDGE ( 'NONE', *, *, #9416, .F. ) ; +#18401 = AXIS2_PLACEMENT_3D ( 'NONE', #11268, #39460, #8202 ) ; +#18402 = DIRECTION ( 'NONE', ( 0.0005884949960004859240, -0.2249510543438426879, 0.9743698870671410051 ) ) ; +#18403 = EDGE_LOOP ( 'NONE', ( #32218, #31903, #23833, #27572 ) ) ; +#18404 = CIRCLE ( 'NONE', #23606, 7.500000216081117443 ) ; +#18405 = EDGE_CURVE ( 'NONE', #28075, #36287, #8533, .T. ) ; +#18406 = CARTESIAN_POINT ( 'NONE', ( -35.93129677041999770, 192.6782481662999942, 106.5844153425000087 ) ) ; +#18407 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18408 = CARTESIAN_POINT ( 'NONE', ( 38.76181814569937245, 79.33382810079746150, 286.2650635282574854 ) ) ; +#18409 = DIRECTION ( 'NONE', ( -0.6087611427401035114, -0.7731004639645453480, -0.1781166575802727303 ) ) ; +#18410 = CARTESIAN_POINT ( 'NONE', ( -1.732810059889645427, 189.4717104458119934, 105.8744020675210038 ) ) ; +#18411 = ORIENTED_EDGE ( 'NONE', *, *, #36923, .T. ) ; +#18412 = DIRECTION ( 'NONE', ( 0.0006039748319336982153, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#18413 = DIRECTION ( 'NONE', ( -0.0005884949961222158072, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#18414 = CARTESIAN_POINT ( 'NONE', ( 42.98787737432541434, 112.9269645703451204, 127.4744954975476077 ) ) ; +#18416 = LINE ( 'NONE', #9044, #25334 ) ; +#18415 = CARTESIAN_POINT ( 'NONE', ( -15.49852919137054741, 126.2381079287689403, 91.37240600825562353 ) ) ; +#18417 = CARTESIAN_POINT ( 'NONE', ( -22.46175939534000321, 113.1257526802999962, 152.4718672074000381 ) ) ; +#18418 = ORIENTED_EDGE ( 'NONE', *, *, #20500, .T. ) ; +#18419 = CIRCLE ( 'NONE', #17135, 4.499999999978602006 ) ; +#18420 = EDGE_LOOP ( 'NONE', ( #35893, #18059, #6219, #39708 ) ) ; +#18421 = CARTESIAN_POINT ( 'NONE', ( 39.52738687544000129, 119.6025781157000125, 90.19533794253000281 ) ) ; +#18422 = LINE ( 'NONE', #34172, #30919 ) ; +#18423 = AXIS2_PLACEMENT_3D ( 'NONE', #6347, #34152, #34344 ) ; +#18424 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18425 = CARTESIAN_POINT ( 'NONE', ( 30.96384560851001311, 128.7443226152467730, 89.35718851987711275 ) ) ; +#18426 = CARTESIAN_POINT ( 'NONE', ( 12.63772998360747124, 130.8858987390867696, 89.98020666840058368 ) ) ; +#18427 = DIRECTION ( 'NONE', ( 0.6086215548477215131, 0.7730393818215735013, 0.1788572534946829551 ) ) ; +#18428 = ORIENTED_EDGE ( 'NONE', *, *, #147, .T. ) ; +#18429 = ORIENTED_EDGE ( 'NONE', *, *, #9974, .T. ) ; +#18430 = EDGE_CURVE ( 'NONE', #7259, #17944, #25272, .T. ) ; +#18431 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825948752246353, 0.0005734119017240838726 ) ) ; +#18432 = ADVANCED_FACE ( 'NONE', ( #9727 ), #4515, .F. ) ; +#18433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18584, #3, #31283, #24968 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18434 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971520438 ) ) ; +#18435 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#18436 = VERTEX_POINT ( 'NONE', #3768 ) ; +#18437 = CARTESIAN_POINT ( 'NONE', ( -36.61650746187000038, 191.3591660024999896, 106.3831759458000050 ) ) ; +#18438 = CARTESIAN_POINT ( 'NONE', ( 13.47257850444245442, 153.4830319772647442, 97.81594653802845585 ) ) ; +#18439 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38713, #10730, #1931, #30143 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18440 = CARTESIAN_POINT ( 'NONE', ( 2.586271793656000018, 189.7072324810999930, 106.3365748873000030 ) ) ; +#18441 = ORIENTED_EDGE ( 'NONE', *, *, #22024, .T. ) ; +#18442 = DIRECTION ( 'NONE', ( 4.718447854759373813E-13, 0.9743700557921590732, 0.2249510932971540700 ) ) ; +#18443 = DIRECTION ( 'NONE', ( -0.9999998268367693566, -0.0001323826063126660698, 0.0005734119608316798605 ) ) ; +#18444 = CARTESIAN_POINT ( 'NONE', ( -6.635715103306525878E-14, 155.6803346354327289, 98.67347229705578115 ) ) ; +#18445 = CARTESIAN_POINT ( 'NONE', ( 4.385479481597147178, 147.3836199698109795, 93.67646283599650303 ) ) ; +#18446 = AXIS2_PLACEMENT_3D ( 'NONE', #35601, #4541, #19874 ) ; +#18447 = ORIENTED_EDGE ( 'NONE', *, *, #12098, .F. ) ; +#18448 = CARTESIAN_POINT ( 'NONE', ( -36.07329620650741475, 123.8070289312214953, 91.33672588886609844 ) ) ; +#18449 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10451, #22919, #12589, #6448 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18450 = CONICAL_SURFACE ( 'NONE', #11291, 2.502999999880697324, 0.7853981633854106859 ) ; +#18451 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250909262, 179.1753088544093657, 103.5954339977318739 ) ) ; +#18452 = CARTESIAN_POINT ( 'NONE', ( -31.70384873206000265, 225.9002260769261738, 76.07765295985980458 ) ) ; +#18453 = EDGE_CURVE ( 'NONE', #8915, #1951, #16241, .T. ) ; +#18454 = AXIS2_PLACEMENT_3D ( 'NONE', #10613, #32865, #17115 ) ; +#18455 = ORIENTED_EDGE ( 'NONE', *, *, #27299, .T. ) ; +#18456 = CARTESIAN_POINT ( 'NONE', ( -35.69644648028999967, 111.0397749124999933, 90.03934455280000293 ) ) ; +#18457 = VERTEX_POINT ( 'NONE', #19105 ) ; +#18458 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #15169, #5339, #27651 ), + ( #25181, #15359, #9431 ), + ( #6344, #34150, #22102 ), + ( #3077, #24980, #28047 ) ), + .UNSPECIFIED., .F., .F., .T. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), + ( 3, 3 ), + ( 0.5322599266487868519, 0.5322688524717417158 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.7511062204421768973, 1.000000000000000000), + ( 1.000000000000000000, 0.7511101270067886970, 1.000000000000000000), + ( 1.000000000000000000, 0.7511140335275009461, 1.000000000000000000), + ( 1.000000000000000000, 0.7511179400042681253, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#18460 = CARTESIAN_POINT ( 'NONE', ( 13.45852275855000180, 174.6481430188156594, 27.63001052910568944 ) ) ; +#18459 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#18461 = ORIENTED_EDGE ( 'NONE', *, *, #9927, .F. ) ; +#18462 = EDGE_LOOP ( 'NONE', ( #22945, #2762, #20960, #11373 ) ) ; +#18463 = EDGE_LOOP ( 'NONE', ( #31265, #12262 ) ) ; +#18464 = CARTESIAN_POINT ( 'NONE', ( 2.404590060478000169, 209.1519362205000050, 75.46481054992999304 ) ) ; +#18465 = CARTESIAN_POINT ( 'NONE', ( 3.416491666947000017, 127.6382454602999985, 89.37504442651001568 ) ) ; +#18466 = VERTEX_POINT ( 'NONE', #29139 ) ; +#18467 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3935, #31776, #16210, #26439, #13167, #26243, #38680, #38891, #3737, #35395 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998477884, 0.3749999999997217781, 0.4374999999997082889, 0.4999999999996947442, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18468 = ORIENTED_EDGE ( 'NONE', *, *, #26264, .T. ) ; +#18469 = ORIENTED_EDGE ( 'NONE', *, *, #31631, .F. ) ; +#18470 = DIRECTION ( 'NONE', ( -0.0005884949961249498398, 0.2249510543439061649, -0.9743698870671263501 ) ) ; +#18471 = FACE_OUTER_BOUND ( 'NONE', #14241, .T. ) ; +#18472 = CARTESIAN_POINT ( 'NONE', ( 21.68370070337708100, 182.2867715710398784, 101.7240440883198005 ) ) ; +#18473 = CARTESIAN_POINT ( 'NONE', ( 30.10540398896155523, 121.2983238331719917, 152.0219651002330750 ) ) ; +#18474 = ORIENTED_EDGE ( 'NONE', *, *, #29394, .F. ) ; +#18475 = CIRCLE ( 'NONE', #2828, 22.50000000000000000 ) ; +#18476 = VERTEX_POINT ( 'NONE', #16042 ) ; +#18477 = ORIENTED_EDGE ( 'NONE', *, *, #21130, .F. ) ; +#18478 = CARTESIAN_POINT ( 'NONE', ( 36.05533436145224613, 118.8155666260000061, 90.24600832072127332 ) ) ; +#18479 = ADVANCED_FACE ( 'NONE', ( #35025 ), #7237, .T. ) ; +#18480 = LINE ( 'NONE', #30985, #440 ) ; +#18481 = EDGE_CURVE ( 'NONE', #4808, #12828, #7037, .T. ) ; +#18482 = CARTESIAN_POINT ( 'NONE', ( 45.29516381819948379, 180.6442485579885329, 103.8963377076147907 ) ) ; +#18483 = EDGE_LOOP ( 'NONE', ( #35165, #14630, #15065, #38576 ) ) ; +#18484 = ORIENTED_EDGE ( 'NONE', *, *, #28842, .F. ) ; +#18485 = VECTOR ( 'NONE', #8246, 1000.000000000000114 ) ; +#18486 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.298960938811000068E-14, 1.000000000000000000 ) ) ; +#18487 = CARTESIAN_POINT ( 'NONE', ( -20.89128718923779005, 182.4208812217193838, 104.8596338257292757 ) ) ; +#18488 = PLANE ( 'NONE', #29372 ) ; +#18489 = ORIENTED_EDGE ( 'NONE', *, *, #11911, .T. ) ; +#18490 = FACE_OUTER_BOUND ( 'NONE', #16398, .T. ) ; +#18491 = CARTESIAN_POINT ( 'NONE', ( 38.65471576631835404, 119.1564763279458816, 90.25899222980254422 ) ) ; +#18492 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 183.4515543678114966, 105.0773313099631139 ) ) ; +#18493 = LINE ( 'NONE', #27948, #37169 ) ; +#18494 = ORIENTED_EDGE ( 'NONE', *, *, #7262, .T. ) ; +#18495 = DIRECTION ( 'NONE', ( -0.0009705195736481808059, 0.2252351989748601624, -0.9743039378112521298 ) ) ; +#18496 = CARTESIAN_POINT ( 'NONE', ( 40.07937669021247729, 78.31427785818142695, 286.1872286878083855 ) ) ; +#18497 = LINE ( 'NONE', #9528, #7501 ) ; +#18498 = LINE ( 'NONE', #8736, #16369 ) ; +#18499 = EDGE_CURVE ( 'NONE', #13580, #13982, #11048, .T. ) ; +#18500 = CARTESIAN_POINT ( 'NONE', ( -29.43192434859718887, 181.8734812664013702, 101.6595010425561867 ) ) ; +#18501 = ORIENTED_EDGE ( 'NONE', *, *, #22306, .F. ) ; +#18502 = AXIS2_PLACEMENT_3D ( 'NONE', #9671, #851, #15990 ) ; +#18503 = AXIS2_PLACEMENT_3D ( 'NONE', #21963, #9898, #16007 ) ; +#18504 = LINE ( 'NONE', #6640, #23278 ) ; +#18505 = VERTEX_POINT ( 'NONE', #22802 ) ; +#18506 = CIRCLE ( 'NONE', #28347, 4.999999999999990230 ) ; +#18507 = CARTESIAN_POINT ( 'NONE', ( -38.02994714804000864, 118.9093675896999969, 90.44388284059000682 ) ) ; +#18508 = AXIS2_PLACEMENT_3D ( 'NONE', #32042, #15872, #19538 ) ; +#18509 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#18510 = ORIENTED_EDGE ( 'NONE', *, *, #37515, .F. ) ; +#18511 = PLANE ( 'NONE', #40143 ) ; +#18512 = EDGE_CURVE ( 'NONE', #37430, #22764, #10994, .T. ) ; +#18513 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971562072 ) ) ; +#18514 = CARTESIAN_POINT ( 'NONE', ( 23.36349092257420068, 177.5980283123824677, 100.8086092966151597 ) ) ; +#18515 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927775143106, 0.0005734119022065908107 ) ) ; +#18516 = ORIENTED_EDGE ( 'NONE', *, *, #681, .T. ) ; +#18517 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; +#18518 = EDGE_CURVE ( 'NONE', #15550, #33101, #25073, .T. ) ; +#18519 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17917, #14477, #4845, #14275, #39394, #17307, #29814, #1799, #39201, #26961, #11399, #23887, #36344, #20803, #33261, #5255, #17718 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999538980, 0.1874999999999222289, 0.2187499999998853972, 0.2343749999998670230, 0.2499999999998486211, 0.3749999999999342193, 0.4374999999999567568, 0.4687499999999593658, 0.4999999999999619194, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18520 = FACE_OUTER_BOUND ( 'NONE', #16967, .T. ) ; +#18521 = ORIENTED_EDGE ( 'NONE', *, *, #39213, .T. ) ; +#18522 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18524 = EDGE_CURVE ( 'NONE', #23147, #14158, #3365, .T. ) ; +#18523 = CARTESIAN_POINT ( 'NONE', ( 36.64477843738828255, 191.1898283041118987, 106.4830069681582074 ) ) ; +#18525 = EDGE_CURVE ( 'NONE', #39067, #20299, #38298, .T. ) ; +#18526 = ORIENTED_EDGE ( 'NONE', *, *, #32621, .F. ) ; +#18527 = FACE_OUTER_BOUND ( 'NONE', #11503, .T. ) ; +#18528 = EDGE_CURVE ( 'NONE', #24799, #25077, #20508, .T. ) ; +#18529 = EDGE_CURVE ( 'NONE', #8915, #26075, #29528, .T. ) ; +#18530 = DIRECTION ( 'NONE', ( -0.6087116037913345989, 0.7730376917437175033, 0.1785578633197842380 ) ) ; +#18531 = EDGE_LOOP ( 'NONE', ( #9064, #6824, #16218, #5097, #35505 ) ) ; +#18532 = CARTESIAN_POINT ( 'NONE', ( -32.65062852997883880, 153.0051697192221241, 291.5782640967074713 ) ) ; +#18533 = AXIS2_PLACEMENT_3D ( 'NONE', #18790, #9428, #3269 ) ; +#18534 = CARTESIAN_POINT ( 'NONE', ( -25.39139182829000063, 190.7622573589000012, 106.1326039723000036 ) ) ; +#18535 = VECTOR ( 'NONE', #22067, 1000.000000000000114 ) ; +#18536 = CARTESIAN_POINT ( 'NONE', ( 30.07150067443713581, 176.9244726588816832, 103.2915126945589464 ) ) ; +#18537 = CARTESIAN_POINT ( 'NONE', ( 3.652606486068469049, 125.3210731118818444, 88.58336425918274415 ) ) ; +#18538 = ORIENTED_EDGE ( 'NONE', *, *, #39115, .F. ) ; +#18539 = LINE ( 'NONE', #3015, #33641 ) ; +#18540 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2213, #8759, #33671, #11823 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18541 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; +#18542 = FACE_OUTER_BOUND ( 'NONE', #3134, .T. ) ; +#18543 = CARTESIAN_POINT ( 'NONE', ( -45.96127116939970847, 125.1268439885110126, 91.78846319988008418 ) ) ; +#18544 = ORIENTED_EDGE ( 'NONE', *, *, #32882, .F. ) ; +#18545 = VERTEX_POINT ( 'NONE', #8049 ) ; +#18546 = CARTESIAN_POINT ( 'NONE', ( 13.50176802971722978, 137.8352832724987422, 94.54854101738141026 ) ) ; +#18547 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12343, #6204, #37290, #31169 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18548 = CARTESIAN_POINT ( 'NONE', ( 19.55565711859851064, 149.3413318931515619, 181.5431738098612584 ) ) ; +#18549 = CARTESIAN_POINT ( 'NONE', ( 25.62717527879522450, 212.5792673437159408, 73.04302591068935158 ) ) ; +#18550 = ADVANCED_FACE ( 'NONE', ( #14396 ), #26673, .F. ) ; +#18551 = CARTESIAN_POINT ( 'NONE', ( -36.36432404130999885, 191.9041063813000108, 104.5545526819000060 ) ) ; +#18552 = CARTESIAN_POINT ( 'NONE', ( -25.50032095308166902, 190.9623827952989927, 106.3160945275165687 ) ) ; +#18553 = AXIS2_PLACEMENT_3D ( 'NONE', #7550, #20020, #26791 ) ; +#18554 = CIRCLE ( 'NONE', #17330, 5.999999999944997775 ) ; +#18555 = CARTESIAN_POINT ( 'NONE', ( -12.63917517144589731, 181.9396764318221642, 102.0104863414155147 ) ) ; +#18556 = DATE_TIME_ROLE ( 'creation_date' ) ; +#18557 = CARTESIAN_POINT ( 'NONE', ( 39.73108058903446249, 110.6933397802364283, 169.4226323853610268 ) ) ; +#18558 = AXIS2_PLACEMENT_3D ( 'NONE', #24069, #30805, #6050 ) ; +#18559 = CIRCLE ( 'NONE', #1587, 2.000000000000000444 ) ; +#18560 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#18561 = CARTESIAN_POINT ( 'NONE', ( -24.38839406860000025, 109.6131156702000027, 152.4718672074000381 ) ) ; +#18562 = DIRECTION ( 'NONE', ( 0.0001358647759535183165, 0.9743700645145553230, 0.2249510144868518968 ) ) ; +#18563 = EDGE_CURVE ( 'NONE', #6533, #39643, #24626, .T. ) ; +#18564 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, -2.333520449303964377E-14, -0.9999998176071847045 ) ) ; +#18565 = CARTESIAN_POINT ( 'NONE', ( 37.18464229284000311, 191.0646458765000091, 106.3082676759999998 ) ) ; +#18566 = AXIS2_PLACEMENT_3D ( 'NONE', #17909, #34065, #2799 ) ; +#18567 = EDGE_LOOP ( 'NONE', ( #19319, #7062, #25500, #3752 ) ) ; +#18569 = ORIENTED_EDGE ( 'NONE', *, *, #36129, .T. ) ; +#18568 = CARTESIAN_POINT ( 'NONE', ( 36.66889965364000403, 191.2377279513000019, 106.4440485215999956 ) ) ; +#18570 = ORIENTED_EDGE ( 'NONE', *, *, #15038, .T. ) ; +#18571 = ORIENTED_EDGE ( 'NONE', *, *, #8055, .T. ) ; +#18572 = LINE ( 'NONE', #18375, #4232 ) ; +#18573 = EDGE_CURVE ( 'NONE', #7592, #13713, #14908, .T. ) ; +#18574 = CARTESIAN_POINT ( 'NONE', ( -20.23290355681359287, 184.9083160715356371, 102.5937630826569915 ) ) ; +#18575 = ADVANCED_FACE ( 'NONE', ( #26072 ), #1911, .F. ) ; +#18576 = CARTESIAN_POINT ( 'NONE', ( -31.33471866875930800, 177.4784205339375660, 100.6459703763841844 ) ) ; +#18577 = EDGE_LOOP ( 'NONE', ( #39420, #26558, #30548, #22296 ) ) ; +#18578 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#18579 = EDGE_CURVE ( 'NONE', #572, #35627, #38769, .T. ) ; +#18580 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 143.0051697192221241, 291.5295797804307654 ) ) ; +#18581 = DIRECTION ( 'NONE', ( -0.1632030864945562820, 0.3417424273710317761, -0.9255143790850607344 ) ) ; +#18582 = ORIENTED_EDGE ( 'NONE', *, *, #16404, .T. ) ; +#18583 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 1.238758140229869750E-30, -0.0006039748319385906776 ) ) ; +#18584 = CARTESIAN_POINT ( 'NONE', ( 41.55397567426885530, 120.6681361272677577, 87.99940985657048031 ) ) ; +#18585 = LINE ( 'NONE', #12084, #33292 ) ; +#18586 = CARTESIAN_POINT ( 'NONE', ( -20.09648534120855246, 211.8755416198732462, 76.07065348104518421 ) ) ; +#18587 = VECTOR ( 'NONE', #38922, 1000.000000000000227 ) ; +#18588 = ORIENTED_EDGE ( 'NONE', *, *, #35365, .F. ) ; +#18589 = CARTESIAN_POINT ( 'NONE', ( 15.83489064692280124, 137.8671913220991883, 94.38025547595243836 ) ) ; +#18590 = CARTESIAN_POINT ( 'NONE', ( -0.04020359587071823532, 115.7390747894103953, 347.0321741129275210 ) ) ; +#18591 = AXIS2_PLACEMENT_3D ( 'NONE', #29791, #14249, #36099 ) ; +#18592 = CARTESIAN_POINT ( 'NONE', ( 21.70633521009782640, 123.1952238384177605, 176.5176797919971250 ) ) ; +#18593 = VECTOR ( 'NONE', #34015, 999.9999999999997726 ) ; +#18594 = VERTEX_POINT ( 'NONE', #13990 ) ; +#18595 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319346908024 ) ) ; +#18596 = ORIENTED_EDGE ( 'NONE', *, *, #23301, .F. ) ; +#18597 = CARTESIAN_POINT ( 'NONE', ( -19.99850934198748931, 160.0545621481389844, 99.69532483852709959 ) ) ; +#18598 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21742, #40121, #39924, #15777 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.0003335382722436411817 ), + .UNSPECIFIED. ) ; +#18599 = DIRECTION ( 'NONE', ( 0.6068733047655823221, 0.7745082036644093115, 0.1784428043363773253 ) ) ; +#18600 = CARTESIAN_POINT ( 'NONE', ( 16.55846291764536105, 123.0757855049963467, 172.1961118494296556 ) ) ; +#18601 = CARTESIAN_POINT ( 'NONE', ( -37.35479255310585245, 191.0186931307436851, 106.3350318144467366 ) ) ; +#18602 = CARTESIAN_POINT ( 'NONE', ( 19.85164219301282884, 148.9679372099747638, 184.3407892933917651 ) ) ; +#18603 = CYLINDRICAL_SURFACE ( 'NONE', #39518, 59.40509898897002472 ) ; +#18604 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999902300, 132.9679238121838978, 90.36185680191219660 ) ) ; +#18605 = EDGE_LOOP ( 'NONE', ( #20687, #34271, #37423, #4732 ) ) ; +#18606 = EDGE_CURVE ( 'NONE', #4577, #36211, #27427, .T. ) ; +#18607 = DIRECTION ( 'NONE', ( 0.9999998268368962551, 0.0001323827092387665195, -0.0005734117158298909301 ) ) ; +#18608 = EDGE_CURVE ( 'NONE', #15233, #32479, #39719, .T. ) ; +#18609 = CARTESIAN_POINT ( 'NONE', ( -0.09191864964710037833, 291.0964424001293196, 217.1925188927256158 ) ) ; +#18610 = CARTESIAN_POINT ( 'NONE', ( -10.03744067673693152, 168.3831169150392668, 99.04644282438005121 ) ) ; +#18611 = EDGE_CURVE ( 'NONE', #10977, #15233, #9090, .T. ) ; +#18612 = EDGE_CURVE ( 'NONE', #20961, #982, #4077, .T. ) ; +#18614 = LINE ( 'NONE', #4035, #23372 ) ; +#18613 = DIRECTION ( 'NONE', ( -0.0005884949961239888030, 0.2249510543439063315, -0.9743698870671262391 ) ) ; +#18615 = CIRCLE ( 'NONE', #14057, 6.000000000000007994 ) ; +#18616 = ORIENTED_EDGE ( 'NONE', *, *, #10947, .F. ) ; +#18617 = AXIS2_PLACEMENT_3D ( 'NONE', #3223, #8984, #19155 ) ; +#18618 = ORIENTED_EDGE ( 'NONE', *, *, #4825, .T. ) ; +#18619 = VECTOR ( 'NONE', #22642, 1000.000000000000114 ) ; +#18620 = VECTOR ( 'NONE', #13360, 999.9999999999998863 ) ; +#18621 = ORIENTED_EDGE ( 'NONE', *, *, #15673, .F. ) ; +#18622 = CARTESIAN_POINT ( 'NONE', ( -21.44517132691637329, 129.4739009503746558, 92.63619159901811884 ) ) ; +#18623 = EDGE_CURVE ( 'NONE', #20022, #37794, #35179, .T. ) ; +#18624 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 1.540743955509788340E-33, 0.0006039748319384538513 ) ) ; +#18625 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498903273, 179.0675991014140607, 104.0619761093665971 ) ) ; +#18626 = CARTESIAN_POINT ( 'NONE', ( 12.63749343440153439, 130.8796612142295146, 89.98410442299223178 ) ) ; +#18627 = DIRECTION ( 'NONE', ( 0.7075337269147008445, -0.000000000000000000, 0.7066795775160008564 ) ) ; +#18628 = ORIENTED_EDGE ( 'NONE', *, *, #29073, .T. ) ; +#18629 = CARTESIAN_POINT ( 'NONE', ( -37.28964750938936845, 162.8083416849163996, 206.0112259113205084 ) ) ; +#18630 = EDGE_LOOP ( 'NONE', ( #32717, #34843, #11191, #7943, #38834 ) ) ; +#18631 = CARTESIAN_POINT ( 'NONE', ( 5.661195405889541732, 124.4055252125605620, 88.42320396559895812 ) ) ; +#18632 = CARTESIAN_POINT ( 'NONE', ( 30.05202364329594289, 126.8409241029880832, 91.48406572323723651 ) ) ; +#18633 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; +#18634 = EDGE_CURVE ( 'NONE', #25706, #4731, #17233, .T. ) ; +#18635 = VERTEX_POINT ( 'NONE', #17643 ) ; +#18636 = CARTESIAN_POINT ( 'NONE', ( -36.18185695497940202, 190.9522038446160082, 106.8424817839080134 ) ) ; +#18637 = CARTESIAN_POINT ( 'NONE', ( 2.893047872412550348, 190.2073145499105635, 103.5639949355635281 ) ) ; +#18638 = CARTESIAN_POINT ( 'NONE', ( 13.47463546662201317, 153.3581425397641453, 97.61606142177900836 ) ) ; +#18639 = AXIS2_PLACEMENT_3D ( 'NONE', #3247, #31475, #9811 ) ; +#18640 = VERTEX_POINT ( 'NONE', #35837 ) ; +#18641 = CARTESIAN_POINT ( 'NONE', ( 0.5641629861702882609, 188.3739978860623410, 106.2349422265271812 ) ) ; +#18642 = AXIS2_PLACEMENT_3D ( 'NONE', #40301, #34547, #9043 ) ; +#18643 = DIRECTION ( 'NONE', ( 0.0005884979656576173456, -0.2249510543434622978, 0.9743698870654352584 ) ) ; +#18644 = CARTESIAN_POINT ( 'NONE', ( 36.23987951694048348, 191.4462391905814229, 103.8298826277539177 ) ) ; +#18645 = CARTESIAN_POINT ( 'NONE', ( -26.13534276609000173, 120.0011205343000000, 90.59101258731999451 ) ) ; +#18646 = VECTOR ( 'NONE', #14377, 1000.000000000000114 ) ; +#18647 = EDGE_LOOP ( 'NONE', ( #20449, #9176, #17845, #16775 ) ) ; +#18648 = CARTESIAN_POINT ( 'NONE', ( -14.29767978178728960, 209.7096097237614742, 73.06713952287860536 ) ) ; +#18649 = CIRCLE ( 'NONE', #7539, 6.499999999988696153 ) ; +#18650 = CARTESIAN_POINT ( 'NONE', ( 15.05197310825490398, 136.6013035982805661, 91.18072662319218580 ) ) ; +#18651 = CARTESIAN_POINT ( 'NONE', ( 15.45514460193059847, 202.1125837722002245, 28.07875028728494371 ) ) ; +#18652 = ORIENTED_EDGE ( 'NONE', *, *, #37118, .T. ) ; +#18653 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282899430, 164.6343173020728443, 97.67551052995993643 ) ) ; +#18654 = ORIENTED_EDGE ( 'NONE', *, *, #14174, .T. ) ; +#18655 = ADVANCED_FACE ( 'NONE', ( #39123 ), #29376, .F. ) ; +#18656 = EDGE_CURVE ( 'NONE', #14925, #39132, #15012, .T. ) ; +#18658 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; +#18657 = CARTESIAN_POINT ( 'NONE', ( 36.20042881978272931, 192.0106638782634718, 104.3804419661056926 ) ) ; +#18659 = ORIENTED_EDGE ( 'NONE', *, *, #10577, .F. ) ; +#18660 = ORIENTED_EDGE ( 'NONE', *, *, #15423, .F. ) ; +#18661 = ORIENTED_EDGE ( 'NONE', *, *, #3030, .T. ) ; +#18662 = CARTESIAN_POINT ( 'NONE', ( 2.337161295297999875, 209.5153078266000364, 75.42148145382999758 ) ) ; +#18663 = VECTOR ( 'NONE', #8294, 1000.000000000000114 ) ; +#18664 = CARTESIAN_POINT ( 'NONE', ( 13.85666887053580787, 124.6499588255688309, 174.6121027900639717 ) ) ; +#18665 = CARTESIAN_POINT ( 'NONE', ( 44.83277154663306874, 186.3180907337439578, 107.7244483083414508 ) ) ; +#18666 = CARTESIAN_POINT ( 'NONE', ( 13.50176814620886390, 151.2963865131595753, 97.65648528510170934 ) ) ; +#18667 = ORIENTED_EDGE ( 'NONE', *, *, #11829, .F. ) ; +#18668 = CIRCLE ( 'NONE', #18003, 2.499999999869602085 ) ; +#18669 = ORIENTED_EDGE ( 'NONE', *, *, #12922, .F. ) ; +#18670 = CARTESIAN_POINT ( 'NONE', ( -14.16859883678303689, 135.5379567964818648, 93.51864244317933128 ) ) ; +#18671 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37857, #4301, #32135, #22738 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999999706563479362 ), + .UNSPECIFIED. ) ; +#18672 = CARTESIAN_POINT ( 'NONE', ( 13.50281259258426658, 187.5541529417837694, 105.8642044353590705 ) ) ; +#18673 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; +#18674 = DIRECTION ( 'NONE', ( -0.9999998268368042176, -0.0001323825929795902155, 0.0005734119030926363879 ) ) ; +#18675 = ORIENTED_EDGE ( 'NONE', *, *, #40004, .T. ) ; +#18676 = AXIS2_PLACEMENT_3D ( 'NONE', #1383, #5413, #35504 ) ; +#18677 = VERTEX_POINT ( 'NONE', #35426 ) ; +#18678 = ORIENTED_EDGE ( 'NONE', *, *, #31069, .T. ) ; +#18679 = PLANE ( 'NONE', #8268 ) ; +#18680 = CARTESIAN_POINT ( 'NONE', ( 24.53499375990451270, 104.1131156706254473, 90.25296631794056168 ) ) ; +#18681 = CARTESIAN_POINT ( 'NONE', ( -20.49913213830728864, 118.1134457197417902, 88.44668923520308113 ) ) ; +#18682 = EDGE_CURVE ( 'NONE', #38161, #37905, #19895, .T. ) ; +#18683 = ORIENTED_EDGE ( 'NONE', *, *, #38617, .T. ) ; +#18684 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023854076 ) ) ; +#18685 = CARTESIAN_POINT ( 'NONE', ( -41.01266184249756463, 189.0687663645294663, 107.2394220196258203 ) ) ; +#18686 = ORIENTED_EDGE ( 'NONE', *, *, #17537, .F. ) ; +#18687 = CARTESIAN_POINT ( 'NONE', ( -36.83654042100931036, 116.2424538687594833, 89.73867524819259245 ) ) ; +#18688 = DIRECTION ( 'NONE', ( -0.7066905233759539495, -0.1590641512579268335, 0.6894106903401016062 ) ) ; +#18689 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825925011399283, 0.0005734119022738485335 ) ) ; +#18690 = CARTESIAN_POINT ( 'NONE', ( -37.62305393521922525, 212.3970732061812896, 73.58122755549422322 ) ) ; +#18691 = CARTESIAN_POINT ( 'NONE', ( 26.11095176941643814, 190.7356467402886722, 103.6719484086482765 ) ) ; +#18692 = AXIS2_PLACEMENT_3D ( 'NONE', #18969, #3231, #12643 ) ; +#18693 = VERTEX_POINT ( 'NONE', #5796 ) ; +#18694 = CARTESIAN_POINT ( 'NONE', ( 26.00076055413803999, 117.7169937519419278, 90.25208103135760496 ) ) ; +#18695 = LINE ( 'NONE', #3772, #3558 ) ; +#18696 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32653, #10195, #19568, #38575 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18697 = AXIS2_PLACEMENT_3D ( 'NONE', #34754, #38047, #31733 ) ; +#18698 = CYLINDRICAL_SURFACE ( 'NONE', #23841, 2.000000000000001332 ) ; +#18699 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #38950, #32817, #14637, #36077 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 2.893989844277871981, 4.712388980384664805 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7429183312171808717, 0.7429183312171808717, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#18700 = CARTESIAN_POINT ( 'NONE', ( -22.64184747305000300, 154.1036202365000065, 95.50079732685999545 ) ) ; +#18701 = EDGE_LOOP ( 'NONE', ( #11589, #13314, #28743, #39162 ) ) ; +#18702 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#18703 = ORIENTED_EDGE ( 'NONE', *, *, #18798, .F. ) ; +#18704 = AXIS2_PLACEMENT_3D ( 'NONE', #9500, #30978, #19284 ) ; +#18705 = EDGE_CURVE ( 'NONE', #8699, #15600, #39805, .T. ) ; +#18706 = ADVANCED_FACE ( 'NONE', ( #9075 ), #36547, .F. ) ; +#18707 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38081, #26375, #37477, #10838 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.02880200696896740784, 0.02994545772932011643 ), + .UNSPECIFIED. ) ; +#18708 = LINE ( 'NONE', #37940, #5025 ) ; +#18709 = DIRECTION ( 'NONE', ( -3.295974604355914547E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#18710 = CARTESIAN_POINT ( 'NONE', ( 38.57040784642907028, 118.4633227499596018, 89.66268640670058687 ) ) ; +#18711 = ORIENTED_EDGE ( 'NONE', *, *, #2314, .T. ) ; +#18712 = CARTESIAN_POINT ( 'NONE', ( 23.36189990591568133, 175.3591898460452114, 100.1205101937285349 ) ) ; +#18713 = DIRECTION ( 'NONE', ( 0.0005884949961279498272, -0.2249510543439066645, 0.9743698870671262391 ) ) ; +#18714 = CARTESIAN_POINT ( 'NONE', ( 15.89469151744206421, 128.5927809666073927, 173.0004654942144384 ) ) ; +#18715 = DIRECTION ( 'NONE', ( 1.117039843155982209E-18, 1.000000000000000000, -1.110223092091563281E-14 ) ) ; +#18716 = VERTEX_POINT ( 'NONE', #30952 ) ; +#18717 = EDGE_LOOP ( 'NONE', ( #25445, #17105, #22533, #1802 ) ) ; +#18718 = CARTESIAN_POINT ( 'NONE', ( 1.176830695733112941, 189.0959465685911027, 105.7644401730694170 ) ) ; +#18719 = DIRECTION ( 'NONE', ( -0.0005884949961247390709, 0.2249510543439058041, -0.9743698870671265722 ) ) ; +#18720 = CONICAL_SURFACE ( 'NONE', #28535, 6.503000000032579386, 0.7853981634494727748 ) ; +#18721 = ORIENTED_EDGE ( 'NONE', *, *, #34355, .F. ) ; +#18722 = CARTESIAN_POINT ( 'NONE', ( 36.04524237818177568, 209.7096540190999860, 73.53673375003081958 ) ) ; +#18723 = LINE ( 'NONE', #12605, #23095 ) ; +#18724 = ORIENTED_EDGE ( 'NONE', *, *, #24351, .T. ) ; +#18725 = CARTESIAN_POINT ( 'NONE', ( 20.89486103759118052, 175.7095848683153463, 103.2849699440975826 ) ) ; +#18726 = AXIS2_PLACEMENT_3D ( 'NONE', #14672, #30404, #2403 ) ; +#18727 = PLANE ( 'NONE', #5589 ) ; +#18728 = CARTESIAN_POINT ( 'NONE', ( 55.75981625165690048, 6.558920741114762976, 161.6918666634598196 ) ) ; +#18729 = ORIENTED_EDGE ( 'NONE', *, *, #39700, .T. ) ; +#18730 = DIRECTION ( 'NONE', ( 0.1305263947812629333, 0.9659212020967675727, 0.2235153050807516528 ) ) ; +#18731 = CARTESIAN_POINT ( 'NONE', ( 3.773549070401551742, 167.8775999163818256, 101.2431827948426246 ) ) ; +#18732 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38905, #28914, #26661, #10323 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18733 = PLANE ( 'NONE', #39045 ) ; +#18734 = CARTESIAN_POINT ( 'NONE', ( 25.49919833444198858, 118.8155663768459505, 87.75236248755290092 ) ) ; +#18735 = CARTESIAN_POINT ( 'NONE', ( -5.668107859520512548, 127.9093576421573601, 92.26856186482403643 ) ) ; +#18736 = ORIENTED_EDGE ( 'NONE', *, *, #37560, .F. ) ; +#18737 = CARTESIAN_POINT ( 'NONE', ( -12.63809837006106918, 177.7897768145701036, 100.7065200156251166 ) ) ; +#18738 = CARTESIAN_POINT ( 'NONE', ( -37.78472778768890805, 118.9454232552457142, 87.29152118331340660 ) ) ; +#18739 = CARTESIAN_POINT ( 'NONE', ( 36.75897388210037775, 191.6299679312680837, 104.3441452898864128 ) ) ; +#18740 = EDGE_CURVE ( 'NONE', #8209, #23911, #20934, .T. ) ; +#18741 = CARTESIAN_POINT ( 'NONE', ( 21.70383484956424525, 182.1705797945729444, 104.4340183909650079 ) ) ; +#18742 = ORIENTED_EDGE ( 'NONE', *, *, #21101, .T. ) ; +#18743 = CARTESIAN_POINT ( 'NONE', ( 38.40137274602947315, 118.9610368294954981, 90.24693936499792812 ) ) ; +#18744 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#18745 = CARTESIAN_POINT ( 'NONE', ( -23.01844285970464909, 211.0902260919000355, 76.07552203529617429 ) ) ; +#18746 = CARTESIAN_POINT ( 'NONE', ( 15.75161875086000052, 167.0113677096000231, 101.0233582269000010 ) ) ; +#18747 = EDGE_CURVE ( 'NONE', #23946, #37955, #14321, .T. ) ; +#18748 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5075, #17132, #8573, #23910, #14500, #26372, #17739 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 4 ), + ( -0.001237974900710671388, 0.000000000000000000, 0.0005872420382195917433 ), + .UNSPECIFIED. ) ; +#18749 = CARTESIAN_POINT ( 'NONE', ( -26.00624730612000235, 190.8511792187000253, 106.8090103475999939 ) ) ; +#18750 = ORIENTED_EDGE ( 'NONE', *, *, #34642, .F. ) ; +#18751 = EDGE_CURVE ( 'NONE', #22101, #17938, #21353, .T. ) ; +#18752 = EDGE_CURVE ( 'NONE', #39941, #32129, #24832, .T. ) ; +#18753 = AXIS2_PLACEMENT_3D ( 'NONE', #8850, #19580, #21322 ) ; +#18754 = EDGE_CURVE ( 'NONE', #16835, #7892, #27699, .T. ) ; +#18755 = CARTESIAN_POINT ( 'NONE', ( -19.70043221429562053, 148.9676548935424307, 183.8355817469811768 ) ) ; +#18756 = CARTESIAN_POINT ( 'NONE', ( -39.35442116922705935, 128.7733328792070893, 92.48526942430152076 ) ) ; +#18757 = VERTEX_POINT ( 'NONE', #33593 ) ; +#18758 = CARTESIAN_POINT ( 'NONE', ( 28.44085705255995222, 124.7864337255197995, 91.35282390664609409 ) ) ; +#18759 = CARTESIAN_POINT ( 'NONE', ( 23.36366720388904383, 183.4529741750082508, 105.0711814503917765 ) ) ; +#18760 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567900 ) ) ; +#18761 = CARTESIAN_POINT ( 'NONE', ( 36.19055538703000252, 192.0349938880000025, 106.4032480048999929 ) ) ; +#18762 = ORIENTED_EDGE ( 'NONE', *, *, #24003, .F. ) ; +#18763 = CARTESIAN_POINT ( 'NONE', ( 36.32855195652999925, 192.0751620672000115, 106.2604880945000048 ) ) ; +#18764 = VERTEX_POINT ( 'NONE', #5387 ) ; +#18765 = ORIENTED_EDGE ( 'NONE', *, *, #11955, .F. ) ; +#18766 = CARTESIAN_POINT ( 'NONE', ( -5.199337174292492314, 135.0593233550645493, 90.83696323977939358 ) ) ; +#18767 = CARTESIAN_POINT ( 'NONE', ( 37.96513776071897439, 190.5638673691689178, 106.5329861992229752 ) ) ; +#18768 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319359794851 ) ) ; +#18769 = FACE_OUTER_BOUND ( 'NONE', #18630, .T. ) ; +#18770 = ORIENTED_EDGE ( 'NONE', *, *, #31281, .F. ) ; +#18771 = EDGE_CURVE ( 'NONE', #20395, #31506, #2332, .T. ) ; +#18772 = DIRECTION ( 'NONE', ( 0.0004161288024119937133, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#18773 = CARTESIAN_POINT ( 'NONE', ( -50.65318414753016185, 137.7514108297640121, 291.5891371891943891 ) ) ; +#18774 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.271205131337280331E-14, 1.000000000000000000 ) ) ; +#18775 = ORIENTED_EDGE ( 'NONE', *, *, #1642, .T. ) ; +#18776 = CARTESIAN_POINT ( 'NONE', ( -3.535970564837537466, 118.9425530769304515, 90.19402121340444012 ) ) ; +#18777 = VECTOR ( 'NONE', #14143, 1000.000000000000000 ) ; +#18778 = CARTESIAN_POINT ( 'NONE', ( 32.75367228194463110, 191.5260139691676500, 103.8504056717556523 ) ) ; +#18779 = CARTESIAN_POINT ( 'NONE', ( -32.61688159666169184, 141.9329143176964863, 280.9718830317659695 ) ) ; +#18780 = CARTESIAN_POINT ( 'NONE', ( 37.81020286017945153, 118.4154792045343214, 90.24494842412454432 ) ) ; +#18781 = AXIS2_PLACEMENT_3D ( 'NONE', #16457, #32223, #22823 ) ; +#18782 = CARTESIAN_POINT ( 'NONE', ( -14.42521491161324043, 130.0078947141052765, 89.84737174885860611 ) ) ; +#18783 = ORIENTED_EDGE ( 'NONE', *, *, #33490, .F. ) ; +#18784 = DIRECTION ( 'NONE', ( -0.7933535594326887042, 0.5932204071694016090, 0.1366736194488628042 ) ) ; +#18785 = CARTESIAN_POINT ( 'NONE', ( 2.076830482329000027, 189.1135835803999896, 103.3113577132999978 ) ) ; +#18786 = DIRECTION ( 'NONE', ( 0.9999998176071716038, -2.143130385943402919E-11, -0.0006039748533745596714 ) ) ; +#18787 = EDGE_CURVE ( 'NONE', #1318, #2629, #15747, .T. ) ; +#18788 = ORIENTED_EDGE ( 'NONE', *, *, #2816, .F. ) ; +#18789 = ORIENTED_EDGE ( 'NONE', *, *, #39391, .F. ) ; +#18790 = CARTESIAN_POINT ( 'NONE', ( 77.76885812527426367, 193.5821525182410880, 188.5104908262173637 ) ) ; +#18791 = ORIENTED_EDGE ( 'NONE', *, *, #6638, .T. ) ; +#18792 = CARTESIAN_POINT ( 'NONE', ( -40.62325456460077078, 220.4002261231981947, 73.24970620723485126 ) ) ; +#18793 = EDGE_CURVE ( 'NONE', #18505, #17427, #18046, .T. ) ; +#18794 = CARTESIAN_POINT ( 'NONE', ( -20.35321988482620270, 209.7094481592175157, 73.40406779581955732 ) ) ; +#18796 = ADVANCED_FACE ( 'NONE', ( #15209 ), #36877, .F. ) ; +#18795 = DIRECTION ( 'NONE', ( 0.6087613508342253343, 0.7731002149716631466, 0.1781170270952703305 ) ) ; +#18797 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#18798 = EDGE_CURVE ( 'NONE', #13713, #16030, #20883, .T. ) ; +#18799 = CARTESIAN_POINT ( 'NONE', ( -15.94527486429822538, 152.8203387458500231, 181.6302711725483050 ) ) ; +#18800 = EDGE_CURVE ( 'NONE', #20316, #29017, #8678, .T. ) ; +#18801 = CARTESIAN_POINT ( 'NONE', ( 28.46460725226640065, 186.8972851080696387, 105.8632825901553218 ) ) ; +#18802 = EDGE_LOOP ( 'NONE', ( #14016, #10515, #20929, #25094 ) ) ; +#18803 = CARTESIAN_POINT ( 'NONE', ( -12.63757342683317653, 134.6434190354682983, 93.48128548710673158 ) ) ; +#18804 = CARTESIAN_POINT ( 'NONE', ( 32.37049208056998140, 174.4092940747139551, 99.89893022217735563 ) ) ; +#18805 = ORIENTED_EDGE ( 'NONE', *, *, #2686, .F. ) ; +#18806 = CARTESIAN_POINT ( 'NONE', ( -5.674480817841737412, 181.6879534348617824, 101.6022789869470131 ) ) ; +#18807 = AXIS2_PLACEMENT_3D ( 'NONE', #4010, #946, #25923 ) ; +#18808 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36831, #21304, #5542, #11280, #8003, #23548 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 4 ), + ( 0.000000000000000000, 0.3333331262867959000, 0.6666662542695979132, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18809 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749386919, 179.6299767372458689, 101.6260513916243866 ) ) ; +#18810 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#18811 = VECTOR ( 'NONE', #37099, 1000.000000000000114 ) ; +#18812 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; +#18813 = VERTEX_POINT ( 'NONE', #30547 ) ; +#18814 = VERTEX_POINT ( 'NONE', #25633 ) ; +#18815 = CARTESIAN_POINT ( 'NONE', ( -5.668109640120363224, 181.0132088949428919, 104.5254489105664817 ) ) ; +#18816 = DIRECTION ( 'NONE', ( -0.0005884949961245158337, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#18817 = CARTESIAN_POINT ( 'NONE', ( 37.18881752615094882, 185.3408534924642765, 105.4986827685707453 ) ) ; +#18818 = ORIENTED_EDGE ( 'NONE', *, *, #28702, .F. ) ; +#18819 = LINE ( 'NONE', #31324, #12005 ) ; +#18820 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058949670, 130.4211554272716000, 90.27959376792703949 ) ) ; +#18821 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16037, #28723, #28529, #38320 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18822 = CARTESIAN_POINT ( 'NONE', ( 23.68358947171641304, 134.6471046790361754, 93.46116000412756364 ) ) ; +#18823 = CARTESIAN_POINT ( 'NONE', ( -25.49120152668656303, 192.3458706269117897, 104.4614799839995953 ) ) ; +#18824 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971580390 ) ) ; +#18825 = FACE_OUTER_BOUND ( 'NONE', #36749, .T. ) ; +#18826 = ORIENTED_EDGE ( 'NONE', *, *, #14019, .F. ) ; +#18827 = FACE_OUTER_BOUND ( 'NONE', #34562, .T. ) ; +#18828 = ORIENTED_EDGE ( 'NONE', *, *, #34773, .T. ) ; +#18829 = CARTESIAN_POINT ( 'NONE', ( 14.78617723117088190, 128.6760556706539091, 91.91695949461106352 ) ) ; +#18830 = LINE ( 'NONE', #15582, #28834 ) ; +#18831 = EDGE_LOOP ( 'NONE', ( #32005, #6194, #4505, #11616 ) ) ; +#18832 = AXIS2_PLACEMENT_3D ( 'NONE', #15971, #21537, #3101 ) ; +#18833 = DIRECTION ( 'NONE', ( 0.0005884949961251572477, -0.2249510543439052768, 0.9743698870671265722 ) ) ; +#18834 = CARTESIAN_POINT ( 'NONE', ( 1.116395081135951539, 188.6745468192101498, 103.2112006113849247 ) ) ; +#18835 = EDGE_CURVE ( 'NONE', #5720, #31583, #9798, .T. ) ; +#18836 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971519606 ) ) ; +#18837 = EDGE_CURVE ( 'NONE', #26136, #28651, #5181, .T. ) ; +#18838 = CONICAL_SURFACE ( 'NONE', #30612, 2.500000000143204115, 0.7853981634269987522 ) ; +#18839 = CONICAL_SURFACE ( 'NONE', #40392, 2.749999999702389175, 0.7853981633701920817 ) ; +#18840 = EDGE_CURVE ( 'NONE', #30394, #36508, #11077, .T. ) ; +#18841 = VERTEX_POINT ( 'NONE', #25028 ) ; +#18842 = DIRECTION ( 'NONE', ( 0.6088835995545408553, 0.7728434649458199024, 0.1788120266761852317 ) ) ; +#18843 = DIRECTION ( 'NONE', ( 4.905797990098339101E-13, 0.9743700557921592953, 0.2249510932971531540 ) ) ; +#18844 = ORIENTED_EDGE ( 'NONE', *, *, #26548, .T. ) ; +#18845 = AXIS2_PLACEMENT_3D ( 'NONE', #32108, #38817, #10840 ) ; +#18846 = EDGE_CURVE ( 'NONE', #38021, #24364, #10925, .T. ) ; +#18847 = DIRECTION ( 'NONE', ( -0.7933530821293338642, -0.5932640870757631690, -0.1364866662427065280 ) ) ; +#18848 = CARTESIAN_POINT ( 'NONE', ( 36.48627557462513948, 191.3199122529084093, 103.8005689337988144 ) ) ; +#18849 = CARTESIAN_POINT ( 'NONE', ( 16.55529869184574210, 151.5392854340460360, 184.4105441063242097 ) ) ; +#18850 = EDGE_CURVE ( 'NONE', #13020, #7718, #11415, .T. ) ; +#18851 = VERTEX_POINT ( 'NONE', #19463 ) ; +#18852 = CARTESIAN_POINT ( 'NONE', ( -19.99839448797337482, 118.1131156702000169, 87.27644273471670999 ) ) ; +#18853 = FACE_OUTER_BOUND ( 'NONE', #10462, .T. ) ; +#18854 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2249510911124609769, 0.9743700461176366678 ) ) ; +#18855 = EDGE_CURVE ( 'NONE', #16187, #27723, #18707, .T. ) ; +#18856 = VERTEX_POINT ( 'NONE', #23299 ) ; +#18857 = FACE_OUTER_BOUND ( 'NONE', #34810, .T. ) ; +#18858 = DIRECTION ( 'NONE', ( 0.0005884949961231208991, -0.2249510543439063315, 0.9743698870671262391 ) ) ; +#18860 = CARTESIAN_POINT ( 'NONE', ( -15.94446068766880487, 121.2107412334159591, 177.4020268254936923 ) ) ; +#18859 = CARTESIAN_POINT ( 'NONE', ( -28.52494644200928064, 186.7521494213145559, 105.8641958179564568 ) ) ; +#18861 = ORIENTED_EDGE ( 'NONE', *, *, #35124, .F. ) ; +#18862 = EDGE_CURVE ( 'NONE', #23375, #15218, #66, .T. ) ; +#18863 = CIRCLE ( 'NONE', #16247, 2.000000000000011546 ) ; +#18864 = FACE_OUTER_BOUND ( 'NONE', #29950, .T. ) ; +#18865 = ORIENTED_EDGE ( 'NONE', *, *, #19370, .F. ) ; +#18866 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 132.6352630048999970, 91.80276880046000088 ) ) ; +#18867 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16593, #19858, #16988, #26639 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18868 = CIRCLE ( 'NONE', #30669, 4.999999999999990230 ) ; +#18869 = CARTESIAN_POINT ( 'NONE', ( -32.37225756577250024, 137.6262283585609794, 94.52490471072836442 ) ) ; +#18870 = CONICAL_SURFACE ( 'NONE', #23473, 2.500001241545478869, 0.7853981633776581095 ) ; +#18871 = DIRECTION ( 'NONE', ( -0.6075493383219849886, 0.7739051213223927528, 0.1787586772592889839 ) ) ; +#18872 = ORIENTED_EDGE ( 'NONE', *, *, #2214, .T. ) ; +#18873 = CONICAL_SURFACE ( 'NONE', #35846, 2.503080759488892415, 0.7853981633955684494 ) ; +#18874 = EDGE_LOOP ( 'NONE', ( #37646, #13329, #21763, #23022 ) ) ; +#18875 = DIRECTION ( 'NONE', ( -0.0005884949961248158324, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#18876 = CARTESIAN_POINT ( 'NONE', ( -19.73804990392530812, 124.3515837127999788, 178.1521725410697741 ) ) ; +#18877 = CARTESIAN_POINT ( 'NONE', ( 2.461057949780893317, 209.5714396328634450, 73.55701857314350889 ) ) ; +#18878 = VERTEX_POINT ( 'NONE', #15792 ) ; +#18879 = EDGE_LOOP ( 'NONE', ( #35856, #18910, #16609, #16802 ) ) ; +#18880 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#18881 = DIRECTION ( 'NONE', ( 1.156482317317869950E-15, 0.9743700557921587402, 0.2249510932971554578 ) ) ; +#18882 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#18883 = CARTESIAN_POINT ( 'NONE', ( -28.53213015704000100, 125.2791341444000039, 88.59304627238000762 ) ) ; +#18884 = ORIENTED_EDGE ( 'NONE', *, *, #16133, .T. ) ; +#18885 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #29698, #32553, #16987, #1466, #13952, #26431, #10896 ), + ( #23362, #32750, #35794, #7804, #4737, #1680, #39079 ), + ( #11089, #23551, #6293, #40438, #15312, #12439, #34103 ), + ( #6691, #34888, #27804, #3421, #31458, #37985, #31868 ), + ( #22056, #22264, #3028, #18961, #12248, #6896, #9986 ), + ( #31057, #19159, #13052, #24938, #15514, #31661, #34299 ), + ( #18749, #40236, #15896, #24738, #16107, #12637, #37191 ), + ( #28392, #28003, #25134, #366, #3623, #12853, #28200 ), + ( #22464, #9183, #25331, #37776, #37386, #6101, #18552 ), + ( #9384, #31249, #28591, #21855, #3226, #15700, #168 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 3, 4 ), + ( 4, 3, 4 ), + ( -2.263537866221000035E-13, 0.2499980354206000066, 0.4999962054489999752, 0.7499943754775000304, 0.9999965259027999709, 1.009996491161830212 ), + ( 0.1756339864888999958, 0.8243141701313000391, 0.8308009719677240668 ), + .UNSPECIFIED. ) ; +#18886 = DIRECTION ( 'NONE', ( 6.071532165918830352E-15, -0.9743700557921586292, -0.2249510932971559296 ) ) ; +#18887 = FACE_OUTER_BOUND ( 'NONE', #19704, .T. ) ; +#18888 = ORIENTED_EDGE ( 'NONE', *, *, #18105, .T. ) ; +#18889 = EDGE_CURVE ( 'NONE', #32946, #37217, #35208, .T. ) ; +#18890 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26740, #29403, #5243, #1371 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18891 = ADVANCED_FACE ( 'NONE', ( #10081 ), #34887, .F. ) ; +#18892 = EDGE_CURVE ( 'NONE', #18856, #7935, #31332, .T. ) ; +#18893 = FACE_OUTER_BOUND ( 'NONE', #29317, .T. ) ; +#18894 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391919761 ) ) ; +#18895 = AXIS2_PLACEMENT_3D ( 'NONE', #27451, #1660, #14340 ) ; +#18896 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971566513 ) ) ; +#18897 = DIRECTION ( 'NONE', ( 0.0002331579778304189888, 0.000000000000000000, -0.9999999728186783621 ) ) ; +#18898 = EDGE_CURVE ( 'NONE', #13580, #29223, #33348, .T. ) ; +#18899 = AXIS2_PLACEMENT_3D ( 'NONE', #32590, #10534, #23000 ) ; +#18900 = ORIENTED_EDGE ( 'NONE', *, *, #26914, .F. ) ; +#18901 = FACE_OUTER_BOUND ( 'NONE', #14114, .T. ) ; +#18902 = AXIS2_PLACEMENT_3D ( 'NONE', #36046, #4770, #20102 ) ; +#18903 = ORIENTED_EDGE ( 'NONE', *, *, #21653, .T. ) ; +#18904 = CARTESIAN_POINT ( 'NONE', ( -20.89285663966641238, 176.3787109218369551, 100.3857757381706222 ) ) ; +#18905 = CARTESIAN_POINT ( 'NONE', ( 36.30826696690632360, 191.7212304793147837, 104.1902916582040888 ) ) ; +#18906 = VECTOR ( 'NONE', #28635, 1000.000000000000227 ) ; +#18907 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#18908 = EDGE_CURVE ( 'NONE', #2995, #3644, #32701, .T. ) ; +#18909 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #13828, #1764 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18910 = ORIENTED_EDGE ( 'NONE', *, *, #25404, .T. ) ; +#18911 = CARTESIAN_POINT ( 'NONE', ( -5.631665583173067091, 110.1833198944677008, 152.0219651185256566 ) ) ; +#18912 = VERTEX_POINT ( 'NONE', #32893 ) ; +#18913 = CARTESIAN_POINT ( 'NONE', ( -25.89361811542643110, 209.7107217741274781, 73.19061257701807222 ) ) ; +#18914 = EDGE_CURVE ( 'NONE', #3576, #18912, #3081, .T. ) ; +#18915 = CARTESIAN_POINT ( 'NONE', ( -38.36762371684000072, 118.5381708343000042, 89.85085864944001344 ) ) ; +#18916 = EDGE_CURVE ( 'NONE', #16019, #11837, #39215, .T. ) ; +#18917 = CARTESIAN_POINT ( 'NONE', ( 15.50029466670349620, 151.8594625334012278, 95.21623178078017702 ) ) ; +#18918 = ORIENTED_EDGE ( 'NONE', *, *, #12774, .T. ) ; +#18919 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 130.2884061588697477, 89.74324129540521255 ) ) ; +#18920 = LINE ( 'NONE', #13410, #7536 ) ; +#18921 = CARTESIAN_POINT ( 'NONE', ( -29.20104124293470349, 162.9607637445586192, 100.3719287999282130 ) ) ; +#18922 = CARTESIAN_POINT ( 'NONE', ( -20.23762457072344745, 159.6993819354047162, 96.53465277977143444 ) ) ; +#18923 = CARTESIAN_POINT ( 'NONE', ( 17.27144951970729991, 122.5453306081213043, 172.0736587966182469 ) ) ; +#18924 = CARTESIAN_POINT ( 'NONE', ( -35.44629553183553838, 112.4664344014998818, 90.28919351346762312 ) ) ; +#18925 = ORIENTED_EDGE ( 'NONE', *, *, #36923, .F. ) ; +#18926 = ORIENTED_EDGE ( 'NONE', *, *, #20337, .T. ) ; +#18928 = AXIS2_PLACEMENT_3D ( 'NONE', #25362, #12468, #31485 ) ; +#18927 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319380584428 ) ) ; +#18929 = AXIS2_PLACEMENT_3D ( 'NONE', #20708, #14586, #14379 ) ; +#18930 = CARTESIAN_POINT ( 'NONE', ( 12.63986553157402781, 174.6815491745478255, 103.0556938779417067 ) ) ; +#18931 = AXIS2_PLACEMENT_3D ( 'NONE', #39194, #11391, #23878 ) ; +#18932 = ORIENTED_EDGE ( 'NONE', *, *, #12992, .F. ) ; +#18933 = CARTESIAN_POINT ( 'NONE', ( -14.78422084203157461, 175.4439834284964945, 102.7320481277236013 ) ) ; +#18934 = AXIS2_PLACEMENT_3D ( 'NONE', #24631, #2134, #2331 ) ; +#18935 = CARTESIAN_POINT ( 'NONE', ( -35.81350251770196280, 107.3141770694631845, 174.6977881228511080 ) ) ; +#18936 = ORIENTED_EDGE ( 'NONE', *, *, #27494, .F. ) ; +#18937 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; +#18938 = PLANE ( 'NONE', #23226 ) ; +#18939 = ORIENTED_EDGE ( 'NONE', *, *, #28500, .T. ) ; +#18940 = CARTESIAN_POINT ( 'NONE', ( 28.36482613956999899, 125.3392128497000044, 88.74362595223000483 ) ) ; +#18941 = DIRECTION ( 'NONE', ( 0.0005884941600622459624, -0.2249510532593050061, 0.9743698873180312026 ) ) ; +#18942 = DIRECTION ( 'NONE', ( 0.7933532970003751572, 0.5930762008556708098, 0.1372995488602871961 ) ) ; +#18943 = ADVANCED_FACE ( 'NONE', ( #17338 ), #8163, .T. ) ; +#18944 = EDGE_CURVE ( 'NONE', #1845, #32051, #9123, .T. ) ; +#18945 = CARTESIAN_POINT ( 'NONE', ( -19.99998949574776930, 122.8402457258809619, 88.02489516763034771 ) ) ; +#18946 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12670, #21289, #18778, #21890 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#18947 = CARTESIAN_POINT ( 'NONE', ( -18.98889543208580122, 125.5955304196095312, 175.3358149539526778 ) ) ; +#18948 = ORIENTED_EDGE ( 'NONE', *, *, #20055, .F. ) ; +#18949 = CARTESIAN_POINT ( 'NONE', ( 16.55826291764536151, 122.5115568680679559, 174.6303284955642994 ) ) ; +#18950 = CARTESIAN_POINT ( 'NONE', ( -37.72967283144954109, 118.8809476575462583, 87.29057205257689134 ) ) ; +#18951 = DIRECTION ( 'NONE', ( 0.7933535320750499942, -0.5931614265261869745, -0.1369295264925045885 ) ) ; +#18952 = CARTESIAN_POINT ( 'NONE', ( 12.63611452238018984, 129.9736765176137965, 92.21783751031847487 ) ) ; +#18953 = ORIENTED_EDGE ( 'NONE', *, *, #18153, .F. ) ; +#18954 = CARTESIAN_POINT ( 'NONE', ( 35.48442776063147619, 88.13433118093483642, 282.5337480928039895 ) ) ; +#18955 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057990016292, 0.1373964268091235619 ) ) ; +#18956 = FACE_OUTER_BOUND ( 'NONE', #25101, .T. ) ; +#18957 = CARTESIAN_POINT ( 'NONE', ( 19.98483764167631094, 211.0849390754169974, 73.04592155476974824 ) ) ; +#18958 = VECTOR ( 'NONE', #37325, 1000.000000000000114 ) ; +#18959 = AXIS2_PLACEMENT_3D ( 'NONE', #12825, #13027, #31638 ) ; +#18960 = CARTESIAN_POINT ( 'NONE', ( 15.99999293039724257, 151.9655111556795362, 94.72726368743165892 ) ) ; +#18961 = CARTESIAN_POINT ( 'NONE', ( -25.72063744915000427, 189.5948766207999938, 106.0056453769999933 ) ) ; +#18962 = ORIENTED_EDGE ( 'NONE', *, *, #18105, .F. ) ; +#18963 = VECTOR ( 'NONE', #26288, 999.9999999999998863 ) ; +#18964 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#18965 = VECTOR ( 'NONE', #7242, 1000.000000000000000 ) ; +#18966 = DIRECTION ( 'NONE', ( 5.551115123177313463E-15, -0.9743700557921587402, -0.2249510932971553467 ) ) ; +#18967 = EDGE_CURVE ( 'NONE', #10469, #29957, #33914, .T. ) ; +#18968 = FACE_OUTER_BOUND ( 'NONE', #38710, .T. ) ; +#18969 = CARTESIAN_POINT ( 'NONE', ( 3.047144816654127730, 209.7096538831000032, 78.05666459524968559 ) ) ; +#18970 = ORIENTED_EDGE ( 'NONE', *, *, #575, .T. ) ; +#18971 = CARTESIAN_POINT ( 'NONE', ( -36.45739912719590592, 115.9577502964445301, 87.74842822314147384 ) ) ; +#18972 = CARTESIAN_POINT ( 'NONE', ( 17.33070710942128301, 121.2635828526781268, 177.4224744102505440 ) ) ; +#18973 = PLANE ( 'NONE', #31977 ) ; +#18974 = CARTESIAN_POINT ( 'NONE', ( 37.68865279781829969, 190.9621098111250319, 106.2899631106229918 ) ) ; +#18976 = ORIENTED_EDGE ( 'NONE', *, *, #20375, .F. ) ; +#18975 = CARTESIAN_POINT ( 'NONE', ( 36.57849226294000289, 191.3118430090999880, 106.4570103174000195 ) ) ; +#18977 = EDGE_LOOP ( 'NONE', ( #26433, #29722, #30082, #31674, #29351, #6884, #17585, #31726, #4394, #9700, #5826 ) ) ; +#18978 = CARTESIAN_POINT ( 'NONE', ( -4.520475493760558017, 135.3895221152266117, 90.91278562870999735 ) ) ; +#18979 = CARTESIAN_POINT ( 'NONE', ( -17.99823451464924418, 132.2930705108461495, 93.28496706202059841 ) ) ; +#18980 = ADVANCED_FACE ( 'NONE', ( #1825 ), #5081, .T. ) ; +#18981 = DIRECTION ( 'NONE', ( -0.0005884949961219008464, 0.2249510543439048049, -0.9743698870671267942 ) ) ; +#18982 = CARTESIAN_POINT ( 'NONE', ( -29.78153364950144422, 126.4887807563219440, 91.43890500524419451 ) ) ; +#18983 = ORIENTED_EDGE ( 'NONE', *, *, #9255, .T. ) ; +#18984 = AXIS2_PLACEMENT_3D ( 'NONE', #14042, #8311, #20355 ) ; +#18985 = AXIS2_PLACEMENT_3D ( 'NONE', #21719, #18810, #22321 ) ; +#18986 = CARTESIAN_POINT ( 'NONE', ( -20.00005051927294986, 192.3656549280321997, 103.9335389961495366 ) ) ; +#18987 = CYLINDRICAL_SURFACE ( 'NONE', #4062, 9.000000000000003553 ) ; +#18988 = ORIENTED_EDGE ( 'NONE', *, *, #28438, .F. ) ; +#18989 = DIRECTION ( 'NONE', ( 0.6773442687123379935, 0.7356661890032381024, 0.000000000000000000 ) ) ; +#18990 = VECTOR ( 'NONE', #30877, 1000.000000000000114 ) ; +#18991 = VECTOR ( 'NONE', #36138, 1000.000000000000227 ) ; +#18992 = DIRECTION ( 'NONE', ( 0.0005884949961252012663, -0.2249510543439044163, 0.9743698870671267942 ) ) ; +#18993 = EDGE_CURVE ( 'NONE', #36593, #39888, #26781, .T. ) ; +#18994 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20083, #23573, #13972, #8243 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.007703849374118843137, 0.008859097743410275852 ), + .UNSPECIFIED. ) ; +#18995 = EDGE_CURVE ( 'NONE', #26666, #2318, #2041, .T. ) ; +#18996 = FACE_OUTER_BOUND ( 'NONE', #25486, .T. ) ; +#18997 = CYLINDRICAL_SURFACE ( 'NONE', #20239, 2.000000000000011546 ) ; +#18998 = PLANE ( 'NONE', #9939 ) ; +#18999 = ORIENTED_EDGE ( 'NONE', *, *, #33494, .T. ) ; +#19000 = DIRECTION ( 'NONE', ( -0.0005884949961299158110, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#19001 = CARTESIAN_POINT ( 'NONE', ( 1.382070334880999951, 189.0309197301999973, 103.5690980493999973 ) ) ; +#19002 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971529042 ) ) ; +#19003 = EDGE_CURVE ( 'NONE', #2592, #28925, #25555, .T. ) ; +#19004 = ORIENTED_EDGE ( 'NONE', *, *, #16184, .F. ) ; +#19005 = ORIENTED_EDGE ( 'NONE', *, *, #13776, .T. ) ; +#19006 = DIRECTION ( 'NONE', ( -0.7763856147932157725, 0.5343480027610243432, 0.3342118924985533757 ) ) ; +#19007 = VERTEX_POINT ( 'NONE', #5285 ) ; +#19008 = DIRECTION ( 'NONE', ( -0.7066903926851649809, 0.000000000000000000, 0.7075229246367126246 ) ) ; +#19009 = CARTESIAN_POINT ( 'NONE', ( 35.80367347626000196, 109.6131156806000035, 87.49615981601000669 ) ) ; +#19010 = DIRECTION ( 'NONE', ( 3.469446952028437646E-15, 0.9743700557921590732, 0.2249510932971540700 ) ) ; +#19011 = CARTESIAN_POINT ( 'NONE', ( -12.63562264099845223, 176.9317098760967895, 103.3366312265686702 ) ) ; +#19012 = AXIS2_PLACEMENT_3D ( 'NONE', #11529, #24218, #30746 ) ; +#19013 = PLANE ( 'NONE', #39611 ) ; +#19014 = VECTOR ( 'NONE', #27800, 1000.000000000000227 ) ; +#19015 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#19016 = CARTESIAN_POINT ( 'NONE', ( -1.203883532793524225, 189.1531580572220719, 105.7825619712950385 ) ) ; +#19017 = VERTEX_POINT ( 'NONE', #37604 ) ; +#19018 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 1.676366911644155200E-18, 0.0006039748319336982153 ) ) ; +#19019 = CARTESIAN_POINT ( 'NONE', ( -39.03036842907830106, 121.1728496032269078, 123.5553118490896907 ) ) ; +#19020 = FACE_OUTER_BOUND ( 'NONE', #36445, .T. ) ; +#19021 = CARTESIAN_POINT ( 'NONE', ( -20.51880467302672173, 211.0905570380611493, 75.57084890002228406 ) ) ; +#19022 = ORIENTED_EDGE ( 'NONE', *, *, #2769, .T. ) ; +#19023 = ORIENTED_EDGE ( 'NONE', *, *, #34752, .F. ) ; +#19024 = CARTESIAN_POINT ( 'NONE', ( 0.5456353394454329653, 210.9999999999944578, 75.55817498829796364 ) ) ; +#19025 = EDGE_CURVE ( 'NONE', #22970, #29453, #4404, .T. ) ; +#19026 = CARTESIAN_POINT ( 'NONE', ( 21.87486947896477929, 115.3317988067956321, 87.25457241900384986 ) ) ; +#19027 = DIRECTION ( 'NONE', ( -0.9914448496661262267, 0.1271494159038595584, 0.02949806952699904686 ) ) ; +#19028 = VERTEX_POINT ( 'NONE', #1143 ) ; +#19029 = FACE_OUTER_BOUND ( 'NONE', #21121, .T. ) ; +#19030 = EDGE_CURVE ( 'NONE', #29413, #32027, #4002, .T. ) ; +#19031 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#19032 = DIRECTION ( 'NONE', ( -0.0006039748319386439119, 0.000000000000000000, -0.9999998176071845934 ) ) ; +#19033 = DIRECTION ( 'NONE', ( 0.0005884949961220700904, -0.2249510543439053878, 0.9743698870671265722 ) ) ; +#19034 = CARTESIAN_POINT ( 'NONE', ( 3.535970564806534266, 118.9434892789997917, 90.18996607748785266 ) ) ; +#19035 = ORIENTED_EDGE ( 'NONE', *, *, #32488, .F. ) ; +#19036 = DIRECTION ( 'NONE', ( -8.326672684584947048E-14, 0.9743700557921587402, 0.2249510932971554023 ) ) ; +#19037 = ORIENTED_EDGE ( 'NONE', *, *, #23748, .F. ) ; +#19038 = ORIENTED_EDGE ( 'NONE', *, *, #13716, .T. ) ; +#19039 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#19040 = AXIS2_PLACEMENT_3D ( 'NONE', #10066, #6979, #19446 ) ; +#19041 = EDGE_CURVE ( 'NONE', #14192, #6308, #26302, .T. ) ; +#19042 = ADVANCED_FACE ( 'NONE', ( #23033 ), #38955, .F. ) ; +#19043 = VECTOR ( 'NONE', #10982, 1000.000000000000114 ) ; +#19044 = ORIENTED_EDGE ( 'NONE', *, *, #40135, .F. ) ; +#19045 = CARTESIAN_POINT ( 'NONE', ( -2.940658112151719905, 191.1132255574039789, 103.7732427199960057 ) ) ; +#19046 = EDGE_CURVE ( 'NONE', #5859, #30529, #23469, .T. ) ; +#19047 = AXIS2_PLACEMENT_3D ( 'NONE', #26380, #19616, #3876 ) ; +#19048 = CARTESIAN_POINT ( 'NONE', ( 2.917437660352353301, 190.2735791520341024, 103.5792785963609788 ) ) ; +#19049 = CARTESIAN_POINT ( 'NONE', ( 42.51962411156773669, 182.5729458539040593, 104.8564411487018049 ) ) ; +#19050 = EDGE_LOOP ( 'NONE', ( #13661, #10357, #30321, #37487 ) ) ; +#19051 = CARTESIAN_POINT ( 'NONE', ( -22.23902781740747869, 214.0141975910763961, 73.07193589793287458 ) ) ; +#19052 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#19053 = VERTEX_POINT ( 'NONE', #23428 ) ; +#19054 = CARTESIAN_POINT ( 'NONE', ( 2.896165866612135265, 191.4885083221446962, 104.0308307092542606 ) ) ; +#19055 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28961, #25507, #31635, #32431 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( -2.096239065088066676E-09, 0.9999999999999998890 ), + .UNSPECIFIED. ) ; +#19056 = DIRECTION ( 'NONE', ( 0.7856007465113961086, 0.6187337610642700270, 0.000000000000000000 ) ) ; +#19057 = CARTESIAN_POINT ( 'NONE', ( -26.62285416470999877, 123.4451883726000005, 90.85907200423000063 ) ) ; +#19058 = ORIENTED_EDGE ( 'NONE', *, *, #11824, .T. ) ; +#19059 = CARTESIAN_POINT ( 'NONE', ( -17.26183737405610330, 121.4975388230068916, 176.5517749385022057 ) ) ; +#19060 = CARTESIAN_POINT ( 'NONE', ( 26.00064436918396282, 118.5819532798333427, 90.25208110153040764 ) ) ; +#19061 = LINE ( 'NONE', #15603, #7118 ) ; +#19062 = EDGE_CURVE ( 'NONE', #36789, #16580, #38550, .T. ) ; +#19063 = ORIENTED_EDGE ( 'NONE', *, *, #6724, .F. ) ; +#19064 = LINE ( 'NONE', #22568, #26059 ) ; +#19065 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971561239 ) ) ; +#19066 = CIRCLE ( 'NONE', #36712, 6.000000000042818193 ) ; +#19067 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16509, #21017, #11615, #30424, #26553, #14478, #26963, #5256, #39395, #24088, #39000, #33468, #11400, #14276, #8135, #18126, #26749, #39202, #5462, #5676 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000270062, 0.1875000000000286160, 0.2187500000000286715, 0.2343750000000307532, 0.2500000000000328626, 0.4999999999999928946, 0.6249999999999711342, 0.6874999999999596989, 0.7187499999999539257, 0.7343749999999555911, 0.7499999999999572564, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19069 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433776002355 ) ) ; +#19068 = CARTESIAN_POINT ( 'NONE', ( -36.08528539247640765, 191.6236262332290323, 104.0629932494446024 ) ) ; +#19070 = ORIENTED_EDGE ( 'NONE', *, *, #18073, .F. ) ; +#19071 = VECTOR ( 'NONE', #12714, 1000.000000000000000 ) ; +#19072 = VECTOR ( 'NONE', #39188, 1000.000000000000114 ) ; +#19073 = ORIENTED_EDGE ( 'NONE', *, *, #29188, .T. ) ; +#19074 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; +#19075 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3201, #28181, #151, #12610, #25110, #35667, #8461, #20922, #13235, #19545 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000526246, 0.3750000000000134892, 0.4375000000000093814, 0.5000000000000052180, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19076 = ADVANCED_FACE ( 'NONE', ( #35870 ), #32322, .F. ) ; +#19077 = FACE_OUTER_BOUND ( 'NONE', #34623, .T. ) ; +#19078 = VERTEX_POINT ( 'NONE', #2253 ) ; +#19079 = EDGE_LOOP ( 'NONE', ( #2006, #3252, #38528, #26206 ) ) ; +#19080 = CARTESIAN_POINT ( 'NONE', ( 39.32399170537503608, 175.4331703188547920, 136.0698303701354348 ) ) ; +#19081 = CARTESIAN_POINT ( 'NONE', ( -13.47030235340321980, 153.5044711432410907, 96.98191525122514633 ) ) ; +#19082 = EDGE_CURVE ( 'NONE', #37526, #5222, #24169, .T. ) ; +#19083 = CARTESIAN_POINT ( 'NONE', ( -19.73768723704201378, 124.3505960279316014, 178.1528323905962452 ) ) ; +#19084 = CARTESIAN_POINT ( 'NONE', ( -2.814039137602999840, 190.9186751583000330, 106.6856912745000017 ) ) ; +#19085 = CARTESIAN_POINT ( 'NONE', ( 36.24311113342000112, 191.7667988338999976, 104.2009492968000046 ) ) ; +#19086 = ORIENTED_EDGE ( 'NONE', *, *, #37521, .T. ) ; +#19087 = ADVANCED_FACE ( 'NONE', ( #1841 ), #16936, .F. ) ; +#19088 = ORIENTED_EDGE ( 'NONE', *, *, #3245, .F. ) ; +#19089 = VERTEX_POINT ( 'NONE', #39040 ) ; +#19090 = CARTESIAN_POINT ( 'NONE', ( 3.062737380639022344, 196.5784460000043055, 103.8732377138169483 ) ) ; +#19091 = CARTESIAN_POINT ( 'NONE', ( 20.50147081420385931, 173.9561948828717561, 102.3672533376207952 ) ) ; +#19092 = LINE ( 'NONE', #6419, #37661 ) ; +#19093 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#19094 = EDGE_CURVE ( 'NONE', #31088, #40142, #24345, .T. ) ; +#19095 = ORIENTED_EDGE ( 'NONE', *, *, #20741, .F. ) ; +#19096 = CARTESIAN_POINT ( 'NONE', ( 20.00025828646017345, 174.5279639952516106, 99.93388581131628712 ) ) ; +#19097 = VERTEX_POINT ( 'NONE', #36794 ) ; +#19098 = CONICAL_SURFACE ( 'NONE', #26980, 10.00000000003960210, 0.7853981633972906273 ) ; +#19099 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18116, #30620, #12013, #30817 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19100 = AXIS2_PLACEMENT_3D ( 'NONE', #34283, #2435, #15688 ) ; +#19101 = FACE_OUTER_BOUND ( 'NONE', #34717, .T. ) ; +#19102 = CARTESIAN_POINT ( 'NONE', ( -5.664428473434217182, 187.6140210707962979, 105.9750649276934382 ) ) ; +#19103 = CIRCLE ( 'NONE', #4063, 2.250000000024274360 ) ; +#19104 = CARTESIAN_POINT ( 'NONE', ( -2.811333532546000047, 190.9942814073000079, 106.7041626420000000 ) ) ; +#19105 = CARTESIAN_POINT ( 'NONE', ( 42.94995788232328238, 77.14301703112133168, 281.7122703257673493 ) ) ; +#19106 = ORIENTED_EDGE ( 'NONE', *, *, #36650, .T. ) ; +#19107 = CARTESIAN_POINT ( 'NONE', ( -42.86442090264492322, 113.2940780347909708, 125.2207354701815660 ) ) ; +#19108 = VERTEX_POINT ( 'NONE', #11657 ) ; +#19109 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#19110 = CARTESIAN_POINT ( 'NONE', ( 20.71769855053793208, 213.0587601636507316, 73.04599111161205371 ) ) ; +#19111 = CARTESIAN_POINT ( 'NONE', ( 30.05202367136483588, 184.7526529953215118, 104.8540442558833234 ) ) ; +#19112 = CARTESIAN_POINT ( 'NONE', ( -40.80749064254901981, 126.9113585741826995, 91.54312417625736487 ) ) ; +#19113 = ORIENTED_EDGE ( 'NONE', *, *, #6032, .F. ) ; +#19114 = FACE_OUTER_BOUND ( 'NONE', #30436, .T. ) ; +#19115 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 135.6522072397366401, 90.95982947643871341 ) ) ; +#19116 = ORIENTED_EDGE ( 'NONE', *, *, #14211, .F. ) ; +#19117 = DIRECTION ( 'NONE', ( 3.880623682586550903E-28, -0.9743043966640312359, -0.2252353050503803078 ) ) ; +#19118 = AXIS2_PLACEMENT_3D ( 'NONE', #31362, #2932, #25044 ) ; +#19119 = ORIENTED_EDGE ( 'NONE', *, *, #22208, .T. ) ; +#19120 = EDGE_CURVE ( 'NONE', #288, #2348, #20212, .T. ) ; +#19121 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098504, 179.0628333272192947, 104.0826189413440375 ) ) ; +#19122 = ADVANCED_FACE ( 'NONE', ( #5302 ), #5094, .F. ) ; +#19123 = CARTESIAN_POINT ( 'NONE', ( 25.49929013439215808, 120.2777482667009536, 87.91897806052588749 ) ) ; +#19124 = ADVANCED_FACE ( 'NONE', ( #17155 ), #21264, .F. ) ; +#19125 = CARTESIAN_POINT ( 'NONE', ( 23.36395032469019029, 177.6218452589418177, 100.7937265896866990 ) ) ; +#19126 = AXIS2_PLACEMENT_3D ( 'NONE', #32183, #19486, #38493 ) ; +#19127 = ADVANCED_FACE ( 'NONE', ( #33712 ), #8478, .F. ) ; +#19128 = ORIENTED_EDGE ( 'NONE', *, *, #18107, .T. ) ; +#19129 = CARTESIAN_POINT ( 'NONE', ( -20.16488847591704925, 173.8709817318066371, 102.7143564760062162 ) ) ; +#19130 = ORIENTED_EDGE ( 'NONE', *, *, #21291, .T. ) ; +#19131 = ORIENTED_EDGE ( 'NONE', *, *, #35864, .T. ) ; +#19132 = CARTESIAN_POINT ( 'NONE', ( 41.56443160834000139, 191.1885863319999999, 105.3066393139000070 ) ) ; +#19133 = EDGE_CURVE ( 'NONE', #25237, #20686, #29655, .T. ) ; +#19134 = ORIENTED_EDGE ( 'NONE', *, *, #28006, .F. ) ; +#19135 = CARTESIAN_POINT ( 'NONE', ( -0.02993291085645299193, 92.27946995574508549, 297.5585631083172302 ) ) ; +#19136 = ORIENTED_EDGE ( 'NONE', *, *, #17082, .F. ) ; +#19137 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265204471, 0.1368326740407822539 ) ) ; +#19138 = ADVANCED_FACE ( 'NONE', ( #27004 ), #36581, .F. ) ; +#19139 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#19140 = ORIENTED_EDGE ( 'NONE', *, *, #18306, .T. ) ; +#19141 = CARTESIAN_POINT ( 'NONE', ( 28.39451994135000135, 125.3580671559000024, 88.74806921993000230 ) ) ; +#19142 = DIRECTION ( 'NONE', ( -0.0005884949961221076038, 0.2249510543439052768, -0.9743698870671265722 ) ) ; +#19143 = CARTESIAN_POINT ( 'NONE', ( 39.74775410638153517, 160.4311919331727267, 202.5621339309882956 ) ) ; +#19144 = CARTESIAN_POINT ( 'NONE', ( 3.952010379223754644, 175.2630895677251601, 100.5417517819387854 ) ) ; +#19145 = CARTESIAN_POINT ( 'NONE', ( 5.376318610052984504, 134.9834408144583620, 90.81305694060634437 ) ) ; +#19146 = ORIENTED_EDGE ( 'NONE', *, *, #28430, .F. ) ; +#19147 = EDGE_CURVE ( 'NONE', #27880, #13220, #28021, .T. ) ; +#19148 = CARTESIAN_POINT ( 'NONE', ( 28.70581487919770680, 163.6075652324868486, 97.92051968927451355 ) ) ; +#19149 = CARTESIAN_POINT ( 'NONE', ( 0.8576005917758692254, 189.0218593756178791, 103.6912331318077634 ) ) ; +#19150 = VECTOR ( 'NONE', #22868, 1000.000000000000114 ) ; +#19151 = CARTESIAN_POINT ( 'NONE', ( -38.93814858684476121, 191.0388300950886560, 103.7812318162937686 ) ) ; +#19152 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19153 = AXIS2_PLACEMENT_3D ( 'NONE', #10106, #16416, #13569 ) ; +#19154 = CARTESIAN_POINT ( 'NONE', ( 21.86154689402108886, 164.5254832386265491, 152.7619684927175570 ) ) ; +#19155 = DIRECTION ( 'NONE', ( -0.6087613186456907188, -0.7730177010543248795, -0.1784749023741044327 ) ) ; +#19156 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 67.27946979429630403, 312.5857197240632104 ) ) ; +#19157 = CARTESIAN_POINT ( 'NONE', ( -20.49852807266789867, 190.9630690214611946, 106.3183227610936541 ) ) ; +#19158 = ORIENTED_EDGE ( 'NONE', *, *, #23611, .T. ) ; +#19159 = CARTESIAN_POINT ( 'NONE', ( -25.87250852686999991, 190.4556140285999959, 106.5465554369999950 ) ) ; +#19160 = ORIENTED_EDGE ( 'NONE', *, *, #10429, .T. ) ; +#19161 = FACE_OUTER_BOUND ( 'NONE', #32720, .T. ) ; +#19162 = EDGE_LOOP ( 'NONE', ( #27338, #20069, #17586, #10417 ) ) ; +#19163 = CARTESIAN_POINT ( 'NONE', ( 21.00012074390967243, 116.5765772913270411, 87.75487408089821884 ) ) ; +#19164 = DIRECTION ( 'NONE', ( -0.0006039748319385906776, -1.261220487827980362E-14, -0.9999998176071844824 ) ) ; +#19165 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927780006295, -0.0005734119022043027104 ) ) ; +#19166 = CARTESIAN_POINT ( 'NONE', ( 20.18512051031240873, 118.1105892767045873, 90.07230193432872056 ) ) ; +#19167 = EDGE_CURVE ( 'NONE', #10027, #7238, #1118, .T. ) ; +#19168 = EDGE_CURVE ( 'NONE', #31792, #8044, #33510, .T. ) ; +#19169 = CARTESIAN_POINT ( 'NONE', ( 13.50160360306296958, 188.0812229192828511, 103.2930363115666808 ) ) ; +#19170 = ORIENTED_EDGE ( 'NONE', *, *, #34134, .F. ) ; +#19171 = CARTESIAN_POINT ( 'NONE', ( -2.787442447965000181, 209.0946215584000072, 75.98264661685000476 ) ) ; +#19172 = DIRECTION ( 'NONE', ( 0.0005884949961229525225, -0.2249510543439062205, 0.9743698870671264611 ) ) ; +#19173 = AXIS2_PLACEMENT_3D ( 'NONE', #30222, #30023, #21031 ) ; +#19174 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19175 = VERTEX_POINT ( 'NONE', #40050 ) ; +#19176 = CARTESIAN_POINT ( 'NONE', ( -32.57215250014812113, 175.3511933304038735, 100.1556091465108267 ) ) ; +#19177 = ORIENTED_EDGE ( 'NONE', *, *, #34991, .F. ) ; +#19178 = CONICAL_SURFACE ( 'NONE', #17863, 2.503022608189757747, 0.7853981633789286487 ) ; +#19179 = CARTESIAN_POINT ( 'NONE', ( -5.958856854636191969, 162.8886998924887166, 100.3412538487635857 ) ) ; +#19180 = CARTESIAN_POINT ( 'NONE', ( -5.345766047747446237, 131.0199116916220703, 89.90447984510488766 ) ) ; +#19181 = DIRECTION ( 'NONE', ( 3.191891195878054554E-14, 0.9743700557921589622, 0.2249510932971539590 ) ) ; +#19182 = PLANE ( 'NONE', #20993 ) ; +#19183 = ORIENTED_EDGE ( 'NONE', *, *, #35532, .F. ) ; +#19184 = CARTESIAN_POINT ( 'NONE', ( 14.16801031327180738, 129.2779008960638976, 92.05627979598381216 ) ) ; +#19185 = DIRECTION ( 'NONE', ( 0.9999998176071385192, 7.614963149315084172E-11, -0.0006039749080918128607 ) ) ; +#19186 = CARTESIAN_POINT ( 'NONE', ( 23.36219596639585916, 184.0153518109154902, 102.6352567327138559 ) ) ; +#19187 = CARTESIAN_POINT ( 'NONE', ( -19.37461243180795378, 124.8797228958847541, 177.8425101811817797 ) ) ; +#19188 = CARTESIAN_POINT ( 'NONE', ( -59.17051632422617757, 248.4236826516141718, 201.1548740838363187 ) ) ; +#19189 = EDGE_LOOP ( 'NONE', ( #33972, #18828, #9527 ) ) ; +#19190 = VERTEX_POINT ( 'NONE', #25342 ) ; +#19191 = ADVANCED_FACE ( 'NONE', ( #6500 ), #16954, .T. ) ; +#19192 = CARTESIAN_POINT ( 'NONE', ( 85.17681536472505854, 108.1708911099030956, 24.92177785579363203 ) ) ; +#19193 = CARTESIAN_POINT ( 'NONE', ( 30.07027234679766892, 177.3926676393851949, 100.9336419489587655 ) ) ; +#19194 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098148, 134.9725883025580515, 93.90358196965131299 ) ) ; +#19195 = CARTESIAN_POINT ( 'NONE', ( -37.96467306556999688, 191.3263843095000141, 104.2384762941000105 ) ) ; +#19196 = EDGE_LOOP ( 'NONE', ( #3937, #2320, #31444, #34440 ) ) ; +#19197 = ORIENTED_EDGE ( 'NONE', *, *, #22172, .T. ) ; +#19198 = DIRECTION ( 'NONE', ( 0.7933533411653341805, 0.5931840316264885837, 0.1368326740407639630 ) ) ; +#19199 = ORIENTED_EDGE ( 'NONE', *, *, #30365, .T. ) ; +#19200 = CONICAL_SURFACE ( 'NONE', #35497, 3.003158621626311309, 0.7854054549419372533 ) ; +#19201 = LINE ( 'NONE', #31714, #10685 ) ; +#19202 = VECTOR ( 'NONE', #10070, 1000.000000000000114 ) ; +#19203 = CARTESIAN_POINT ( 'NONE', ( -30.05261220090111607, 184.7446961265794698, 104.8885090344142128 ) ) ; +#19204 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; +#19205 = CARTESIAN_POINT ( 'NONE', ( 24.25081341993703887, 213.2747061037831600, 75.54404290781627651 ) ) ; +#19206 = AXIS2_PLACEMENT_3D ( 'NONE', #3632, #6908, #13460 ) ; +#19207 = DIRECTION ( 'NONE', ( 0.0006039748319417797499, -6.167438909947000466E-15, 0.9999998176071845934 ) ) ; +#19208 = CARTESIAN_POINT ( 'NONE', ( -15.99849772754149591, 160.0724928513803036, 99.69724197557108880 ) ) ; +#19209 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19210 = CARTESIAN_POINT ( 'NONE', ( -2.253170442581999833, 209.5024975169000072, 73.69426871254999867 ) ) ; +#19211 = CARTESIAN_POINT ( 'NONE', ( 38.13861604779999936, 118.9104954337999942, 90.39786711313999490 ) ) ; +#19212 = ORIENTED_EDGE ( 'NONE', *, *, #9974, .F. ) ; +#19213 = CARTESIAN_POINT ( 'NONE', ( 19.98635445618997863, 211.0854288155255460, 76.04696776081749476 ) ) ; +#19214 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -4.990135403222676764E-16, -0.0006039748319386972547 ) ) ; +#19215 = CARTESIAN_POINT ( 'NONE', ( -14.78424365577531141, 182.9075039701052958, 104.4551379424934083 ) ) ; +#19216 = EDGE_CURVE ( 'NONE', #19007, #22181, #2155, .T. ) ; +#19217 = ADVANCED_FACE ( 'NONE', ( #25544 ), #7847, .T. ) ; +#19218 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24479, #27557, #3560, #28730 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 6.426987119048715613E-11, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19219 = LINE ( 'NONE', #9850, #33657 ) ; +#19220 = VERTEX_POINT ( 'NONE', #13064 ) ; +#19221 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #6833, #7235, #31397, #4157 ), + ( #32003, #16634, #37718, #6629 ), + ( #28330, #12791, #7036, #38512 ), + ( #9726, #300, #3557, #37927 ), + ( #705, #3767, #3965, #3364 ), + ( #10533, #29137, #22202, #28729 ), + ( #34632, #500, #13193, #13588 ), + ( #16240, #22998, #25683, #35424 ), + ( #34825, #38132, #10128, #12993 ), + ( #22605, #22405, #35024, #19306 ), + ( #16435, #19104, #16041, #25473 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.03247871438895000296, 0.000000000000000000, 0.1666667475158999934, 0.3333334272719000180, 0.5000001070281000493, 0.6666667867843000250, 0.8333334665403999697, 1.000000000000000000, 1.031494677006000060 ), + ( 5.959201254652000376E-06, 0.9994001533858000164 ), + .UNSPECIFIED. ) ; +#19222 = ORIENTED_EDGE ( 'NONE', *, *, #26083, .F. ) ; +#19223 = CARTESIAN_POINT ( 'NONE', ( 12.63839252860101148, 175.2446016636384911, 100.6168460505910360 ) ) ; +#19224 = CARTESIAN_POINT ( 'NONE', ( 28.46318946417061468, 181.4174751352287274, 104.2560874084225588 ) ) ; +#19225 = CARTESIAN_POINT ( 'NONE', ( -25.49999614780579549, 119.8278461530010759, 89.89852083535538441 ) ) ; +#19227 = ORIENTED_EDGE ( 'NONE', *, *, #25115, .F. ) ; +#19226 = AXIS2_PLACEMENT_3D ( 'NONE', #1217, #7749, #20424 ) ; +#19228 = CARTESIAN_POINT ( 'NONE', ( 25.49060739074860749, 211.0902261026000417, 73.54297825541816280 ) ) ; +#19229 = CARTESIAN_POINT ( 'NONE', ( -38.34602178450000309, 118.5791799481999931, 89.90303731784000263 ) ) ; +#19230 = CARTESIAN_POINT ( 'NONE', ( 37.34127192387609284, 166.8872991867534097, 188.4876025152064187 ) ) ; +#19231 = VECTOR ( 'NONE', #36979, 1000.000000000000000 ) ; +#19232 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#19233 = ORIENTED_EDGE ( 'NONE', *, *, #4597, .F. ) ; +#19234 = FACE_OUTER_BOUND ( 'NONE', #15095, .T. ) ; +#19235 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33700, #23498, #11430, #36161 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19236 = EDGE_LOOP ( 'NONE', ( #6802, #9087, #18168, #34407, #12582, #4730, #421, #9099, #5127, #23953, #31833, #27720 ) ) ; +#19237 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19238 = CARTESIAN_POINT ( 'NONE', ( -23.32730709679323056, 115.6131156702003011, 89.78183858414666929 ) ) ; +#19239 = CIRCLE ( 'NONE', #27099, 4.999999999999990230 ) ; +#19240 = CARTESIAN_POINT ( 'NONE', ( 41.39926400812499452, 120.5685452915470108, 90.54227133756512558 ) ) ; +#19241 = ORIENTED_EDGE ( 'NONE', *, *, #15360, .F. ) ; +#19242 = ORIENTED_EDGE ( 'NONE', *, *, #24713, .T. ) ; +#19243 = EDGE_CURVE ( 'NONE', #32409, #34827, #25748, .T. ) ; +#19244 = CARTESIAN_POINT ( 'NONE', ( -19.99903504035571800, 194.7641645988118455, 106.1244872497271672 ) ) ; +#19245 = CARTESIAN_POINT ( 'NONE', ( 1.991510566260412007, 189.0611364870325133, 103.2999233371572529 ) ) ; +#19246 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19247 = ORIENTED_EDGE ( 'NONE', *, *, #21704, .F. ) ; +#19248 = CARTESIAN_POINT ( 'NONE', ( 15.50029466867484551, 138.3983482085316723, 92.10848809867536602 ) ) ; +#19249 = DIRECTION ( 'NONE', ( 0.8135696865073147599, 0.000000000000000000, -0.5814674240199442234 ) ) ; +#19250 = ORIENTED_EDGE ( 'NONE', *, *, #17086, .T. ) ; +#19251 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#19252 = CARTESIAN_POINT ( 'NONE', ( -45.39081410773631831, 123.6896955036549741, 91.26380522522237015 ) ) ; +#19253 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#19254 = ADVANCED_FACE ( 'NONE', ( #32075 ), #9830, .T. ) ; +#19255 = VERTEX_POINT ( 'NONE', #29407 ) ; +#19256 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32756, #39285, #4943, #7607 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.9992950541840658341, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19257 = CARTESIAN_POINT ( 'NONE', ( 26.00056762447263026, 118.1139028608674408, 90.25209678512123901 ) ) ; +#19258 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -5.046468293989541410E-15, -0.0006039748319412812337 ) ) ; +#19259 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971555410 ) ) ; +#19260 = VECTOR ( 'NONE', #22761, 1000.000000000000114 ) ; +#19261 = EDGE_CURVE ( 'NONE', #12107, #31197, #7488, .T. ) ; +#19262 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35519, #13094, #16148, #32298 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19263 = AXIS2_PLACEMENT_3D ( 'NONE', #34477, #6479, #37180 ) ; +#19264 = ORIENTED_EDGE ( 'NONE', *, *, #262, .T. ) ; +#19265 = AXIS2_PLACEMENT_3D ( 'NONE', #9571, #159, #12238 ) ; +#19266 = CARTESIAN_POINT ( 'NONE', ( -23.36190348438398345, 175.3529862697351120, 100.1473808295323096 ) ) ; +#19267 = CARTESIAN_POINT ( 'NONE', ( 6.271009707311050896, 148.6549594042781450, 94.48198805953025214 ) ) ; +#19268 = AXIS2_PLACEMENT_3D ( 'NONE', #25561, #28030, #38007 ) ; +#19269 = ADVANCED_FACE ( 'NONE', ( #32467 ), #35910, .T. ) ; +#19270 = ADVANCED_FACE ( 'NONE', ( #3634 ), #11199, .F. ) ; +#19272 = CARTESIAN_POINT ( 'NONE', ( -30.05261222213120931, 184.7446961453429424, 104.8885090255323718 ) ) ; +#19271 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799611204, 137.3509909075980886, 91.38105903661011098 ) ) ; +#19273 = EDGE_CURVE ( 'NONE', #39956, #2172, #22151, .T. ) ; +#19274 = EDGE_CURVE ( 'NONE', #10482, #13543, #33460, .T. ) ; +#19275 = EDGE_LOOP ( 'NONE', ( #14452, #21068, #4380, #18818 ) ) ; +#19276 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#19277 = DIRECTION ( 'NONE', ( 0.0005884949961272565883, -0.2249510543439071641, 0.9743698870671261281 ) ) ; +#19278 = CARTESIAN_POINT ( 'NONE', ( 77.66057557573886072, 193.1738148078198378, 189.4424374941742144 ) ) ; +#19279 = VERTEX_POINT ( 'NONE', #21008 ) ; +#19280 = ORIENTED_EDGE ( 'NONE', *, *, #3572, .T. ) ; +#19281 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#19282 = CARTESIAN_POINT ( 'NONE', ( -25.98973257537553749, 191.3166157958662836, 106.8934875062374203 ) ) ; +#19283 = LINE ( 'NONE', #3746, #12176 ) ; +#19284 = DIRECTION ( 'NONE', ( -6.938892725157353033E-15, 0.9743700559946818496, 0.2249510924199315531 ) ) ; +#19285 = LINE ( 'NONE', #31789, #29401 ) ; +#19286 = VERTEX_POINT ( 'NONE', #29810 ) ; +#19287 = ORIENTED_EDGE ( 'NONE', *, *, #3611, .F. ) ; +#19288 = ORIENTED_EDGE ( 'NONE', *, *, #9008, .F. ) ; +#19289 = AXIS2_PLACEMENT_3D ( 'NONE', #16127, #3441, #34506 ) ; +#19290 = CARTESIAN_POINT ( 'NONE', ( -15.66486529302079589, 151.3708617756205399, 97.34567295342098703 ) ) ; +#19291 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555133 ) ) ; +#19292 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #1568, #14256 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19293 = CIRCLE ( 'NONE', #4938, 8.000001045079370599 ) ; +#19294 = LINE ( 'NONE', #35413, #17018 ) ; +#19295 = CARTESIAN_POINT ( 'NONE', ( 16.88249520722548169, 148.9778306577506726, 176.8903484419645622 ) ) ; +#19296 = ORIENTED_EDGE ( 'NONE', *, *, #35605, .F. ) ; +#19297 = ADVANCED_FACE ( 'NONE', ( #20588 ), #33055, .T. ) ; +#19298 = DIRECTION ( 'NONE', ( -0.6087611427424954869, -0.7731004630501229213, -0.1781166615410720577 ) ) ; +#19299 = ORIENTED_EDGE ( 'NONE', *, *, #18131, .T. ) ; +#19300 = VECTOR ( 'NONE', #29068, 1000.000000000000000 ) ; +#19301 = VECTOR ( 'NONE', #37120, 1000.000000000000000 ) ; +#19302 = ORIENTED_EDGE ( 'NONE', *, *, #398, .T. ) ; +#19303 = CARTESIAN_POINT ( 'NONE', ( -39.61054748937312553, 129.5177821288435780, 336.3042500576304974 ) ) ; +#19304 = ORIENTED_EDGE ( 'NONE', *, *, #33311, .F. ) ; +#19305 = CARTESIAN_POINT ( 'NONE', ( -38.90357209447083164, 164.7996974313793999, 188.0966889302359561 ) ) ; +#19306 = CARTESIAN_POINT ( 'NONE', ( -2.300096019559000116, 191.0630006485000081, 106.1942960410000012 ) ) ; +#19307 = CARTESIAN_POINT ( 'NONE', ( -3.336458024882414719, 126.7630962693081500, 89.09156782095561766 ) ) ; +#19309 = ADVANCED_FACE ( 'NONE', ( #5247 ), #19576, .F. ) ; +#19308 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24232, #8691, #21148, #2543, #11952, #31772, #16405, #35198, #38091, #37895 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.009024888469274735397, 0.2567686663519560542, 0.5045124442346373694, 0.7522562221173186847, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19310 = ORIENTED_EDGE ( 'NONE', *, *, #863, .T. ) ; +#19311 = LINE ( 'NONE', #22608, #10605 ) ; +#19312 = VERTEX_POINT ( 'NONE', #11002 ) ; +#19313 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#19314 = CARTESIAN_POINT ( 'NONE', ( -37.69582204082962562, 164.0995084088371527, 198.0927439109664476 ) ) ; +#19315 = DIRECTION ( 'NONE', ( 0.0005734119072325883325, 0.000000000000000000, 0.9999998355993788834 ) ) ; +#19316 = EDGE_CURVE ( 'NONE', #31691, #15233, #39597, .T. ) ; +#19317 = LINE ( 'NONE', #27957, #34107 ) ; +#19318 = DIRECTION ( 'NONE', ( 0.0004161288024365940980, -0.8480480898180946525, 0.5299191109902535723 ) ) ; +#19319 = ORIENTED_EDGE ( 'NONE', *, *, #13655, .T. ) ; +#19320 = EDGE_CURVE ( 'NONE', #1973, #4424, #18259, .T. ) ; +#19321 = AXIS2_PLACEMENT_3D ( 'NONE', #38953, #4801, #14641 ) ; +#19322 = CARTESIAN_POINT ( 'NONE', ( -45.30255556275930928, 123.8777291761282129, 93.38906572069882372 ) ) ; +#19323 = AXIS2_PLACEMENT_3D ( 'NONE', #28600, #32273, #31682 ) ; +#19324 = EDGE_CURVE ( 'NONE', #36415, #4594, #16969, .T. ) ; +#19325 = VECTOR ( 'NONE', #38524, 999.9999999999998863 ) ; +#19326 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#19327 = EDGE_CURVE ( 'NONE', #15824, #40142, #33252, .T. ) ; +#19328 = EDGE_LOOP ( 'NONE', ( #39148, #10431, #35775 ) ) ; +#19329 = VERTEX_POINT ( 'NONE', #23462 ) ; +#19331 = VECTOR ( 'NONE', #29003, 1000.000000000000000 ) ; +#19330 = CARTESIAN_POINT ( 'NONE', ( 39.53555642364394629, 119.7153706430301554, 90.34642614193101906 ) ) ; +#19332 = CARTESIAN_POINT ( 'NONE', ( -26.00329743126571813, 121.2302541217067215, 87.65683552929112921 ) ) ; +#19333 = CARTESIAN_POINT ( 'NONE', ( -3.780571208821432272, 174.7337882003822642, 102.8237057398510785 ) ) ; +#19334 = CYLINDRICAL_SURFACE ( 'NONE', #3643, 59.40509898897001051 ) ; +#19335 = ORIENTED_EDGE ( 'NONE', *, *, #26318, .T. ) ; +#19336 = ORIENTED_EDGE ( 'NONE', *, *, #17874, .F. ) ; +#19337 = CARTESIAN_POINT ( 'NONE', ( 39.76231351996260344, 182.5576203638986215, 106.5366729533402719 ) ) ; +#19338 = CARTESIAN_POINT ( 'NONE', ( -1.212288473603901018, 140.3952820277004605, 157.8550920018487318 ) ) ; +#19339 = CARTESIAN_POINT ( 'NONE', ( 8.470678213537377488, 151.0674926792860049, 95.03763680969706229 ) ) ; +#19340 = PLANE ( 'NONE', #37255 ) ; +#19341 = ORIENTED_EDGE ( 'NONE', *, *, #38124, .T. ) ; +#19342 = DIRECTION ( 'NONE', ( -0.1843855713908465477, -0.08049128666858569592, 0.9795525069302342125 ) ) ; +#19343 = CARTESIAN_POINT ( 'NONE', ( 44.05265128906093963, 113.3760414474945009, 85.80123528811638778 ) ) ; +#19344 = ORIENTED_EDGE ( 'NONE', *, *, #3172, .T. ) ; +#19345 = CARTESIAN_POINT ( 'NONE', ( -1.216565595234769148, 136.3705012149207789, 175.2651585126169209 ) ) ; +#19346 = CARTESIAN_POINT ( 'NONE', ( -20.00089539691495233, 118.1272453392662527, 87.27993277136866368 ) ) ; +#19347 = DIRECTION ( 'NONE', ( 0.4303597330247870278, 0.7060138277436147636, -0.5624366410767025481 ) ) ; +#19348 = CARTESIAN_POINT ( 'NONE', ( 0.05421747281792377304, 83.21792371834001756, 89.76775200199907090 ) ) ; +#19349 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #25877, #19673 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19350 = ORIENTED_EDGE ( 'NONE', *, *, #395, .F. ) ; +#19351 = CARTESIAN_POINT ( 'NONE', ( 27.53717704466000171, 125.0577440870000174, 89.02147418570000070 ) ) ; +#19352 = CIRCLE ( 'NONE', #31138, 2.499999999997815525 ) ; +#19353 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971554578 ) ) ; +#19354 = CARTESIAN_POINT ( 'NONE', ( 39.86742295541759518, 165.0107917281946186, 182.9225538859983544 ) ) ; +#19355 = VECTOR ( 'NONE', #4294, 1000.000000000000114 ) ; +#19356 = DIRECTION ( 'NONE', ( 0.0002393071182784984501, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#19357 = CARTESIAN_POINT ( 'NONE', ( -18.91554917980427675, 125.6711736200330165, 175.2587820826857410 ) ) ; +#19358 = AXIS2_PLACEMENT_3D ( 'NONE', #7502, #38578, #29399 ) ; +#19359 = ORIENTED_EDGE ( 'NONE', *, *, #22412, .T. ) ; +#19360 = FACE_OUTER_BOUND ( 'NONE', #35196, .T. ) ; +#19361 = CARTESIAN_POINT ( 'NONE', ( 0.8759982955651735015, 189.0247036241306944, 103.6920166762249664 ) ) ; +#19362 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825911398296938, 0.0005734119025854594051 ) ) ; +#19363 = ADVANCED_FACE ( 'NONE', ( #14470 ), #35912, .T. ) ; +#19364 = VECTOR ( 'NONE', #22150, 1000.000000000000114 ) ; +#19365 = ADVANCED_FACE ( 'NONE', ( #1789 ), #26954, .F. ) ; +#19366 = CARTESIAN_POINT ( 'NONE', ( -21.82963565732912059, 176.4928003187452816, 100.9258332941378455 ) ) ; +#19367 = EDGE_CURVE ( 'NONE', #10943, #6999, #26742, .T. ) ; +#19368 = VECTOR ( 'NONE', #16484, 1000.000000000000227 ) ; +#19369 = CARTESIAN_POINT ( 'NONE', ( -33.46311609814530641, 218.5902260770998282, 61.07871277729011439 ) ) ; +#19370 = EDGE_CURVE ( 'NONE', #30562, #29835, #1303, .T. ) ; +#19371 = PLANE ( 'NONE', #12709 ) ; +#19372 = CARTESIAN_POINT ( 'NONE', ( 21.10734183263222974, 176.0605026285803092, 100.6290478223103975 ) ) ; +#19373 = VERTEX_POINT ( 'NONE', #37542 ) ; +#19374 = EDGE_CURVE ( 'NONE', #24313, #5278, #30047, .T. ) ; +#19375 = CARTESIAN_POINT ( 'NONE', ( -12.64088427125098235, 181.7768506542429066, 101.7499118960562186 ) ) ; +#19376 = EDGE_CURVE ( 'NONE', #1519, #19980, #24699, .T. ) ; +#19377 = DIRECTION ( 'NONE', ( 0.0004726756300157089648, 0.6225146366376117513, 0.7826080141103149979 ) ) ; +#19378 = DIRECTION ( 'NONE', ( -0.6087614109020721420, -0.7729348355671186166, -0.1788331193133692598 ) ) ; +#19379 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19380 = CIRCLE ( 'NONE', #20701, 2.499999999931187933 ) ; +#19381 = FACE_OUTER_BOUND ( 'NONE', #8184, .T. ) ; +#19382 = CARTESIAN_POINT ( 'NONE', ( 36.06425384701000070, 192.4066394740000021, 105.0139338433999967 ) ) ; +#19383 = CARTESIAN_POINT ( 'NONE', ( 22.64184747305000300, 157.9319024309000099, 98.92303659383000536 ) ) ; +#19384 = AXIS2_PLACEMENT_3D ( 'NONE', #37012, #2857, #28414 ) ; +#19385 = CARTESIAN_POINT ( 'NONE', ( 20.89486103759118052, 175.7095848683153463, 103.2849699440975826 ) ) ; +#19386 = CONICAL_SURFACE ( 'NONE', #6978, 4.999999999987116972, 0.7853981633861885081 ) ; +#19387 = ORIENTED_EDGE ( 'NONE', *, *, #15545, .F. ) ; +#19388 = EDGE_CURVE ( 'NONE', #2798, #37821, #33945, .T. ) ; +#19389 = CARTESIAN_POINT ( 'NONE', ( -2.691515551155000185, 209.6623428544999967, 75.89346375227999886 ) ) ; +#19390 = CARTESIAN_POINT ( 'NONE', ( 36.87849788990180144, 117.6060897978989743, 87.24551060340307629 ) ) ; +#19391 = AXIS2_PLACEMENT_3D ( 'NONE', #12553, #24859, #6608 ) ; +#19392 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; +#19393 = ORIENTED_EDGE ( 'NONE', *, *, #21894, .F. ) ; +#19394 = CARTESIAN_POINT ( 'NONE', ( 6.034640325019517526, 177.1924675499267892, 101.0705349078851327 ) ) ; +#19395 = ORIENTED_EDGE ( 'NONE', *, *, #20715, .T. ) ; +#19396 = CARTESIAN_POINT ( 'NONE', ( -3.296694232897449339, 129.3530670243922316, 89.51842077367476236 ) ) ; +#19397 = FACE_OUTER_BOUND ( 'NONE', #14140, .T. ) ; +#19398 = DIRECTION ( 'NONE', ( 2.515349040166355772E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#19399 = CARTESIAN_POINT ( 'NONE', ( -45.49101484277578322, 185.9174214959355709, 105.9473892799664014 ) ) ; +#19400 = CARTESIAN_POINT ( 'NONE', ( -37.07257225381636800, 191.0462222942348376, 103.7818103174439273 ) ) ; +#19401 = FACE_OUTER_BOUND ( 'NONE', #119, .T. ) ; +#19402 = VERTEX_POINT ( 'NONE', #18117 ) ; +#19403 = CARTESIAN_POINT ( 'NONE', ( 15.95613733389899025, 121.8961617987971238, 174.4891947115541484 ) ) ; +#19404 = CARTESIAN_POINT ( 'NONE', ( -3.558845676726785978, 175.7327080916274156, 100.2261648978108468 ) ) ; +#19405 = FACE_OUTER_BOUND ( 'NONE', #36097, .T. ) ; +#19406 = VECTOR ( 'NONE', #30539, 1000.000000000000000 ) ; +#19407 = CARTESIAN_POINT ( 'NONE', ( 25.75054841324000421, 118.4643410412000009, 90.00223210762001713 ) ) ; +#19408 = EDGE_CURVE ( 'NONE', #21071, #39904, #14245, .T. ) ; +#19409 = VERTEX_POINT ( 'NONE', #37150 ) ; +#19410 = CARTESIAN_POINT ( 'NONE', ( -13.49823352225588913, 184.2872290888800819, 105.2891383389777076 ) ) ; +#19411 = EDGE_CURVE ( 'NONE', #9171, #2569, #3903, .T. ) ; +#19412 = ORIENTED_EDGE ( 'NONE', *, *, #26815, .F. ) ; +#19413 = CIRCLE ( 'NONE', #29238, 2.250000000020502711 ) ; +#19414 = CARTESIAN_POINT ( 'NONE', ( -15.74985326587000145, 167.5695991370999991, 98.60550149261000286 ) ) ; +#19415 = LINE ( 'NONE', #19203, #17532 ) ; +#19416 = CARTESIAN_POINT ( 'NONE', ( -28.94629671773202162, 110.6131156702000027, 90.28526767707491274 ) ) ; +#19417 = PLANE ( 'NONE', #35003 ) ; +#19418 = EDGE_CURVE ( 'NONE', #14229, #5686, #10377, .T. ) ; +#19419 = DIRECTION ( 'NONE', ( 1.619075244243125847E-14, -0.9743700557921582961, -0.2249510932971570121 ) ) ; +#19420 = CARTESIAN_POINT ( 'NONE', ( -2.319384444843000104, 208.9645219994999934, 73.76273522338999555 ) ) ; +#19421 = CARTESIAN_POINT ( 'NONE', ( 38.50000310099999723, 118.5649250008000024, 89.80765680167999676 ) ) ; +#19422 = ORIENTED_EDGE ( 'NONE', *, *, #23864, .T. ) ; +#19423 = LINE ( 'NONE', #22521, #29007 ) ; +#19424 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19425 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; +#19426 = LINE ( 'NONE', #625, #21950 ) ; +#19427 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #7432, #28927, #9931, #31804 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.570796320676825619, 2.588537152379762230 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9155302586764009209, 0.9155302586764009209, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#19428 = ORIENTED_EDGE ( 'NONE', *, *, #18787, .F. ) ; +#19429 = VERTEX_POINT ( 'NONE', #34066 ) ; +#19430 = EDGE_CURVE ( 'NONE', #8220, #32422, #12014, .T. ) ; +#19431 = ORIENTED_EDGE ( 'NONE', *, *, #7086, .F. ) ; +#19432 = CARTESIAN_POINT ( 'NONE', ( 40.54675149425525404, 217.7719116180000185, 76.03401540786036605 ) ) ; +#19433 = VECTOR ( 'NONE', #30223, 1000.000000000000000 ) ; +#19434 = LINE ( 'NONE', #29662, #19355 ) ; +#19435 = VECTOR ( 'NONE', #23618, 1000.000000000000114 ) ; +#19436 = ORIENTED_EDGE ( 'NONE', *, *, #4774, .T. ) ; +#19437 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319376442775 ) ) ; +#19438 = CARTESIAN_POINT ( 'NONE', ( -33.88284817031402696, 159.3826839816843233, 187.1022045530551736 ) ) ; +#19439 = CARTESIAN_POINT ( 'NONE', ( 13.50147201673213893, 151.4095814229721668, 97.16618435358425643 ) ) ; +#19440 = CARTESIAN_POINT ( 'NONE', ( -38.25727539327999693, 118.9592153865000057, 87.58113317161999589 ) ) ; +#19441 = CARTESIAN_POINT ( 'NONE', ( 29.05533563819793486, 110.6131156702000027, 90.25023614447037801 ) ) ; +#19442 = ORIENTED_EDGE ( 'NONE', *, *, #35494, .T. ) ; +#19443 = CARTESIAN_POINT ( 'NONE', ( 35.04494057328185619, 220.4002260770999726, 73.03733781617431475 ) ) ; +#19444 = VERTEX_POINT ( 'NONE', #9343 ) ; +#19445 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364818587623, 136.5649596138779884, 181.4686487119677167 ) ) ; +#19446 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971539312 ) ) ; +#19447 = EDGE_LOOP ( 'NONE', ( #10870, #36693, #3374, #20956, #24965 ) ) ; +#19448 = ORIENTED_EDGE ( 'NONE', *, *, #7300, .F. ) ; +#19449 = LINE ( 'NONE', #37868, #38912 ) ; +#19450 = CARTESIAN_POINT ( 'NONE', ( 20.00025828646017345, 174.5279639952516106, 99.93388581131628712 ) ) ; +#19451 = CARTESIAN_POINT ( 'NONE', ( -26.01051778642650092, 208.7352112813564418, 73.14552897845221935 ) ) ; +#19452 = DIRECTION ( 'NONE', ( 0.0006039748319386430446, 1.236414387799018187E-14, 0.9999998176071845934 ) ) ; +#19453 = ORIENTED_EDGE ( 'NONE', *, *, #33124, .F. ) ; +#19454 = EDGE_CURVE ( 'NONE', #4160, #14577, #21210, .T. ) ; +#19455 = ORIENTED_EDGE ( 'NONE', *, *, #4073, .T. ) ; +#19456 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#19457 = LINE ( 'NONE', #31547, #19364 ) ; +#19458 = ADVANCED_FACE ( 'NONE', ( #2610 ), #34453, .F. ) ; +#19459 = VERTEX_POINT ( 'NONE', #33663 ) ; +#19460 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10201, #35847, #371, #23205 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19461 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250611660, 132.8554482850406089, 90.84904174544712419 ) ) ; +#19462 = CARTESIAN_POINT ( 'NONE', ( 36.23355974028325477, 191.4499673472672612, 103.8307471576879379 ) ) ; +#19463 = CARTESIAN_POINT ( 'NONE', ( -12.64347415174542810, 134.2426399615423236, 93.73178815038983203 ) ) ; +#19464 = AXIS2_PLACEMENT_3D ( 'NONE', #29282, #16387, #1453 ) ; +#19465 = EDGE_LOOP ( 'NONE', ( #30872, #17390, #7214, #26063 ) ) ; +#19466 = EDGE_CURVE ( 'NONE', #39537, #7275, #5216, .T. ) ; +#19467 = CARTESIAN_POINT ( 'NONE', ( 0.5641566566382231196, 188.3875244742078223, 106.2241826925672257 ) ) ; +#19468 = DIRECTION ( 'NONE', ( 0.0002393071182785117587, 0.2252352986010041080, -0.9743043687658491381 ) ) ; +#19469 = LINE ( 'NONE', #31770, #29346 ) ; +#19470 = CARTESIAN_POINT ( 'NONE', ( 48.84485507728539488, 75.31855144216289943, 291.5290428667154288 ) ) ; +#19471 = VERTEX_POINT ( 'NONE', #130 ) ; +#19472 = ORIENTED_EDGE ( 'NONE', *, *, #20294, .T. ) ; +#19473 = CARTESIAN_POINT ( 'NONE', ( 26.00178518556128893, 120.0897341375864755, 90.43300729485713418 ) ) ; +#19474 = DIRECTION ( 'NONE', ( -0.6087614115774889756, -0.7729348350621332298, -0.1788331191967985345 ) ) ; +#19475 = CARTESIAN_POINT ( 'NONE', ( 6.065815740701999914, 163.2729245447999915, 152.4718672074000381 ) ) ; +#19477 = CARTESIAN_POINT ( 'NONE', ( -37.28640831843555503, 117.9292370818984352, 123.9370462788764087 ) ) ; +#19476 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561239 ) ) ; +#19478 = CARTESIAN_POINT ( 'NONE', ( 36.04593084803796188, 218.5902260770999987, 76.03673379054495740 ) ) ; +#19479 = DIRECTION ( 'NONE', ( 0.0005734119072324324242, 0.000000000000000000, 0.9999998355993788834 ) ) ; +#19480 = ORIENTED_EDGE ( 'NONE', *, *, #2931, .T. ) ; +#19481 = CARTESIAN_POINT ( 'NONE', ( -20.01829689993581596, 209.7096928646539880, 76.07061354826153377 ) ) ; +#19482 = CARTESIAN_POINT ( 'NONE', ( -35.96566301449503555, 192.2060209908892432, 104.4274987125427714 ) ) ; +#19483 = CARTESIAN_POINT ( 'NONE', ( 25.51819783872340608, 191.5524126122537325, 104.3741215340442920 ) ) ; +#19484 = ORIENTED_EDGE ( 'NONE', *, *, #39955, .F. ) ; +#19485 = ORIENTED_EDGE ( 'NONE', *, *, #6460, .F. ) ; +#19486 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; +#19487 = CIRCLE ( 'NONE', #548, 2.500000720456942105 ) ; +#19488 = CARTESIAN_POINT ( 'NONE', ( -46.26150339730361338, 126.0976992386087261, 91.87172231767381447 ) ) ; +#19489 = CARTESIAN_POINT ( 'NONE', ( -3.070713250341000400, 190.8329090761000089, 106.9302175993999953 ) ) ; +#19490 = ORIENTED_EDGE ( 'NONE', *, *, #11535, .F. ) ; +#19491 = EDGE_CURVE ( 'NONE', #9438, #6175, #18320, .T. ) ; +#19492 = ORIENTED_EDGE ( 'NONE', *, *, #23125, .F. ) ; +#19493 = CARTESIAN_POINT ( 'NONE', ( 14.16801031327180738, 129.2779008960638976, 92.05627979598381216 ) ) ; +#19494 = AXIS2_PLACEMENT_3D ( 'NONE', #15799, #19474, #38480 ) ; +#19495 = CARTESIAN_POINT ( 'NONE', ( -40.95517856244259747, 217.7719116394999901, 75.58324044002641529 ) ) ; +#19496 = DIRECTION ( 'NONE', ( 0.0005884949961209894661, -0.2249510543439065813, 0.9743698870671262391 ) ) ; +#19497 = VECTOR ( 'NONE', #6408, 1000.000000000000114 ) ; +#19498 = ORIENTED_EDGE ( 'NONE', *, *, #36784, .F. ) ; +#19499 = ORIENTED_EDGE ( 'NONE', *, *, #37145, .T. ) ; +#19500 = CARTESIAN_POINT ( 'NONE', ( -22.69283010918674037, 213.5901956524609204, 73.57227693392532331 ) ) ; +#19501 = ORIENTED_EDGE ( 'NONE', *, *, #4029, .T. ) ; +#19502 = EDGE_CURVE ( 'NONE', #33812, #25425, #12410, .T. ) ; +#19503 = CARTESIAN_POINT ( 'NONE', ( 0.05451946023390212559, 83.21792371834001756, 90.26775191081758010 ) ) ; +#19504 = EDGE_CURVE ( 'NONE', #30625, #28499, #14766, .T. ) ; +#19505 = CARTESIAN_POINT ( 'NONE', ( -5.658908186421000686, 187.6682623620686172, 106.0618792668577015 ) ) ; +#19506 = ADVANCED_FACE ( 'NONE', ( #27576 ), #20908, .T. ) ; +#19507 = CARTESIAN_POINT ( 'NONE', ( -26.00145235156885093, 120.5160882189163942, 87.49195619469584528 ) ) ; +#19508 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #6016, #28699 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19509 = VERTEX_POINT ( 'NONE', #15473 ) ; +#19510 = CARTESIAN_POINT ( 'NONE', ( -25.49272530211510812, 191.9759150222000130, 101.9368443075920396 ) ) ; +#19511 = CARTESIAN_POINT ( 'NONE', ( -25.50413503257686898, 209.7096538831000032, 78.07390885283565751 ) ) ; +#19512 = CARTESIAN_POINT ( 'NONE', ( 22.59321899614865714, 214.0705223858939235, 73.04485834425945256 ) ) ; +#19513 = CARTESIAN_POINT ( 'NONE', ( -25.99970180913262041, 119.7153704765195670, 90.38600773184769821 ) ) ; +#19514 = AXIS2_PLACEMENT_3D ( 'NONE', #13431, #19139, #31435 ) ; +#19515 = CARTESIAN_POINT ( 'NONE', ( -41.76244517127567946, 189.2343572370725724, 106.9213286744051175 ) ) ; +#19516 = ORIENTED_EDGE ( 'NONE', *, *, #5514, .F. ) ; +#19517 = AXIS2_PLACEMENT_3D ( 'NONE', #27347, #30598, #2589 ) ; +#19518 = CONICAL_SURFACE ( 'NONE', #38463, 9.999999999997360334, 0.7853981633972983989 ) ; +#19519 = CARTESIAN_POINT ( 'NONE', ( 33.52281821381428983, 83.75585590586079832, 284.9772999313669288 ) ) ; +#19520 = AXIS2_PLACEMENT_3D ( 'NONE', #4474, #10637, #7544 ) ; +#19521 = CARTESIAN_POINT ( 'NONE', ( -37.00494418646000838, 117.3004826001999987, 90.15313654179000480 ) ) ; +#19522 = ORIENTED_EDGE ( 'NONE', *, *, #39307, .T. ) ; +#19523 = EDGE_LOOP ( 'NONE', ( #4794, #4983 ) ) ; +#19524 = CARTESIAN_POINT ( 'NONE', ( 8.724446752596358934, 160.3956799297461373, 96.67791350217905233 ) ) ; +#19525 = DIRECTION ( 'NONE', ( -0.0001408404346092576671, 0.2255194953558363191, -0.9742386449830560124 ) ) ; +#19526 = CARTESIAN_POINT ( 'NONE', ( -15.99823486136621398, 118.9409032897849983, 90.20116722531788866 ) ) ; +#19527 = ORIENTED_EDGE ( 'NONE', *, *, #34488, .T. ) ; +#19528 = ORIENTED_EDGE ( 'NONE', *, *, #7770, .F. ) ; +#19529 = PLANE ( 'NONE', #38296 ) ; +#19530 = ORIENTED_EDGE ( 'NONE', *, *, #22579, .T. ) ; +#19531 = ORIENTED_EDGE ( 'NONE', *, *, #10383, .F. ) ; +#19532 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#19533 = CARTESIAN_POINT ( 'NONE', ( 1.760485921653847319, 189.3960626710020847, 105.8506353753109863 ) ) ; +#19534 = CARTESIAN_POINT ( 'NONE', ( -43.90747471557000381, 97.51241190807002113, 154.5673021613000060 ) ) ; +#19535 = ADVANCED_FACE ( 'NONE', ( #34256 ), #6256, .F. ) ; +#19536 = EDGE_LOOP ( 'NONE', ( #12541, #16011, #7356, #24140 ) ) ; +#19537 = CARTESIAN_POINT ( 'NONE', ( 75.24049004471834223, 196.2565561541850059, 190.1544973454941783 ) ) ; +#19538 = DIRECTION ( 'NONE', ( 3.191891195770216638E-14, 0.9743700557921578520, 0.2249510932971589827 ) ) ; +#19539 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452350121, 0.1781166614240801416 ) ) ; +#19540 = CARTESIAN_POINT ( 'NONE', ( -38.71167219077999988, 118.8429159421000065, 89.85853435920999743 ) ) ; +#19541 = CARTESIAN_POINT ( 'NONE', ( -6.272775217941449988, 148.2033965809511074, 96.43792127017829330 ) ) ; +#19542 = VECTOR ( 'NONE', #33530, 1000.000000000000114 ) ; +#19543 = EDGE_CURVE ( 'NONE', #39586, #30774, #38621, .T. ) ; +#19544 = PLANE ( 'NONE', #1245 ) ; +#19545 = CARTESIAN_POINT ( 'NONE', ( -30.07826481366596738, 134.2402275243734096, 93.74179301315371049 ) ) ; +#19546 = ORIENTED_EDGE ( 'NONE', *, *, #17793, .T. ) ; +#19547 = DIRECTION ( 'NONE', ( -0.9914447795421228449, 0.1270909273342987478, 0.02975139169819295340 ) ) ; +#19548 = AXIS2_PLACEMENT_3D ( 'NONE', #38813, #21954, #16397 ) ; +#19549 = CYLINDRICAL_SURFACE ( 'NONE', #7440, 2.000000000000011546 ) ; +#19550 = VECTOR ( 'NONE', #13784, 1000.000000000000000 ) ; +#19551 = DIRECTION ( 'NONE', ( 0.0005884949961241524091, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#19552 = ADVANCED_FACE ( 'NONE', ( #31624 ), #16456, .T. ) ; +#19553 = CARTESIAN_POINT ( 'NONE', ( 3.585698494325503916, 175.3488639359234469, 100.1860491892580995 ) ) ; +#19554 = ADVANCED_FACE ( 'NONE', ( #13608 ), #518, .T. ) ; +#19555 = AXIS2_PLACEMENT_3D ( 'NONE', #22561, #28492, #37682 ) ; +#19556 = CARTESIAN_POINT ( 'NONE', ( 4.602553811274089135, 124.5979440950363539, 88.41584299628244992 ) ) ; +#19557 = EDGE_CURVE ( 'NONE', #30753, #28523, #25901, .T. ) ; +#19558 = EDGE_LOOP ( 'NONE', ( #18501, #20260, #32476, #35654, #5425, #26401 ) ) ; +#19559 = CARTESIAN_POINT ( 'NONE', ( -40.55663739063058415, 184.8193262793416807, 102.8594742714833075 ) ) ; +#19560 = EDGE_CURVE ( 'NONE', #723, #18111, #38533, .T. ) ; +#19561 = CARTESIAN_POINT ( 'NONE', ( 0.5808265436351435218, 189.0001712365193214, 103.6949147857697398 ) ) ; +#19562 = CARTESIAN_POINT ( 'NONE', ( 36.41214121066919063, 191.8141173754956696, 104.3617157949233700 ) ) ; +#19563 = DIRECTION ( 'NONE', ( 0.6773442687123943928, 0.7356661890031861439, 0.000000000000000000 ) ) ; +#19564 = ORIENTED_EDGE ( 'NONE', *, *, #25071, .F. ) ; +#19565 = CARTESIAN_POINT ( 'NONE', ( -25.87121615895999938, 191.8689891060000150, 104.0514611635999955 ) ) ; +#19566 = CARTESIAN_POINT ( 'NONE', ( -3.760261628207208329, 168.4451244408993773, 98.77232846146148404 ) ) ; +#19567 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #31842, #10564, #16865, #28763 ), + ( #7466, #22640, #13623, #35065 ), + ( #19735, #3052, #4405, #13428 ), + ( #10367, #35267, #3797, #28024 ), + ( #1339, #741, #13818, #26303 ), + ( #40463, #12460, #21883, #24961 ), + ( #38551, #37412, #22834, #25714 ), + ( #32236, #16672, #29173, #23034 ), + ( #33019, #26917, #27126, #1965 ), + ( #11164, #36297, #14433, #39562 ), + ( #8507, #29564, #1754, #17264 ), + ( #1541, #33215, #11571, #14025 ), + ( #23838, #17678, #20345, #29967 ), + ( #32625, #30173, #20138, #23635 ), + ( #2169, #20546, #26507, #8086 ), + ( #29775, #17064, #36084, #39155 ), + ( #14233, #8296, #36501, #7881 ), + ( #14643, #26709, #5010, #20758 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.0009806055231174999002, 0.000000000000000000, 4.212333002590999939E-07, 0.005187662470730000121, 0.01039649399989999931, 0.02081415705823999943, 0.04164948317493000207, 0.06248480929161000230, 0.08332013540829999454, 0.1249907876417000047, 0.1666614398750999870, 0.3333440488084999931, 0.5000118277423000190, 0.6666796066758999828, 1.000000000000000000, 1.050434996582999991 ), + ( 0.001431525339720999927, 0.9999964804755000491 ), + .UNSPECIFIED. ) ; +#19568 = CARTESIAN_POINT ( 'NONE', ( -15.83155413418625379, 173.8826594657223552, 102.7142068274063718 ) ) ; +#19569 = ORIENTED_EDGE ( 'NONE', *, *, #18106, .F. ) ; +#19570 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20422, #26187, #8173, #38624 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19571 = DIRECTION ( 'NONE', ( 0.5614015438085974141, -0.5784168556941973183, 0.5918295765320973345 ) ) ; +#19572 = CIRCLE ( 'NONE', #30043, 9.999999999987798205 ) ; +#19573 = AXIS2_PLACEMENT_3D ( 'NONE', #33827, #33624, #18673 ) ; +#19574 = DIRECTION ( 'NONE', ( -0.0005884949961269095352, 0.2249510543439041110, -0.9743698870671267942 ) ) ; +#19575 = CARTESIAN_POINT ( 'NONE', ( 5.666730638602090586, 181.4890245458614686, 104.2225643677910654 ) ) ; +#19576 = CONICAL_SURFACE ( 'NONE', #37230, 2.500000001920880344, 0.7853981633737419088 ) ; +#19577 = CARTESIAN_POINT ( 'NONE', ( 37.83625397016000136, 190.8148265806999859, 106.3740856161000181 ) ) ; +#19578 = CARTESIAN_POINT ( 'NONE', ( 36.06382944065250484, 192.3722895124269883, 104.3112924986229757 ) ) ; +#19579 = AXIS2_PLACEMENT_3D ( 'NONE', #28388, #3822, #16297 ) ; +#19580 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19581 = CARTESIAN_POINT ( 'NONE', ( 42.51962411156773669, 182.5729458539040593, 104.8564411487018049 ) ) ; +#19582 = CARTESIAN_POINT ( 'NONE', ( -22.49823373577489960, 137.5169523091206543, 94.49371267932974661 ) ) ; +#19583 = ORIENTED_EDGE ( 'NONE', *, *, #18944, .F. ) ; +#19584 = CARTESIAN_POINT ( 'NONE', ( -2.454301599558000202, 209.0000008648000005, 75.66282294831999877 ) ) ; +#19585 = CARTESIAN_POINT ( 'NONE', ( 37.78115515336936880, 118.8155650090541968, 87.24496173037786662 ) ) ; +#19586 = EDGE_CURVE ( 'NONE', #25255, #16953, #22237, .T. ) ; +#19587 = CARTESIAN_POINT ( 'NONE', ( 25.49183423580130636, 211.0903769678246817, 75.54322026927223988 ) ) ; +#19588 = CARTESIAN_POINT ( 'NONE', ( -23.35635573182313607, 131.0183818788550241, 89.91503395410319399 ) ) ; +#19589 = ORIENTED_EDGE ( 'NONE', *, *, #23483, .F. ) ; +#19590 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569047542183, 0.8480481632226759547 ) ) ; +#19591 = EDGE_CURVE ( 'NONE', #26352, #12388, #27484, .T. ) ; +#19592 = ORIENTED_EDGE ( 'NONE', *, *, #19168, .T. ) ; +#19593 = EDGE_CURVE ( 'NONE', #13220, #6773, #29381, .T. ) ; +#19594 = CARTESIAN_POINT ( 'NONE', ( 35.02219272657116278, 120.3902226468004386, 87.42604107993363982 ) ) ; +#19595 = CARTESIAN_POINT ( 'NONE', ( 37.48938149088855454, 212.8449748121827838, 73.03586143537702924 ) ) ; +#19596 = EDGE_CURVE ( 'NONE', #33109, #11983, #27465, .T. ) ; +#19597 = CARTESIAN_POINT ( 'NONE', ( -44.12540495473819391, 185.7838962199085131, 107.1417462355754253 ) ) ; +#19598 = CARTESIAN_POINT ( 'NONE', ( -37.83810969319355166, 191.0388331516561777, 103.7805696149103909 ) ) ; +#19599 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457972811109, -32.89481530046835189, 142.2936922234671613 ) ) ; +#19600 = EDGE_CURVE ( 'NONE', #39158, #16454, #36751, .T. ) ; +#19601 = ORIENTED_EDGE ( 'NONE', *, *, #38254, .T. ) ; +#19602 = AXIS2_PLACEMENT_3D ( 'NONE', #19303, #16432, #31801 ) ; +#19603 = CARTESIAN_POINT ( 'NONE', ( 15.94065427327126550, 152.5997264813005643, 182.6073182000202451 ) ) ; +#19604 = CONICAL_SURFACE ( 'NONE', #36, 2.503011087841876758, 0.7854316141493700165 ) ; +#19605 = CARTESIAN_POINT ( 'NONE', ( 30.07001606276714867, 177.5308891517198902, 100.8472716789253951 ) ) ; +#19606 = CARTESIAN_POINT ( 'NONE', ( 3.599205426421769438, 175.9949742709780764, 100.2823905437740848 ) ) ; +#19607 = AXIS2_PLACEMENT_3D ( 'NONE', #30569, #24446, #34949 ) ; +#19608 = VECTOR ( 'NONE', #22213, 1000.000000000000227 ) ; +#19609 = CARTESIAN_POINT ( 'NONE', ( -20.24838124913999948, 123.4480542337999935, 90.98771610887000350 ) ) ; +#19610 = EDGE_LOOP ( 'NONE', ( #38107, #31370, #14965 ) ) ; +#19611 = CARTESIAN_POINT ( 'NONE', ( 18.90090771971125960, 120.9219860925226300, 173.6350968582803205 ) ) ; +#19612 = ORIENTED_EDGE ( 'NONE', *, *, #24096, .T. ) ; +#19613 = DIRECTION ( 'NONE', ( -0.7075337269147008445, -0.000000000000000000, -0.7066795775160008564 ) ) ; +#19614 = CARTESIAN_POINT ( 'NONE', ( 36.05382442437669965, 112.9281706447458760, 87.74600877593400128 ) ) ; +#19615 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#19616 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#19617 = CARTESIAN_POINT ( 'NONE', ( 28.49403691938354299, 170.5609214717077009, 152.0219651408380912 ) ) ; +#19618 = CARTESIAN_POINT ( 'NONE', ( 38.48171694004999921, 118.5499200410999947, 89.80803649567999969 ) ) ; +#19619 = ORIENTED_EDGE ( 'NONE', *, *, #38836, .T. ) ; +#19620 = CARTESIAN_POINT ( 'NONE', ( 35.56535286263039808, 192.7868339794035251, 106.8337704962199268 ) ) ; +#19621 = DIRECTION ( 'NONE', ( -0.7763856153004775607, 0.5343480021168224292, 0.3342118923501363748 ) ) ; +#19622 = FACE_OUTER_BOUND ( 'NONE', #6921, .T. ) ; +#19623 = CARTESIAN_POINT ( 'NONE', ( -27.50624172263541212, 187.5021564113302190, 106.0367331495152996 ) ) ; +#19624 = ORIENTED_EDGE ( 'NONE', *, *, #2034, .T. ) ; +#19625 = AXIS2_PLACEMENT_3D ( 'NONE', #29788, #26931, #11173 ) ; +#19626 = CIRCLE ( 'NONE', #29454, 6.000000000000001776 ) ; +#19627 = ORIENTED_EDGE ( 'NONE', *, *, #23908, .T. ) ; +#19628 = CARTESIAN_POINT ( 'NONE', ( 25.99886678296517672, 118.8155665066540934, 87.25209012101137773 ) ) ; +#19629 = EDGE_CURVE ( 'NONE', #9250, #9326, #2086, .T. ) ; +#19630 = AXIS2_PLACEMENT_3D ( 'NONE', #36546, #33669, #33263 ) ; +#19631 = FACE_OUTER_BOUND ( 'NONE', #11762, .T. ) ; +#19632 = CARTESIAN_POINT ( 'NONE', ( 15.66800366920011811, 160.1398306428952480, 99.35122504555626222 ) ) ; +#19633 = EDGE_CURVE ( 'NONE', #35236, #19816, #12810, .T. ) ; +#19634 = ORIENTED_EDGE ( 'NONE', *, *, #28849, .F. ) ; +#19635 = ORIENTED_EDGE ( 'NONE', *, *, #20608, .F. ) ; +#19636 = CARTESIAN_POINT ( 'NONE', ( -17.26213291099019997, 152.2612616225560771, 183.6636115490260863 ) ) ; +#19637 = CARTESIAN_POINT ( 'NONE', ( 12.31694666162038132, 134.8454845483305178, 93.34277599231758415 ) ) ; +#19638 = CARTESIAN_POINT ( 'NONE', ( -38.16347685272999968, 118.8553488218999945, 90.29083592950999559 ) ) ; +#19639 = DIRECTION ( 'NONE', ( 0.0002393070154807156044, 0.2243321270822452584, -0.9745127189990429040 ) ) ; +#19640 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971577060 ) ) ; +#19641 = FACE_OUTER_BOUND ( 'NONE', #1399, .T. ) ; +#19642 = ORIENTED_EDGE ( 'NONE', *, *, #24667, .T. ) ; +#19643 = EDGE_CURVE ( 'NONE', #22354, #39827, #4520, .T. ) ; +#19644 = DIRECTION ( 'NONE', ( 0.8094300156679565816, 0.2340581597534485969, -0.5385534584315662121 ) ) ; +#19645 = ORIENTED_EDGE ( 'NONE', *, *, #37429, .F. ) ; +#19646 = CARTESIAN_POINT ( 'NONE', ( 3.666638747404692200, 128.4736512688999994, 89.82433808078000936 ) ) ; +#19647 = CARTESIAN_POINT ( 'NONE', ( 20.00158012229879745, 184.2984082083453359, 105.2684676661315422 ) ) ; +#19648 = CARTESIAN_POINT ( 'NONE', ( 22.53365398945999942, 147.8783627793000051, 152.4718672074000381 ) ) ; +#19649 = PLANE ( 'NONE', #17072 ) ; +#19650 = EDGE_CURVE ( 'NONE', #17466, #19471, #20247, .T. ) ; +#19651 = EDGE_LOOP ( 'NONE', ( #2026, #30707, #17849, #17534 ) ) ; +#19652 = CARTESIAN_POINT ( 'NONE', ( -39.60061239353461815, 123.2105914118956349, 92.88326245006905424 ) ) ; +#19653 = CARTESIAN_POINT ( 'NONE', ( -2.454301921840380096, 209.0000005845445230, 75.66282330657800514 ) ) ; +#19654 = CARTESIAN_POINT ( 'NONE', ( 0.04593741417267090121, 271.9029643395999187, 76.05847688452558941 ) ) ; +#19655 = ORIENTED_EDGE ( 'NONE', *, *, #21562, .F. ) ; +#19656 = VERTEX_POINT ( 'NONE', #14412 ) ; +#19657 = AXIS2_PLACEMENT_3D ( 'NONE', #36968, #36560, #20819 ) ; +#19658 = DIRECTION ( 'NONE', ( -0.0005884949961254158299, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#19659 = DIRECTION ( 'NONE', ( -1.040834085563523426E-15, 0.9743700557921581851, 0.2249510932971578170 ) ) ; +#19660 = ORIENTED_EDGE ( 'NONE', *, *, #12278, .T. ) ; +#19661 = AXIS2_PLACEMENT_3D ( 'NONE', #25650, #10907, #19479 ) ; +#19662 = FACE_OUTER_BOUND ( 'NONE', #39707, .T. ) ; +#19663 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27371, #27165, #5246, #39596 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19664 = ORIENTED_EDGE ( 'NONE', *, *, #11330, .F. ) ; +#19665 = DIRECTION ( 'NONE', ( -0.0005884949961245158337, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#19666 = LINE ( 'NONE', #3728, #11458 ) ; +#19667 = CARTESIAN_POINT ( 'NONE', ( -5.023710534412880513, 124.4265388225056199, 88.38208498629704479 ) ) ; +#19668 = ORIENTED_EDGE ( 'NONE', *, *, #9413, .T. ) ; +#19669 = CARTESIAN_POINT ( 'NONE', ( 26.00948329231449563, 120.3022281478970115, 90.49543144136558226 ) ) ; +#19670 = CARTESIAN_POINT ( 'NONE', ( 13.76437287132147169, 125.3330071254293898, 174.7699841533003564 ) ) ; +#19672 = CARTESIAN_POINT ( 'NONE', ( -8.864578607679121092, 152.4548234462477865, 94.85524532604028991 ) ) ; +#19671 = CARTESIAN_POINT ( 'NONE', ( 20.48147657974056557, 209.1197527550900475, 75.61653826598076478 ) ) ; +#19673 = CARTESIAN_POINT ( 'NONE', ( 25.50879993301148829, 196.1181868571946438, 103.6643310760977670 ) ) ; +#19674 = ORIENTED_EDGE ( 'NONE', *, *, #26396, .T. ) ; +#19675 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19676 = DIRECTION ( 'NONE', ( -0.0002393071182785116774, -0.2252352986010041080, 0.9743043687658491381 ) ) ; +#19677 = CARTESIAN_POINT ( 'NONE', ( -13.49970653172800361, 153.8046016247899956, 95.68281787800398774 ) ) ; +#19678 = EDGE_CURVE ( 'NONE', #16874, #4210, #36482, .T. ) ; +#19679 = ORIENTED_EDGE ( 'NONE', *, *, #32900, .T. ) ; +#19680 = VECTOR ( 'NONE', #24413, 999.9999999999998863 ) ; +#19681 = EDGE_CURVE ( 'NONE', #328, #23937, #17188, .T. ) ; +#19682 = VERTEX_POINT ( 'NONE', #8071 ) ; +#19684 = AXIS2_PLACEMENT_3D ( 'NONE', #23245, #29794, #29988 ) ; +#19683 = CARTESIAN_POINT ( 'NONE', ( -13.47107783232944378, 153.8044057555319739, 95.68275536702104489 ) ) ; +#19685 = CARTESIAN_POINT ( 'NONE', ( -46.63416014034300616, 123.1294690227910138, 92.09012308399532287 ) ) ; +#19686 = CARTESIAN_POINT ( 'NONE', ( -3.070812541647999883, 190.8627820810999935, 106.9366044881000164 ) ) ; +#19687 = CARTESIAN_POINT ( 'NONE', ( 35.86829647990000325, 191.6740030496000031, 103.8700504923999972 ) ) ; +#19688 = ORIENTED_EDGE ( 'NONE', *, *, #32956, .T. ) ; +#19689 = ORIENTED_EDGE ( 'NONE', *, *, #22386, .T. ) ; +#19690 = CARTESIAN_POINT ( 'NONE', ( 46.51720693556681852, 124.8110556520572771, 91.00548902218217506 ) ) ; +#19691 = CARTESIAN_POINT ( 'NONE', ( -23.36156076520060054, 134.6453726937913586, 93.48532686071666831 ) ) ; +#19692 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; +#19693 = ORIENTED_EDGE ( 'NONE', *, *, #35402, .T. ) ; +#19694 = DIRECTION ( 'NONE', ( 0.7865509479255969882, 0.6175253892086907115, 0.000000000000000000 ) ) ; +#19695 = ORIENTED_EDGE ( 'NONE', *, *, #27069, .T. ) ; +#19696 = CARTESIAN_POINT ( 'NONE', ( 21.63968147918147977, 115.2790866430819534, 189.0193985992423791 ) ) ; +#19697 = LINE ( 'NONE', #37713, #33324 ) ; +#19698 = VERTEX_POINT ( 'NONE', #11553 ) ; +#19699 = CARTESIAN_POINT ( 'NONE', ( -30.07656309493742341, 134.9532562613949551, 90.87980234836240356 ) ) ; +#19700 = ADVANCED_FACE ( 'NONE', ( #13803 ), #11809, .T. ) ; +#19701 = CARTESIAN_POINT ( 'NONE', ( -26.00146729410618107, 120.3902237924994836, 87.46289810595230563 ) ) ; +#19702 = CARTESIAN_POINT ( 'NONE', ( -15.49852919541873675, 127.1814504007998892, 91.59019381936052184 ) ) ; +#19703 = CARTESIAN_POINT ( 'NONE', ( 44.73086057231283519, 108.4360122525000492, 169.8450455613742349 ) ) ; +#19704 = EDGE_LOOP ( 'NONE', ( #21360, #16819, #2389, #1781 ) ) ; +#19705 = CARTESIAN_POINT ( 'NONE', ( -25.02112241941476611, 129.9358920626651752, 92.74501084285193997 ) ) ; +#19706 = CIRCLE ( 'NONE', #4715, 2.500000000000002220 ) ; +#19707 = CARTESIAN_POINT ( 'NONE', ( -2.954034027471755142, 205.1071153524148372, 76.10666676077381965 ) ) ; +#19708 = CARTESIAN_POINT ( 'NONE', ( 19.35814820635435041, 126.1315274695410977, 175.4780701241052157 ) ) ; +#19709 = CIRCLE ( 'NONE', #36052, 2.499999999994426236 ) ; +#19710 = CIRCLE ( 'NONE', #24979, 2.500000000048662407 ) ; +#19711 = CARTESIAN_POINT ( 'NONE', ( -41.04085718237605107, 188.5195315767678039, 107.5577504359371375 ) ) ; +#19712 = ORIENTED_EDGE ( 'NONE', *, *, #33565, .F. ) ; +#19713 = CARTESIAN_POINT ( 'NONE', ( 22.77977433793355999, 158.3069438176785582, 96.18720162681876218 ) ) ; +#19714 = CARTESIAN_POINT ( 'NONE', ( 17.48463111787128810, 153.4425669637734586, 179.2163951893537615 ) ) ; +#19715 = VERTEX_POINT ( 'NONE', #39332 ) ; +#19716 = ORIENTED_EDGE ( 'NONE', *, *, #26080, .T. ) ; +#19717 = CARTESIAN_POINT ( 'NONE', ( -20.24985248663000093, 145.0237349194999865, 93.40309554072000253 ) ) ; +#19718 = CARTESIAN_POINT ( 'NONE', ( 28.18621395003418328, 187.0539859719742140, 103.3338670887423376 ) ) ; +#19719 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950524827, 137.3532831589782006, 178.0585834213013072 ) ) ; +#19720 = CARTESIAN_POINT ( 'NONE', ( -2.853038766185818087, 209.7096500570610544, 73.06022702708840200 ) ) ; +#19721 = EDGE_CURVE ( 'NONE', #6712, #36184, #609, .T. ) ; +#19722 = ORIENTED_EDGE ( 'NONE', *, *, #31911, .F. ) ; +#19723 = EDGE_CURVE ( 'NONE', #8845, #9960, #26484, .T. ) ; +#19724 = VERTEX_POINT ( 'NONE', #26692 ) ; +#19725 = CARTESIAN_POINT ( 'NONE', ( -9.583319590155999990, 123.9902035785000010, 91.10643974023000169 ) ) ; +#19726 = VERTEX_POINT ( 'NONE', #17661 ) ; +#19727 = ORIENTED_EDGE ( 'NONE', *, *, #17784, .T. ) ; +#19728 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#19729 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; +#19730 = VERTEX_POINT ( 'NONE', #14009 ) ; +#19731 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24947, #38200, #16117, #34896 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 2.930308335499677012E-08, 0.9999999706969182611 ), + .UNSPECIFIED. ) ; +#19732 = ORIENTED_EDGE ( 'NONE', *, *, #8766, .F. ) ; +#19733 = DIRECTION ( 'NONE', ( -0.7933531821952876095, -0.5932639600228909460, -0.1364866368497979210 ) ) ; +#19734 = DIRECTION ( 'NONE', ( 0.7075280717106061656, 0.1146811194785925248, 0.6973179106954074946 ) ) ; +#19736 = CONICAL_SURFACE ( 'NONE', #35393, 2.503000015584043503, 0.7853981634850645266 ) ; +#19735 = CARTESIAN_POINT ( 'NONE', ( 36.02810672577000162, 191.4409537047000072, 103.6991216587000082 ) ) ; +#19737 = CARTESIAN_POINT ( 'NONE', ( 19.99938796732458712, 193.5973206684549837, 103.1031867269298772 ) ) ; +#19738 = AXIS2_PLACEMENT_3D ( 'NONE', #22336, #34761, #19232 ) ; +#19739 = AXIS2_PLACEMENT_3D ( 'NONE', #36790, #8589, #17958 ) ; +#19740 = CARTESIAN_POINT ( 'NONE', ( -16.26675888560721006, 127.7434586696155066, 175.3198452907780620 ) ) ; +#19741 = ORIENTED_EDGE ( 'NONE', *, *, #35865, .T. ) ; +#19742 = CARTESIAN_POINT ( 'NONE', ( 14.44402852477210430, 188.1654067176696401, 103.0856067790360839 ) ) ; +#19743 = CARTESIAN_POINT ( 'NONE', ( -19.99800679399352532, 151.2849267590962654, 97.67087031631508864 ) ) ; +#19744 = CARTESIAN_POINT ( 'NONE', ( 9.584790827646999745, 187.4829414530000236, 105.7533188981000052 ) ) ; +#19745 = DIRECTION ( 'NONE', ( 4.625929269207597055E-15, -0.9743700557921582961, -0.2249510932971568178 ) ) ; +#19746 = PLANE ( 'NONE', #31522 ) ; +#19747 = ORIENTED_EDGE ( 'NONE', *, *, #31768, .F. ) ; +#19748 = CARTESIAN_POINT ( 'NONE', ( -22.50072399476195528, 158.3009599602069954, 96.21317557253242114 ) ) ; +#19749 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673442394, 160.6295158081618411, 97.24216643309391372 ) ) ; +#19750 = CARTESIAN_POINT ( 'NONE', ( -38.20478932694192764, 191.0388335128845654, 103.7807883132890083 ) ) ; +#19751 = CARTESIAN_POINT ( 'NONE', ( 39.74588592090670147, 161.7500298686462088, 196.6039331146026825 ) ) ; +#19752 = ORIENTED_EDGE ( 'NONE', *, *, #20896, .T. ) ; +#19753 = CARTESIAN_POINT ( 'NONE', ( -25.84175230540873969, 191.4759398539146389, 104.0452857451015660 ) ) ; +#19754 = DIRECTION ( 'NONE', ( -4.631401517333630859E-11, 0.9743700734954054976, 0.2249510166159694735 ) ) ; +#19755 = CARTESIAN_POINT ( 'NONE', ( 21.21457926054944920, 175.8986325760867828, 100.7626612099922454 ) ) ; +#19756 = AXIS2_PLACEMENT_3D ( 'NONE', #10261, #34169, #6364 ) ; +#19757 = CARTESIAN_POINT ( 'NONE', ( -39.39862580925689883, 128.4305629161120805, 92.40616142701088620 ) ) ; +#19758 = ORIENTED_EDGE ( 'NONE', *, *, #21951, .T. ) ; +#19759 = EDGE_CURVE ( 'NONE', #14180, #1138, #35854, .T. ) ; +#19760 = CARTESIAN_POINT ( 'NONE', ( -22.78341386699941040, 154.2035449131175824, 95.43842691770261411 ) ) ; +#19761 = EDGE_CURVE ( 'NONE', #2366, #10263, #1323, .T. ) ; +#19762 = CONICAL_SURFACE ( 'NONE', #7367, 2.249999999870928136, 0.7853981634347139140 ) ; +#19763 = ORIENTED_EDGE ( 'NONE', *, *, #23687, .F. ) ; +#19764 = CARTESIAN_POINT ( 'NONE', ( -25.26021706816886692, 117.1739734221355889, 170.8214860574283591 ) ) ; +#19765 = DIRECTION ( 'NONE', ( -3.172065784687725564E-14, -1.000000000000000000, 1.586032892343862782E-14 ) ) ; +#19766 = CARTESIAN_POINT ( 'NONE', ( -14.99831633147801746, 135.8139285211284175, 93.92495969594287430 ) ) ; +#19767 = CARTESIAN_POINT ( 'NONE', ( 36.06383557508251414, 192.3108559936939912, 104.3213896746180041 ) ) ; +#19768 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#19769 = EDGE_CURVE ( 'NONE', #10767, #34687, #24025, .T. ) ; +#19770 = ADVANCED_FACE ( 'NONE', ( #38726 ), #10741, .T. ) ; +#19771 = CARTESIAN_POINT ( 'NONE', ( 13.50151702522348174, 187.8430237215617069, 103.4418797477903809 ) ) ; +#19772 = VERTEX_POINT ( 'NONE', #4787 ) ; +#19773 = EDGE_CURVE ( 'NONE', #5120, #16970, #27110, .T. ) ; +#19774 = CARTESIAN_POINT ( 'NONE', ( -2.454332449978999797, 209.0617968418999908, 75.63992803070000548 ) ) ; +#19775 = EDGE_CURVE ( 'NONE', #23677, #8441, #32998, .T. ) ; +#19776 = CARTESIAN_POINT ( 'NONE', ( 13.50718655633492382, 188.3455032986072979, 103.1278069412195748 ) ) ; +#19777 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#19778 = ORIENTED_EDGE ( 'NONE', *, *, #10487, .T. ) ; +#19779 = CARTESIAN_POINT ( 'NONE', ( -23.36013624460098725, 134.2411009257855028, 93.73794322563884407 ) ) ; +#19780 = ORIENTED_EDGE ( 'NONE', *, *, #17182, .T. ) ; +#19781 = CARTESIAN_POINT ( 'NONE', ( -3.656326336327488491, 130.0672526925883119, 89.68352076587126476 ) ) ; +#19782 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#19783 = EDGE_LOOP ( 'NONE', ( #24663, #5438, #39551, #22387 ) ) ; +#19784 = FACE_OUTER_BOUND ( 'NONE', #27700, .T. ) ; +#19785 = CARTESIAN_POINT ( 'NONE', ( -41.11490486740327555, 77.14301703112185749, 323.4755791661175408 ) ) ; +#19786 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #252, #9886, #19054, #28876 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19787 = CARTESIAN_POINT ( 'NONE', ( 36.06269812966176858, 123.8464190861335794, 91.30225149133501361 ) ) ; +#19788 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620729128, 0.0004744508866335532104 ) ) ; +#19789 = ORIENTED_EDGE ( 'NONE', *, *, #25307, .F. ) ; +#19790 = CARTESIAN_POINT ( 'NONE', ( 29.05352371370200615, 110.6131156702000027, 87.25023669171606855 ) ) ; +#19791 = EDGE_CURVE ( 'NONE', #35062, #4201, #9394, .T. ) ; +#19792 = CARTESIAN_POINT ( 'NONE', ( 30.06998914975339687, 177.5021616893372141, 100.8652226047939564 ) ) ; +#19793 = CARTESIAN_POINT ( 'NONE', ( 31.51075026500899767, 191.3597297869251292, 106.8916795150186516 ) ) ; +#19794 = CARTESIAN_POINT ( 'NONE', ( -6.042234299931061869, 134.2432640563548318, 93.72802809502178434 ) ) ; +#19795 = EDGE_LOOP ( 'NONE', ( #39509, #10091, #22916, #17695 ) ) ; +#19796 = EDGE_LOOP ( 'NONE', ( #34796, #17965, #34475, #36522 ) ) ; +#19797 = CARTESIAN_POINT ( 'NONE', ( -58.64525294468500505, 28.72802687364639596, 151.8110389321206242 ) ) ; +#19798 = CARTESIAN_POINT ( 'NONE', ( 36.70717078082609675, 115.7236482597848664, 89.70125722292402770 ) ) ; +#19799 = CARTESIAN_POINT ( 'NONE', ( 32.06514546973478019, 137.5830230609005298, 94.13390997160884410 ) ) ; +#19800 = EDGE_CURVE ( 'NONE', #5945, #20371, #23823, .T. ) ; +#19801 = FACE_OUTER_BOUND ( 'NONE', #8495, .T. ) ; +#19802 = DIRECTION ( 'NONE', ( 0.0006039748319389621253, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#19803 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250900735, 132.4055461762762604, 92.79778151960539390 ) ) ; +#19804 = EDGE_CURVE ( 'NONE', #30145, #27328, #20121, .T. ) ; +#19805 = CARTESIAN_POINT ( 'NONE', ( 38.34430631207000317, 119.2562741942000031, 87.36327662843000041 ) ) ; +#19806 = FACE_OUTER_BOUND ( 'NONE', #34593, .T. ) ; +#19807 = CARTESIAN_POINT ( 'NONE', ( 38.70517594201000122, 118.4177626759999953, 89.51241173148000030 ) ) ; +#19808 = AXIS2_PLACEMENT_3D ( 'NONE', #28043, #16, #6140 ) ; +#19809 = CIRCLE ( 'NONE', #40059, 2.499999999890851754 ) ; +#19810 = VERTEX_POINT ( 'NONE', #2757 ) ; +#19811 = EDGE_CURVE ( 'NONE', #10943, #31399, #20935, .T. ) ; +#19812 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#19813 = CARTESIAN_POINT ( 'NONE', ( -26.47922269804969275, 118.7188176348483353, 171.1783167788773596 ) ) ; +#19814 = LINE ( 'NONE', #622, #12461 ) ; +#19815 = CARTESIAN_POINT ( 'NONE', ( -3.589080270957198504, 147.6459880593766343, 129.6608555926431166 ) ) ; +#19816 = VERTEX_POINT ( 'NONE', #22530 ) ; +#19817 = VERTEX_POINT ( 'NONE', #37847 ) ; +#19818 = ADVANCED_FACE ( 'NONE', ( #31730 ), #32694, .T. ) ; +#19819 = EDGE_LOOP ( 'NONE', ( #7176, #16181, #15831, #429, #14930, #15544, #25470, #24470, #4114, #18290, #35983 ) ) ; +#19820 = CARTESIAN_POINT ( 'NONE', ( -10.08030268265000018, 184.7670343400000377, 28.07991271570000080 ) ) ; +#19821 = FACE_OUTER_BOUND ( 'NONE', #24377, .T. ) ; +#19822 = VERTEX_POINT ( 'NONE', #17855 ) ; +#19823 = LINE ( 'NONE', #13521, #30946 ) ; +#19824 = CYLINDRICAL_SURFACE ( 'NONE', #17223, 2.499999999999997335 ) ; +#19825 = DIRECTION ( 'NONE', ( -0.0005884949961240085355, 0.2249510543439064425, -0.9743698870671262391 ) ) ; +#19826 = CARTESIAN_POINT ( 'NONE', ( -38.55421100171000859, 119.2443145780000009, 87.60185880502000089 ) ) ; +#19827 = CYLINDRICAL_SURFACE ( 'NONE', #35970, 2.000000000000011546 ) ; +#19828 = FACE_OUTER_BOUND ( 'NONE', #24887, .T. ) ; +#19829 = ORIENTED_EDGE ( 'NONE', *, *, #29725, .T. ) ; +#19830 = CARTESIAN_POINT ( 'NONE', ( -19.21652826239685652, 125.8330942992555634, 175.8856240629868068 ) ) ; +#19831 = VERTEX_POINT ( 'NONE', #15960 ) ; +#19832 = DIRECTION ( 'NONE', ( -0.5988682214889347044, 0.8008475843072014877, 0.000000000000000000 ) ) ; +#19833 = FACE_OUTER_BOUND ( 'NONE', #24580, .T. ) ; +#19834 = DIRECTION ( 'NONE', ( 0.001086453504404431012, -0.2255832328198436876, 0.9742232930336509611 ) ) ; +#19835 = CARTESIAN_POINT ( 'NONE', ( 46.51603001997818865, 125.2609579198457368, 89.05674941267899669 ) ) ; +#19836 = VECTOR ( 'NONE', #21912, 1000.000000000000227 ) ; +#19837 = ORIENTED_EDGE ( 'NONE', *, *, #34101, .T. ) ; +#19838 = CARTESIAN_POINT ( 'NONE', ( -1.970835579912000091, 189.4718220514999985, 103.6836576495000060 ) ) ; +#19839 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #794, #6726, #16140, #10821, #13084, #26167, #10623, #34724, #22696, #7129, #4251 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999997788436, 0.3749999999996432853, 0.4374999999995754507, 0.4687499999995714539, 0.4999999999995674571, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19840 = LINE ( 'NONE', #38267, #5534 ) ; +#19841 = CONICAL_SURFACE ( 'NONE', #10096, 2.503011062257897379, 0.7853981634071111051 ) ; +#19842 = CONICAL_SURFACE ( 'NONE', #34834, 2.503090949441038493, 0.7853981633487705505 ) ; +#19843 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433776002355 ) ) ; +#19844 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #7982, #35557, #4710, #11260 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 6.154269794435091256, 6.194940170588882467 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9998621647918570776, 0.9998621647918570776, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#19845 = AXIS2_PLACEMENT_3D ( 'NONE', #28991, #38582, #19765 ) ; +#19846 = VERTEX_POINT ( 'NONE', #15225 ) ; +#19847 = LINE ( 'NONE', #7593, #6114 ) ; +#19848 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19849 = ORIENTED_EDGE ( 'NONE', *, *, #14262, .F. ) ; +#19850 = CARTESIAN_POINT ( 'NONE', ( -42.20772307256024192, 120.8083491825531013, 90.64813103358072510 ) ) ; +#19851 = EDGE_CURVE ( 'NONE', #30059, #39941, #5981, .T. ) ; +#19852 = EDGE_CURVE ( 'NONE', #22581, #30982, #25602, .T. ) ; +#19853 = ORIENTED_EDGE ( 'NONE', *, *, #33281, .F. ) ; +#19854 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#19855 = EDGE_CURVE ( 'NONE', #1699, #26164, #29892, .T. ) ; +#19856 = EDGE_CURVE ( 'NONE', #22954, #1917, #26816, .T. ) ; +#19857 = CARTESIAN_POINT ( 'NONE', ( 14.82295868926343019, 114.6164157062401330, 152.8159396943794093 ) ) ; +#19858 = CARTESIAN_POINT ( 'NONE', ( -8.189842673156130459, 150.7129460345074961, 97.36055581103926215 ) ) ; +#19859 = CARTESIAN_POINT ( 'NONE', ( -20.00011960254677845, 119.8743726790490882, 87.34018024778070810 ) ) ; +#19860 = VERTEX_POINT ( 'NONE', #28652 ) ; +#19861 = ADVANCED_FACE ( 'NONE', ( #33816 ), #39870, .F. ) ; +#19862 = CARTESIAN_POINT ( 'NONE', ( 26.00614868755149800, 120.3031002262990086, 90.49221237271520124 ) ) ; +#19863 = CARTESIAN_POINT ( 'NONE', ( -25.45411666281046692, 211.7447201612124843, 75.57429487795135969 ) ) ; +#19864 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33942, #3657, #31905, #25770, #19605, #29020, #32102, #19792, #19193, #7532, #26370 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000001768585, 0.3750000000002153833, 0.4375000000002170486, 0.4687500000001579292, 0.5000000000000986988, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19866 = CARTESIAN_POINT ( 'NONE', ( -9.450221470825175274, 153.0100899376908501, 94.98379243350829881 ) ) ; +#19865 = CARTESIAN_POINT ( 'NONE', ( 20.48212217007521829, 207.7963227301765414, 76.43687548430384027 ) ) ; +#19867 = CIRCLE ( 'NONE', #7469, 6.499999999928477656 ) ; +#19868 = ADVANCED_FACE ( 'NONE', ( #5608 ), #11757, .F. ) ; +#19869 = AXIS2_PLACEMENT_3D ( 'NONE', #7093, #37575, #10188 ) ; +#19870 = CIRCLE ( 'NONE', #36857, 2.500000000000002220 ) ; +#19871 = VERTEX_POINT ( 'NONE', #14832 ) ; +#19872 = CARTESIAN_POINT ( 'NONE', ( 22.50147045826000181, 153.3598638654891886, 97.61100683846059667 ) ) ; +#19873 = CARTESIAN_POINT ( 'NONE', ( -36.10626650516888247, 191.9730893684615864, 104.4211779715851520 ) ) ; +#19874 = DIRECTION ( 'NONE', ( -0.6185863125140933505, -0.7857168535612664151, 0.000000000000000000 ) ) ; +#19875 = CARTESIAN_POINT ( 'NONE', ( -35.94700007828220834, 109.6131156696666693, 89.12282904685666551 ) ) ; +#19877 = ORIENTED_EDGE ( 'NONE', *, *, #18747, .F. ) ; +#19876 = AXIS2_PLACEMENT_3D ( 'NONE', #18318, #21208, #33661 ) ; +#19878 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17322, #10819, #5064, #11413 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19879 = EDGE_LOOP ( 'NONE', ( #24618, #11502, #31474, #6781, #9955, #35406, #5775, #28151, #32958, #25476, #14352, #2819 ) ) ; +#19880 = CARTESIAN_POINT ( 'NONE', ( 116.6747096975787059, 205.3448423347536789, 192.2656634464534591 ) ) ; +#19881 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971546529 ) ) ; +#19882 = CARTESIAN_POINT ( 'NONE', ( -3.070812596811999917, 190.8630721979000384, 106.9366657634000006 ) ) ; +#19883 = ORIENTED_EDGE ( 'NONE', *, *, #37556, .F. ) ; +#19884 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559851 ) ) ; +#19885 = DIRECTION ( 'NONE', ( 0.0005884949961199763876, -0.2249510543439082189, 0.9743698870671259060 ) ) ; +#19886 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#19887 = ORIENTED_EDGE ( 'NONE', *, *, #16626, .F. ) ; +#19888 = VERTEX_POINT ( 'NONE', #28455 ) ; +#19889 = CARTESIAN_POINT ( 'NONE', ( 30.06789428293084043, 135.1172793263938843, 91.09506464709090778 ) ) ; +#19890 = CARTESIAN_POINT ( 'NONE', ( 3.064317959841779349, 190.8642559078977854, 106.7952278870890410 ) ) ; +#19891 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319401588676 ) ) ; +#19892 = DIRECTION ( 'NONE', ( 0.0006039748319382907873, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#19893 = AXIS2_PLACEMENT_3D ( 'NONE', #20776, #33231, #14658 ) ; +#19894 = CARTESIAN_POINT ( 'NONE', ( 39.72739263165712487, 107.0606345199744283, 184.9165446084303426 ) ) ; +#19895 = LINE ( 'NONE', #16833, #28698 ) ; +#19896 = ORIENTED_EDGE ( 'NONE', *, *, #88, .T. ) ; +#19897 = ADVANCED_FACE ( 'NONE', ( #24241 ), #11963, .F. ) ; +#19898 = VECTOR ( 'NONE', #25752, 1000.000000000000114 ) ; +#19899 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700562169598234, -0.2249510914571402620 ) ) ; +#19900 = EDGE_CURVE ( 'NONE', #4711, #15715, #24873, .T. ) ; +#19901 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#19902 = CARTESIAN_POINT ( 'NONE', ( 20.55731024319839406, 211.7441868440044743, 75.54576727287884808 ) ) ; +#19903 = FACE_OUTER_BOUND ( 'NONE', #31255, .T. ) ; +#19904 = ORIENTED_EDGE ( 'NONE', *, *, #29672, .T. ) ; +#19905 = EDGE_CURVE ( 'NONE', #34680, #32839, #5819, .T. ) ; +#19906 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#19907 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22298, #34337, #10, #6333 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19908 = CARTESIAN_POINT ( 'NONE', ( -36.16375936368000055, 113.8378354543000057, 89.62930055153999831 ) ) ; +#19909 = EDGE_CURVE ( 'NONE', #28773, #12858, #27527, .T. ) ; +#19910 = ORIENTED_EDGE ( 'NONE', *, *, #36654, .F. ) ; +#19911 = CARTESIAN_POINT ( 'NONE', ( -38.81266452666582722, 133.7633419217194160, 337.2839330447861812 ) ) ; +#19912 = ORIENTED_EDGE ( 'NONE', *, *, #35543, .F. ) ; +#19913 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19914 = CARTESIAN_POINT ( 'NONE', ( -28.46737701145232791, 128.5818728664343951, 89.35557892710436079 ) ) ; +#19915 = CARTESIAN_POINT ( 'NONE', ( -26.57351927219633581, 123.1588308314834421, 88.10242702663742875 ) ) ; +#19916 = FACE_OUTER_BOUND ( 'NONE', #34390, .T. ) ; +#19917 = DIRECTION ( 'NONE', ( -0.7933532970003721596, -0.5930762008556746956, -0.1372995488602881120 ) ) ; +#19918 = VERTEX_POINT ( 'NONE', #40151 ) ; +#19919 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7677, #938, #20140, #1145, #37963, #32237 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 3.272432770486283937E-05, 0.001540884923091554544, 0.003049045518478246241 ), + .UNSPECIFIED. ) ; +#19920 = EDGE_LOOP ( 'NONE', ( #13258, #33620, #11083, #23023, #13053, #34078, #37698, #4556, #4713, #2547, #14733, #36478, #17229, #13180, #6988, #884, #28201, #6678, #14826, #16844, #19716, #28622, #24996, #31496, #20748 ) ) ; +#19921 = FACE_BOUND ( 'NONE', #13283, .T. ) ; +#19922 = ORIENTED_EDGE ( 'NONE', *, *, #2303, .T. ) ; +#19923 = VERTEX_POINT ( 'NONE', #12163 ) ; +#19924 = VERTEX_POINT ( 'NONE', #24650 ) ; +#19925 = CARTESIAN_POINT ( 'NONE', ( 1.956228930436368030, 189.5641622393101215, 105.8987958274937284 ) ) ; +#19926 = EDGE_CURVE ( 'NONE', #5402, #35793, #34552, .T. ) ; +#19927 = VECTOR ( 'NONE', #35586, 1000.000000000000000 ) ; +#19928 = LINE ( 'NONE', #3792, #38511 ) ; +#19929 = AXIS2_PLACEMENT_3D ( 'NONE', #4110, #16395, #6989 ) ; +#19930 = AXIS2_PLACEMENT_3D ( 'NONE', #9114, #37510, #9512 ) ; +#19931 = ORIENTED_EDGE ( 'NONE', *, *, #29026, .T. ) ; +#19932 = CARTESIAN_POINT ( 'NONE', ( -45.80561840739365920, 187.2331216690805604, 105.4495952916396533 ) ) ; +#19933 = AXIS2_PLACEMENT_3D ( 'NONE', #15730, #27837, #19398 ) ; +#19934 = CARTESIAN_POINT ( 'NONE', ( -18.98889543208580122, 125.5955304196095312, 175.3358149539526778 ) ) ; +#19935 = CARTESIAN_POINT ( 'NONE', ( 36.67125386629000161, 117.6422922943000060, 87.11622953641000322 ) ) ; +#19936 = CARTESIAN_POINT ( 'NONE', ( -38.90145940069999853, 118.6908308601000073, 89.55944009604000655 ) ) ; +#19937 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32522, #17167, #29265, #1031, #1235, #11257, #35552, #36185, #8190, #20659 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.002377699347871517228, 0.2517832745109036541, 0.5011888496739357324, 0.7505944248369678107, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#19938 = LINE ( 'NONE', #32434, #9826 ) ; +#19939 = ORIENTED_EDGE ( 'NONE', *, *, #16094, .F. ) ; +#19940 = CARTESIAN_POINT ( 'NONE', ( 19.99991105671495362, 118.5778858161331470, 87.25549460550637093 ) ) ; +#19941 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971547361 ) ) ; +#19942 = EDGE_LOOP ( 'NONE', ( #13585, #11250, #37122, #18983 ) ) ; +#19943 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971519328 ) ) ; +#19944 = CARTESIAN_POINT ( 'NONE', ( -29.30090432678149170, 112.1830789903917349, 175.8249585680744644 ) ) ; +#19945 = CARTESIAN_POINT ( 'NONE', ( 20.50029387904210765, 120.2778657767349841, 87.92202505056270923 ) ) ; +#19946 = CARTESIAN_POINT ( 'NONE', ( 44.91139781548088905, 186.4056730800002128, 107.2645705271051781 ) ) ; +#19947 = VERTEX_POINT ( 'NONE', #6557 ) ; +#19948 = CARTESIAN_POINT ( 'NONE', ( 39.86749636578412748, 165.2362371599454320, 181.9483004261018095 ) ) ; +#19949 = CARTESIAN_POINT ( 'NONE', ( 0.6691617680251428224, 189.0028253544776362, 103.6871807533737808 ) ) ; +#19950 = CARTESIAN_POINT ( 'NONE', ( 32.56862209515505668, 137.3592834573111929, 91.34514006402139330 ) ) ; +#19951 = VECTOR ( 'NONE', #5418, 1000.000000000000227 ) ; +#19952 = CARTESIAN_POINT ( 'NONE', ( -30.17790838424820521, 126.0796625456713826, 91.85784435949031490 ) ) ; +#19953 = CARTESIAN_POINT ( 'NONE', ( -25.87048433357000121, 191.8304227716000128, 104.0529250579999996 ) ) ; +#19954 = EDGE_CURVE ( 'NONE', #35766, #34206, #24472, .T. ) ; +#19955 = AXIS2_PLACEMENT_3D ( 'NONE', #13707, #34945, #26195 ) ; +#19956 = DIRECTION ( 'NONE', ( -0.0005884949961262653023, 0.2249510543439053600, -0.9743698870671265722 ) ) ; +#19957 = CIRCLE ( 'NONE', #7561, 22.50000000000000000 ) ; +#19958 = LINE ( 'NONE', #23454, #39195 ) ; +#19959 = CARTESIAN_POINT ( 'NONE', ( 19.45260910890439021, 147.6922889574200042, 183.5326060071998597 ) ) ; +#19960 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989941907, 0.1373964268091567298 ) ) ; +#19961 = CARTESIAN_POINT ( 'NONE', ( -28.26185612672702518, 125.5768230428473373, 89.17483656727264929 ) ) ; +#19962 = ORIENTED_EDGE ( 'NONE', *, *, #7014, .F. ) ; +#19963 = AXIS2_PLACEMENT_3D ( 'NONE', #24457, #36905, #21384 ) ; +#19964 = CIRCLE ( 'NONE', #4972, 1.749999999999998446 ) ; +#19965 = FACE_OUTER_BOUND ( 'NONE', #25371, .T. ) ; +#19966 = ORIENTED_EDGE ( 'NONE', *, *, #12285, .F. ) ; +#19967 = CARTESIAN_POINT ( 'NONE', ( 94.27699944285315325, 220.8868603236405761, 200.9849624698713910 ) ) ; +#19968 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#19969 = CARTESIAN_POINT ( 'NONE', ( 37.80694793874999959, 190.1982698422000055, 106.7585076721000092 ) ) ; +#19970 = CARTESIAN_POINT ( 'NONE', ( 20.24032085432765271, 118.1109234118111431, 90.01703651609138035 ) ) ; +#19971 = DIRECTION ( 'NONE', ( -0.0001422274014914441545, 0.2255205321518429784, -0.9742384047805320302 ) ) ; +#19972 = CARTESIAN_POINT ( 'NONE', ( 13.50520662904530234, 188.2844610440680242, 103.1660372551096145 ) ) ; +#19973 = ORIENTED_EDGE ( 'NONE', *, *, #30589, .T. ) ; +#19974 = CARTESIAN_POINT ( 'NONE', ( -5.669824853826463951, 181.4158645661298692, 104.2738425377782647 ) ) ; +#19975 = FACE_OUTER_BOUND ( 'NONE', #14558, .T. ) ; +#19976 = CARTESIAN_POINT ( 'NONE', ( 37.09343845436652032, 117.9403996252154059, 87.24538078468812330 ) ) ; +#19977 = LINE ( 'NONE', #23470, #27193 ) ; +#19978 = CARTESIAN_POINT ( 'NONE', ( -14.22265864990228401, 129.0629248693782074, 176.7848948385215806 ) ) ; +#19979 = VECTOR ( 'NONE', #1731, 1000.000000000000227 ) ; +#19980 = VERTEX_POINT ( 'NONE', #19024 ) ; +#19981 = CARTESIAN_POINT ( 'NONE', ( -26.00476204355895860, 118.1131156702000169, 87.28007043021332834 ) ) ; +#19982 = AXIS2_PLACEMENT_3D ( 'NONE', #39243, #14523, #30253 ) ; +#19983 = ORIENTED_EDGE ( 'NONE', *, *, #15764, .F. ) ; +#19984 = VECTOR ( 'NONE', #36431, 1000.000000000000000 ) ; +#19985 = FACE_OUTER_BOUND ( 'NONE', #26082, .T. ) ; +#19986 = LINE ( 'NONE', #35318, #39773 ) ; +#19987 = CARTESIAN_POINT ( 'NONE', ( 24.51428771926448036, 115.4939956718079088, 87.25297827652497062 ) ) ; +#19988 = ORIENTED_EDGE ( 'NONE', *, *, #25301, .F. ) ; +#19989 = CARTESIAN_POINT ( 'NONE', ( -2.937969491697683733, 193.8169247291332340, 102.7046841998142241 ) ) ; +#19990 = AXIS2_PLACEMENT_3D ( 'NONE', #29417, #7717, #30579 ) ; +#19991 = EDGE_CURVE ( 'NONE', #10713, #38615, #4953, .T. ) ; +#19992 = CARTESIAN_POINT ( 'NONE', ( 40.67360545558243956, 184.2591260079552740, 105.2468408042174275 ) ) ; +#19993 = CARTESIAN_POINT ( 'NONE', ( -25.66788536014817979, 120.6928529548877833, 87.87466536108948389 ) ) ; +#19994 = VECTOR ( 'NONE', #25570, 1000.000000000000000 ) ; +#19995 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#19996 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#19997 = VERTEX_POINT ( 'NONE', #19432 ) ; +#19998 = VERTEX_POINT ( 'NONE', #7163 ) ; +#19999 = EDGE_CURVE ( 'NONE', #35056, #11575, #7201, .T. ) ; +#20000 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#20001 = CARTESIAN_POINT ( 'NONE', ( -3.663555850038422435, 176.1198545594807570, 100.3156079611679132 ) ) ; +#20002 = CARTESIAN_POINT ( 'NONE', ( -19.31979924309097996, 124.8061162773214079, 177.8324071844828893 ) ) ; +#20003 = FACE_OUTER_BOUND ( 'NONE', #40153, .T. ) ; +#20004 = ADVANCED_FACE ( 'NONE', ( #29456 ), #35351, .F. ) ; +#20005 = ORIENTED_EDGE ( 'NONE', *, *, #8055, .F. ) ; +#20006 = CARTESIAN_POINT ( 'NONE', ( 35.54678067552502796, 205.1071296091747627, 76.08337964645130569 ) ) ; +#20007 = ADVANCED_FACE ( 'NONE', ( #32721 ), #23328, .T. ) ; +#20008 = EDGE_CURVE ( 'NONE', #11405, #1726, #7565, .T. ) ; +#20009 = CARTESIAN_POINT ( 'NONE', ( 5.666344154467410910, 131.0223139869003148, 89.89838483048988849 ) ) ; +#20010 = CARTESIAN_POINT ( 'NONE', ( 36.81642380686323435, 115.9749306341711730, 89.69778768397191016 ) ) ; +#20011 = FACE_OUTER_BOUND ( 'NONE', #12891, .T. ) ; +#20012 = CARTESIAN_POINT ( 'NONE', ( 5.957091414655063311, 149.1468224720344438, 94.08258114083251655 ) ) ; +#20013 = AXIS2_PLACEMENT_3D ( 'NONE', #22592, #38312, #35412 ) ; +#20014 = CARTESIAN_POINT ( 'NONE', ( 20.49980344970378354, 118.1127835573565221, 87.75514417896067698 ) ) ; +#20015 = CIRCLE ( 'NONE', #20703, 16.50000000000598277 ) ; +#20016 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -7.930164461720913721E-15, 0.0006039748319378585159 ) ) ; +#20017 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #35378, #38866, #13140, #1052 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 2.962184725352719816, 4.532607311606953182 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8048259373832478136, 0.8048259373832478136, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#20018 = CIRCLE ( 'NONE', #7619, 5.000000000000007994 ) ; +#20019 = CARTESIAN_POINT ( 'NONE', ( 25.63509192864999875, 191.6570031512000298, 106.5184188570000003 ) ) ; +#20020 = DIRECTION ( 'NONE', ( 0.0006039748319378811757, 1.385389704782810608E-14, 0.9999998176071845934 ) ) ; +#20021 = CARTESIAN_POINT ( 'NONE', ( -37.95805881438000284, 190.5117572160999941, 106.6130310081000090 ) ) ; +#20022 = VERTEX_POINT ( 'NONE', #20033 ) ; +#20023 = CARTESIAN_POINT ( 'NONE', ( 15.50033646246506258, 125.3079633380212670, 88.57318189682698062 ) ) ; +#20024 = AXIS2_PLACEMENT_3D ( 'NONE', #36029, #1702, #11507 ) ; +#20025 = CARTESIAN_POINT ( 'NONE', ( -28.44200545076591524, 125.3783868041292493, 88.78703055465665273 ) ) ; +#20026 = CARTESIAN_POINT ( 'NONE', ( -35.93657502954287253, 192.7057404805565568, 106.3835757455632063 ) ) ; +#20027 = DIRECTION ( 'NONE', ( 1.314737622555947214E-14, -0.9743700557921584071, -0.2249510932971566513 ) ) ; +#20029 = ORIENTED_EDGE ( 'NONE', *, *, #39187, .F. ) ; +#20028 = CARTESIAN_POINT ( 'NONE', ( -26.72558643308320114, 188.4929049624550430, 106.2649940209322921 ) ) ; +#20030 = EDGE_LOOP ( 'NONE', ( #18411, #8431, #28514, #5326 ) ) ; +#20031 = ORIENTED_EDGE ( 'NONE', *, *, #14824, .F. ) ; +#20032 = ORIENTED_EDGE ( 'NONE', *, *, #40103, .F. ) ; +#20033 = CARTESIAN_POINT ( 'NONE', ( 45.29516381819948379, 180.6442485579885329, 103.8963377076147907 ) ) ; +#20034 = DIRECTION ( 'NONE', ( 0.6087614810001779064, -0.7729390313185917627, -0.1788147452386051328 ) ) ; +#20035 = ORIENTED_EDGE ( 'NONE', *, *, #15280, .T. ) ; +#20036 = FACE_OUTER_BOUND ( 'NONE', #2230, .T. ) ; +#20037 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#20038 = CARTESIAN_POINT ( 'NONE', ( -39.34394936606000215, 120.1039698687000055, 87.57589102765001599 ) ) ; +#20039 = CARTESIAN_POINT ( 'NONE', ( -35.82528985044000081, 113.4061984923000068, 87.66687329503000115 ) ) ; +#20040 = ORIENTED_EDGE ( 'NONE', *, *, #15911, .T. ) ; +#20041 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385689936 ) ) ; +#20042 = EDGE_CURVE ( 'NONE', #27317, #14482, #4603, .T. ) ; +#20043 = AXIS2_PLACEMENT_3D ( 'NONE', #18235, #31537, #21940 ) ; +#20044 = CARTESIAN_POINT ( 'NONE', ( 16.56169987041441161, 121.8384666780658563, 177.5555275195565059 ) ) ; +#20045 = CARTESIAN_POINT ( 'NONE', ( 19.98232544185748694, 209.7096131673859816, 76.04619115725449774 ) ) ; +#20046 = LINE ( 'NONE', #22744, #30663 ) ; +#20047 = AXIS2_PLACEMENT_3D ( 'NONE', #2606, #11386, #20791 ) ; +#20048 = CARTESIAN_POINT ( 'NONE', ( -21.69818314611236332, 120.0177369536598775, 190.2070442068906573 ) ) ; +#20049 = ORIENTED_EDGE ( 'NONE', *, *, #5296, .T. ) ; +#20050 = ORIENTED_EDGE ( 'NONE', *, *, #31800, .T. ) ; +#20051 = EDGE_CURVE ( 'NONE', #25148, #10571, #3888, .T. ) ; +#20052 = CARTESIAN_POINT ( 'NONE', ( -2.209344093541980136, 189.3042501796560089, 103.3557222930819961 ) ) ; +#20053 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#20054 = LINE ( 'NONE', #6779, #24729 ) ; +#20055 = EDGE_CURVE ( 'NONE', #23240, #21775, #16555, .T. ) ; +#20056 = ORIENTED_EDGE ( 'NONE', *, *, #4915, .T. ) ; +#20057 = LINE ( 'NONE', #29690, #39406 ) ; +#20058 = CARTESIAN_POINT ( 'NONE', ( 37.19332676480694744, 118.8604558151628794, 122.9910815359380507 ) ) ; +#20059 = EDGE_CURVE ( 'NONE', #35389, #19772, #1042, .T. ) ; +#20060 = ORIENTED_EDGE ( 'NONE', *, *, #23966, .T. ) ; +#20061 = ADVANCED_FACE ( 'NONE', ( #26606 ), #39044, .F. ) ; +#20062 = EDGE_CURVE ( 'NONE', #2348, #23133, #13118, .T. ) ; +#20063 = VERTEX_POINT ( 'NONE', #26201 ) ; +#20064 = EDGE_LOOP ( 'NONE', ( #20906, #7474, #32728, #21724 ) ) ; +#20065 = CARTESIAN_POINT ( 'NONE', ( 30.05503346839188694, 109.6131156702000027, 89.74963226069121447 ) ) ; +#20066 = FACE_OUTER_BOUND ( 'NONE', #37398, .T. ) ; +#20067 = CARTESIAN_POINT ( 'NONE', ( -31.70415073531002292, 226.4002260770687371, 75.57765305101875697 ) ) ; +#20068 = CARTESIAN_POINT ( 'NONE', ( -39.75024793617362917, 128.4756217986020488, 92.41677646255658374 ) ) ; +#20069 = ORIENTED_EDGE ( 'NONE', *, *, #27895, .F. ) ; +#20070 = CARTESIAN_POINT ( 'NONE', ( 25.83394384250999920, 120.1761492849000064, 90.28722222492000071 ) ) ; +#20071 = VECTOR ( 'NONE', #19185, 1000.000000000000114 ) ; +#20072 = DIRECTION ( 'NONE', ( 0.5614017635044570298, 0.2604362742582519430, 0.7854941164544558818 ) ) ; +#20073 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3228, #13056, #34491, #40439, #13256, #37391, #19375, #34106, #12442, #15902, #6695, #15706, #6103, #24942, #18555, #174, #22467 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999995268229, 0.1874999999993464395, 0.2187499999992812416, 0.2343749999992737199, 0.2499999999992661981, 0.3749999999993902655, 0.4374999999995085043, 0.4687499999995676236, 0.4999999999996267430, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20074 = AXIS2_PLACEMENT_3D ( 'NONE', #5866, #18322, #27577 ) ; +#20076 = DIRECTION ( 'NONE', ( 0.7933310414247660702, 0.5931044597393384521, 0.1373060761554397435 ) ) ; +#20075 = DIRECTION ( 'NONE', ( -0.6087614109020721420, -0.7729348355671187276, -0.1788331193133693153 ) ) ; +#20077 = EDGE_LOOP ( 'NONE', ( #22034, #38750, #25979, #27023 ) ) ; +#20078 = CARTESIAN_POINT ( 'NONE', ( -36.00107217495795453, 192.1246088503090164, 104.4282414194491082 ) ) ; +#20079 = DIRECTION ( 'NONE', ( -0.0001408402303593218278, 0.2255194953820404136, -0.9742386449770196188 ) ) ; +#20080 = ORIENTED_EDGE ( 'NONE', *, *, #17082, .T. ) ; +#20081 = CARTESIAN_POINT ( 'NONE', ( -12.63766980425000064, 130.4202329732130465, 90.28358935463637636 ) ) ; +#20082 = CARTESIAN_POINT ( 'NONE', ( 5.675516847681189248, 187.6699105947183170, 106.0554762087619025 ) ) ; +#20083 = CARTESIAN_POINT ( 'NONE', ( -37.56657168646712108, 112.0458133426950695, 151.1389157892933781 ) ) ; +#20084 = ORIENTED_EDGE ( 'NONE', *, *, #36268, .T. ) ; +#20085 = EDGE_CURVE ( 'NONE', #32617, #23829, #29049, .T. ) ; +#20086 = EDGE_LOOP ( 'NONE', ( #22742, #1706, #36977, #34008 ) ) ; +#20087 = EDGE_CURVE ( 'NONE', #37138, #33109, #15676, .T. ) ; +#20088 = ORIENTED_EDGE ( 'NONE', *, *, #2314, .F. ) ; +#20089 = ADVANCED_FACE ( 'NONE', ( #4082 ), #25533, .F. ) ; +#20090 = CARTESIAN_POINT ( 'NONE', ( -23.36212846483814332, 134.4076661005499318, 93.63386271954821893 ) ) ; +#20091 = EDGE_LOOP ( 'NONE', ( #27712, #9243, #34863, #36503, #13382 ) ) ; +#20092 = EDGE_CURVE ( 'NONE', #20475, #25492, #11131, .T. ) ; +#20093 = CARTESIAN_POINT ( 'NONE', ( -35.93657504925000268, 192.7057423503999871, 106.3835754178000172 ) ) ; +#20094 = EDGE_CURVE ( 'NONE', #15161, #15606, #23558, .T. ) ; +#20095 = AXIS2_PLACEMENT_3D ( 'NONE', #16871, #32830, #10772 ) ; +#20096 = DIRECTION ( 'NONE', ( -1.586032892343862782E-14, -1.000000000000000000, 1.586032892343862782E-14 ) ) ; +#20097 = ORIENTED_EDGE ( 'NONE', *, *, #36163, .T. ) ; +#20098 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#20099 = CIRCLE ( 'NONE', #16830, 5.500000000058693495 ) ; +#20100 = EDGE_CURVE ( 'NONE', #33382, #28516, #2469, .T. ) ; +#20101 = CARTESIAN_POINT ( 'NONE', ( 13.85658554608299831, 124.7833813603056683, 174.0357207381452156 ) ) ; +#20102 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971598709 ) ) ; +#20103 = DIRECTION ( 'NONE', ( 1.226844142311109452E-09, -0.9743700560678152378, -0.2249510921031558919 ) ) ; +#20104 = ORIENTED_EDGE ( 'NONE', *, *, #17259, .T. ) ; +#20105 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17864, #13469, #13269, #19587 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20106 = CARTESIAN_POINT ( 'NONE', ( 7.983582054365251146, 181.6899197882616193, 101.5945976457548880 ) ) ; +#20107 = CARTESIAN_POINT ( 'NONE', ( 28.49424211975999910, 172.5096616001999905, 152.4718672074000381 ) ) ; +#20108 = CARTESIAN_POINT ( 'NONE', ( -2.436201573125298392, 191.0000000999000065, 105.6316717966334835 ) ) ; +#20109 = EDGE_CURVE ( 'NONE', #14645, #9305, #8185, .T. ) ; +#20110 = VERTEX_POINT ( 'NONE', #39250 ) ; +#20111 = CARTESIAN_POINT ( 'NONE', ( -13.46162628924000160, 112.1320600213999938, 152.4718672074000381 ) ) ; +#20113 = CARTESIAN_POINT ( 'NONE', ( -38.15628031149999799, 118.6857350137999987, 90.14919392147000110 ) ) ; +#20112 = DIRECTION ( 'NONE', ( -0.0005884949961213889946, 0.2249510543439060262, -0.9743698870671263501 ) ) ; +#20114 = CIRCLE ( 'NONE', #2524, 47.49999999998843236 ) ; +#20115 = ORIENTED_EDGE ( 'NONE', *, *, #37817, .T. ) ; +#20116 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33524, #27636, #21886, #12080 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20117 = CARTESIAN_POINT ( 'NONE', ( 38.58505542112862230, 118.4768865310855546, 89.66249146129999303 ) ) ; +#20118 = VERTEX_POINT ( 'NONE', #17570 ) ; +#20119 = LINE ( 'NONE', #5191, #14694 ) ; +#20120 = CIRCLE ( 'NONE', #18807, 2.000000000000011546 ) ; +#20121 = LINE ( 'NONE', #32608, #37253 ) ; +#20122 = CYLINDRICAL_SURFACE ( 'NONE', #30887, 10.00000000000000178 ) ; +#20123 = VECTOR ( 'NONE', #416, 1000.000000000000114 ) ; +#20124 = CARTESIAN_POINT ( 'NONE', ( -40.80719639505100105, 126.7988830470261092, 92.03030911972437877 ) ) ; +#20125 = VERTEX_POINT ( 'NONE', #5102 ) ; +#20126 = ORIENTED_EDGE ( 'NONE', *, *, #26133, .T. ) ; +#20127 = CARTESIAN_POINT ( 'NONE', ( 0.001369398875241253791, 310.9463197190910364, 131.4405422427762460 ) ) ; +#20128 = ORIENTED_EDGE ( 'NONE', *, *, #26635, .F. ) ; +#20129 = ORIENTED_EDGE ( 'NONE', *, *, #28159, .T. ) ; +#20130 = LINE ( 'NONE', #38948, #26992 ) ; +#20131 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#20132 = CARTESIAN_POINT ( 'NONE', ( 2.877577089652000097, 209.0276610102999939, 73.27023792178999884 ) ) ; +#20133 = ORIENTED_EDGE ( 'NONE', *, *, #14548, .F. ) ; +#20134 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971560684 ) ) ; +#20135 = EDGE_CURVE ( 'NONE', #26903, #23621, #5905, .T. ) ; +#20136 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178570922545E-05, 0.0002331579774915894113 ) ) ; +#20137 = CARTESIAN_POINT ( 'NONE', ( 37.67861426795000312, 118.9189040495000143, 87.12037504482999850 ) ) ; +#20138 = CARTESIAN_POINT ( 'NONE', ( 37.02982213692000357, 191.4383110333000104, 104.2026399808000008 ) ) ; +#20139 = ADVANCED_FACE ( 'NONE', ( #7975 ), #5245, .T. ) ; +#20140 = CARTESIAN_POINT ( 'NONE', ( -44.16761895448573227, 122.1071564039501709, 90.82511025668200944 ) ) ; +#20141 = CARTESIAN_POINT ( 'NONE', ( -26.28499170964820664, 153.7823183505510372, 185.4424242478054055 ) ) ; +#20142 = ORIENTED_EDGE ( 'NONE', *, *, #23637, .F. ) ; +#20143 = CARTESIAN_POINT ( 'NONE', ( -2.372094777808882782, 209.5677220771418376, 75.55993702015497604 ) ) ; +#20144 = LINE ( 'NONE', #11166, #35593 ) ; +#20145 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#20146 = ORIENTED_EDGE ( 'NONE', *, *, #16594, .T. ) ; +#20147 = EDGE_CURVE ( 'NONE', #15604, #35217, #31774, .T. ) ; +#20148 = CARTESIAN_POINT ( 'NONE', ( -6.037555838614446557, 134.4709255380399497, 93.58583283458662549 ) ) ; +#20149 = CARTESIAN_POINT ( 'NONE', ( 14.55482866507330009, 176.2484294118512196, 103.4132012473699973 ) ) ; +#20150 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38142, #32211, #33145, #29145 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20151 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319388554398 ) ) ; +#20152 = DIRECTION ( 'NONE', ( -0.0006039748319368717835, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#20153 = ORIENTED_EDGE ( 'NONE', *, *, #681, .F. ) ; +#20155 = EDGE_CURVE ( 'NONE', #32491, #8481, #40058, .T. ) ; +#20154 = DIRECTION ( 'NONE', ( 0.5989082241854611910, -0.8008175873178838833, -0.0003617255600150170222 ) ) ; +#20156 = CARTESIAN_POINT ( 'NONE', ( 2.503834950870377440, 190.4977034652589509, 104.1155233866760170 ) ) ; +#20157 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#20158 = CIRCLE ( 'NONE', #29318, 2.500000000039518611 ) ; +#20159 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452351231, 0.1781166614240801693 ) ) ; +#20160 = ORIENTED_EDGE ( 'NONE', *, *, #36640, .T. ) ; +#20161 = CIRCLE ( 'NONE', #15615, 6.000000000000007994 ) ; +#20162 = CARTESIAN_POINT ( 'NONE', ( -25.61323588163000053, 191.8524878963000333, 104.3050741500999976 ) ) ; +#20163 = DIRECTION ( 'NONE', ( 0.0005884949961234139590, -0.2249510543439055266, 0.9743698870671265722 ) ) ; +#20164 = VECTOR ( 'NONE', #2336, 1000.000000000000114 ) ; +#20165 = CARTESIAN_POINT ( 'NONE', ( -19.99942535523411635, 128.1006027498353319, 89.23935459048128394 ) ) ; +#20166 = LINE ( 'NONE', #10192, #34026 ) ; +#20167 = CARTESIAN_POINT ( 'NONE', ( 18.98784741603935089, 148.4369364876176292, 183.7046361175107450 ) ) ; +#20168 = VERTEX_POINT ( 'NONE', #2261 ) ; +#20169 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673505100, 126.6917321208253497, 89.40701027384199051 ) ) ; +#20170 = CARTESIAN_POINT ( 'NONE', ( -35.94456900099999785, 192.7584594706000019, 105.7490308641999945 ) ) ; +#20171 = CARTESIAN_POINT ( 'NONE', ( -2.937969491482879114, 193.8169247290916246, 102.7046841997964322 ) ) ; +#20172 = CARTESIAN_POINT ( 'NONE', ( 36.29514527253999745, 190.7638126662999980, 106.9007060872000068 ) ) ; +#20173 = DIRECTION ( 'NONE', ( 0.7933533411653060918, -0.5930537057989945238, -0.1373964268091609486 ) ) ; +#20174 = CARTESIAN_POINT ( 'NONE', ( 23.00070175390608895, 118.1131156702000169, 90.25694839687047022 ) ) ; +#20175 = CARTESIAN_POINT ( 'NONE', ( 39.76231351996260344, 182.5576203638986215, 106.5366729533402719 ) ) ; +#20176 = CARTESIAN_POINT ( 'NONE', ( -38.36106832263448752, 118.8212171802660606, 87.72011982685570786 ) ) ; +#20177 = ORIENTED_EDGE ( 'NONE', *, *, #16950, .F. ) ; +#20178 = CARTESIAN_POINT ( 'NONE', ( 14.17154132021859780, 182.3114712258959571, 104.3000443475247749 ) ) ; +#20180 = AXIS2_PLACEMENT_3D ( 'NONE', #7182, #23136, #32142 ) ; +#20179 = LINE ( 'NONE', #7715, #6694 ) ; +#20181 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561517 ) ) ; +#20182 = AXIS2_PLACEMENT_3D ( 'NONE', #36100, #1983, #8317 ) ; +#20183 = CARTESIAN_POINT ( 'NONE', ( -28.81944710292443546, 225.0820812887928071, 73.07591030630263162 ) ) ; +#20184 = VERTEX_POINT ( 'NONE', #5507 ) ; +#20185 = CARTESIAN_POINT ( 'NONE', ( 6.035604575172206054, 177.4784050041099874, 100.8918608666842260 ) ) ; +#20186 = AXIS2_PLACEMENT_3D ( 'NONE', #6748, #19214, #3472 ) ; +#20187 = EDGE_CURVE ( 'NONE', #14950, #1836, #38063, .T. ) ; +#20188 = EDGE_CURVE ( 'NONE', #35054, #14375, #14931, .T. ) ; +#20189 = CIRCLE ( 'NONE', #31305, 2.000000000000011546 ) ; +#20190 = ORIENTED_EDGE ( 'NONE', *, *, #16682, .T. ) ; +#20191 = CARTESIAN_POINT ( 'NONE', ( 22.99060780684998662, 213.5902260770751866, 73.54442216390444287 ) ) ; +#20192 = ORIENTED_EDGE ( 'NONE', *, *, #33726, .F. ) ; +#20193 = CARTESIAN_POINT ( 'NONE', ( 36.28407941860832864, 191.8749775445511148, 106.3918753536163280 ) ) ; +#20194 = CARTESIAN_POINT ( 'NONE', ( 3.566874771730911498, 167.8344183770249458, 101.4455740320023835 ) ) ; +#20195 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971568455 ) ) ; +#20196 = CARTESIAN_POINT ( 'NONE', ( 3.534237804969728280, 170.7884223425121490, 99.08043590382904142 ) ) ; +#20197 = CARTESIAN_POINT ( 'NONE', ( -3.669188902170177791, 185.6448324164332462, 103.7119811838688861 ) ) ; +#20198 = ORIENTED_EDGE ( 'NONE', *, *, #23858, .F. ) ; +#20199 = ORIENTED_EDGE ( 'NONE', *, *, #34527, .T. ) ; +#20200 = CARTESIAN_POINT ( 'NONE', ( -8.473620771760185022, 151.0652496779955811, 95.04735290400581960 ) ) ; +#20201 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33691, #30450, #18741, #31238 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20202 = CARTESIAN_POINT ( 'NONE', ( -2.955836285853710610, 208.9211498072354800, 73.12285454242802984 ) ) ; +#20203 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319374244013 ) ) ; +#20204 = CARTESIAN_POINT ( 'NONE', ( -41.90907465551327249, 121.4486244169956279, 92.84837845933365941 ) ) ; +#20205 = VERTEX_POINT ( 'NONE', #27438 ) ; +#20206 = CARTESIAN_POINT ( 'NONE', ( 19.99994977660901085, 119.8743760980646016, 87.31602173384072785 ) ) ; +#20207 = CARTESIAN_POINT ( 'NONE', ( -20.50418741012917678, 191.9757880780653068, 101.9338467359436322 ) ) ; +#20208 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#20209 = EDGE_CURVE ( 'NONE', #26904, #13401, #20512, .T. ) ; +#20210 = CARTESIAN_POINT ( 'NONE', ( -20.16668442107143022, 138.1480115094573762, 91.73025317471680751 ) ) ; +#20211 = CARTESIAN_POINT ( 'NONE', ( 18.98784741603935089, 148.4369364876176292, 183.7046361175107450 ) ) ; +#20212 = CIRCLE ( 'NONE', #40446, 7.500000256701354395 ) ; +#20213 = VECTOR ( 'NONE', #5995, 1000.000000000000114 ) ; +#20214 = LINE ( 'NONE', #35740, #15137 ) ; +#20215 = CONICAL_SURFACE ( 'NONE', #25388, 2.249999999984611421, 0.7853981634347277918 ) ; +#20216 = CARTESIAN_POINT ( 'NONE', ( -33.32951419975000107, 226.1502260771000010, 75.82863477539001451 ) ) ; +#20217 = CARTESIAN_POINT ( 'NONE', ( -2.620872059391936126, 209.0473114311415941, 75.82273480382318098 ) ) ; +#20218 = DIRECTION ( 'NONE', ( 0.9914447998358270064, 0.1271190489968018755, 0.02963032670501063170 ) ) ; +#20219 = CARTESIAN_POINT ( 'NONE', ( 26.29147157072674545, 122.5138351861346138, 87.92158889176852199 ) ) ; +#20220 = VERTEX_POINT ( 'NONE', #34503 ) ; +#20221 = CARTESIAN_POINT ( 'NONE', ( -35.75637239799589651, 166.8986143474667756, 183.3403976234064316 ) ) ; +#20222 = EDGE_CURVE ( 'NONE', #10321, #11452, #39222, .T. ) ; +#20223 = FACE_OUTER_BOUND ( 'NONE', #39355, .T. ) ; +#20224 = CARTESIAN_POINT ( 'NONE', ( -36.33853380484101336, 191.6162106434876193, 106.4168239506901301 ) ) ; +#20225 = CARTESIAN_POINT ( 'NONE', ( 18.00000000036189007, 132.9726894484250579, 90.34121456742754219 ) ) ; +#20227 = ORIENTED_EDGE ( 'NONE', *, *, #3637, .F. ) ; +#20226 = CARTESIAN_POINT ( 'NONE', ( 27.30503396996934740, 110.6131156702000027, 89.75129319167177755 ) ) ; +#20228 = ORIENTED_EDGE ( 'NONE', *, *, #13429, .F. ) ; +#20229 = ORIENTED_EDGE ( 'NONE', *, *, #3346, .T. ) ; +#20230 = ADVANCED_FACE ( 'NONE', ( #24550 ), #16123, .T. ) ; +#20231 = VERTEX_POINT ( 'NONE', #9807 ) ; +#20232 = CARTESIAN_POINT ( 'NONE', ( -26.00815500690995918, 208.2808508419710449, 76.62167493815645969 ) ) ; +#20233 = DIRECTION ( 'NONE', ( 0.7947983679126050527, -0.5912140607310475415, -0.1369725839625022812 ) ) ; +#20234 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 138.4461071782706370, 291.5876487235603918 ) ) ; +#20235 = EDGE_CURVE ( 'NONE', #21726, #4758, #3933, .T. ) ; +#20236 = EDGE_CURVE ( 'NONE', #25425, #16199, #3958, .T. ) ; +#20237 = ORIENTED_EDGE ( 'NONE', *, *, #16703, .T. ) ; +#20238 = PLANE ( 'NONE', #13309 ) ; +#20239 = AXIS2_PLACEMENT_3D ( 'NONE', #37025, #18393, #27840 ) ; +#20240 = CIRCLE ( 'NONE', #2653, 51.40509898939924938 ) ; +#20241 = DIRECTION ( 'NONE', ( 0.5634794340701355653, -0.8261300910752492621, 0.000000000000000000 ) ) ; +#20242 = CARTESIAN_POINT ( 'NONE', ( 14.29439949335858984, 129.8697084204042085, 89.96917383280258207 ) ) ; +#20243 = CARTESIAN_POINT ( 'NONE', ( -37.65475944653000084, 119.3162909960000064, 87.08039723494000839 ) ) ; +#20244 = VERTEX_POINT ( 'NONE', #381 ) ; +#20245 = EDGE_CURVE ( 'NONE', #40361, #26865, #6708, .T. ) ; +#20246 = CARTESIAN_POINT ( 'NONE', ( 30.11350050138999990, 127.0266740211999945, 89.21772768451999980 ) ) ; +#20247 = CIRCLE ( 'NONE', #35938, 2.250000000041454840 ) ; +#20248 = CIRCLE ( 'NONE', #39166, 2.000000000000011546 ) ; +#20249 = ORIENTED_EDGE ( 'NONE', *, *, #14355, .F. ) ; +#20250 = CARTESIAN_POINT ( 'NONE', ( 5.665061383869522516, 124.5483335507806260, 88.65174210881859551 ) ) ; +#20251 = CARTESIAN_POINT ( 'NONE', ( 5.669556187319027885, 130.2057153021515887, 92.59464791233423853 ) ) ; +#20252 = CARTESIAN_POINT ( 'NONE', ( -20.49970531963089115, 127.6304983849970398, 89.64427665959277647 ) ) ; +#20253 = CARTESIAN_POINT ( 'NONE', ( -3.316445002960699107, 186.7295836731814234, 102.7648477304885688 ) ) ; +#20254 = FACE_OUTER_BOUND ( 'NONE', #35751, .T. ) ; +#20255 = ORIENTED_EDGE ( 'NONE', *, *, #27450, .T. ) ; +#20256 = CARTESIAN_POINT ( 'NONE', ( -20.33427348652767463, 194.1237406430038561, 102.8453134758369742 ) ) ; +#20257 = CARTESIAN_POINT ( 'NONE', ( 20.50147078032796344, 191.2995707972209800, 106.3712455992080095 ) ) ; +#20258 = CARTESIAN_POINT ( 'NONE', ( -35.98731795423564250, 191.1787413534061670, 106.8792589541737357 ) ) ; +#20259 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #363, #12852, #25329, #2837 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20260 = ORIENTED_EDGE ( 'NONE', *, *, #32131, .T. ) ; +#20261 = DIRECTION ( 'NONE', ( -0.9999998176056756893, -1.060373006915629092E-09, 0.0006039773300193558179 ) ) ; +#20262 = CARTESIAN_POINT ( 'NONE', ( -25.63832272700906501, 212.6000592722514284, 76.07217362786134629 ) ) ; +#20263 = ORIENTED_EDGE ( 'NONE', *, *, #34225, .F. ) ; +#20264 = VERTEX_POINT ( 'NONE', #12656 ) ; +#20265 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #35862, #26907, #5414, #24035 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.679923615753293298, 4.712388980384685233 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999121686036021028, 0.9999121686036021028, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#20266 = ADVANCED_FACE ( 'NONE', ( #31688 ), #15718, .T. ) ; +#20267 = ORIENTED_EDGE ( 'NONE', *, *, #9829, .F. ) ; +#20268 = LINE ( 'NONE', #29088, #11950 ) ; +#20269 = EDGE_LOOP ( 'NONE', ( #920, #23747, #12354, #37603 ) ) ; +#20270 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825880664215480, 0.0005734119032936251361 ) ) ; +#20271 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 132.6352630048999970, 91.80276880046000088 ) ) ; +#20272 = LINE ( 'NONE', #20067, #15210 ) ; +#20273 = AXIS2_PLACEMENT_3D ( 'NONE', #8724, #15641, #11988 ) ; +#20274 = CONICAL_SURFACE ( 'NONE', #11152, 2.503068098927295537, 0.7853981634093413211 ) ; +#20275 = CARTESIAN_POINT ( 'NONE', ( -5.670114813667185949, 182.0317179319149261, 102.1523109898032828 ) ) ; +#20276 = ORIENTED_EDGE ( 'NONE', *, *, #10789, .T. ) ; +#20277 = ADVANCED_FACE ( 'NONE', ( #5920 ), #2855, .T. ) ; +#20278 = AXIS2_PLACEMENT_3D ( 'NONE', #13117, #9646, #2352 ) ; +#20279 = CARTESIAN_POINT ( 'NONE', ( 26.00345064650588256, 120.0893543522608269, 90.43463095281319397 ) ) ; +#20280 = CONICAL_SURFACE ( 'NONE', #37279, 2.503077409001481790, 0.7853981634551400193 ) ; +#20281 = DIRECTION ( 'NONE', ( 0.0006039748319390937474, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#20282 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4574, #35239, #22609, #3969, #35030, #4373, #16440, #29531, #28932, #32208 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20284 = CARTESIAN_POINT ( 'NONE', ( -42.70458103469926670, 67.79617006382294164, 322.0565592465368354 ) ) ; +#20283 = DIRECTION ( 'NONE', ( -0.0005884949961244357111, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#20285 = ORIENTED_EDGE ( 'NONE', *, *, #30889, .F. ) ; +#20286 = EDGE_CURVE ( 'NONE', #17411, #14482, #11156, .T. ) ; +#20287 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391913256 ) ) ; +#20288 = ORIENTED_EDGE ( 'NONE', *, *, #17037, .F. ) ; +#20289 = EDGE_CURVE ( 'NONE', #29223, #33670, #20307, .T. ) ; +#20290 = EDGE_CURVE ( 'NONE', #40179, #17419, #22279, .T. ) ; +#20291 = ORIENTED_EDGE ( 'NONE', *, *, #27232, .T. ) ; +#20292 = EDGE_CURVE ( 'NONE', #456, #14326, #23004, .T. ) ; +#20293 = LINE ( 'NONE', #17009, #17195 ) ; +#20294 = EDGE_CURVE ( 'NONE', #23937, #34665, #6402, .T. ) ; +#20295 = CARTESIAN_POINT ( 'NONE', ( 17.18127995227040117, 121.6259304897876774, 177.7629839600756156 ) ) ; +#20296 = DIRECTION ( 'NONE', ( 0.7066795775423997394, 4.436109046689753065E-15, -0.7075337268883338249 ) ) ; +#20297 = PLANE ( 'NONE', #18257 ) ; +#20298 = CARTESIAN_POINT ( 'NONE', ( 36.31598756814000240, 191.7186560094999948, 104.1922410006000064 ) ) ; +#20299 = VERTEX_POINT ( 'NONE', #24958 ) ; +#20300 = ORIENTED_EDGE ( 'NONE', *, *, #23613, .T. ) ; +#20301 = CARTESIAN_POINT ( 'NONE', ( -44.77033340054011745, 107.3146598463498691, 174.6956997662179560 ) ) ; +#20302 = ORIENTED_EDGE ( 'NONE', *, *, #9195, .F. ) ; +#20303 = ORIENTED_EDGE ( 'NONE', *, *, #15093, .T. ) ; +#20304 = CARTESIAN_POINT ( 'NONE', ( 5.667731215173129833, 181.6143669964321248, 104.1442412133662998 ) ) ; +#20305 = VECTOR ( 'NONE', #21853, 1000.000000000000227 ) ; +#20306 = CARTESIAN_POINT ( 'NONE', ( -38.27073585962602209, 118.2708731254052452, 89.71117186317353287 ) ) ; +#20307 = CIRCLE ( 'NONE', #26202, 4.499999385342085212 ) ; +#20308 = AXIS2_PLACEMENT_3D ( 'NONE', #6926, #28027, #15727 ) ; +#20309 = LINE ( 'NONE', #17637, #18285 ) ; +#20310 = ORIENTED_EDGE ( 'NONE', *, *, #31061, .T. ) ; +#20311 = CARTESIAN_POINT ( 'NONE', ( 39.00418697206374929, 118.8512999931317040, 89.67778981664979199 ) ) ; +#20312 = ADVANCED_FACE ( 'NONE', ( #26349 ), #35705, .F. ) ; +#20313 = CARTESIAN_POINT ( 'NONE', ( 6.028443089694566659, 134.2450043241766195, 93.72108952724657627 ) ) ; +#20314 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049013801, 181.0091974213876540, 104.5428127881306466 ) ) ; +#20315 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#20316 = VERTEX_POINT ( 'NONE', #25957 ) ; +#20317 = LINE ( 'NONE', #11134, #27129 ) ; +#20318 = CARTESIAN_POINT ( 'NONE', ( -12.63569525989105458, 131.0198822475661586, 89.90887598198150954 ) ) ; +#20319 = ORIENTED_EDGE ( 'NONE', *, *, #769, .T. ) ; +#20320 = EDGE_CURVE ( 'NONE', #12828, #28145, #13152, .T. ) ; +#20321 = PLANE ( 'NONE', #18203 ) ; +#20322 = VECTOR ( 'NONE', #37757, 1000.000000000000227 ) ; +#20323 = CARTESIAN_POINT ( 'NONE', ( -37.07468550886999736, 116.4345806408999948, 89.58399973487999546 ) ) ; +#20325 = ORIENTED_EDGE ( 'NONE', *, *, #34878, .T. ) ; +#20324 = EDGE_CURVE ( 'NONE', #29784, #38065, #30310, .T. ) ; +#20326 = AXIS2_PLACEMENT_3D ( 'NONE', #35690, #32655, #26948 ) ; +#20327 = ORIENTED_EDGE ( 'NONE', *, *, #5909, .T. ) ; +#20328 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#20329 = EDGE_CURVE ( 'NONE', #37303, #16617, #5907, .T. ) ; +#20330 = CARTESIAN_POINT ( 'NONE', ( -52.65110396967892115, 67.06234983503514968, 291.5903438827041896 ) ) ; +#20331 = CARTESIAN_POINT ( 'NONE', ( 28.46953594426098277, 131.0252485042709338, 89.88531577736306133 ) ) ; +#20332 = CARTESIAN_POINT ( 'NONE', ( -13.49923265964514307, 124.2402241865850669, 90.95213100867620426 ) ) ; +#20333 = ORIENTED_EDGE ( 'NONE', *, *, #30144, .T. ) ; +#20334 = ORIENTED_EDGE ( 'NONE', *, *, #20324, .T. ) ; +#20335 = ORIENTED_EDGE ( 'NONE', *, *, #16047, .T. ) ; +#20336 = VERTEX_POINT ( 'NONE', #29213 ) ; +#20337 = EDGE_CURVE ( 'NONE', #23280, #14032, #16599, .T. ) ; +#20338 = LINE ( 'NONE', #1530, #17808 ) ; +#20339 = CARTESIAN_POINT ( 'NONE', ( 2.704416956323000054, 209.1895506582999928, 73.41360722180999687 ) ) ; +#20340 = CARTESIAN_POINT ( 'NONE', ( 37.33701730692213516, 104.0256123824346446, 184.2143347311343859 ) ) ; +#20341 = VERTEX_POINT ( 'NONE', #13468 ) ; +#20342 = ORIENTED_EDGE ( 'NONE', *, *, #39955, .T. ) ; +#20343 = LINE ( 'NONE', #14021, #19951 ) ; +#20344 = CARTESIAN_POINT ( 'NONE', ( -32.54948526281216203, 154.4229389456382080, 204.0724398423583352 ) ) ; +#20345 = CARTESIAN_POINT ( 'NONE', ( 36.76761661513999968, 191.5224872912000080, 104.2108918073000012 ) ) ; +#20346 = CARTESIAN_POINT ( 'NONE', ( -26.00149624230000356, 120.7678355711999956, 87.55002952287999562 ) ) ; +#20347 = VERTEX_POINT ( 'NONE', #7716 ) ; +#20348 = DIRECTION ( 'NONE', ( 7.205774438685422002E-15, 0.9743700557921587402, 0.2249510932971556798 ) ) ; +#20349 = CARTESIAN_POINT ( 'NONE', ( 26.80352412410122653, 110.6131156702000027, 87.25159563508790939 ) ) ; +#20350 = ORIENTED_EDGE ( 'NONE', *, *, #28173, .T. ) ; +#20351 = CARTESIAN_POINT ( 'NONE', ( 0.6112267146314604993, 188.6153602092752806, 103.1978414123530428 ) ) ; +#20352 = CARTESIAN_POINT ( 'NONE', ( 14.17154134345668126, 176.0476639716964939, 102.8539302333655172 ) ) ; +#20353 = AXIS2_PLACEMENT_3D ( 'NONE', #35325, #28820, #34517 ) ; +#20354 = CARTESIAN_POINT ( 'NONE', ( 37.88647102489763796, 118.9430397943745135, 87.24490182366666602 ) ) ; +#20355 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; +#20356 = ORIENTED_EDGE ( 'NONE', *, *, #36409, .T. ) ; +#20357 = AXIS2_PLACEMENT_3D ( 'NONE', #36768, #30850, #25127 ) ; +#20358 = LINE ( 'NONE', #1559, #38941 ) ; +#20359 = CIRCLE ( 'NONE', #2754, 6.000000000000001776 ) ; +#20360 = CARTESIAN_POINT ( 'NONE', ( -4.037441717428633225, 144.1002716341167229, 93.43668138785120902 ) ) ; +#20361 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12034, #156, #30841, #18734 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20362 = LINE ( 'NONE', #5226, #23447 ) ; +#20363 = ORIENTED_EDGE ( 'NONE', *, *, #5340, .F. ) ; +#20364 = CARTESIAN_POINT ( 'NONE', ( 13.55367387944100521, 148.0748368286726873, 93.83050549135094798 ) ) ; +#20365 = ORIENTED_EDGE ( 'NONE', *, *, #26228, .F. ) ; +#20366 = CARTESIAN_POINT ( 'NONE', ( -25.87045016268000097, 191.8520160948000068, 104.0542010324000017 ) ) ; +#20367 = CARTESIAN_POINT ( 'NONE', ( 38.29411851305506076, 218.5902260770999987, 73.03537539447567895 ) ) ; +#20368 = CARTESIAN_POINT ( 'NONE', ( 26.15601811298000001, 191.6340342645000021, 103.7468180973999949 ) ) ; +#20369 = DIRECTION ( 'NONE', ( 0.0005884969506430524347, -0.2249510543435863097, 0.9743698870660195688 ) ) ; +#20370 = EDGE_CURVE ( 'NONE', #27000, #27115, #36638, .T. ) ; +#20371 = VERTEX_POINT ( 'NONE', #7113 ) ; +#20372 = UNCERTAINTY_MEASURE_WITH_UNIT (LENGTH_MEASURE( 1.000000000000000082E-05 ), #20638, 'distance_accuracy_value', 'NONE'); +#20373 = EDGE_CURVE ( 'NONE', #29818, #9665, #28805, .T. ) ; +#20374 = EDGE_CURVE ( 'NONE', #11012, #20941, #21569, .T. ) ; +#20375 = EDGE_CURVE ( 'NONE', #127, #38213, #36165, .T. ) ; +#20376 = CARTESIAN_POINT ( 'NONE', ( -22.78353008612967301, 154.0036580403303219, 95.56333016833679039 ) ) ; +#20377 = FACE_OUTER_BOUND ( 'NONE', #2581, .T. ) ; +#20378 = CARTESIAN_POINT ( 'NONE', ( 20.00135278145989659, 174.8851862048874182, 100.0162692476921649 ) ) ; +#20379 = CARTESIAN_POINT ( 'NONE', ( 20.14922697058586110, 211.0865878849932358, 73.21573723756705476 ) ) ; +#20380 = EDGE_CURVE ( 'NONE', #10977, #37463, #12293, .T. ) ; +#20381 = CARTESIAN_POINT ( 'NONE', ( -14.89127950026240654, 135.9758345030836892, 93.79122248673127160 ) ) ; +#20382 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#20383 = CARTESIAN_POINT ( 'NONE', ( 47.96253192634828366, 82.27946979429619034, 302.5295777741103507 ) ) ; +#20384 = LINE ( 'NONE', #20591, #33129 ) ; +#20385 = CARTESIAN_POINT ( 'NONE', ( -38.43507781192505490, 118.8935719617735458, 87.72377630256418968 ) ) ; +#20386 = ORIENTED_EDGE ( 'NONE', *, *, #13434, .T. ) ; +#20387 = ORIENTED_EDGE ( 'NONE', *, *, #19316, .T. ) ; +#20388 = CONICAL_SURFACE ( 'NONE', #21054, 3.003059068065875081, 0.7854054309186528915 ) ; +#20389 = EDGE_CURVE ( 'NONE', #1120, #34551, #31251, .T. ) ; +#20390 = CARTESIAN_POINT ( 'NONE', ( -40.45668859077597546, 220.4002261445999693, 73.08293890851697938 ) ) ; +#20391 = CIRCLE ( 'NONE', #15808, 47.49999999997262279 ) ; +#20392 = CARTESIAN_POINT ( 'NONE', ( 25.99285328132001283, 207.8686442202362343, 77.26134345908540979 ) ) ; +#20393 = EDGE_LOOP ( 'NONE', ( #39559, #2907, #8274, #2625 ) ) ; +#20394 = CARTESIAN_POINT ( 'NONE', ( 2.563994175896955774, 190.9709097722040099, 106.3045652864306874 ) ) ; +#20395 = VERTEX_POINT ( 'NONE', #32083 ) ; +#20396 = EDGE_CURVE ( 'NONE', #29495, #3941, #19067, .T. ) ; +#20397 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455648630811, -31.54510897440487938, 136.4474729010643443 ) ) ; +#20398 = CARTESIAN_POINT ( 'NONE', ( -3.169906973602109712, 126.7999172216492099, 88.92891361563410157 ) ) ; +#20399 = ORIENTED_EDGE ( 'NONE', *, *, #38791, .F. ) ; +#20400 = DIRECTION ( 'NONE', ( -0.0005884949961233868539, 0.2249510543439054988, -0.9743698870671265722 ) ) ; +#20401 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, -1.295171136338797037E-14 ) ) ; +#20402 = CARTESIAN_POINT ( 'NONE', ( -12.63503821882216194, 130.2039158256102951, 92.60614216895966422 ) ) ; +#20403 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#20404 = CARTESIAN_POINT ( 'NONE', ( 39.80650967021875175, 141.4494999055034725, 284.7279790684100931 ) ) ; +#20405 = ORIENTED_EDGE ( 'NONE', *, *, #30483, .T. ) ; +#20406 = VERTEX_POINT ( 'NONE', #1801 ) ; +#20407 = DIRECTION ( 'NONE', ( 0.0004269737726122545892, -0.7071067811864967245, 0.7071066522763517215 ) ) ; +#20408 = CARTESIAN_POINT ( 'NONE', ( -15.10537787283572619, 182.4218088933851050, 104.8563524828814764 ) ) ; +#20409 = VECTOR ( 'NONE', #27853, 1000.000000000000227 ) ; +#20410 = CARTESIAN_POINT ( 'NONE', ( 15.50147166925602527, 127.1825504195482353, 91.57172455528431954 ) ) ; +#20411 = DIRECTION ( 'NONE', ( -0.9999998268367796816, -0.0001323826439079756935, 0.0005734119341589764265 ) ) ; +#20412 = ORIENTED_EDGE ( 'NONE', *, *, #19851, .F. ) ; +#20413 = CIRCLE ( 'NONE', #2803, 4.499999998673683166 ) ; +#20414 = DIRECTION ( 'NONE', ( -0.7933530821293314217, -0.5932640870757661666, -0.1364866662427072774 ) ) ; +#20415 = CARTESIAN_POINT ( 'NONE', ( 15.10890892604210478, 182.4258086152457849, 104.8390273514353481 ) ) ; +#20416 = CARTESIAN_POINT ( 'NONE', ( -14.55132762993606477, 129.4747796237930118, 92.63223137880015656 ) ) ; +#20417 = AXIS2_PLACEMENT_3D ( 'NONE', #1062, #19854, #4326 ) ; +#20418 = FACE_OUTER_BOUND ( 'NONE', #26197, .T. ) ; +#20419 = EDGE_CURVE ( 'NONE', #21765, #19772, #11192, .T. ) ; +#20420 = EDGE_CURVE ( 'NONE', #11556, #23778, #33997, .T. ) ; +#20421 = CARTESIAN_POINT ( 'NONE', ( -40.96777089817398121, 130.0214998612392208, 92.77440595303380633 ) ) ; +#20422 = CARTESIAN_POINT ( 'NONE', ( 28.46953594426098277, 131.0252485042709338, 89.88531577736306133 ) ) ; +#20423 = CARTESIAN_POINT ( 'NONE', ( 37.73713366997999685, 118.5781713341999932, 87.34687967086999549 ) ) ; +#20424 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597599 ) ) ; +#20425 = CARTESIAN_POINT ( 'NONE', ( 26.13661543724075287, 121.9717845184987368, 87.79654014103218174 ) ) ; +#20426 = ORIENTED_EDGE ( 'NONE', *, *, #6305, .T. ) ; +#20427 = CARTESIAN_POINT ( 'NONE', ( -44.12429222051905242, 188.3338783572263253, 106.2387882118758995 ) ) ; +#20428 = DIRECTION ( 'NONE', ( -0.0006039748319375786833, -1.154910271103230591E-14, -0.9999998176071847045 ) ) ; +#20429 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#20430 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3214, #6679, #15690, #21648 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20431 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30523, #14976, #33562, #29708 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0005089247275372631900, 0.003508924730680751218 ), + .UNSPECIFIED. ) ; +#20432 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#20433 = ORIENTED_EDGE ( 'NONE', *, *, #15634, .F. ) ; +#20434 = ORIENTED_EDGE ( 'NONE', *, *, #2856, .F. ) ; +#20435 = ORIENTED_EDGE ( 'NONE', *, *, #28530, .F. ) ; +#20436 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#20437 = CIRCLE ( 'NONE', #24394, 2.499999999932184025 ) ; +#20438 = CARTESIAN_POINT ( 'NONE', ( -21.44693694427656538, 176.9185168219783009, 100.5107344958116897 ) ) ; +#20439 = VECTOR ( 'NONE', #32961, 1000.000000000000114 ) ; +#20440 = VERTEX_POINT ( 'NONE', #23681 ) ; +#20441 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#20442 = ADVANCED_FACE ( 'NONE', ( #20806, #2417, #23888 ), #29816, .F. ) ; +#20443 = AXIS2_PLACEMENT_3D ( 'NONE', #6021, #9498, #19281 ) ; +#20444 = CARTESIAN_POINT ( 'NONE', ( -36.63704418209608349, 161.0545052254310576, 189.2590029874323250 ) ) ; +#20445 = CARTESIAN_POINT ( 'NONE', ( 14.42196567089940551, 130.0116138273199624, 89.83080764171403132 ) ) ; +#20446 = CARTESIAN_POINT ( 'NONE', ( -35.83126867952999817, 112.8257052805000171, 87.67285600459000250 ) ) ; +#20447 = VERTEX_POINT ( 'NONE', #17919 ) ; +#20448 = CYLINDRICAL_SURFACE ( 'NONE', #15379, 2.000000000000001332 ) ; +#20449 = ORIENTED_EDGE ( 'NONE', *, *, #15506, .T. ) ; +#20450 = CARTESIAN_POINT ( 'NONE', ( 20.24340012504648456, 184.3478868362093124, 105.0315358237107262 ) ) ; +#20451 = CARTESIAN_POINT ( 'NONE', ( 31.94703631595417903, 124.0076240133925154, 152.6463441463639299 ) ) ; +#20452 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001011, 118.9382625071999939, 90.21260570929000266 ) ) ; +#20453 = CARTESIAN_POINT ( 'NONE', ( 23.36940079100686063, 177.7945392694463749, 100.6858723966742843 ) ) ; +#20454 = ORIENTED_EDGE ( 'NONE', *, *, #26594, .F. ) ; +#20455 = VERTEX_POINT ( 'NONE', #17720 ) ; +#20456 = CARTESIAN_POINT ( 'NONE', ( -25.88023834311999849, 191.5854047303000414, 104.0242687773999961 ) ) ; +#20457 = CARTESIAN_POINT ( 'NONE', ( 0.5757405066256999771, 188.5879547071000104, 103.1867946966000176 ) ) ; +#20458 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; +#20459 = EDGE_LOOP ( 'NONE', ( #9460, #29789, #17206, #17250 ) ) ; +#20460 = VERTEX_POINT ( 'NONE', #20597 ) ; +#20461 = DIRECTION ( 'NONE', ( 0.1943643238945209628, -0.07321898756438961764, 0.9781929714821464561 ) ) ; +#20462 = ORIENTED_EDGE ( 'NONE', *, *, #22665, .T. ) ; +#20463 = ORIENTED_EDGE ( 'NONE', *, *, #38650, .F. ) ; +#20464 = CONICAL_SURFACE ( 'NONE', #10071, 2.503093604169667863, 0.7853981634373672360 ) ; +#20465 = CIRCLE ( 'NONE', #27042, 4.500000000037911008 ) ; +#20466 = ORIENTED_EDGE ( 'NONE', *, *, #17795, .F. ) ; +#20467 = ORIENTED_EDGE ( 'NONE', *, *, #35122, .T. ) ; +#20468 = EDGE_CURVE ( 'NONE', #22597, #37703, #15109, .T. ) ; +#20469 = VECTOR ( 'NONE', #20706, 1000.000000000000227 ) ; +#20470 = ADVANCED_FACE ( 'NONE', ( #24303 ), #14885, .T. ) ; +#20471 = FACE_OUTER_BOUND ( 'NONE', #10394, .T. ) ; +#20472 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#20473 = CARTESIAN_POINT ( 'NONE', ( 23.69156854525416733, 130.3499206859899857, 92.81120348820789445 ) ) ; +#20474 = VECTOR ( 'NONE', #19237, 1000.000000000000000 ) ; +#20475 = VERTEX_POINT ( 'NONE', #32862 ) ; +#20476 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118781, 170.6398910447159949, 189.3556964435907446 ) ) ; +#20477 = ORIENTED_EDGE ( 'NONE', *, *, #23387, .F. ) ; +#20478 = CARTESIAN_POINT ( 'NONE', ( 28.44086645079000064, 124.7864354190000000, 91.35282799386999386 ) ) ; +#20479 = CARTESIAN_POINT ( 'NONE', ( -25.51924826026508342, 211.4175472833761376, 75.57438331478515181 ) ) ; +#20481 = CARTESIAN_POINT ( 'NONE', ( 10.03567519174115574, 167.9358719820149588, 100.9836731081407777 ) ) ; +#20480 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 132.6352630048999970, 91.80276880046000088 ) ) ; +#20482 = ORIENTED_EDGE ( 'NONE', *, *, #31125, .T. ) ; +#20483 = ORIENTED_EDGE ( 'NONE', *, *, #4353, .F. ) ; +#20484 = ORIENTED_EDGE ( 'NONE', *, *, #10052, .F. ) ; +#20485 = DIRECTION ( 'NONE', ( -8.673617379883984985E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#20486 = EDGE_CURVE ( 'NONE', #89, #31534, #2211, .T. ) ; +#20487 = CYLINDRICAL_SURFACE ( 'NONE', #2430, 5.999999999902005499 ) ; +#20488 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 81.56522751071939581, 291.5295797804316180 ) ) ; +#20489 = EDGE_LOOP ( 'NONE', ( #35611, #36318, #27522, #9577 ) ) ; +#20490 = AXIS2_PLACEMENT_3D ( 'NONE', #17690, #36715, #27555 ) ; +#20491 = VECTOR ( 'NONE', #37561, 1000.000000000000227 ) ; +#20492 = ORIENTED_EDGE ( 'NONE', *, *, #32395, .T. ) ; +#20493 = ORIENTED_EDGE ( 'NONE', *, *, #40436, .F. ) ; +#20494 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; +#20495 = CIRCLE ( 'NONE', #8074, 5.500000707771594222 ) ; +#20496 = FACE_OUTER_BOUND ( 'NONE', #30196, .T. ) ; +#20497 = EDGE_LOOP ( 'NONE', ( #12821, #23099, #13363, #10694 ) ) ; +#20498 = CARTESIAN_POINT ( 'NONE', ( -35.43294179687799783, 192.7873747655199850, 106.8799408643880042 ) ) ; +#20499 = CARTESIAN_POINT ( 'NONE', ( -38.44508659247977533, 118.4462124937045218, 89.70884898329646262 ) ) ; +#20500 = EDGE_CURVE ( 'NONE', #9773, #10082, #1586, .T. ) ; +#20501 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19096, #1099, #22794, #25670 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20502 = CARTESIAN_POINT ( 'NONE', ( 2.563981052588999887, 190.9709182148999957, 106.3045539368000050 ) ) ; +#20503 = ORIENTED_EDGE ( 'NONE', *, *, #37105, .F. ) ; +#20504 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; +#20505 = ADVANCED_FACE ( 'NONE', ( #39803 ), #11008, .T. ) ; +#20506 = CARTESIAN_POINT ( 'NONE', ( 39.76618942616960339, 163.8081586012825710, 187.7763762584039853 ) ) ; +#20507 = CARTESIAN_POINT ( 'NONE', ( 20.97958059557665678, 153.9356402334431095, 95.17909375711693087 ) ) ; +#20508 = LINE ( 'NONE', #29738, #16251 ) ; +#20509 = EDGE_LOOP ( 'NONE', ( #23227, #8088, #8713, #283 ) ) ; +#20510 = CARTESIAN_POINT ( 'NONE', ( 44.73086057231283519, 106.6863158914248402, 169.4405586320514487 ) ) ; +#20511 = EDGE_CURVE ( 'NONE', #5373, #30736, #2010, .T. ) ; +#20512 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17970, #30478, #39855, #8805, #11871, #36801, #21273, #33720, #33923, #3047, #9600, #18377, #22078, #576, #21875 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000038303, 0.3749999999999905076, 0.4374999999999594769, 0.4999999999999283906, 0.6249999999999291678, 0.6874999999999332756, 0.7499999999999372724, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20513 = ADVANCED_FACE ( 'NONE', ( #39602 ), #23468, .T. ) ; +#20514 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265220014, -0.1368326740407744824 ) ) ; +#20515 = DIRECTION ( 'NONE', ( -0.9999998268370088317, -0.0001323825148140369483, 0.0005734115644994438417 ) ) ; +#20516 = CIRCLE ( 'NONE', #18553, 2.500000000051350924 ) ; +#20517 = EDGE_CURVE ( 'NONE', #1633, #35236, #36085, .T. ) ; +#20518 = ADVANCED_FACE ( 'NONE', ( #18520 ), #16368, .T. ) ; +#20519 = VECTOR ( 'NONE', #40282, 1000.000000000000227 ) ; +#20520 = AXIS2_PLACEMENT_3D ( 'NONE', #30448, #27404, #33486 ) ; +#20521 = VERTEX_POINT ( 'NONE', #40408 ) ; +#20522 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32482, #23085, #16915, #19987, #26357, #7934, #23689, #32095, #987, #39403 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2498237635460164585, 0.4996475270920329170, 0.7494712906380494033, 0.9992950541840658341 ), + .UNSPECIFIED. ) ; +#20523 = FACE_OUTER_BOUND ( 'NONE', #29613, .T. ) ; +#20524 = VECTOR ( 'NONE', #12646, 1000.000000000000114 ) ; +#20526 = CARTESIAN_POINT ( 'NONE', ( 15.99970520780110483, 160.7332544674666508, 96.75156078672274873 ) ) ; +#20525 = PLANE ( 'NONE', #13527 ) ; +#20527 = ORIENTED_EDGE ( 'NONE', *, *, #34773, .F. ) ; +#20528 = FACE_OUTER_BOUND ( 'NONE', #31771, .T. ) ; +#20529 = VERTEX_POINT ( 'NONE', #2809 ) ; +#20530 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825997698160678, 0.0005734119005972442571 ) ) ; +#20531 = DIRECTION ( 'NONE', ( 0.0004270746993329993849, -0.7071067811864992780, 0.7071066522153991452 ) ) ; +#20532 = CARTESIAN_POINT ( 'NONE', ( 26.87765175238869730, 131.0250772092131228, 89.88625090952056951 ) ) ; +#20533 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971560406 ) ) ; +#20534 = EDGE_LOOP ( 'NONE', ( #21036, #16616, #30575, #169 ) ) ; +#20535 = ORIENTED_EDGE ( 'NONE', *, *, #14580, .T. ) ; +#20536 = CARTESIAN_POINT ( 'NONE', ( -42.84344863773063850, 120.8780380861919070, 92.13377048202671915 ) ) ; +#20537 = VERTEX_POINT ( 'NONE', #6657 ) ; +#20538 = ORIENTED_EDGE ( 'NONE', *, *, #18182, .F. ) ; +#20539 = DIRECTION ( 'NONE', ( 0.0005884949961246526600, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#20540 = EDGE_CURVE ( 'NONE', #16662, #10050, #12408, .T. ) ; +#20541 = CARTESIAN_POINT ( 'NONE', ( 19.31742904446021214, 125.1883107725499400, 178.1765085822854928 ) ) ; +#20542 = EDGE_LOOP ( 'NONE', ( #17366, #14847, #23528, #36496, #30152 ) ) ; +#20543 = ORIENTED_EDGE ( 'NONE', *, *, #20573, .T. ) ; +#20544 = CARTESIAN_POINT ( 'NONE', ( 20.24096834406000056, 201.9934486150999930, 90.46617277008999736 ) ) ; +#20545 = CARTESIAN_POINT ( 'NONE', ( -36.20356047594999893, 191.7540012393999973, 104.2845888805000101 ) ) ; +#20546 = CARTESIAN_POINT ( 'NONE', ( 37.37622315816000906, 191.1580451908000100, 103.8827374828999979 ) ) ; +#20547 = ORIENTED_EDGE ( 'NONE', *, *, #27017, .T. ) ; +#20548 = CARTESIAN_POINT ( 'NONE', ( -25.50343790679000122, 120.8386615232000167, 88.07942342773999655 ) ) ; +#20549 = AXIS2_PLACEMENT_3D ( 'NONE', #21611, #33652, #37723 ) ; +#20550 = ORIENTED_EDGE ( 'NONE', *, *, #29776, .F. ) ; +#20551 = CARTESIAN_POINT ( 'NONE', ( 46.04999121755292890, 184.7621468979810970, 107.4123344626420220 ) ) ; +#20552 = FACE_OUTER_BOUND ( 'NONE', #16797, .T. ) ; +#20553 = CARTESIAN_POINT ( 'NONE', ( -23.35929995763761369, 176.9091105951141571, 103.3088857729690488 ) ) ; +#20554 = EDGE_LOOP ( 'NONE', ( #34188, #30139, #39352, #7668 ) ) ; +#20555 = AXIS2_PLACEMENT_3D ( 'NONE', #5439, #36525, #20572 ) ; +#20556 = CONICAL_SURFACE ( 'NONE', #19893, 47.99999999999141664, 0.7853981633972882959 ) ; +#20557 = ADVANCED_FACE ( 'NONE', ( #3195 ), #34265, .F. ) ; +#20558 = CARTESIAN_POINT ( 'NONE', ( 0.6442863471694358912, 188.6132303553982865, 103.1973297295617442 ) ) ; +#20559 = FACE_OUTER_BOUND ( 'NONE', #5917, .T. ) ; +#20560 = VECTOR ( 'NONE', #31415, 1000.000000000000000 ) ; +#20561 = DIRECTION ( 'NONE', ( 0.0006039748319388572829, 3.099784637799882324E-15, 0.9999998176071847045 ) ) ; +#20562 = CARTESIAN_POINT ( 'NONE', ( 44.99461912816793330, 186.3824492941473352, 106.8827324323605268 ) ) ; +#20563 = ORIENTED_EDGE ( 'NONE', *, *, #5508, .T. ) ; +#20564 = CARTESIAN_POINT ( 'NONE', ( 15.50147166947062871, 184.4041534623167991, 104.7823749529912760 ) ) ; +#20565 = ADVANCED_FACE ( 'NONE', ( #30823 ), #4635, .F. ) ; +#20566 = CARTESIAN_POINT ( 'NONE', ( -25.99734782913206388, 118.8155664120999973, 94.28348731542583039 ) ) ; +#20567 = CARTESIAN_POINT ( 'NONE', ( 25.50832794965532457, 194.2771770615957507, 102.8828691708982035 ) ) ; +#20568 = ADVANCED_FACE ( 'NONE', ( #6070 ), #8572, .T. ) ; +#20569 = VERTEX_POINT ( 'NONE', #40014 ) ; +#20570 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366368657916, 137.4659008082770697, 177.5714312369256049 ) ) ; +#20571 = EDGE_LOOP ( 'NONE', ( #3453, #32616, #29455, #14279 ) ) ; +#20572 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971572064 ) ) ; +#20573 = EDGE_CURVE ( 'NONE', #33199, #11353, #13649, .T. ) ; +#20574 = FACE_OUTER_BOUND ( 'NONE', #30016, .T. ) ; +#20575 = CARTESIAN_POINT ( 'NONE', ( 25.42017281157999875, 191.1447232209999925, 104.4148045236999991 ) ) ; +#20576 = CARTESIAN_POINT ( 'NONE', ( 16.00178211024919861, 127.0692136201035680, 92.05841426505114100 ) ) ; +#20577 = ADVANCED_FACE ( 'NONE', ( #31028 ), #9754, .T. ) ; +#20578 = CARTESIAN_POINT ( 'NONE', ( -21.01972750631221132, 212.6267245168959903, 75.57113062347616506 ) ) ; +#20579 = CARTESIAN_POINT ( 'NONE', ( 30.08094848415407796, 173.6961895202413189, 152.7448404810986062 ) ) ; +#20580 = ORIENTED_EDGE ( 'NONE', *, *, #12544, .F. ) ; +#20581 = CARTESIAN_POINT ( 'NONE', ( 36.05442839919999898, 113.8881156701999942, 88.74600859430999833 ) ) ; +#20582 = CARTESIAN_POINT ( 'NONE', ( 18.08181496610683325, 152.6337752236594270, 184.7490501355361232 ) ) ; +#20583 = AXIS2_PLACEMENT_3D ( 'NONE', #24528, #31052, #3418 ) ; +#20584 = FACE_OUTER_BOUND ( 'NONE', #5730, .T. ) ; +#20586 = VECTOR ( 'NONE', #37361, 1000.000000000000227 ) ; +#20585 = CARTESIAN_POINT ( 'NONE', ( -75.43109585698152841, 195.4393986266174750, 195.0604493769935459 ) ) ; +#20587 = CARTESIAN_POINT ( 'NONE', ( 21.60217933682451985, 154.2468726602517393, 95.25057140358079266 ) ) ; +#20588 = FACE_OUTER_BOUND ( 'NONE', #4665, .T. ) ; +#20589 = CARTESIAN_POINT ( 'NONE', ( 37.19332676460864917, 118.8604558150308463, 122.9910815359075116 ) ) ; +#20590 = AXIS2_PLACEMENT_3D ( 'NONE', #22575, #28901, #37693 ) ; +#20591 = CARTESIAN_POINT ( 'NONE', ( -22.49964039506760471, 137.3544959182455045, 178.0533373667986439 ) ) ; +#20592 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #40043, #24538, #5086, #33301, #21468, #17549, #5295, #17753, #25740, #25538, #31060 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999995211608, 0.3749999999993379185, 0.4374999999992462696, 0.4687499999992686961, 0.4999999999992911226, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20593 = CARTESIAN_POINT ( 'NONE', ( -13.83205090698264605, 124.7811071226292938, 174.0455584457899079 ) ) ; +#20594 = CARTESIAN_POINT ( 'NONE', ( 21.98730234560195029, 115.2895908701552798, 90.25450505954673019 ) ) ; +#20595 = VERTEX_POINT ( 'NONE', #37354 ) ; +#20596 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971549859 ) ) ; +#20597 = CARTESIAN_POINT ( 'NONE', ( 17.15851712144672447, 126.2135305925408062, 179.0798665085958703 ) ) ; +#20598 = VERTEX_POINT ( 'NONE', #2618 ) ; +#20599 = CARTESIAN_POINT ( 'NONE', ( 5.663781961983408664, 181.7799031239528631, 101.7404227914676937 ) ) ; +#20600 = CARTESIAN_POINT ( 'NONE', ( 3.953345342120641259, 136.7756878582844706, 93.87799634107939539 ) ) ; +#20601 = ORIENTED_EDGE ( 'NONE', *, *, #28253, .T. ) ; +#20602 = CARTESIAN_POINT ( 'NONE', ( 13.51095425345201129, 187.6707999454940818, 106.0508869016509266 ) ) ; +#20603 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#20604 = ORIENTED_EDGE ( 'NONE', *, *, #2853, .F. ) ; +#20605 = CARTESIAN_POINT ( 'NONE', ( 36.27208580333611110, 191.8965914794161449, 106.3926531859080171 ) ) ; +#20606 = EDGE_CURVE ( 'NONE', #30446, #13611, #9352, .T. ) ; +#20607 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9131, #20995, #15464, #40186 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20608 = EDGE_CURVE ( 'NONE', #21069, #28767, #27376, .T. ) ; +#20609 = VECTOR ( 'NONE', #33065, 1000.000000000000114 ) ; +#20610 = DIRECTION ( 'NONE', ( -0.0001358700408348381271, -0.9743680519818410657, -0.2249597315442128931 ) ) ; +#20612 = EDGE_CURVE ( 'NONE', #27638, #7714, #36616, .T. ) ; +#20611 = CARTESIAN_POINT ( 'NONE', ( 21.83022412997393502, 182.7623874074516266, 102.3469123272103189 ) ) ; +#20613 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564847 ) ) ; +#20614 = CARTESIAN_POINT ( 'NONE', ( -2.954034027524032879, 205.1071153523706698, 76.10666676075513237 ) ) ; +#20615 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#20616 = ORIENTED_EDGE ( 'NONE', *, *, #5400, .T. ) ; +#20617 = ORIENTED_EDGE ( 'NONE', *, *, #62, .F. ) ; +#20618 = CARTESIAN_POINT ( 'NONE', ( 39.79355934349000989, 120.0246790264999959, 87.73041059682999787 ) ) ; +#20619 = CARTESIAN_POINT ( 'NONE', ( -28.46708276390721792, 128.4693973224412105, 89.84276394412744082 ) ) ; +#20620 = CARTESIAN_POINT ( 'NONE', ( 28.52919418227002879, 125.2871234584923883, 88.56050369811191558 ) ) ; +#20621 = AXIS2_PLACEMENT_3D ( 'NONE', #22483, #12267, #21879 ) ; +#20622 = CARTESIAN_POINT ( 'NONE', ( 22.54464659634000157, 110.3681964162000071, 162.9824824849000322 ) ) ; +#20623 = AXIS2_PLACEMENT_3D ( 'NONE', #16430, #7227, #19694 ) ; +#20624 = ORIENTED_EDGE ( 'NONE', *, *, #28033, .T. ) ; +#20625 = CARTESIAN_POINT ( 'NONE', ( 39.31997709954917042, 182.6349382312036767, 104.8726857259417926 ) ) ; +#20626 = CARTESIAN_POINT ( 'NONE', ( -42.30728356964600323, 121.5171895888447722, 91.19632820234058102 ) ) ; +#20627 = DIRECTION ( 'NONE', ( 0.0005884949961249847511, -0.2249510543439063592, 0.9743698870671262391 ) ) ; +#20628 = CARTESIAN_POINT ( 'NONE', ( -2.954034027429888631, 205.1071153524133308, 76.10666676077315174 ) ) ; +#20629 = CARTESIAN_POINT ( 'NONE', ( -2.937264483575730001, 191.5260295967991340, 103.8719657111370367 ) ) ; +#20630 = ADVANCED_FACE ( 'NONE', ( #40207 ), #12020, .T. ) ; +#20631 = CARTESIAN_POINT ( 'NONE', ( 20.00175897098971589, 118.8155681873422651, 90.25573236258343002 ) ) ; +#20632 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#20633 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3913, #15588, #34573, #34966, #31542, #12517, #3503, #19451, #12940, #9875 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20634 = FACE_OUTER_BOUND ( 'NONE', #22638, .T. ) ; +#20635 = DIRECTION ( 'NONE', ( -0.7856637149787866203, 0.6186538021912836305, 0.000000000000000000 ) ) ; +#20636 = CARTESIAN_POINT ( 'NONE', ( -2.954012481561790970, 209.1419323005786737, 76.14255792608456375 ) ) ; +#20637 = EDGE_CURVE ( 'NONE', #6941, #19724, #37747, .T. ) ; +#20638 =( LENGTH_UNIT ( ) NAMED_UNIT ( * ) SI_UNIT ( .MILLI., .METRE. ) ); +#20639 = DIRECTION ( 'NONE', ( -2.580909394681725950E-08, 0.9743700499795614478, 0.2249511184742725434 ) ) ; +#20640 = ORIENTED_EDGE ( 'NONE', *, *, #17551, .T. ) ; +#20641 = LINE ( 'NONE', #32906, #25088 ) ; +#20642 = DIRECTION ( 'NONE', ( 0.0006039748319395906373, 1.314021223879979485E-14, 0.9999998176071844824 ) ) ; +#20643 = CARTESIAN_POINT ( 'NONE', ( 32.36187368851994961, 209.7096486318000075, 76.03895886878429167 ) ) ; +#20644 = CARTESIAN_POINT ( 'NONE', ( -20.38344128331733174, 116.5964058994408674, 87.28009537979973231 ) ) ; +#20645 = CONICAL_SURFACE ( 'NONE', #3010, 2.503093604169667863, 0.7853981634373672360 ) ; +#20646 = LINE ( 'NONE', #17564, #36973 ) ; +#20647 = AXIS2_PLACEMENT_3D ( 'NONE', #35037, #9945, #7049 ) ; +#20648 = ORIENTED_EDGE ( 'NONE', *, *, #23038, .T. ) ; +#20649 = VERTEX_POINT ( 'NONE', #24504 ) ; +#20650 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#20651 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23691, #30022, #29423, #32484, #8143, #35715, #11217, #1394, #4248, #23087, #8356, #35511, #20605, #33073, #11410, #20193, #1599, #26972, #7936, #16917, #16726, #29224, #14085, #7524, #13871, #26359, #38797, #7726, #26562, #32683 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 1, 1, 2, 2, 2, 2, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.06250000000189853688, 0.1250000000037970738, 0.1875000000056956106, 0.2187500000066624761, 0.2343750000071459227, 0.2421875000073611395, 0.2460937500074432405, 0.2500000000075253137, 0.3750000000075452422, 0.4375000000075314199, 0.4687500000075252027, 0.4843750000075221496, 0.4921875000075311424, 0.4960937500075226492, 0.4980468750075085493, 0.5000000000074944495, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20652 = ORIENTED_EDGE ( 'NONE', *, *, #32799, .T. ) ; +#20653 = CARTESIAN_POINT ( 'NONE', ( 77.66418106072950422, 192.0495531737880697, 194.3144031859467020 ) ) ; +#20654 = AXIS2_PLACEMENT_3D ( 'NONE', #22880, #13470, #34505 ) ; +#20655 = DIRECTION ( 'NONE', ( 0.7933533405432852126, -0.5930537065887689918, -0.1373964269918706016 ) ) ; +#20656 = AXIS2_PLACEMENT_3D ( 'NONE', #27034, #18193, #12088 ) ; +#20657 = ORIENTED_EDGE ( 'NONE', *, *, #16538, .F. ) ; +#20658 = EDGE_LOOP ( 'NONE', ( #26482, #5162, #15595, #17667 ) ) ; +#20659 = CARTESIAN_POINT ( 'NONE', ( -15.99998595512920652, 185.9065961375156348, 102.5825112407314634 ) ) ; +#20660 = DIRECTION ( 'NONE', ( 0.0005884949961156549746, -0.2249510543439098842, 0.9743698870671255730 ) ) ; +#20661 = CARTESIAN_POINT ( 'NONE', ( 20.16571866901157151, 193.9703124975374067, 102.7561131839733122 ) ) ; +#20662 = CARTESIAN_POINT ( 'NONE', ( -37.42772058735000229, 118.3648470007000100, 87.39136188095001501 ) ) ; +#20663 = ORIENTED_EDGE ( 'NONE', *, *, #13267, .F. ) ; +#20664 = CARTESIAN_POINT ( 'NONE', ( -42.07083071865692858, 121.3276643233232619, 92.82055031282301627 ) ) ; +#20665 = EDGE_CURVE ( 'NONE', #19923, #372, #20973, .T. ) ; +#20666 = VERTEX_POINT ( 'NONE', #15287 ) ; +#20668 = EDGE_CURVE ( 'NONE', #13982, #1155, #31836, .T. ) ; +#20667 = CARTESIAN_POINT ( 'NONE', ( 16.55946513390808406, 121.8573583107191780, 177.5776958584335148 ) ) ; +#20669 = LINE ( 'NONE', #11470, #6391 ) ; +#20670 = EDGE_CURVE ( 'NONE', #1120, #37138, #25909, .T. ) ; +#20671 = FACE_OUTER_BOUND ( 'NONE', #11980, .T. ) ; +#20672 = CARTESIAN_POINT ( 'NONE', ( 39.70674893776387648, 114.9516458920610660, 150.7368254606779772 ) ) ; +#20673 = ORIENTED_EDGE ( 'NONE', *, *, #29904, .F. ) ; +#20674 = CARTESIAN_POINT ( 'NONE', ( -2.620399866750759532, 189.8256140888599930, 103.4746636074519870 ) ) ; +#20675 = CARTESIAN_POINT ( 'NONE', ( 0.5625186772154999737, 188.8757079055000077, 103.5281422730000003 ) ) ; +#20676 = CARTESIAN_POINT ( 'NONE', ( -35.84664934362761812, 191.3612728695171654, 106.9073814223122838 ) ) ; +#20677 = EDGE_CURVE ( 'NONE', #11101, #14526, #13022, .T. ) ; +#20678 = VECTOR ( 'NONE', #28205, 1000.000000000000114 ) ; +#20679 = EDGE_LOOP ( 'NONE', ( #20801, #19350, #27648, #23619 ) ) ; +#20680 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265227786, 0.1368326740407719844 ) ) ; +#20681 = CONICAL_SURFACE ( 'NONE', #26557, 2.502986411962893953, 0.7853981633941236051 ) ; +#20682 = ORIENTED_EDGE ( 'NONE', *, *, #6435, .F. ) ; +#20683 = CIRCLE ( 'NONE', #19358, 4.500000000175836234 ) ; +#20684 = ADVANCED_FACE ( 'NONE', ( #35261 ), #10525, .F. ) ; +#20685 = VECTOR ( 'NONE', #40159, 1000.000000000000114 ) ; +#20686 = VERTEX_POINT ( 'NONE', #10363 ) ; +#20687 = ORIENTED_EDGE ( 'NONE', *, *, #15330, .F. ) ; +#20688 = CARTESIAN_POINT ( 'NONE', ( 3.062737380639022344, 196.5784460000043055, 103.8732377138169483 ) ) ; +#20689 = CARTESIAN_POINT ( 'NONE', ( -20.01904012474069106, 206.5436284133448055, 74.17009909478734642 ) ) ; +#20690 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#20691 = EDGE_CURVE ( 'NONE', #8706, #31838, #35293, .T. ) ; +#20692 = ORIENTED_EDGE ( 'NONE', *, *, #577, .T. ) ; +#20693 = LINE ( 'NONE', #20068, #29094 ) ; +#20694 = ORIENTED_EDGE ( 'NONE', *, *, #10229, .F. ) ; +#20695 = CARTESIAN_POINT ( 'NONE', ( 25.56568947770999856, 121.0913649998000068, 90.15922698159999982 ) ) ; +#20696 = LINE ( 'NONE', #4948, #37829 ) ; +#20698 = PLANE ( 'NONE', #27302 ) ; +#20697 = CARTESIAN_POINT ( 'NONE', ( 44.41839271451227233, 188.4409858425211155, 106.0389898025652684 ) ) ; +#20699 = VERTEX_POINT ( 'NONE', #35658 ) ; +#20700 = ORIENTED_EDGE ( 'NONE', *, *, #39876, .F. ) ; +#20701 = AXIS2_PLACEMENT_3D ( 'NONE', #22269, #28397, #14213 ) ; +#20702 = CARTESIAN_POINT ( 'NONE', ( -36.01025967986358012, 192.1075852240773827, 104.4279189550095168 ) ) ; +#20703 = AXIS2_PLACEMENT_3D ( 'NONE', #14329, #39450, #30070 ) ; +#20704 = CONICAL_SURFACE ( 'NONE', #4376, 4.999999999982071230, 0.7853981633822315622 ) ; +#20705 = ORIENTED_EDGE ( 'NONE', *, *, #31850, .T. ) ; +#20706 = DIRECTION ( 'NONE', ( 0.0001358647818257961324, 0.9743700622685637081, 0.2249510242153081319 ) ) ; +#20707 = LINE ( 'NONE', #27070, #38975 ) ; +#20708 = CARTESIAN_POINT ( 'NONE', ( 13.50176625667807428, 160.0671410552039333, 99.67807866355113333 ) ) ; +#20709 = CARTESIAN_POINT ( 'NONE', ( 36.11507279325000042, 191.5161335024000095, 103.8351628704999996 ) ) ; +#20710 = ORIENTED_EDGE ( 'NONE', *, *, #30044, .T. ) ; +#20711 = ORIENTED_EDGE ( 'NONE', *, *, #33811, .F. ) ; +#20712 = EDGE_LOOP ( 'NONE', ( #29360, #35800, #21297, #25962 ) ) ; +#20713 = ADVANCED_FACE ( 'NONE', ( #4189 ), #25709, .T. ) ; +#20714 = CARTESIAN_POINT ( 'NONE', ( -35.44629553178003079, 0.000000000000000000, 90.28919351349927069 ) ) ; +#20715 = EDGE_CURVE ( 'NONE', #30682, #11066, #27540, .T. ) ; +#20716 = CARTESIAN_POINT ( 'NONE', ( 15.85327786988247745, 186.7325363318280722, 102.7539513733114802 ) ) ; +#20717 = ORIENTED_EDGE ( 'NONE', *, *, #26774, .F. ) ; +#20718 = CARTESIAN_POINT ( 'NONE', ( 30.06787517242528551, 135.1370919582721228, 91.12677150993297914 ) ) ; +#20719 = EDGE_LOOP ( 'NONE', ( #21812, #34904, #1326, #28014 ) ) ; +#20720 = CARTESIAN_POINT ( 'NONE', ( 2.897653083742676383, 190.9155335423768349, 106.6359108618391645 ) ) ; +#20721 = VERTEX_POINT ( 'NONE', #13619 ) ; +#20722 = CARTESIAN_POINT ( 'NONE', ( -20.51956765322097453, 208.6217303766487419, 73.70372706148434361 ) ) ; +#20723 = DIRECTION ( 'NONE', ( -0.0005884949961245237483, 0.2249510543439061649, -0.9743698870671263501 ) ) ; +#20724 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1819, #8371, #39626, #23295 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20725 = FACE_OUTER_BOUND ( 'NONE', #33759, .T. ) ; +#20726 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#20727 = VECTOR ( 'NONE', #2123, 1000.000000000000000 ) ; +#20728 = EDGE_LOOP ( 'NONE', ( #22946, #11279, #34266, #17605 ) ) ; +#20729 = DIRECTION ( 'NONE', ( -0.0005884949954653724124, 0.2249971753701230093, -0.9743592380375456496 ) ) ; +#20730 = AXIS2_PLACEMENT_3D ( 'NONE', #36226, #14576, #2509 ) ; +#20731 = CARTESIAN_POINT ( 'NONE', ( 22.99181599359000217, 213.5902260771004819, 75.54481431629028521 ) ) ; +#20732 = EDGE_CURVE ( 'NONE', #17419, #15229, #32231, .T. ) ; +#20733 = VERTEX_POINT ( 'NONE', #19339 ) ; +#20734 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971562904 ) ) ; +#20735 = CARTESIAN_POINT ( 'NONE', ( 15.93316958989016108, 160.0956563697703245, 96.60429370500047241 ) ) ; +#20736 = ORIENTED_EDGE ( 'NONE', *, *, #6537, .F. ) ; +#20737 = ORIENTED_EDGE ( 'NONE', *, *, #22290, .T. ) ; +#20738 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387284797 ) ) ; +#20739 = VERTEX_POINT ( 'NONE', #31633 ) ; +#20740 = CARTESIAN_POINT ( 'NONE', ( 20.00025828646017345, 174.5279639952516106, 99.93388581131628712 ) ) ; +#20741 = EDGE_CURVE ( 'NONE', #11269, #14324, #26850, .T. ) ; +#20742 = CARTESIAN_POINT ( 'NONE', ( 25.50924666640047178, 191.9759150222000130, 104.4060420921210692 ) ) ; +#20743 = CARTESIAN_POINT ( 'NONE', ( 6.035971952557307674, 174.6806538430182911, 103.0595719845621261 ) ) ; +#20744 = ORIENTED_EDGE ( 'NONE', *, *, #16923, .F. ) ; +#20745 = EDGE_LOOP ( 'NONE', ( #226, #28135 ) ) ; +#20746 = CARTESIAN_POINT ( 'NONE', ( -37.68439733255148383, 188.7463803737940395, 106.3301322885044016 ) ) ; +#20747 = EDGE_LOOP ( 'NONE', ( #37801, #18266, #13620, #26239 ) ) ; +#20748 = ORIENTED_EDGE ( 'NONE', *, *, #20670, .F. ) ; +#20749 = CARTESIAN_POINT ( 'NONE', ( 12.63456555637604772, 128.5879888860239078, 89.32908754111066685 ) ) ; +#20750 = CARTESIAN_POINT ( 'NONE', ( 2.941287612453000300, 209.7096559091000074, 73.05672761937999837 ) ) ; +#20751 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#20752 = ORIENTED_EDGE ( 'NONE', *, *, #5855, .F. ) ; +#20753 = CONICAL_SURFACE ( 'NONE', #3127, 4.999999999934928496, 0.7853981633665815254 ) ; +#20754 = ORIENTED_EDGE ( 'NONE', *, *, #4073, .F. ) ; +#20755 = CYLINDRICAL_SURFACE ( 'NONE', #2351, 6.000000000000001776 ) ; +#20756 = ADVANCED_FACE ( 'NONE', ( #16665 ), #5277, .F. ) ; +#20757 = CARTESIAN_POINT ( 'NONE', ( -36.19862354458000198, 191.7578647985999964, 104.2851651960999959 ) ) ; +#20758 = CARTESIAN_POINT ( 'NONE', ( 38.06062437970000190, 191.5239802229999952, 104.5086379071999971 ) ) ; +#20759 = EDGE_CURVE ( 'NONE', #21867, #15824, #9889, .T. ) ; +#20760 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20002, #13290, #28627, #16527 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( -0.0005424209979737538209, 0.0007183273991515231899 ), + .UNSPECIFIED. ) ; +#20761 = CARTESIAN_POINT ( 'NONE', ( -25.50098156286000162, 120.6553366659000091, 88.03708033630999807 ) ) ; +#20762 = CONICAL_SURFACE ( 'NONE', #12283, 2.503093757893994464, 0.7853981633779187899 ) ; +#20763 = ADVANCED_FACE ( 'NONE', ( #32428 ), #16075, .F. ) ; +#20764 = ORIENTED_EDGE ( 'NONE', *, *, #6616, .T. ) ; +#20765 = CARTESIAN_POINT ( 'NONE', ( 3.882702609227124846, 148.9606115484772602, 129.9617790688552077 ) ) ; +#20766 = ORIENTED_EDGE ( 'NONE', *, *, #14189, .F. ) ; +#20767 = CARTESIAN_POINT ( 'NONE', ( 26.00773540302725451, 191.9759150222000130, 101.9057393198873882 ) ) ; +#20768 = LINE ( 'NONE', #8304, #12377 ) ; +#20769 = ORIENTED_EDGE ( 'NONE', *, *, #24206, .T. ) ; +#20770 = CARTESIAN_POINT ( 'NONE', ( -6.037342800704852408, 134.5082041216288644, 93.56253848326802824 ) ) ; +#20771 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#20772 = CARTESIAN_POINT ( 'NONE', ( 28.46561152637904257, 183.4536495838093231, 105.0682559342871798 ) ) ; +#20773 = CARTESIAN_POINT ( 'NONE', ( 44.88097455134456482, 186.3872722715140355, 107.5207334959314807 ) ) ; +#20774 = ORIENTED_EDGE ( 'NONE', *, *, #31268, .F. ) ; +#20775 = DIRECTION ( 'NONE', ( 0.0005884949961219661154, -0.2249510543439071364, 0.9743698870671262391 ) ) ; +#20776 = CARTESIAN_POINT ( 'NONE', ( -76.10807331611901816, 155.7750440820818199, 98.22815292147129185 ) ) ; +#20777 = CARTESIAN_POINT ( 'NONE', ( -15.99985838160595719, 147.3843139169566712, 93.68908089291861074 ) ) ; +#20778 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24834, #37479, #30954, #21957 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20779 = ORIENTED_EDGE ( 'NONE', *, *, #3901, .F. ) ; +#20780 = FACE_OUTER_BOUND ( 'NONE', #31948, .T. ) ; +#20781 = ORIENTED_EDGE ( 'NONE', *, *, #19905, .T. ) ; +#20782 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971571509 ) ) ; +#20783 = CARTESIAN_POINT ( 'NONE', ( -35.78841217721779344, 209.7096535896600358, 75.74678653814358142 ) ) ; +#20784 = CARTESIAN_POINT ( 'NONE', ( 25.62658393337000007, 191.8386319365000077, 104.2890221055999973 ) ) ; +#20785 = CARTESIAN_POINT ( 'NONE', ( -16.53460274203917635, 121.8354022778151204, 177.5673403339679055 ) ) ; +#20786 = LINE ( 'NONE', #27150, #30406 ) ; +#20787 = CARTESIAN_POINT ( 'NONE', ( 30.06878009388999473, 135.2977368436336292, 91.38385643049517171 ) ) ; +#20788 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#20789 = EDGE_LOOP ( 'NONE', ( #20535, #12205, #22867, #15259 ) ) ; +#20790 = CIRCLE ( 'NONE', #3150, 2.250000000025644820 ) ; +#20791 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971561239 ) ) ; +#20792 = CARTESIAN_POINT ( 'NONE', ( 20.08022773305264863, 175.2265315334001912, 100.0950274021143542 ) ) ; +#20793 = CARTESIAN_POINT ( 'NONE', ( 5.659893952243699289, 181.0147214850249782, 104.5189528120545646 ) ) ; +#20794 = EDGE_CURVE ( 'NONE', #25434, #7776, #34857, .T. ) ; +#20795 = CARTESIAN_POINT ( 'NONE', ( 41.43279363010753258, 73.81335444380819411, 323.3949191073975271 ) ) ; +#20796 = CARTESIAN_POINT ( 'NONE', ( 0.04427648338465999672, 211.2500000000000000, 73.30847738610999897 ) ) ; +#20797 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2490, #2700, #31101, #27463, #8832, #20885 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.0009283347615722905340, 0.001856669523144581068 ), + .UNSPECIFIED. ) ; +#20798 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858958, 183.1686750955933576, 104.5300206044594091 ) ) ; +#20799 = CARTESIAN_POINT ( 'NONE', ( 37.96499115479794284, 190.9636352758437567, 106.2831835360932615 ) ) ; +#20800 = CARTESIAN_POINT ( 'NONE', ( 22.53004187958038784, 115.1395609704796641, 90.25417725846811834 ) ) ; +#20801 = ORIENTED_EDGE ( 'NONE', *, *, #20085, .T. ) ; +#20802 = ORIENTED_EDGE ( 'NONE', *, *, #947, .T. ) ; +#20803 = CARTESIAN_POINT ( 'NONE', ( 3.776208428536367290, 144.1607590108100396, 93.18099764601012680 ) ) ; +#20804 = EDGE_CURVE ( 'NONE', #31462, #19997, #19928, .T. ) ; +#20805 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1554, #30185, #20354, #36308 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20806 = FACE_BOUND ( 'NONE', #2850, .T. ) ; +#20807 = EDGE_LOOP ( 'NONE', ( #38219, #10823, #37540, #21575 ) ) ; +#20808 = DIRECTION ( 'NONE', ( 0.0005884949961209279918, -0.2249510543439041388, 0.9743698870671267942 ) ) ; +#20810 = ADVANCED_FACE ( 'NONE', ( #22635 ), #35059, .F. ) ; +#20809 = CARTESIAN_POINT ( 'NONE', ( -22.60121221446328121, 115.1131394343234859, 90.28143540504643738 ) ) ; +#20811 = EDGE_CURVE ( 'NONE', #18343, #25248, #25401, .T. ) ; +#20812 = VERTEX_POINT ( 'NONE', #33011 ) ; +#20813 = CARTESIAN_POINT ( 'NONE', ( -38.39707737110000352, 119.0972084867999996, 87.58953676641999664 ) ) ; +#20814 = EDGE_CURVE ( 'NONE', #2286, #28821, #18699, .T. ) ; +#20815 = AXIS2_PLACEMENT_3D ( 'NONE', #16562, #20037, #28660 ) ; +#20816 = ADVANCED_FACE ( 'NONE', ( #14423 ), #1298, .F. ) ; +#20817 = CARTESIAN_POINT ( 'NONE', ( -31.95188145317385420, 152.7252871959512106, 28.25650152248850944 ) ) ; +#20818 = VERTEX_POINT ( 'NONE', #7671 ) ; +#20819 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560129 ) ) ; +#20820 = AXIS2_PLACEMENT_3D ( 'NONE', #33745, #21699, #6336 ) ; +#20821 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 3.780719906273090593E-12, 291.5295797804326980 ) ) ; +#20822 = AXIS2_PLACEMENT_3D ( 'NONE', #3520, #3733, #31970 ) ; +#20823 = CARTESIAN_POINT ( 'NONE', ( 12.64700864260225366, 177.1180462903230364, 103.6150826217330803 ) ) ; +#20824 = CARTESIAN_POINT ( 'NONE', ( 3.534206243108678702, 168.5015396740323581, 98.55243403413919623 ) ) ; +#20825 = AXIS2_PLACEMENT_3D ( 'NONE', #24532, #30046, #20838 ) ; +#20826 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; +#20827 = ORIENTED_EDGE ( 'NONE', *, *, #2120, .F. ) ; +#20828 = CARTESIAN_POINT ( 'NONE', ( 38.13084791448000033, 119.4318491095000070, 87.14044217235999668 ) ) ; +#20829 = PLANE ( 'NONE', #20520 ) ; +#20830 = CARTESIAN_POINT ( 'NONE', ( -15.49970618539471268, 185.7934281236995844, 103.0692296848312282 ) ) ; +#20831 = VERTEX_POINT ( 'NONE', #30367 ) ; +#20832 = CARTESIAN_POINT ( 'NONE', ( -20.51745969899640087, 207.4083551867479116, 77.09396086730279762 ) ) ; +#20833 = ORIENTED_EDGE ( 'NONE', *, *, #21789, .F. ) ; +#20834 = CARTESIAN_POINT ( 'NONE', ( 15.66829157622652602, 173.9153742532822662, 102.5318555933223479 ) ) ; +#20835 = CARTESIAN_POINT ( 'NONE', ( -43.29012348651439623, 120.5557648100765249, 92.00614762530858570 ) ) ; +#20836 = PLANE ( 'NONE', #30049 ) ; +#20837 = DIRECTION ( 'NONE', ( 0.0003164010435218795225, -0.8480480961507480542, 0.5299191697848559812 ) ) ; +#20838 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971574562 ) ) ; +#20839 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21747, #12518, #31343, #5987 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20840 = FACE_OUTER_BOUND ( 'NONE', #12425, .T. ) ; +#20841 = AXIS2_PLACEMENT_3D ( 'NONE', #38363, #538, #940 ) ; +#20842 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#20843 = CARTESIAN_POINT ( 'NONE', ( 38.70942909611000005, 119.0583547086000067, 90.11453506928999957 ) ) ; +#20844 = ORIENTED_EDGE ( 'NONE', *, *, #25447, .T. ) ; +#20845 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; +#20846 = CARTESIAN_POINT ( 'NONE', ( -20.50037936456179821, 118.1134456052949560, 87.78011095654957785 ) ) ; +#20847 = EDGE_CURVE ( 'NONE', #29235, #21316, #15601, .T. ) ; +#20848 = DIRECTION ( 'NONE', ( 0.0006039748319392653766, -1.164951251755207723E-15, 0.9999998176071847045 ) ) ; +#20849 = CARTESIAN_POINT ( 'NONE', ( -20.00111550347676115, 117.9148692135038488, 87.27986446460897696 ) ) ; +#20850 = AXIS2_PLACEMENT_3D ( 'NONE', #29906, #29706, #26646 ) ; +#20851 = VECTOR ( 'NONE', #18049, 1000.000000000000114 ) ; +#20852 = CARTESIAN_POINT ( 'NONE', ( -42.84985448536668429, 114.0190474468247146, 121.9016368595544151 ) ) ; +#20853 = VERTEX_POINT ( 'NONE', #17671 ) ; +#20854 = ORIENTED_EDGE ( 'NONE', *, *, #14827, .F. ) ; +#20855 = CARTESIAN_POINT ( 'NONE', ( -16.53681909317384324, 122.5194902194745055, 174.6067105814985609 ) ) ; +#20856 = EDGE_CURVE ( 'NONE', #654, #14670, #964, .T. ) ; +#20857 = ORIENTED_EDGE ( 'NONE', *, *, #16949, .F. ) ; +#20858 = DIRECTION ( 'NONE', ( 0.7933533411653073131, 0.5931840316265220014, 0.1368326740407738717 ) ) ; +#20859 = EDGE_CURVE ( 'NONE', #11205, #27587, #2617, .T. ) ; +#20860 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971570121 ) ) ; +#20861 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26235, #4329, #11485, #38668, #16798, #1678, #14166, #29290, #39078, #17400, #23550, #23973 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000033307, 0.5000000000000066613, 0.6250000000000014433, 0.7499999999999962252, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20862 = CARTESIAN_POINT ( 'NONE', ( 17.08567597318895892, 152.1079231434187591, 183.8451549712952442 ) ) ; +#20863 = CARTESIAN_POINT ( 'NONE', ( 29.77977082001254061, 126.9465717062777372, 89.45601244832610632 ) ) ; +#20864 = ORIENTED_EDGE ( 'NONE', *, *, #37881, .T. ) ; +#20865 = CARTESIAN_POINT ( 'NONE', ( -0.4373761302338000645, 189.0000000000009095, 103.6849941534999999 ) ) ; +#20866 = ADVANCED_FACE ( 'NONE', ( #23423 ), #29559, .F. ) ; +#20867 = PLANE ( 'NONE', #36838 ) ; +#20868 = DIRECTION ( 'NONE', ( -0.7947985590179719173, 0.5913221741348984040, 0.1365039814779489546 ) ) ; +#20869 = CARTESIAN_POINT ( 'NONE', ( -38.04112740183000341, 118.7060968625000186, 87.44750983263999444 ) ) ; +#20870 = ORIENTED_EDGE ( 'NONE', *, *, #28213, .T. ) ; +#20871 = CARTESIAN_POINT ( 'NONE', ( -42.69707587204211308, 120.8996466381492496, 92.53868120850997059 ) ) ; +#20872 = VERTEX_POINT ( 'NONE', #39754 ) ; +#20873 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#20874 = DIRECTION ( 'NONE', ( -0.0005884949961255136249, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#20875 = CYLINDRICAL_SURFACE ( 'NONE', #34950, 6.000000000000011546 ) ; +#20876 = CARTESIAN_POINT ( 'NONE', ( 35.79285166799878937, 114.5355110621730717, 90.24616685369409197 ) ) ; +#20877 = CARTESIAN_POINT ( 'NONE', ( -12.63758525726122883, 181.4885551368883227, 104.2318394346509649 ) ) ; +#20878 = VERTEX_POINT ( 'NONE', #8502 ) ; +#20879 = CONICAL_SURFACE ( 'NONE', #33909, 2.999999999998151257, 0.7853981634371727250 ) ; +#20880 = CARTESIAN_POINT ( 'NONE', ( -25.40281222480000167, 190.9098522726999931, 104.3953673413000018 ) ) ; +#20881 = CARTESIAN_POINT ( 'NONE', ( 0.6370597539463290770, 189.0086924880019410, 103.7002870655890092 ) ) ; +#20882 = CARTESIAN_POINT ( 'NONE', ( 27.32241654998495406, 123.5931195352329865, 91.24905158260060034 ) ) ; +#20883 = CIRCLE ( 'NONE', #14348, 9.500000000008954615 ) ; +#20884 = ORIENTED_EDGE ( 'NONE', *, *, #21795, .T. ) ; +#20885 = CARTESIAN_POINT ( 'NONE', ( -39.42815928026088557, 120.3902238028007616, 87.47100753998802247 ) ) ; +#20886 = ORIENTED_EDGE ( 'NONE', *, *, #32556, .F. ) ; +#20887 = AXIS2_PLACEMENT_3D ( 'NONE', #7148, #16748, #35741 ) ; +#20888 = ORIENTED_EDGE ( 'NONE', *, *, #4413, .T. ) ; +#20889 = ORIENTED_EDGE ( 'NONE', *, *, #27103, .F. ) ; +#20890 = FACE_OUTER_BOUND ( 'NONE', #34168, .T. ) ; +#20891 = DIRECTION ( 'NONE', ( -0.0005884949961245158337, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#20892 = CARTESIAN_POINT ( 'NONE', ( 39.11388936584986453, 77.23415618633558211, 290.4399554335766993 ) ) ; +#20893 = ORIENTED_EDGE ( 'NONE', *, *, #21296, .F. ) ; +#20894 = DIRECTION ( 'NONE', ( -0.6087614810001747978, 0.7729390313185946493, 0.1788147452386024683 ) ) ; +#20895 = ORIENTED_EDGE ( 'NONE', *, *, #30611, .T. ) ; +#20896 = EDGE_CURVE ( 'NONE', #32498, #38540, #20265, .T. ) ; +#20897 = CARTESIAN_POINT ( 'NONE', ( 26.03107217181060662, 120.6373387495500253, 90.57271201131170812 ) ) ; +#20898 = ADVANCED_FACE ( 'NONE', ( #29766 ), #32651, .F. ) ; +#20899 = CARTESIAN_POINT ( 'NONE', ( -35.89743280148279325, 191.5812194053145276, 103.9038232423688584 ) ) ; +#20900 = ADVANCED_FACE ( 'NONE', ( #36699 ), #6024, .F. ) ; +#20901 = EDGE_CURVE ( 'NONE', #6504, #30059, #6829, .T. ) ; +#20903 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#20902 = FACE_OUTER_BOUND ( 'NONE', #3849, .T. ) ; +#20904 = ORIENTED_EDGE ( 'NONE', *, *, #13557, .F. ) ; +#20905 = AXIS2_PLACEMENT_3D ( 'NONE', #14896, #20403, #36563 ) ; +#20906 = ORIENTED_EDGE ( 'NONE', *, *, #6305, .F. ) ; +#20907 = EDGE_CURVE ( 'NONE', #34652, #32946, #34029, .T. ) ; +#20908 = CONICAL_SURFACE ( 'NONE', #8514, 5.000000000099491082, 0.7853981633997491052 ) ; +#20909 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -6.071530832037190021E-16, -0.0006039748319384735838 ) ) ; +#20910 = VECTOR ( 'NONE', #38570, 1000.000000000000114 ) ; +#20911 = ORIENTED_EDGE ( 'NONE', *, *, #27064, .T. ) ; +#20912 = CARTESIAN_POINT ( 'NONE', ( -35.93925692297263197, 191.9759150222000130, 101.9431537509077259 ) ) ; +#20913 = ADVANCED_FACE ( 'NONE', ( #21386 ), #37310, .F. ) ; +#20914 = CARTESIAN_POINT ( 'NONE', ( -14.59022374134706901, 128.1503308081717876, 179.4782974412063936 ) ) ; +#20915 = DIRECTION ( 'NONE', ( -0.7933531821996063771, -0.5932639600174075545, -0.1364866368485285197 ) ) ; +#20916 = CARTESIAN_POINT ( 'NONE', ( 3.534179144852753307, 139.6466882096548261, 91.89073863240385265 ) ) ; +#20917 = ORIENTED_EDGE ( 'NONE', *, *, #4537, .T. ) ; +#20918 = ORIENTED_EDGE ( 'NONE', *, *, #5428, .T. ) ; +#20919 = VERTEX_POINT ( 'NONE', #21780 ) ; +#20920 = CARTESIAN_POINT ( 'NONE', ( 5.958856853884591409, 162.8902775912074787, 100.3344200888616200 ) ) ; +#20921 = FACE_OUTER_BOUND ( 'NONE', #35565, .T. ) ; +#20922 = CARTESIAN_POINT ( 'NONE', ( -30.07145675046769284, 134.4269501514953618, 93.62510490720951850 ) ) ; +#20923 = CARTESIAN_POINT ( 'NONE', ( 26.66104490297999874, 123.3439525863999933, 88.11293733339999790 ) ) ; +#20924 = ORIENTED_EDGE ( 'NONE', *, *, #23814, .T. ) ; +#20925 = ORIENTED_EDGE ( 'NONE', *, *, #18051, .F. ) ; +#20926 = CARTESIAN_POINT ( 'NONE', ( -35.93727186606000146, 191.2092751614000292, 106.8903646179000049 ) ) ; +#20927 = LINE ( 'NONE', #24418, #15304 ) ; +#20928 = CARTESIAN_POINT ( 'NONE', ( 1.632345292716000040, 189.0492994540000211, 105.9662563011000032 ) ) ; +#20929 = ORIENTED_EDGE ( 'NONE', *, *, #8292, .T. ) ; +#20930 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319385852566 ) ) ; +#20931 = CIRCLE ( 'NONE', #30075, 5.000000000000007994 ) ; +#20932 = CARTESIAN_POINT ( 'NONE', ( 13.49924681881780764, 124.6650593666242344, 88.83239057565374708 ) ) ; +#20933 = CARTESIAN_POINT ( 'NONE', ( -14.22271344828364903, 128.9395125011611754, 177.3181667287759069 ) ) ; +#20934 = LINE ( 'NONE', #9276, #22842 ) ; +#20935 = CIRCLE ( 'NONE', #19607, 5.999999999759224600 ) ; +#20936 = EDGE_LOOP ( 'NONE', ( #21018, #4130, #35571, #31293 ) ) ; +#20937 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6343, #3668, #15555, #6737 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20938 = VECTOR ( 'NONE', #24687, 999.9999999999998863 ) ; +#20939 = CARTESIAN_POINT ( 'NONE', ( -6.858865372957902551, 155.8781062955033576, 98.72327407370771368 ) ) ; +#20940 = CARTESIAN_POINT ( 'NONE', ( -20.21854228498681394, 127.1165482757314891, 91.86524267595261506 ) ) ; +#20941 = VERTEX_POINT ( 'NONE', #30779 ) ; +#20942 = LINE ( 'NONE', #7853, #11694 ) ; +#20943 = VERTEX_POINT ( 'NONE', #93 ) ; +#20944 = EDGE_CURVE ( 'NONE', #14541, #34227, #9105, .T. ) ; +#20945 = EDGE_CURVE ( 'NONE', #10469, #38882, #6414, .T. ) ; +#20947 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825852987664379, 0.0005734119039362157175 ) ) ; +#20946 = CARTESIAN_POINT ( 'NONE', ( 15.83342444354847522, 184.9284620445380654, 102.5085181819803495 ) ) ; +#20948 = ORIENTED_EDGE ( 'NONE', *, *, #18019, .F. ) ; +#20949 = ORIENTED_EDGE ( 'NONE', *, *, #2631, .F. ) ; +#20950 = VERTEX_POINT ( 'NONE', #39963 ) ; +#20951 = CARTESIAN_POINT ( 'NONE', ( 2.345797604942000181, 209.4826787798999987, 75.42228542885000309 ) ) ; +#20952 = CARTESIAN_POINT ( 'NONE', ( -20.49970530398912771, 127.6304983571866813, 89.64427666219336288 ) ) ; +#20953 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#20954 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9421, #3262, #12892, #15736, #38014, #37622, #9825, #31289, #10020, #28236, #202, #9620, #28625, #3860 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000594524, 0.3750000000000891509, 0.5000000000001189049, 0.6250000000001486589, 0.6875000000001635359, 0.7500000000001783018, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#20955 = DIRECTION ( 'NONE', ( 0.0005884949961216158097, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#20956 = ORIENTED_EDGE ( 'NONE', *, *, #5523, .T. ) ; +#20957 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8234, #17410, #8445, #5143 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 3.498928553401127738E-05, 0.0009596819072843342392 ), + .UNSPECIFIED. ) ; +#20958 = ORIENTED_EDGE ( 'NONE', *, *, #33244, .T. ) ; +#20959 = FACE_OUTER_BOUND ( 'NONE', #21161, .T. ) ; +#20960 = ORIENTED_EDGE ( 'NONE', *, *, #308, .F. ) ; +#20961 = VERTEX_POINT ( 'NONE', #5829 ) ; +#20962 = ORIENTED_EDGE ( 'NONE', *, *, #17359, .F. ) ; +#20963 = DIRECTION ( 'NONE', ( -0.0002331579778304450367, 0.000000000000000000, 0.9999999728186783621 ) ) ; +#20964 = VECTOR ( 'NONE', #38831, 1000.000000000000000 ) ; +#20965 = CARTESIAN_POINT ( 'NONE', ( -15.49931385410608797, 126.5379994198332128, 90.07323617695428197 ) ) ; +#20966 = CARTESIAN_POINT ( 'NONE', ( 28.90769808291203091, 225.0820812890804348, 73.04104455706797694 ) ) ; +#20967 = ORIENTED_EDGE ( 'NONE', *, *, #4254, .F. ) ; +#20968 = ORIENTED_EDGE ( 'NONE', *, *, #9102, .T. ) ; +#20969 = FACE_OUTER_BOUND ( 'NONE', #30387, .T. ) ; +#20970 = CIRCLE ( 'NONE', #2714, 59.40509992922265070 ) ; +#20971 = CARTESIAN_POINT ( 'NONE', ( -36.01420119997000313, 191.6214486215999955, 104.0185275158000024 ) ) ; +#20972 = PLANE ( 'NONE', #6780 ) ; +#20973 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5873, #37157, #21633, #26103 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.004429580596844295143, 0.005383752238790704553 ), + .UNSPECIFIED. ) ; +#20974 = CARTESIAN_POINT ( 'NONE', ( -26.00156157406000190, 120.7704101891000050, 87.55230281532000447 ) ) ; +#20975 = EDGE_CURVE ( 'NONE', #29413, #36900, #15237, .T. ) ; +#20976 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927785862613, -0.0005734119022076208027 ) ) ; +#20977 = ORIENTED_EDGE ( 'NONE', *, *, #8872, .F. ) ; +#20978 = CARTESIAN_POINT ( 'NONE', ( -35.93878493987468659, 193.8169247291150441, 102.7246158654215407 ) ) ; +#20979 = CARTESIAN_POINT ( 'NONE', ( -10.03773492422904035, 144.2121259786891585, 92.95297688159946858 ) ) ; +#20980 = CARTESIAN_POINT ( 'NONE', ( -40.50060808723890204, 187.9905118568378839, 108.0074710440303534 ) ) ; +#20981 = EDGE_LOOP ( 'NONE', ( #33692, #13913, #28684, #25266, #19116, #24953 ) ) ; +#20982 = CARTESIAN_POINT ( 'NONE', ( 0.9069838061199879675, 188.6357051019811024, 103.2023597719151695 ) ) ; +#20983 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971566235 ) ) ; +#20984 = CARTESIAN_POINT ( 'NONE', ( 38.86765437999894601, 119.3076485421969295, 90.27457848768588633 ) ) ; +#20985 = ORIENTED_EDGE ( 'NONE', *, *, #38352, .F. ) ; +#20986 = CARTESIAN_POINT ( 'NONE', ( -19.32686018148266172, 125.5899111567603512, 176.6758355686243931 ) ) ; +#20987 = CARTESIAN_POINT ( 'NONE', ( 2.243271862260145522, 189.9155782016669320, 103.9476138140318824 ) ) ; +#20988 = FACE_OUTER_BOUND ( 'NONE', #35721, .T. ) ; +#20989 = ORIENTED_EDGE ( 'NONE', *, *, #12359, .T. ) ; +#20990 = CARTESIAN_POINT ( 'NONE', ( 28.22275640945365893, 173.0857027608089709, 163.8371377877124075 ) ) ; +#20991 = ORIENTED_EDGE ( 'NONE', *, *, #15997, .T. ) ; +#20992 = CARTESIAN_POINT ( 'NONE', ( -26.16677798958000523, 191.4023415389999911, 103.7088623374999941 ) ) ; +#20993 = AXIS2_PLACEMENT_3D ( 'NONE', #37808, #25156, #6927 ) ; +#20994 = DIRECTION ( 'NONE', ( -0.7933533411653341805, 0.5930537057989598848, 0.1373964268091485141 ) ) ; +#20995 = CARTESIAN_POINT ( 'NONE', ( 25.65860218431893358, 209.7091953648101708, 75.70969353744057173 ) ) ; +#20996 = AXIS2_PLACEMENT_3D ( 'NONE', #1921, #36043, #20098 ) ; +#20997 = CIRCLE ( 'NONE', #9239, 2.000000000000000000 ) ; +#20998 = CARTESIAN_POINT ( 'NONE', ( 22.78189145297202245, 157.6320869253407011, 99.11031191928994133 ) ) ; +#20999 = ORIENTED_EDGE ( 'NONE', *, *, #17708, .F. ) ; +#21000 = EDGE_CURVE ( 'NONE', #37846, #34146, #5872, .T. ) ; +#21001 = ADVANCED_FACE ( 'NONE', ( #12554, #2765 ), #25055, .T. ) ; +#21002 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#21003 = LINE ( 'NONE', #4834, #38026 ) ; +#21004 = CARTESIAN_POINT ( 'NONE', ( -25.62047675601055374, 116.5971733958860312, 87.28325841799609464 ) ) ; +#21005 = CARTESIAN_POINT ( 'NONE', ( 22.50071842841086678, 154.4094130781474803, 95.28756121982962668 ) ) ; +#21006 = EDGE_CURVE ( 'NONE', #28275, #7159, #15437, .T. ) ; +#21007 = DIRECTION ( 'NONE', ( -0.0005884949961246856197, 0.2249510543439059984, -0.9743698870671264611 ) ) ; +#21008 = CARTESIAN_POINT ( 'NONE', ( 21.72603247161529438, 129.4256177271351760, 92.59897021125679828 ) ) ; +#21009 = FACE_OUTER_BOUND ( 'NONE', #18104, .T. ) ; +#21010 = CARTESIAN_POINT ( 'NONE', ( 29.19927575787174234, 149.0747586894985659, 94.05190613317014936 ) ) ; +#21011 = CARTESIAN_POINT ( 'NONE', ( 22.05420076943320140, 115.2658143850467241, 90.25446465457505951 ) ) ; +#21012 = ORIENTED_EDGE ( 'NONE', *, *, #15579, .F. ) ; +#21013 = VERTEX_POINT ( 'NONE', #7415 ) ; +#21014 = LINE ( 'NONE', #5672, #29597 ) ; +#21015 = CARTESIAN_POINT ( 'NONE', ( 25.99211731546482795, 209.7096512574500480, 76.04280604205342797 ) ) ; +#21016 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14687, #2415, #11203, #36130 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.002613673017241889291 ), + .UNSPECIFIED. ) ; +#21017 = CARTESIAN_POINT ( 'NONE', ( -32.57215242110157050, 137.1961775011903626, 91.34682747567867978 ) ) ; +#21018 = ORIENTED_EDGE ( 'NONE', *, *, #25902, .F. ) ; +#21019 = CARTESIAN_POINT ( 'NONE', ( 39.76268190624871579, 165.1489056186390485, 181.9689639978837192 ) ) ; +#21020 = CARTESIAN_POINT ( 'NONE', ( 36.74499328828947142, 191.3591568088928909, 106.3388620510278457 ) ) ; +#21021 = EDGE_LOOP ( 'NONE', ( #7977, #30007, #12549, #6560 ) ) ; +#21022 = CARTESIAN_POINT ( 'NONE', ( -17.26181899215141158, 121.5888068968943827, 176.1573250596364062 ) ) ; +#21023 = AXIS2_PLACEMENT_3D ( 'NONE', #11590, #38760, #26727 ) ; +#21024 = EDGE_CURVE ( 'NONE', #19097, #9106, #22587, .T. ) ; +#21025 = AXIS2_PLACEMENT_3D ( 'NONE', #40441, #9387, #18361 ) ; +#21026 = CARTESIAN_POINT ( 'NONE', ( 26.01073959733328067, 191.4239670711786516, 106.8751801458234496 ) ) ; +#21027 = FACE_OUTER_BOUND ( 'NONE', #7265, .T. ) ; +#21028 = CARTESIAN_POINT ( 'NONE', ( 1.222756100067673435, 140.3958132876599620, 157.8527939211185753 ) ) ; +#21029 = VERTEX_POINT ( 'NONE', #35008 ) ; +#21030 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620729128, 0.0004744508866335443741 ) ) ; +#21031 = DIRECTION ( 'NONE', ( 0.0005734119072255677982, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#21032 = CARTESIAN_POINT ( 'NONE', ( 16.57899994050853465, 122.1654929642032101, 174.6492536331854808 ) ) ; +#21033 = DIRECTION ( 'NONE', ( 0.6087611427401035114, 0.7731004639645453480, 0.1781166575802727303 ) ) ; +#21034 = CARTESIAN_POINT ( 'NONE', ( 5.666342389698421300, 128.5870658017565233, 89.33308585708306282 ) ) ; +#21035 = ORIENTED_EDGE ( 'NONE', *, *, #3306, .F. ) ; +#21036 = ORIENTED_EDGE ( 'NONE', *, *, #33627, .F. ) ; +#21037 = CARTESIAN_POINT ( 'NONE', ( 39.95940241497999779, 119.7619408805000063, 87.93975461783000469 ) ) ; +#21038 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250611660, 132.8554482850406089, 90.84904174544712419 ) ) ; +#21039 = CARTESIAN_POINT ( 'NONE', ( 35.04675249778818369, 217.7719116314000303, 76.03733726961077366 ) ) ; +#21040 = ADVANCED_FACE ( 'NONE', ( #7217 ), #38306, .T. ) ; +#21041 = CARTESIAN_POINT ( 'NONE', ( -17.94609826156584731, 126.0030689616275197, 174.3309067019738734 ) ) ; +#21042 = ORIENTED_EDGE ( 'NONE', *, *, #35881, .T. ) ; +#21043 = DIRECTION ( 'NONE', ( -1.974915567353954948E-14, 0.9743700556569576676, 0.2249510938827756212 ) ) ; +#21044 = CARTESIAN_POINT ( 'NONE', ( -41.68575839595558108, 120.6855336692081266, 90.61946157941947888 ) ) ; +#21045 = CARTESIAN_POINT ( 'NONE', ( 12.31694666162038132, 134.8454845483305178, 93.34277599231758415 ) ) ; +#21046 = CARTESIAN_POINT ( 'NONE', ( -14.16859889492986468, 129.2741495211867004, 92.07252832466726034 ) ) ; +#21047 = EDGE_CURVE ( 'NONE', #7827, #29667, #3947, .T. ) ; +#21048 = CARTESIAN_POINT ( 'NONE', ( -20.00009287209055131, 187.1460516500350195, 102.8711691885999500 ) ) ; +#21049 = EDGE_CURVE ( 'NONE', #28516, #21533, #13717, .T. ) ; +#21050 = AXIS2_PLACEMENT_3D ( 'NONE', #4670, #14493, #10624 ) ; +#21051 = EDGE_CURVE ( 'NONE', #8665, #17763, #28728, .T. ) ; +#21052 = DIRECTION ( 'NONE', ( -0.0005884949961204158147, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#21053 = EDGE_CURVE ( 'NONE', #29822, #21381, #16614, .T. ) ; +#21054 = AXIS2_PLACEMENT_3D ( 'NONE', #25608, #16565, #35363 ) ; +#21055 = DIRECTION ( 'NONE', ( 0.0006039748319392010834, 1.387181216573299978E-14, 0.9999998176071847045 ) ) ; +#21056 = ADVANCED_FACE ( 'NONE', ( #34612 ), #22528, .F. ) ; +#21057 = CIRCLE ( 'NONE', #5365, 4.999999999999990230 ) ; +#21058 = COORDINATED_UNIVERSAL_TIME_OFFSET ( 8, 0, .AHEAD. ) ; +#21059 = CARTESIAN_POINT ( 'NONE', ( 27.30892892946447148, 124.2550657910854142, 88.32296920643761950 ) ) ; +#21060 = CARTESIAN_POINT ( 'NONE', ( 25.51004206032530064, 191.6308693524351554, 105.7209185049416931 ) ) ; +#21061 = CARTESIAN_POINT ( 'NONE', ( 5.659931281361317623, 181.6896837046558346, 101.5959228839198687 ) ) ; +#21062 = CARTESIAN_POINT ( 'NONE', ( 39.74188351515407192, 169.2517364656017946, 164.2561587285271969 ) ) ; +#21063 = CARTESIAN_POINT ( 'NONE', ( -20.09733952647779631, 117.3367250912880877, 87.27992258150773353 ) ) ; +#21064 = ORIENTED_EDGE ( 'NONE', *, *, #20222, .T. ) ; +#21066 = ORIENTED_EDGE ( 'NONE', *, *, #31760, .F. ) ; +#21065 = CARTESIAN_POINT ( 'NONE', ( -20.49997183667262490, 192.9349667875385137, 104.2562123716132447 ) ) ; +#21067 = VERTEX_POINT ( 'NONE', #22382 ) ; +#21068 = ORIENTED_EDGE ( 'NONE', *, *, #31240, .T. ) ; +#21069 = VERTEX_POINT ( 'NONE', #16420 ) ; +#21070 = CARTESIAN_POINT ( 'NONE', ( -17.02518187280848494, 122.0151939964033119, 175.1199121015164337 ) ) ; +#21071 = VERTEX_POINT ( 'NONE', #6609 ) ; +#21072 = CARTESIAN_POINT ( 'NONE', ( -23.35907867311044228, 177.6446616419575548, 100.8023958600040686 ) ) ; +#21073 = CARTESIAN_POINT ( 'NONE', ( -43.56994142101562062, 121.4012961811330626, 90.41976514615660676 ) ) ; +#21074 = VERTEX_POINT ( 'NONE', #31581 ) ; +#21075 = CARTESIAN_POINT ( 'NONE', ( 13.88517613221250713, 135.5848694388539002, 93.51252930518586481 ) ) ; +#21076 = CARTESIAN_POINT ( 'NONE', ( 14.31397849533732725, 130.4269649200152230, 89.75571327846994052 ) ) ; +#21077 = CARTESIAN_POINT ( 'NONE', ( -32.54948496751784148, 154.4229393206493057, 204.0724399287581434 ) ) ; +#21078 = CIRCLE ( 'NONE', #9985, 58.90509898899683350 ) ; +#21079 = ORIENTED_EDGE ( 'NONE', *, *, #3482, .F. ) ; +#21080 = PLANE ( 'NONE', #32980 ) ; +#21081 = CIRCLE ( 'NONE', #36049, 22.00000000001089973 ) ; +#21082 = FACE_OUTER_BOUND ( 'NONE', #24695, .T. ) ; +#21083 = CARTESIAN_POINT ( 'NONE', ( -2.935421602322794588, 191.9759150222000130, 106.9232211747876278 ) ) ; +#21084 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21085 = ORIENTED_EDGE ( 'NONE', *, *, #21281, .T. ) ; +#21086 = LINE ( 'NONE', #8823, #10225 ) ; +#21087 = VECTOR ( 'NONE', #8432, 1000.000000000000114 ) ; +#21088 = CARTESIAN_POINT ( 'NONE', ( 0.7499007542371000090, 188.6218793108000114, 103.1994418971000016 ) ) ; +#21089 = CARTESIAN_POINT ( 'NONE', ( -40.96659390818172852, 129.5715977525514120, 94.72314572716805969 ) ) ; +#21090 = EDGE_CURVE ( 'NONE', #22698, #22776, #26336, .T. ) ; +#21091 = ORIENTED_EDGE ( 'NONE', *, *, #15811, .F. ) ; +#21092 = CARTESIAN_POINT ( 'NONE', ( 2.547144903132902094, 209.7096538831000032, 78.05696658267085297 ) ) ; +#21093 = ORIENTED_EDGE ( 'NONE', *, *, #14309, .T. ) ; +#21094 = EDGE_CURVE ( 'NONE', #14326, #14324, #3541, .T. ) ; +#21095 = VERTEX_POINT ( 'NONE', #6814 ) ; +#21096 = EDGE_CURVE ( 'NONE', #33655, #20063, #19285, .T. ) ; +#21097 = VERTEX_POINT ( 'NONE', #689 ) ; +#21098 = VERTEX_POINT ( 'NONE', #25661 ) ; +#21099 = CARTESIAN_POINT ( 'NONE', ( -37.60508999318000178, 191.0942080147000013, 105.7280175294000060 ) ) ; +#21100 = CARTESIAN_POINT ( 'NONE', ( -20.00004361580415591, 118.8155695144462669, 87.27991261026372172 ) ) ; +#21101 = EDGE_CURVE ( 'NONE', #27687, #38501, #18994, .T. ) ; +#21102 = FACE_OUTER_BOUND ( 'NONE', #28433, .T. ) ; +#21103 = ORIENTED_EDGE ( 'NONE', *, *, #8536, .T. ) ; +#21104 = CARTESIAN_POINT ( 'NONE', ( -13.49869758878028669, 124.2895155517476127, 90.92133008179847309 ) ) ; +#21105 = VECTOR ( 'NONE', #18459, 1000.000000000000000 ) ; +#21106 = ORIENTED_EDGE ( 'NONE', *, *, #2901, .T. ) ; +#21107 = CARTESIAN_POINT ( 'NONE', ( 25.79908993445999954, 121.4038166283999942, 90.40237219540999547 ) ) ; +#21108 = CARTESIAN_POINT ( 'NONE', ( -39.71509910335698379, 121.1775733798183552, 123.9347607182968574 ) ) ; +#21109 = AXIS2_PLACEMENT_3D ( 'NONE', #23422, #35861, #20131 ) ; +#21111 = FACE_OUTER_BOUND ( 'NONE', #15639, .T. ) ; +#21110 = CARTESIAN_POINT ( 'NONE', ( 18.92701962846999919, 158.4561920815999940, 97.76344171338000422 ) ) ; +#21112 = ORIENTED_EDGE ( 'NONE', *, *, #26367, .F. ) ; +#21113 = CARTESIAN_POINT ( 'NONE', ( 3.804321419319733444, 143.6008336270662937, 95.60682967125522680 ) ) ; +#21114 = ORIENTED_EDGE ( 'NONE', *, *, #25837, .T. ) ; +#21115 = ORIENTED_EDGE ( 'NONE', *, *, #19560, .F. ) ; +#21116 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971573729 ) ) ; +#21117 = DIRECTION ( 'NONE', ( 0.0006039748319386906410, -0.000000000000000000, 0.9999998176071844824 ) ) ; +#21118 = CYLINDRICAL_SURFACE ( 'NONE', #13089, 2.000000000000001332 ) ; +#21119 = CARTESIAN_POINT ( 'NONE', ( 20.50029382537679723, 138.3995138256450446, 92.10573732898133414 ) ) ; +#21120 = ORIENTED_EDGE ( 'NONE', *, *, #27164, .T. ) ; +#21121 = EDGE_LOOP ( 'NONE', ( #12390, #38121, #16422, #7972 ) ) ; +#21122 = CARTESIAN_POINT ( 'NONE', ( 44.86515336672587040, 186.3325894068457274, 107.7750559962146752 ) ) ; +#21123 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555133 ) ) ; +#21124 = CARTESIAN_POINT ( 'NONE', ( 25.49917220875000012, 120.6644043121000038, 88.00842120017000525 ) ) ; +#21125 = ORIENTED_EDGE ( 'NONE', *, *, #14646, .F. ) ; +#21126 = VERTEX_POINT ( 'NONE', #17820 ) ; +#21127 = CARTESIAN_POINT ( 'NONE', ( -15.49852919464750833, 127.1814504007330839, 91.59019381971197049 ) ) ; +#21128 = CONICAL_SURFACE ( 'NONE', #15238, 4.999999999914826354, 0.7853981634347279028 ) ; +#21130 = EDGE_CURVE ( 'NONE', #26863, #29325, #1488, .T. ) ; +#21129 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684796025, 220.4002260771000010, 75.57961659102821272 ) ) ; +#21131 = EDGE_CURVE ( 'NONE', #12858, #4754, #26452, .T. ) ; +#21132 = EDGE_CURVE ( 'NONE', #33491, #3175, #4538, .T. ) ; +#21133 = VECTOR ( 'NONE', #33778, 1000.000000000000000 ) ; +#21134 = EDGE_CURVE ( 'NONE', #22424, #34827, #23381, .T. ) ; +#21135 = CARTESIAN_POINT ( 'NONE', ( 1.148461899826000110, 188.6401437957000269, 106.0734205451999941 ) ) ; +#21136 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#21137 = AXIS2_PLACEMENT_3D ( 'NONE', #28420, #25762, #22694 ) ; +#21138 = DIRECTION ( 'NONE', ( 0.0006039748319381496242, 1.231904546584163304E-14, 0.9999998176071845934 ) ) ; +#21139 = PLANE ( 'NONE', #37231 ) ; +#21140 = CARTESIAN_POINT ( 'NONE', ( -77.81044467944656162, 193.2853083808247163, 188.4036545891195544 ) ) ; +#21141 = EDGE_CURVE ( 'NONE', #2058, #22348, #11111, .T. ) ; +#21142 = EDGE_LOOP ( 'NONE', ( #40273, #32284, #26293, #15617 ) ) ; +#21143 = CARTESIAN_POINT ( 'NONE', ( 15.91461714735487654, 137.7804811271876986, 91.45243982764233692 ) ) ; +#21144 = CARTESIAN_POINT ( 'NONE', ( 17.33275958572512110, 132.4033582165222072, 151.6354730222171554 ) ) ; +#21145 = EDGE_CURVE ( 'NONE', #10469, #17896, #35814, .T. ) ; +#21146 = VERTEX_POINT ( 'NONE', #7624 ) ; +#21147 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5316, #12271, #36607, #37017 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21148 = CARTESIAN_POINT ( 'NONE', ( -14.14964769712242720, 154.3421575665795444, 95.29416286922138113 ) ) ; +#21149 = EDGE_LOOP ( 'NONE', ( #800, #20962, #38040, #20060 ) ) ; +#21151 = CARTESIAN_POINT ( 'NONE', ( -13.46991461394048706, 153.3545038370762654, 97.63149519329859061 ) ) ; +#21150 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2249510911124609769, 0.9743700461176366678 ) ) ; +#21152 = VERTEX_POINT ( 'NONE', #32573 ) ; +#21153 = EDGE_CURVE ( 'NONE', #22508, #3193, #21498, .T. ) ; +#21154 = EDGE_LOOP ( 'NONE', ( #1528, #23847, #37100, #28904 ) ) ; +#21155 = CIRCLE ( 'NONE', #29649, 2.000000000040191850 ) ; +#21156 = ORIENTED_EDGE ( 'NONE', *, *, #22259, .T. ) ; +#21157 = CARTESIAN_POINT ( 'NONE', ( 3.178648524536999975, 209.0894144632000007, 76.29602415331001453 ) ) ; +#21158 = FACE_OUTER_BOUND ( 'NONE', #2887, .T. ) ; +#21159 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319383098692 ) ) ; +#21160 = CARTESIAN_POINT ( 'NONE', ( 12.63909433778480462, 177.5476369569251744, 100.8453596693047700 ) ) ; +#21161 = EDGE_LOOP ( 'NONE', ( #31786, #35714, #14464, #11307, #19428, #11277, #25296 ) ) ; +#21162 = ORIENTED_EDGE ( 'NONE', *, *, #22625, .F. ) ; +#21163 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178662923876E-05, -0.0002331579774918193435 ) ) ; +#21164 = ORIENTED_EDGE ( 'NONE', *, *, #15556, .T. ) ; +#21165 = EDGE_LOOP ( 'NONE', ( #20426, #25320, #25411, #36636 ) ) ; +#21166 = DIRECTION ( 'NONE', ( 0.5976534202554322217, -0.8017545692149086189, 0.000000000000000000 ) ) ; +#21167 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 82.27946979429631824, 312.5857197240630967 ) ) ; +#21168 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#21169 = CARTESIAN_POINT ( 'NONE', ( 14.20046068010607421, 171.2571027691364804, 152.1817658904702171 ) ) ; +#21170 = ORIENTED_EDGE ( 'NONE', *, *, #11593, .F. ) ; +#21171 = VERTEX_POINT ( 'NONE', #1907 ) ; +#21172 = CARTESIAN_POINT ( 'NONE', ( 25.74916992513999858, 120.5273334846000068, 87.71987236393999865 ) ) ; +#21173 = FACE_OUTER_BOUND ( 'NONE', #40161, .T. ) ; +#21174 = CARTESIAN_POINT ( 'NONE', ( -36.04262883852999977, 191.6038256765999961, 104.0150152128000087 ) ) ; +#21175 = ORIENTED_EDGE ( 'NONE', *, *, #35227, .F. ) ; +#21176 = CARTESIAN_POINT ( 'NONE', ( -25.50107848504000074, 120.6980294115000021, 88.04691121081999938 ) ) ; +#21177 = ORIENTED_EDGE ( 'NONE', *, *, #2312, .T. ) ; +#21178 = ORIENTED_EDGE ( 'NONE', *, *, #36025, .T. ) ; +#21179 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501101346, 134.9725883025117810, 93.90358196957727444 ) ) ; +#21180 = CARTESIAN_POINT ( 'NONE', ( 40.67160727233613926, 188.2341991642046821, 107.8019268565751645 ) ) ; +#21181 = VERTEX_POINT ( 'NONE', #20488 ) ; +#21182 = ADVANCED_FACE ( 'NONE', ( #4553 ), #31356, .F. ) ; +#21183 = ADVANCED_FACE ( 'NONE', ( #10709 ), #7814, .F. ) ; +#21184 = ADVANCED_FACE ( 'NONE', ( #17424 ), #20297, .T. ) ; +#21185 = FACE_OUTER_BOUND ( 'NONE', #33374, .T. ) ; +#21186 = CARTESIAN_POINT ( 'NONE', ( -14.95236425134362257, 124.8050312121227705, 88.47546351363439499 ) ) ; +#21187 = DIRECTION ( 'NONE', ( -0.7069397881080353718, 0.6509003778324177203, 0.2767035130376589436 ) ) ; +#21188 = CARTESIAN_POINT ( 'NONE', ( 42.08971007137151332, 189.5930990985782216, 106.5991435967087710 ) ) ; +#21189 = AXIS2_PLACEMENT_3D ( 'NONE', #36771, #5282, #8779 ) ; +#21190 = AXIS2_PLACEMENT_3D ( 'NONE', #23283, #11411, #35717 ) ; +#21191 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#21192 = EDGE_CURVE ( 'NONE', #32173, #5686, #4753, .T. ) ; +#21193 = ORIENTED_EDGE ( 'NONE', *, *, #33124, .T. ) ; +#21194 = DIRECTION ( 'NONE', ( 0.0006039748319392586546, 1.665208279866278382E-14, 0.9999998176071847045 ) ) ; +#21195 = ORIENTED_EDGE ( 'NONE', *, *, #11756, .F. ) ; +#21196 = ORIENTED_EDGE ( 'NONE', *, *, #10307, .T. ) ; +#21197 = CIRCLE ( 'NONE', #26423, 10.00000000000000533 ) ; +#21198 = CARTESIAN_POINT ( 'NONE', ( -25.38982233400999888, 191.1550647745000049, 104.4477984829999997 ) ) ; +#21199 = CARTESIAN_POINT ( 'NONE', ( -38.21285156308999831, 118.8458964008000009, 87.61704921257999956 ) ) ; +#21200 = CARTESIAN_POINT ( 'NONE', ( -14.55306305638819886, 182.5568561273574630, 101.8082842025129366 ) ) ; +#21201 = EDGE_CURVE ( 'NONE', #11382, #20569, #26256, .T. ) ; +#21202 = CARTESIAN_POINT ( 'NONE', ( 20.00140612192502942, 118.1043503129110093, 90.25575274657424529 ) ) ; +#21203 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#21204 = ORIENTED_EDGE ( 'NONE', *, *, #3858, .T. ) ; +#21205 = CARTESIAN_POINT ( 'NONE', ( -6.038826999385723759, 135.1142834552483407, 91.11862372168455693 ) ) ; +#21206 = EDGE_CURVE ( 'NONE', #29513, #28170, #32200, .T. ) ; +#21207 = ORIENTED_EDGE ( 'NONE', *, *, #2856, .T. ) ; +#21208 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21209 = CARTESIAN_POINT ( 'NONE', ( -21.21281380558005125, 182.9066539643694966, 104.4588199671594850 ) ) ; +#21210 = LINE ( 'NONE', #8749, #1974 ) ; +#21211 = CARTESIAN_POINT ( 'NONE', ( -36.88585087101509430, 165.0203428823977845, 195.0301372465660847 ) ) ; +#21212 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971557908 ) ) ; +#21213 = CARTESIAN_POINT ( 'NONE', ( 30.77440290267000123, 184.0596580533000122, 103.6673131442999960 ) ) ; +#21214 = ORIENTED_EDGE ( 'NONE', *, *, #38473, .F. ) ; +#21215 = AXIS2_PLACEMENT_3D ( 'NONE', #713, #25886, #25482 ) ; +#21216 = ORIENTED_EDGE ( 'NONE', *, *, #27759, .F. ) ; +#21217 = DIRECTION ( 'NONE', ( 0.0006039748319383739456, -3.094196748328522329E-15, 0.9999998176071845934 ) ) ; +#21218 = CARTESIAN_POINT ( 'NONE', ( 40.24910017280793539, 69.86439126638083508, 297.5342355816429745 ) ) ; +#21219 = CIRCLE ( 'NONE', #37523, 2.499999999946084017 ) ; +#21220 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363196004925E-14, 0.9999998176071845934 ) ) ; +#21221 = AXIS2_PLACEMENT_3D ( 'NONE', #34673, #6880, #19353 ) ; +#21222 = ORIENTED_EDGE ( 'NONE', *, *, #33805, .F. ) ; +#21223 = CARTESIAN_POINT ( 'NONE', ( 38.59086485963890567, 79.69179921679354095, 285.2955982571226059 ) ) ; +#21224 = AXIS2_PLACEMENT_3D ( 'NONE', #37946, #22421, #23612 ) ; +#21225 = ORIENTED_EDGE ( 'NONE', *, *, #31892, .T. ) ; +#21226 = CARTESIAN_POINT ( 'NONE', ( -38.44420815374000000, 119.3830914533000112, 87.46411065086999770 ) ) ; +#21227 = CARTESIAN_POINT ( 'NONE', ( -43.57128771414367918, 121.9172130293124212, 88.19101713714755419 ) ) ; +#21228 = ORIENTED_EDGE ( 'NONE', *, *, #35824, .F. ) ; +#21229 = CARTESIAN_POINT ( 'NONE', ( 35.56535286263039808, 192.7868339794035251, 106.8337704962199268 ) ) ; +#21230 = CARTESIAN_POINT ( 'NONE', ( 25.99018610745488900, 211.0908525021142168, 73.04280463953621449 ) ) ; +#21231 = CARTESIAN_POINT ( 'NONE', ( 17.12152900317391513, 122.0605713307357263, 174.6251451077950776 ) ) ; +#21232 = EDGE_CURVE ( 'NONE', #9304, #10943, #25325, .T. ) ; +#21233 = EDGE_CURVE ( 'NONE', #6430, #37955, #23869, .T. ) ; +#21234 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501096727, 179.0628333272140367, 104.0826189413666043 ) ) ; +#21235 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21236 = ORIENTED_EDGE ( 'NONE', *, *, #30002, .F. ) ; +#21237 = ORIENTED_EDGE ( 'NONE', *, *, #14080, .F. ) ; +#21238 = LINE ( 'NONE', #33687, #2401 ) ; +#21239 = LINE ( 'NONE', #40428, #13358 ) ; +#21240 = CARTESIAN_POINT ( 'NONE', ( 37.23958122199455545, 191.4853617004306159, 104.3373353119450258 ) ) ; +#21241 = CARTESIAN_POINT ( 'NONE', ( -46.39364199823201318, 124.7770151420462525, 91.05374585112593877 ) ) ; +#21242 = EDGE_CURVE ( 'NONE', #14524, #3978, #30118, .T. ) ; +#21243 = ORIENTED_EDGE ( 'NONE', *, *, #38187, .T. ) ; +#21244 = LINE ( 'NONE', #27196, #38783 ) ; +#21245 = CARTESIAN_POINT ( 'NONE', ( -41.90795178536294685, 120.7420511615134728, 90.63264387236358743 ) ) ; +#21246 = VECTOR ( 'NONE', #35386, 1000.000000000000000 ) ; +#21247 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971564015 ) ) ; +#21248 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29635, #26576, #11031, #23491, #35940, #7948, #4875, #31047, #28193, #18543, #9575, #24932, #24730, #34481, #5698, #2830, #12429, #3020 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 2, 4 ), + ( 7.505561329662602745E-17, 0.0006195336865909711627, 0.001239067373181867299, 0.001858601059772763651, 0.002168367903068206190, 0.002323251324715956950, 0.002400693035539833847, 0.002439413890951765140, 0.002478134746363696433 ), + .UNSPECIFIED. ) ; +#21249 = AXIS2_PLACEMENT_3D ( 'NONE', #23002, #13992, #35428 ) ; +#21250 = AXIS2_PLACEMENT_3D ( 'NONE', #19749, #38372, #7483 ) ; +#21251 = FACE_OUTER_BOUND ( 'NONE', #27552, .T. ) ; +#21252 = FACE_OUTER_BOUND ( 'NONE', #27650, .T. ) ; +#21253 = VECTOR ( 'NONE', #11840, 1000.000000000000114 ) ; +#21254 = CARTESIAN_POINT ( 'NONE', ( -30.96737657857003256, 183.9660670339539479, 102.1435399962739297 ) ) ; +#21255 = AXIS2_PLACEMENT_3D ( 'NONE', #21482, #37594, #3436 ) ; +#21256 = CARTESIAN_POINT ( 'NONE', ( -25.52810189352114634, 209.7152177947368443, 73.55569084695761717 ) ) ; +#21257 = LINE ( 'NONE', #30860, #37663 ) ; +#21258 = EDGE_CURVE ( 'NONE', #15288, #17741, #40433, .T. ) ; +#21259 = CARTESIAN_POINT ( 'NONE', ( 0.000000000000000000, 0.000000000000000000, 0.000000000000000000 ) ) ; +#21260 = CARTESIAN_POINT ( 'NONE', ( 5.658901668160544851, 123.6924101227050699, 91.28505159842420369 ) ) ; +#21261 = PLANE ( 'NONE', #27689 ) ; +#21262 = DIRECTION ( 'NONE', ( 0.6087611434179116543, -0.7728348325624403437, -0.1792657018023851578 ) ) ; +#21263 = CARTESIAN_POINT ( 'NONE', ( -18.04546768527096035, 119.4165901137118198, 183.0978515824491240 ) ) ; +#21264 = PLANE ( 'NONE', #38487 ) ; +#21265 = VERTEX_POINT ( 'NONE', #6371 ) ; +#21267 = VERTEX_POINT ( 'NONE', #21733 ) ; +#21266 = CARTESIAN_POINT ( 'NONE', ( -20.49977814371478146, 192.2078853970874661, 104.4261425811200752 ) ) ; +#21268 = ORIENTED_EDGE ( 'NONE', *, *, #23176, .F. ) ; +#21269 = ORIENTED_EDGE ( 'NONE', *, *, #9636, .F. ) ; +#21270 = ORIENTED_EDGE ( 'NONE', *, *, #39463, .F. ) ; +#21271 = CARTESIAN_POINT ( 'NONE', ( -39.76450099176925335, 182.5239991202462306, 106.7001999176872715 ) ) ; +#21272 = EDGE_LOOP ( 'NONE', ( #2158, #11661, #36797, #35432 ) ) ; +#21273 = CARTESIAN_POINT ( 'NONE', ( 20.26447891146207425, 126.8205566995678168, 91.72864402998783362 ) ) ; +#21274 = EDGE_CURVE ( 'NONE', #31339, #34253, #11, .T. ) ; +#21275 = CARTESIAN_POINT ( 'NONE', ( 19.00982909665260934, 124.9426515599988079, 178.2686586979558570 ) ) ; +#21276 = DIRECTION ( 'NONE', ( -0.7933533175743878729, 0.5931616988744193852, 0.1369295895054284395 ) ) ; +#21277 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15696, #166, #12245, #15115 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21278 = VECTOR ( 'NONE', #31725, 1000.000000000000114 ) ; +#21279 = VERTEX_POINT ( 'NONE', #24407 ) ; +#21280 = CARTESIAN_POINT ( 'NONE', ( -39.57601231736000358, 119.6892406455000071, 90.26371608389000301 ) ) ; +#21281 = EDGE_CURVE ( 'NONE', #26700, #31921, #37227, .T. ) ; +#21282 = CARTESIAN_POINT ( 'NONE', ( 37.56355726554620134, 212.6956742645159011, 73.20248333212254011 ) ) ; +#21283 = VECTOR ( 'NONE', #26844, 1000.000000000000000 ) ; +#21284 = VECTOR ( 'NONE', #32160, 999.9999999999998863 ) ; +#21285 = DIRECTION ( 'NONE', ( 0.0006039748319386906410, -0.000000000000000000, 0.9999998176071845934 ) ) ; +#21286 = ORIENTED_EDGE ( 'NONE', *, *, #674, .F. ) ; +#21287 = VECTOR ( 'NONE', #36557, 999.9999999999998863 ) ; +#21288 = LINE ( 'NONE', #9014, #332 ) ; +#21289 = CARTESIAN_POINT ( 'NONE', ( 29.39370237474554770, 191.5260169245929092, 103.8524356916996396 ) ) ; +#21290 = CIRCLE ( 'NONE', #19933, 2.000000000000011546 ) ; +#21291 = EDGE_CURVE ( 'NONE', #34215, #9595, #27276, .T. ) ; +#21292 = ADVANCED_FACE ( 'NONE', ( #40111 ), #33573, .T. ) ; +#21293 = FACE_OUTER_BOUND ( 'NONE', #3804, .T. ) ; +#21294 = CARTESIAN_POINT ( 'NONE', ( -3.656136860141406153, 187.3893018360669203, 102.9173608625563361 ) ) ; +#21295 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568178 ) ) ; +#21296 = EDGE_CURVE ( 'NONE', #37440, #24578, #12407, .T. ) ; +#21297 = ORIENTED_EDGE ( 'NONE', *, *, #2494, .T. ) ; +#21298 = CARTESIAN_POINT ( 'NONE', ( -31.84898476996059813, 157.9423125112969331, 186.4027463543498584 ) ) ; +#21299 = CARTESIAN_POINT ( 'NONE', ( 1.206895876459000094, 188.8306159436000087, 103.3834228997999958 ) ) ; +#21300 = FACE_OUTER_BOUND ( 'NONE', #17158, .T. ) ; +#21301 = ORIENTED_EDGE ( 'NONE', *, *, #34047, .F. ) ; +#21302 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058996743, 130.4211554272961280, 90.27959376775912403 ) ) ; +#21303 = ORIENTED_EDGE ( 'NONE', *, *, #27056, .F. ) ; +#21304 = CARTESIAN_POINT ( 'NONE', ( -38.81769244209999670, 118.7847089182999980, 89.71781930851000197 ) ) ; +#21305 = VECTOR ( 'NONE', #22639, 1000.000000000000114 ) ; +#21306 = ORIENTED_EDGE ( 'NONE', *, *, #33542, .T. ) ; +#21307 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971561517 ) ) ; +#21308 = AXIS2_PLACEMENT_3D ( 'NONE', #25704, #10158, #22425 ) ; +#21309 = CARTESIAN_POINT ( 'NONE', ( -35.93960179980999925, 192.7068948186999933, 105.7594716616000028 ) ) ; +#21310 = CARTESIAN_POINT ( 'NONE', ( -37.39932010222903358, 212.8449755639020111, 76.08109288175667473 ) ) ; +#21311 = AXIS2_PLACEMENT_3D ( 'NONE', #21713, #3085, #5347 ) ; +#21312 = CARTESIAN_POINT ( 'NONE', ( 38.97366284846734175, 78.18638126909256414, 288.5917584186810814 ) ) ; +#21313 = VERTEX_POINT ( 'NONE', #27488 ) ; +#21314 = CARTESIAN_POINT ( 'NONE', ( -29.94659852520202037, 103.6131156702491865, 89.78587174319537212 ) ) ; +#21315 = CARTESIAN_POINT ( 'NONE', ( -1.630689202969549667, 189.3908836070928032, 105.8511190046429107 ) ) ; +#21316 = VERTEX_POINT ( 'NONE', #24608 ) ; +#21317 = CONICAL_SURFACE ( 'NONE', #27836, 2.500000073598442896, 0.7853981634226060438 ) ; +#21318 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21319 = CYLINDRICAL_SURFACE ( 'NONE', #24134, 2.000000000000014655 ) ; +#21320 = CONICAL_SURFACE ( 'NONE', #25232, 2.499999999987588595, 0.7853981634197695350 ) ; +#21322 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#21321 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#21323 = ORIENTED_EDGE ( 'NONE', *, *, #16359, .T. ) ; +#21324 = ADVANCED_FACE ( 'NONE', ( #37062 ), #11716, .F. ) ; +#21325 = CARTESIAN_POINT ( 'NONE', ( 15.94065395167610788, 152.5983745658832902, 182.6131612411744527 ) ) ; +#21326 = ORIENTED_EDGE ( 'NONE', *, *, #25267, .F. ) ; +#21327 = DIRECTION ( 'NONE', ( 0.6087611434179116543, -0.7728348325624403437, -0.1792657018023851578 ) ) ; +#21328 = ADVANCED_FACE ( 'NONE', ( #9454 ), #21118, .F. ) ; +#21329 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971544308 ) ) ; +#21330 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; +#21331 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21332 = EDGE_CURVE ( 'NONE', #24453, #32145, #16991, .T. ) ; +#21333 = ORIENTED_EDGE ( 'NONE', *, *, #19586, .T. ) ; +#21334 = ORIENTED_EDGE ( 'NONE', *, *, #16896, .F. ) ; +#21335 = VECTOR ( 'NONE', #16025, 1000.000000000000227 ) ; +#21336 = CARTESIAN_POINT ( 'NONE', ( 36.03687122555673739, 218.5902260770998282, 61.03673652646995862 ) ) ; +#21337 = VECTOR ( 'NONE', #11967, 1000.000000000000227 ) ; +#21338 = EDGE_CURVE ( 'NONE', #38178, #31820, #36532, .T. ) ; +#21339 = AXIS2_PLACEMENT_3D ( 'NONE', #28637, #37437, #19615 ) ; +#21340 = FACE_OUTER_BOUND ( 'NONE', #8936, .T. ) ; +#21341 = EDGE_LOOP ( 'NONE', ( #22991, #18400, #23787, #39852 ) ) ; +#21342 = EDGE_CURVE ( 'NONE', #5436, #28807, #16519, .T. ) ; +#21343 = ORIENTED_EDGE ( 'NONE', *, *, #37789, .F. ) ; +#21344 = CARTESIAN_POINT ( 'NONE', ( -3.692940375663182451, 144.1765304566810642, 93.10030759800980604 ) ) ; +#21345 = EDGE_CURVE ( 'NONE', #19726, #19846, #28756, .T. ) ; +#21346 = AXIS2_PLACEMENT_3D ( 'NONE', #35783, #1254, #38869 ) ; +#21347 = VECTOR ( 'NONE', #3412, 1000.000000000000114 ) ; +#21348 = ORIENTED_EDGE ( 'NONE', *, *, #31299, .F. ) ; +#21349 = CARTESIAN_POINT ( 'NONE', ( 2.332801095514406509, 189.0539861093840273, 106.3967151195623728 ) ) ; +#21350 = CARTESIAN_POINT ( 'NONE', ( -20.51938464653014549, 208.0070366894154006, 73.88096774075889073 ) ) ; +#21351 = CARTESIAN_POINT ( 'NONE', ( -13.59923565109000165, 180.7017300104000128, 28.07991271570000080 ) ) ; +#21352 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; +#21353 = LINE ( 'NONE', #8472, #22204 ) ; +#21354 = ORIENTED_EDGE ( 'NONE', *, *, #32354, .F. ) ; +#21355 = CARTESIAN_POINT ( 'NONE', ( 39.75749670546768044, 190.3327792175265074, 106.6496084232941683 ) ) ; +#21356 = LINE ( 'NONE', #12150, #20164 ) ; +#21357 = ORIENTED_EDGE ( 'NONE', *, *, #13099, .T. ) ; +#21358 = VECTOR ( 'NONE', #7854, 1000.000000000000114 ) ; +#21359 = FACE_OUTER_BOUND ( 'NONE', #29512, .T. ) ; +#21360 = ORIENTED_EDGE ( 'NONE', *, *, #37790, .T. ) ; +#21361 = CONICAL_SURFACE ( 'NONE', #1018, 2.749999999950583973, 0.7853981633811774055 ) ; +#21362 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #16816, #26451, #16221 ), + ( #25858, #35606, #19685 ), + ( #10108, #7623, #28709 ), + ( #688, #38690, #29510 ), + ( #13178, #23178, #13766 ), + ( #25660, #16613, #29112 ), + ( #13572, #35007, #22981 ), + ( #19488, #31982, #26052 ), + ( #1487, #38305, #10708 ), + ( #32572, #4348, #13971 ) ), + .UNSPECIFIED., .F., .F., .T. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 2, 2, 2, 4 ), + ( 3, 3 ), + ( 0.0006290844662723365198, 0.001453074859921644037, 0.002277065253570951554, 0.003101055647220258855, 0.003925046040869566155 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.8214630073245949848, 1.000000000000000000), + ( 1.000000000000000000, 0.8179501931302566309, 1.000000000000000000), + ( 1.000000000000000000, 0.8120421346113418926, 1.000000000000000000), + ( 1.000000000000000000, 0.7953930622375270376, 1.000000000000000000), + ( 1.000000000000000000, 0.7845309420939873268, 1.000000000000000000), + ( 1.000000000000000000, 0.7575129545167481604, 1.000000000000000000), + ( 1.000000000000000000, 0.7411181031346090187, 1.000000000000000000), + ( 1.000000000000000000, 0.7023451256331760817, 1.000000000000000000), + ( 1.000000000000000000, 0.6795235542076561996, 1.000000000000000000), + ( 1.000000000000000000, 0.6536732819161872321, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#21363 = VECTOR ( 'NONE', #36274, 1000.000000000000000 ) ; +#21365 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; +#21364 = CARTESIAN_POINT ( 'NONE', ( 13.84826647186673654, 135.4318207773943641, 90.91145678624771165 ) ) ; +#21366 = ORIENTED_EDGE ( 'NONE', *, *, #37569, .T. ) ; +#21367 = ORIENTED_EDGE ( 'NONE', *, *, #6812, .T. ) ; +#21368 = CARTESIAN_POINT ( 'NONE', ( 25.49202135914930523, 205.7387363836115526, 75.88112788460828995 ) ) ; +#21369 = ORIENTED_EDGE ( 'NONE', *, *, #16823, .T. ) ; +#21370 = EDGE_CURVE ( 'NONE', #267, #4577, #7257, .T. ) ; +#21372 = CONICAL_SURFACE ( 'NONE', #18064, 2.749999999949247709, 0.7853981633862016087 ) ; +#21371 = CARTESIAN_POINT ( 'NONE', ( 2.385423998479000218, 209.2946138833000020, 75.43815394924999396 ) ) ; +#21373 = EDGE_CURVE ( 'NONE', #25751, #18083, #15972, .T. ) ; +#21374 = DIRECTION ( 'NONE', ( 0.0005734119072316638333, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#21375 = EDGE_CURVE ( 'NONE', #27561, #28078, #34560, .T. ) ; +#21376 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825964864930728, 0.0005734119013526018391 ) ) ; +#21377 = VERTEX_POINT ( 'NONE', #1034 ) ; +#21378 = ORIENTED_EDGE ( 'NONE', *, *, #24583, .T. ) ; +#21379 = CARTESIAN_POINT ( 'NONE', ( -20.49960732757744353, 118.8154816606033393, 87.78015075453545535 ) ) ; +#21380 = ORIENTED_EDGE ( 'NONE', *, *, #3839, .F. ) ; +#21381 = VERTEX_POINT ( 'NONE', #19230 ) ; +#21382 = FACE_OUTER_BOUND ( 'NONE', #22690, .T. ) ; +#21383 = EDGE_CURVE ( 'NONE', #22385, #6692, #23401, .T. ) ; +#21384 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384972194 ) ) ; +#21385 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524157562, 149.3470289647612219, 130.0514119197758305 ) ) ; +#21386 = FACE_OUTER_BOUND ( 'NONE', #22433, .T. ) ; +#21387 = CARTESIAN_POINT ( 'NONE', ( 35.55365739661999669, 192.3091292246000421, 103.8613361242999957 ) ) ; +#21388 = ADVANCED_FACE ( 'NONE', ( #26006 ), #9181, .F. ) ; +#21389 = EDGE_LOOP ( 'NONE', ( #39246, #12037, #23448, #18029 ) ) ; +#21390 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33702, #15122, #24740, #12052 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21391 = EDGE_LOOP ( 'NONE', ( #36072, #4153, #2471, #18999 ) ) ; +#21392 = DIRECTION ( 'NONE', ( 1.249000902704392418E-14, 0.9743700557921585181, 0.2249510932971566235 ) ) ; +#21393 = LINE ( 'NONE', #5834, #39383 ) ; +#21394 = CARTESIAN_POINT ( 'NONE', ( 31.50927902734200359, 191.9221074921661057, 104.4557544969390506 ) ) ; +#21395 = CARTESIAN_POINT ( 'NONE', ( -25.56609382933000063, 121.5324527806999981, 88.23963119317001258 ) ) ; +#21396 = EDGE_CURVE ( 'NONE', #33783, #26891, #33968, .T. ) ; +#21397 = ORIENTED_EDGE ( 'NONE', *, *, #4139, .T. ) ; +#21398 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989908600, -0.1373964268091705798 ) ) ; +#21399 = CARTESIAN_POINT ( 'NONE', ( -39.78547281363039900, 190.3169928286148718, 106.6940055862042271 ) ) ; +#21400 = ORIENTED_EDGE ( 'NONE', *, *, #23814, .F. ) ; +#21401 = AXIS2_PLACEMENT_3D ( 'NONE', #24818, #37662, #11931 ) ; +#21402 = LINE ( 'NONE', #15255, #18958 ) ; +#21403 = CARTESIAN_POINT ( 'NONE', ( -4.036264727110095762, 167.9338357148023704, 100.9917020970900410 ) ) ; +#21404 = AXIS2_PLACEMENT_3D ( 'NONE', #36117, #24077, #36533 ) ; +#21405 = ADVANCED_FACE ( 'NONE', ( #16177 ), #35224, .F. ) ; +#21406 = DIRECTION ( 'NONE', ( -0.6087613502019256773, 0.7729389820454566351, 0.1788154035167601741 ) ) ; +#21407 = CARTESIAN_POINT ( 'NONE', ( -15.99847796691061852, 137.5244930513001975, 94.49161329741416182 ) ) ; +#21408 = ORIENTED_EDGE ( 'NONE', *, *, #17146, .F. ) ; +#21409 = CARTESIAN_POINT ( 'NONE', ( -2.438441564891038915, 191.9759150222000130, 101.9229200978912075 ) ) ; +#21410 = VERTEX_POINT ( 'NONE', #1440 ) ; +#21411 = EDGE_LOOP ( 'NONE', ( #8630, #8082, #28466, #6830, #22983, #1874 ) ) ; +#21412 = CARTESIAN_POINT ( 'NONE', ( 3.009765127882288116, 209.4523184236957434, 73.05668452217646802 ) ) ; +#21413 = CARTESIAN_POINT ( 'NONE', ( 3.578322037540619505, 149.3470289647403320, 130.0514119197709988 ) ) ; +#21414 = CARTESIAN_POINT ( 'NONE', ( 38.53393130996000338, 118.5935268415999957, 89.80359806433999381 ) ) ; +#21415 = CARTESIAN_POINT ( 'NONE', ( -29.91895087148420629, 182.1247778028852622, 101.7178115817681032 ) ) ; +#21416 = ORIENTED_EDGE ( 'NONE', *, *, #22489, .T. ) ; +#21417 = LINE ( 'NONE', #33853, #30472 ) ; +#21418 = ORIENTED_EDGE ( 'NONE', *, *, #9842, .F. ) ; +#21419 = CARTESIAN_POINT ( 'NONE', ( 18.08235529168842604, 152.6330892152822685, 184.7488916507021202 ) ) ; +#21420 = DIRECTION ( 'NONE', ( -0.0006039748319356123742, 6.151140898304641511E-15, -0.9999998176071847045 ) ) ; +#21421 = EDGE_LOOP ( 'NONE', ( #37906, #31165, #12854, #7218, #16605, #100, #2121, #19359, #7562 ) ) ; +#21422 = ADVANCED_FACE ( 'NONE', ( #27588 ), #6555, .T. ) ; +#21423 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#21424 = EDGE_CURVE ( 'NONE', #34711, #9488, #24094, .T. ) ; +#21425 = VECTOR ( 'NONE', #35323, 1000.000000000000227 ) ; +#21426 = DIRECTION ( 'NONE', ( -0.7936449239197745920, 0.5927912671287571822, 0.1368438831378941400 ) ) ; +#21427 = EDGE_CURVE ( 'NONE', #2373, #33167, #35638, .T. ) ; +#21428 = CARTESIAN_POINT ( 'NONE', ( -14.16977583430312926, 135.9878589137828726, 91.56990267135316230 ) ) ; +#21429 = EDGE_CURVE ( 'NONE', #21678, #26191, #39609, .T. ) ; +#21430 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091564245 ) ) ; +#21431 = AXIS2_PLACEMENT_3D ( 'NONE', #2300, #17613, #14368 ) ; +#21432 = EDGE_LOOP ( 'NONE', ( #24604, #19516, #24245, #9004 ) ) ; +#21433 = VERTEX_POINT ( 'NONE', #12226 ) ; +#21434 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457972811109, -32.89481530046835189, 142.2936922234671613 ) ) ; +#21435 = CARTESIAN_POINT ( 'NONE', ( 13.47116993038426358, 154.0079171905443047, 95.54241653341313167 ) ) ; +#21436 = ADVANCED_FACE ( 'NONE', ( #6271 ), #15678, .F. ) ; +#21437 = ORIENTED_EDGE ( 'NONE', *, *, #40103, .T. ) ; +#21438 = CARTESIAN_POINT ( 'NONE', ( -35.93686737616000215, 193.5538913732000026, 105.8995219524000078 ) ) ; +#21439 = PLANE ( 'NONE', #34789 ) ; +#21440 = ORIENTED_EDGE ( 'NONE', *, *, #39463, .T. ) ; +#21441 = FACE_OUTER_BOUND ( 'NONE', #11079, .T. ) ; +#21442 = EDGE_CURVE ( 'NONE', #32994, #30422, #26171, .T. ) ; +#21443 = CARTESIAN_POINT ( 'NONE', ( 35.56284489036890051, 193.8169247291054376, 102.6814306727405750 ) ) ; +#21444 = CARTESIAN_POINT ( 'NONE', ( -26.00800983458967508, 191.5260122442129216, 103.8858970416150385 ) ) ; +#21445 = ORIENTED_EDGE ( 'NONE', *, *, #26676, .T. ) ; +#21446 = CARTESIAN_POINT ( 'NONE', ( -20.99850207568253424, 135.8130112225352661, 93.92837029496691059 ) ) ; +#21447 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21448 = CARTESIAN_POINT ( 'NONE', ( -26.13262776858000080, 190.9207843215999958, 106.9673394545999940 ) ) ; +#21449 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25264, #28524, #890, #10523 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 5.933558708143790383, 7.730894538220764112 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7484352496336026395, 0.7484352496336026395, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#21450 = CARTESIAN_POINT ( 'NONE', ( -24.82787921266102771, 115.6987712569605833, 90.28278025611777480 ) ) ; +#21451 = CARTESIAN_POINT ( 'NONE', ( 3.251699916679381630, 126.1628332823677709, 88.77794208007185262 ) ) ; +#21452 = EDGE_LOOP ( 'NONE', ( #8600, #10776, #25453, #26549 ) ) ; +#21453 = ORIENTED_EDGE ( 'NONE', *, *, #25916, .F. ) ; +#21454 = LINE ( 'NONE', #5069, #10253 ) ; +#21455 = CARTESIAN_POINT ( 'NONE', ( -0.4543644846840136919, 210.9999999999990621, 75.55877896310728659 ) ) ; +#21456 = CARTESIAN_POINT ( 'NONE', ( 37.31639193983529879, 111.9096183688354245, 150.0649592369359766 ) ) ; +#21457 = CONICAL_SURFACE ( 'NONE', #25359, 2.502965858498830354, 0.7853981633840887433 ) ; +#21458 = CARTESIAN_POINT ( 'NONE', ( -15.94475015168131726, 152.3695000724660531, 183.5849529441521781 ) ) ; +#21459 = VERTEX_POINT ( 'NONE', #25108 ) ; +#21460 = EDGE_LOOP ( 'NONE', ( #18239, #3991, #247, #38205, #5504, #28929, #20774, #13756, #2755, #8800 ) ) ; +#21461 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971531540 ) ) ; +#21462 = CARTESIAN_POINT ( 'NONE', ( 2.546082943913467123, 205.5673828937494534, 76.29867481864103240 ) ) ; +#21463 = CIRCLE ( 'NONE', #34457, 5.500000000097090336 ) ; +#21464 = CARTESIAN_POINT ( 'NONE', ( 23.74081244260071344, 214.0195164535212200, 73.04416522657409416 ) ) ; +#21465 = CARTESIAN_POINT ( 'NONE', ( -25.64792389571747933, 212.5442448628288901, 73.07399478574440366 ) ) ; +#21466 = CARTESIAN_POINT ( 'NONE', ( -30.80669558541512387, 183.2612378953851362, 101.9807202910270405 ) ) ; +#21467 = CARTESIAN_POINT ( 'NONE', ( -35.94659742851874284, 109.6131156826799895, 89.78949559170979455 ) ) ; +#21468 = CARTESIAN_POINT ( 'NONE', ( 6.037083992585445813, 176.9518112263966714, 103.3541370315850259 ) ) ; +#21469 = LINE ( 'NONE', #31670, #10583 ) ; +#21470 = CARTESIAN_POINT ( 'NONE', ( 4.603077704204733500, 181.9200065296383286, 101.6496859594862627 ) ) ; +#21471 = DIRECTION ( 'NONE', ( 0.0004270746993300993609, -0.7071067811864992780, 0.7071066522153991452 ) ) ; +#21472 = CARTESIAN_POINT ( 'NONE', ( 25.49929013439852099, 120.2777482667000015, 87.91897806053000863 ) ) ; +#21473 = LINE ( 'NONE', #11446, #22844 ) ; +#21474 = CARTESIAN_POINT ( 'NONE', ( 37.68744678548170413, 191.4230900328749954, 104.2932531994780021 ) ) ; +#21475 = ADVANCED_FACE ( 'NONE', ( #24715 ), #145, .T. ) ; +#21476 = ADVANCED_FACE ( 'NONE', ( #21441 ), #19604, .F. ) ; +#21477 = ORIENTED_EDGE ( 'NONE', *, *, #9550, .T. ) ; +#21478 = CARTESIAN_POINT ( 'NONE', ( 36.60667824930000336, 191.2880709291999892, 106.4529399168999930 ) ) ; +#21479 = ORIENTED_EDGE ( 'NONE', *, *, #11912, .T. ) ; +#21480 = EDGE_LOOP ( 'NONE', ( #34182, #30844 ) ) ; +#21481 = ORIENTED_EDGE ( 'NONE', *, *, #14174, .F. ) ; +#21483 = AXIS2_PLACEMENT_3D ( 'NONE', #36608, #35977, #39053 ) ; +#21482 = CARTESIAN_POINT ( 'NONE', ( 2.561557522426482159, 191.9759150222000130, 101.9199002238076162 ) ) ; +#21484 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15630, #3950, #4146, #19493 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21485 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#21486 = CONICAL_SURFACE ( 'NONE', #4485, 6.499999999957617014, 0.7853981634197665374 ) ; +#21487 = CARTESIAN_POINT ( 'NONE', ( 45.11685896322114786, 125.4654678076909846, 91.67056992293602491 ) ) ; +#21488 = CIRCLE ( 'NONE', #1882, 2.000000000223707275 ) ; +#21489 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4746, #36016, #39698, #8019 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21490 = VERTEX_POINT ( 'NONE', #18725 ) ; +#21491 = CARTESIAN_POINT ( 'NONE', ( -39.33809393978000202, 119.3098376324000043, 89.91474602178001874 ) ) ; +#21492 = LINE ( 'NONE', #24359, #7426 ) ; +#21493 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21494 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; +#21495 = ORIENTED_EDGE ( 'NONE', *, *, #24156, .F. ) ; +#21496 = CARTESIAN_POINT ( 'NONE', ( -42.50703640508957903, 189.8244386586393375, 106.5819344532048234 ) ) ; +#21497 = CARTESIAN_POINT ( 'NONE', ( 23.37050237754266391, 177.1040287634355650, 103.5841246925966601 ) ) ; +#21498 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5153, #33373, #14191, #36030, #23783, #29919 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21499 = CARTESIAN_POINT ( 'NONE', ( 5.669001395941777766, 130.0333311697188492, 92.31877599091235709 ) ) ; +#21500 = CARTESIAN_POINT ( 'NONE', ( -3.537744320960331645, 175.3497732290038300, 100.1377481765469355 ) ) ; +#21501 = CARTESIAN_POINT ( 'NONE', ( -15.49970618479461137, 184.8500655517521807, 102.8514372352811108 ) ) ; +#21502 = ORIENTED_EDGE ( 'NONE', *, *, #23720, .F. ) ; +#21503 = ADVANCED_FACE ( 'NONE', ( #37754 ), #34669, .T. ) ; +#21504 = CARTESIAN_POINT ( 'NONE', ( -26.62773329666000421, 189.0698272449000115, 103.4439533488999956 ) ) ; +#21505 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971556798 ) ) ; +#21506 = CARTESIAN_POINT ( 'NONE', ( -22.78373664920998465, 158.6756214348941967, 96.81298893720612853 ) ) ; +#21507 = ORIENTED_EDGE ( 'NONE', *, *, #20975, .T. ) ; +#21508 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#21509 = EDGE_LOOP ( 'NONE', ( #30557, #30566, #24179, #23013 ) ) ; +#21510 = CONICAL_SURFACE ( 'NONE', #20841, 2.749999999928335992, 0.7853981634201930850 ) ; +#21511 = LINE ( 'NONE', #15939, #20409 ) ; +#21512 = AXIS2_PLACEMENT_3D ( 'NONE', #7484, #26323, #20157 ) ; +#21513 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; +#21514 = CIRCLE ( 'NONE', #35180, 3.500000265863834947 ) ; +#21515 = CARTESIAN_POINT ( 'NONE', ( -36.23875406263000087, 191.8022506627999917, 105.0197184015000005 ) ) ; +#21516 = VECTOR ( 'NONE', #1619, 1000.000000000000227 ) ; +#21517 = CARTESIAN_POINT ( 'NONE', ( -20.01999405515273622, 209.2223495200929619, 73.07050896365778669 ) ) ; +#21519 = ADVANCED_FACE ( 'NONE', ( #12416, #25309 ), #34079, .T. ) ; +#21518 = CARTESIAN_POINT ( 'NONE', ( -37.77017277285205665, 190.9635658029147010, 106.3292223135493941 ) ) ; +#21520 = ORIENTED_EDGE ( 'NONE', *, *, #38117, .T. ) ; +#21521 = CARTESIAN_POINT ( 'NONE', ( -12.63753158754559180, 134.7187973715719522, 93.43418384966304302 ) ) ; +#21522 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971557631 ) ) ; +#21523 = EDGE_LOOP ( 'NONE', ( #19896, #36281, #31037, #1768 ) ) ; +#21524 = DIRECTION ( 'NONE', ( -0.0005559617641341623026, 0.3907311285998608663, -0.9205046855120270211 ) ) ; +#21525 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37674, #25225, #22356, #38272 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21526 = CARTESIAN_POINT ( 'NONE', ( 20.00140612192502942, 118.1043503129110093, 90.25575274657424529 ) ) ; +#21527 = DIRECTION ( 'NONE', ( -0.0005884949961280444780, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#21528 = ADVANCED_FACE ( 'NONE', ( #18527 ), #16337, .F. ) ; +#21529 = EDGE_CURVE ( 'NONE', #38636, #15042, #1997, .T. ) ; +#21531 = CARTESIAN_POINT ( 'NONE', ( 14.27749844727565076, 135.1700550567618961, 93.92967703643782329 ) ) ; +#21530 = CARTESIAN_POINT ( 'NONE', ( -3.668404236601097601, 185.3449489774860979, 105.0111528754605530 ) ) ; +#21532 = VERTEX_POINT ( 'NONE', #15291 ) ; +#21533 = VERTEX_POINT ( 'NONE', #3199 ) ; +#21534 = ORIENTED_EDGE ( 'NONE', *, *, #20517, .F. ) ; +#21535 = CARTESIAN_POINT ( 'NONE', ( 8.189646510984831096, 160.7227069166503668, 99.66159882002607162 ) ) ; +#21536 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319386171321 ) ) ; +#21537 = DIRECTION ( 'NONE', ( 0.0006039748319386430446, 1.236414387799018187E-14, 0.9999998176071845934 ) ) ; +#21538 = CARTESIAN_POINT ( 'NONE', ( 35.04494057328201961, 217.7719116313999734, 73.03733781645851764 ) ) ; +#21539 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; +#21540 = DIRECTION ( 'NONE', ( -0.7933532970003740470, -0.5930762008556723641, -0.1372995488602875569 ) ) ; +#21541 = ORIENTED_EDGE ( 'NONE', *, *, #17002, .F. ) ; +#21542 = VECTOR ( 'NONE', #19734, 999.9999999999998863 ) ; +#21543 = ORIENTED_EDGE ( 'NONE', *, *, #26039, .T. ) ; +#21544 = VECTOR ( 'NONE', #21007, 999.9999999999998863 ) ; +#21545 = CARTESIAN_POINT ( 'NONE', ( 32.37225756566472512, 173.7344409119733086, 102.8220398834807980 ) ) ; +#21546 = AXIS2_PLACEMENT_3D ( 'NONE', #6791, #6397, #19258 ) ; +#21547 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#21548 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#21549 = ORIENTED_EDGE ( 'NONE', *, *, #18846, .T. ) ; +#21550 = CARTESIAN_POINT ( 'NONE', ( 35.71331820330245677, 209.7096552214366909, 75.87026816044664201 ) ) ; +#21551 = CARTESIAN_POINT ( 'NONE', ( -19.99806018810932429, 127.0618145191346713, 92.07850957579123019 ) ) ; +#21552 = CARTESIAN_POINT ( 'NONE', ( 2.745160164167272487, 189.5703853151680676, 106.5150923011538993 ) ) ; +#21553 = CARTESIAN_POINT ( 'NONE', ( 23.36940079100686063, 177.7945392694463749, 100.6858723966742843 ) ) ; +#21554 = CARTESIAN_POINT ( 'NONE', ( 13.49917495365670739, 124.5253171415348845, 88.60875626113156045 ) ) ; +#21555 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319363512580 ) ) ; +#21556 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988562940165, 156.3551877983851170, 95.75036263592699015 ) ) ; +#21557 = EDGE_CURVE ( 'NONE', #27979, #31021, #24221, .T. ) ; +#21558 = EDGE_LOOP ( 'NONE', ( #19106, #12165, #32732, #32797 ) ) ; +#21559 = PLANE ( 'NONE', #29092 ) ; +#21560 = DIRECTION ( 'NONE', ( -0.0002393071182782277790, -0.2252352986010052460, 0.9743043687658488050 ) ) ; +#21561 = AXIS2_PLACEMENT_3D ( 'NONE', #30228, #30027, #35719 ) ; +#21562 = EDGE_CURVE ( 'NONE', #17896, #21784, #27482, .T. ) ; +#21563 = VECTOR ( 'NONE', #15388, 1000.000000000000114 ) ; +#21564 = ORIENTED_EDGE ( 'NONE', *, *, #624, .T. ) ; +#21565 = AXIS2_PLACEMENT_3D ( 'NONE', #8162, #20627, #33092 ) ; +#21566 = LINE ( 'NONE', #18261, #22789 ) ; +#21567 = ORIENTED_EDGE ( 'NONE', *, *, #11674, .F. ) ; +#21568 = ADVANCED_FACE ( 'NONE', ( #15488 ), #21829, .T. ) ; +#21569 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7312, #32277, #23075, #26156 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.002691258517243560675, 0.003374075896545886393 ), + .UNSPECIFIED. ) ; +#21570 = EDGE_CURVE ( 'NONE', #37986, #407, #3399, .T. ) ; +#21572 = CARTESIAN_POINT ( 'NONE', ( 35.66415592867893025, 191.9426605352722106, 103.8996477256188484 ) ) ; +#21571 = CARTESIAN_POINT ( 'NONE', ( 12.69440440448767937, 134.9200954942802468, 90.79401257800917335 ) ) ; +#21573 = EDGE_CURVE ( 'NONE', #34987, #39550, #20931, .T. ) ; +#21574 = ORIENTED_EDGE ( 'NONE', *, *, #30652, .F. ) ; +#21575 = ORIENTED_EDGE ( 'NONE', *, *, #4545, .T. ) ; +#21576 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557741681312, -0.2249510933750812069 ) ) ; +#21577 = EDGE_CURVE ( 'NONE', #20244, #12970, #25510, .T. ) ; +#21578 = ORIENTED_EDGE ( 'NONE', *, *, #10349, .T. ) ; +#21579 = CARTESIAN_POINT ( 'NONE', ( 2.335069725756000025, 209.5243782654999904, 75.42221763621000719 ) ) ; +#21580 = CARTESIAN_POINT ( 'NONE', ( 1.218001437391567077, 135.9198998882713170, 177.2143327488629154 ) ) ; +#21581 = PLANE ( 'NONE', #35116 ) ; +#21582 = ORIENTED_EDGE ( 'NONE', *, *, #29539, .T. ) ; +#21583 = VERTEX_POINT ( 'NONE', #5880 ) ; +#21584 = VERTEX_POINT ( 'NONE', #13430 ) ; +#21585 = DIRECTION ( 'NONE', ( -0.7942818278044030400, -0.5920830005357836656, -0.1362134299408093163 ) ) ; +#21586 = CARTESIAN_POINT ( 'NONE', ( -19.73823131666757291, 124.3520775053762719, 178.1518425532499919 ) ) ; +#21587 = CARTESIAN_POINT ( 'NONE', ( 22.68181547863324710, 135.1246333993239830, 90.83520173675087506 ) ) ; +#21588 = ORIENTED_EDGE ( 'NONE', *, *, #4215, .T. ) ; +#21589 = ORIENTED_EDGE ( 'NONE', *, *, #16051, .F. ) ; +#21590 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; +#21591 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21592 = DIRECTION ( 'NONE', ( -0.0005884952006634126126, 0.2255194586134631751, -0.9742384859263615304 ) ) ; +#21593 = ORIENTED_EDGE ( 'NONE', *, *, #1673, .F. ) ; +#21594 = CARTESIAN_POINT ( 'NONE', ( 19.99999382154498662, 120.3902235794415816, 87.43511282661482653 ) ) ; +#21595 = AXIS2_PLACEMENT_3D ( 'NONE', #20772, #33225, #8516 ) ; +#21596 = EDGE_LOOP ( 'NONE', ( #8746, #20263, #27682, #12292, #27406, #24655, #3596, #16734, #29286, #23788, #6415, #34219, #21303, #39988, #35212, #1286, #10981, #18616, #38288, #7615, #1274, #19448, #15525, #24706, #6965, #31468, #3167 ) ) ; +#21597 = LINE ( 'NONE', #30378, #33017 ) ; +#21598 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; +#21599 = VECTOR ( 'NONE', #38552, 1000.000000000000114 ) ; +#21600 = VERTEX_POINT ( 'NONE', #19541 ) ; +#21601 = FACE_OUTER_BOUND ( 'NONE', #31545, .T. ) ; +#21602 = VECTOR ( 'NONE', #31816, 1000.000000000000000 ) ; +#21603 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178582671909E-05, -0.0002331579774919533509 ) ) ; +#21604 = CARTESIAN_POINT ( 'NONE', ( -15.83315360615156564, 125.9251344721852917, 88.73459174902453128 ) ) ; +#21605 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21606 = CARTESIAN_POINT ( 'NONE', ( -15.66515283670559100, 137.5952383037110565, 94.16561455557221905 ) ) ; +#21607 = EDGE_CURVE ( 'NONE', #2217, #32971, #32663, .T. ) ; +#21608 = ORIENTED_EDGE ( 'NONE', *, *, #15626, .F. ) ; +#21609 = CARTESIAN_POINT ( 'NONE', ( -31.91335489270172232, 174.4783875135883875, 100.4668596826281970 ) ) ; +#21610 = CARTESIAN_POINT ( 'NONE', ( 39.41132636150051383, 77.88677779677399826, 290.3259969045751063 ) ) ; +#21611 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606776115838874, 137.3532831589803322, 178.0585834212922123 ) ) ; +#21612 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8751, #40006, #33255, #2612 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.442078219984857190, 1.442116544522912047 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999998776024634, 0.9999999998776024634, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#21613 = DIRECTION ( 'NONE', ( 0.7933533411653073131, 0.5931840316265226676, 0.1368326740407721509 ) ) ; +#21614 = EDGE_CURVE ( 'NONE', #39643, #32491, #17640, .T. ) ; +#21615 = CARTESIAN_POINT ( 'NONE', ( -13.49823529424112145, 157.6276863903721051, 99.13120655217578303 ) ) ; +#21616 = ORIENTED_EDGE ( 'NONE', *, *, #13153, .T. ) ; +#21617 = EDGE_CURVE ( 'NONE', #15846, #23762, #3286, .T. ) ; +#21618 = CARTESIAN_POINT ( 'NONE', ( -38.02669066786999963, 118.9111989599000054, 90.44675963502000116 ) ) ; +#21619 = EDGE_CURVE ( 'NONE', #3510, #17327, #1332, .T. ) ; +#21620 = CARTESIAN_POINT ( 'NONE', ( 15.50147166558119594, 185.3474886484798390, 105.0001610792874942 ) ) ; +#21621 = VECTOR ( 'NONE', #31121, 1000.000000000000000 ) ; +#21622 = EDGE_LOOP ( 'NONE', ( #27932, #10625, #23110, #24017 ) ) ; +#21623 = CARTESIAN_POINT ( 'NONE', ( -9.153839578580999614, 181.8749524105000148, 101.9041693016999943 ) ) ; +#21624 = AXIS2_PLACEMENT_3D ( 'NONE', #40254, #12265, #24755 ) ; +#21625 = DIRECTION ( 'NONE', ( -0.6087611434179115433, 0.7728348325624404547, 0.1792657018023851023 ) ) ; +#21626 = DIRECTION ( 'NONE', ( -0.5986917825334797660, -0.8009794122048706777, 0.0003615948347011558174 ) ) ; +#21627 = CARTESIAN_POINT ( 'NONE', ( -34.64484841518558511, 164.3107434246603873, 190.4508713907742674 ) ) ; +#21628 = CARTESIAN_POINT ( 'NONE', ( -37.70556563760820978, 218.5902260770999987, 73.58127739041549376 ) ) ; +#21629 = CARTESIAN_POINT ( 'NONE', ( -37.05329340999391263, 117.5716747318153637, 90.29016409994973458 ) ) ; +#21630 = ORIENTED_EDGE ( 'NONE', *, *, #38471, .F. ) ; +#21631 = FACE_OUTER_BOUND ( 'NONE', #27706, .T. ) ; +#21632 = LINE ( 'NONE', #15868, #9963 ) ; +#21633 = CARTESIAN_POINT ( 'NONE', ( -26.97471921114255267, 119.7805572225935151, 171.4236432547711502 ) ) ; +#21634 = ORIENTED_EDGE ( 'NONE', *, *, #34326, .F. ) ; +#21635 = DIRECTION ( 'NONE', ( -0.0006039748319392907469, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#21636 = ORIENTED_EDGE ( 'NONE', *, *, #2745, .T. ) ; +#21637 = CARTESIAN_POINT ( 'NONE', ( -26.71688049004999854, 135.1028646788000174, 91.11658767897000644 ) ) ; +#21638 = CARTESIAN_POINT ( 'NONE', ( 37.42228677652877877, 190.4043295697634051, 106.6675375349840351 ) ) ; +#21639 = LINE ( 'NONE', #34082, #5279 ) ; +#21640 = ORIENTED_EDGE ( 'NONE', *, *, #40359, .F. ) ; +#21641 = CARTESIAN_POINT ( 'NONE', ( -61.84220049570045319, 78.72323700374752775, 282.5958934331605406 ) ) ; +#21642 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989907490, -0.1373964268091706076 ) ) ; +#21643 = CARTESIAN_POINT ( 'NONE', ( -25.87622840024999959, 190.9583691121999891, 106.7120253463000097 ) ) ; +#21644 = CARTESIAN_POINT ( 'NONE', ( -30.07068226051992355, 174.7890454599799739, 102.5900763959416935 ) ) ; +#21645 = CARTESIAN_POINT ( 'NONE', ( 15.59065710780919289, 127.6518116315415483, 175.3064835111600814 ) ) ; +#21646 = ORIENTED_EDGE ( 'NONE', *, *, #15755, .F. ) ; +#21647 = AXIS2_PLACEMENT_3D ( 'NONE', #38130, #28532, #499 ) ; +#21648 = CARTESIAN_POINT ( 'NONE', ( -28.45663166759245399, 131.0177812377234545, 89.91795229967709702 ) ) ; +#21649 = AXIS2_PLACEMENT_3D ( 'NONE', #36106, #37280, #11188 ) ; +#21650 = PLANE ( 'NONE', #19263 ) ; +#21651 = DIRECTION ( 'NONE', ( 0.4308752614361646138, -0.7059430892986333639, 0.5621306465171763689 ) ) ; +#21652 = ADVANCED_FACE ( 'NONE', ( #38361 ), #17065, .T. ) ; +#21653 = EDGE_CURVE ( 'NONE', #35621, #1138, #11806, .T. ) ; +#21654 = AXIS2_PLACEMENT_3D ( 'NONE', #40120, #9061, #21547 ) ; +#21655 = DIRECTION ( 'NONE', ( -0.0004161288024515960951, -0.5299192578740949955, -0.8480479980348919478 ) ) ; +#21656 = EDGE_CURVE ( 'NONE', #3220, #31100, #39978, .T. ) ; +#21657 = ORIENTED_EDGE ( 'NONE', *, *, #20289, .F. ) ; +#21658 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#21659 = EDGE_CURVE ( 'NONE', #31399, #29634, #32613, .T. ) ; +#21660 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#21661 = FACE_OUTER_BOUND ( 'NONE', #21149, .T. ) ; +#21662 = CARTESIAN_POINT ( 'NONE', ( -23.36013443277664692, 181.0071930014282486, 104.5378893608259574 ) ) ; +#21663 = EDGE_CURVE ( 'NONE', #11457, #10716, #19919, .T. ) ; +#21664 = CARTESIAN_POINT ( 'NONE', ( -30.66586300490362405, 182.9132905847569646, 101.9003052508140286 ) ) ; +#21665 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22768, #17000, #10903, #23373 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21666 = CARTESIAN_POINT ( 'NONE', ( 3.333113470500536302, 184.0886249089593605, 102.3221730663416764 ) ) ; +#21667 = CARTESIAN_POINT ( 'NONE', ( 14.89305388520275208, 183.2744346433559315, 102.2982670498846289 ) ) ; +#21668 = ADVANCED_FACE ( 'NONE', ( #9965 ), #667, .T. ) ; +#21669 = APPLICATION_PROTOCOL_DEFINITION ( 'international standard', 'config_control_design', 1994, #17458 ) ; +#21670 = CARTESIAN_POINT ( 'NONE', ( 5.659931281361317623, 181.6896837046558346, 101.5959228839198687 ) ) ; +#21671 = ORIENTED_EDGE ( 'NONE', *, *, #15811, .T. ) ; +#21672 = CARTESIAN_POINT ( 'NONE', ( -28.46570037481023974, 129.9682353462455353, 92.24140578278095859 ) ) ; +#21673 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16561, #22333, #15970, #19637 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21674 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 132.6352630048999970, 91.80276880046000088 ) ) ; +#21675 = CARTESIAN_POINT ( 'NONE', ( 37.96378318839221322, 191.4261383972079500, 104.2798627878850084 ) ) ; +#21676 = CIRCLE ( 'NONE', #12511, 51.90509898881521877 ) ; +#21677 = CARTESIAN_POINT ( 'NONE', ( 36.33054282364000187, 190.7404929015999926, 106.8950113761000011 ) ) ; +#21678 = VERTEX_POINT ( 'NONE', #35460 ) ; +#21679 = EDGE_LOOP ( 'NONE', ( #11966, #37136, #10496, #20227 ) ) ; +#21680 = EDGE_CURVE ( 'NONE', #20316, #14606, #16673, .T. ) ; +#21681 = FACE_OUTER_BOUND ( 'NONE', #36405, .T. ) ; +#21682 = CIRCLE ( 'NONE', #11897, 22.00000000001092815 ) ; +#21683 = CARTESIAN_POINT ( 'NONE', ( -30.11673635876000077, 127.0186994863999814, 89.25226417157000469 ) ) ; +#21684 = CARTESIAN_POINT ( 'NONE', ( -30.17790838424820521, 126.0796625456713826, 91.85784435949031490 ) ) ; +#21685 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #5661, #12591, #37541, #24493 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.750577995572639267, 3.321000581826867304 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8048259373832490349, 0.8048259373832490349, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#21686 = ORIENTED_EDGE ( 'NONE', *, *, #25084, .T. ) ; +#21687 = DIRECTION ( 'NONE', ( 0.7942820423213359238, 0.5918950211223032998, 0.1370267171630252800 ) ) ; +#21688 = CARTESIAN_POINT ( 'NONE', ( -20.00051264146630459, 193.4048159825563005, 103.3861754394172294 ) ) ; +#21689 = DIRECTION ( 'NONE', ( 0.6087614115774878654, 0.7729348350621346730, 0.1788331191967953149 ) ) ; +#21690 = VERTEX_POINT ( 'NONE', #10566 ) ; +#21691 = CARTESIAN_POINT ( 'NONE', ( 5.666638401078903264, 128.4739160337908288, 89.82319125807045168 ) ) ; +#21692 = LINE ( 'NONE', #2866, #35090 ) ; +#21693 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971562627 ) ) ; +#21694 = CARTESIAN_POINT ( 'NONE', ( -34.20556627594935861, 218.5902260770999987, 73.57916347850368766 ) ) ; +#21695 = ORIENTED_EDGE ( 'NONE', *, *, #6389, .F. ) ; +#21696 = ORIENTED_EDGE ( 'NONE', *, *, #34058, .F. ) ; +#21697 = CARTESIAN_POINT ( 'NONE', ( -25.65790946531999950, 191.0048140716000376, 104.1537698728999999 ) ) ; +#21698 = CARTESIAN_POINT ( 'NONE', ( 2.893325850217000283, 191.0743569784000044, 103.9380752567000030 ) ) ; +#21699 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; +#21700 = EDGE_CURVE ( 'NONE', #32568, #9773, #19938, .T. ) ; +#21701 = ORIENTED_EDGE ( 'NONE', *, *, #30265, .F. ) ; +#21702 = AXIS2_PLACEMENT_3D ( 'NONE', #18190, #2869, #18394 ) ; +#21703 = CARTESIAN_POINT ( 'NONE', ( -3.796900415192997702, 136.7373034043747850, 94.03478540737643243 ) ) ; +#21704 = EDGE_CURVE ( 'NONE', #31968, #9285, #38472, .T. ) ; +#21705 = VERTEX_POINT ( 'NONE', #16866 ) ; +#21706 = VECTOR ( 'NONE', #21540, 1000.000000000000000 ) ; +#21707 = VECTOR ( 'NONE', #38096, 1000.000000000000000 ) ; +#21708 = FACE_OUTER_BOUND ( 'NONE', #3062, .T. ) ; +#21709 = CARTESIAN_POINT ( 'NONE', ( 0.5459373363532030732, 211.4999999999976694, 76.05817489710604207 ) ) ; +#21710 = CARTESIAN_POINT ( 'NONE', ( 25.49273537670449130, 207.4083917605111367, 77.06627999559472642 ) ) ; +#21711 = CARTESIAN_POINT ( 'NONE', ( -36.06180846984999988, 192.0376933189999988, 106.6384909970000194 ) ) ; +#21712 = DIRECTION ( 'NONE', ( 0.0002393071182785538528, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#21713 = CARTESIAN_POINT ( 'NONE', ( -23.00157826576616671, 118.1131156702000169, 87.27825658246501916 ) ) ; +#21714 = CARTESIAN_POINT ( 'NONE', ( -12.63788667702346302, 134.4389615668880822, 93.60904485994920776 ) ) ; +#21715 = CARTESIAN_POINT ( 'NONE', ( -36.91676615048000087, 190.9988463978000084, 106.4471113082999949 ) ) ; +#21716 = ORIENTED_EDGE ( 'NONE', *, *, #7291, .F. ) ; +#21717 = CARTESIAN_POINT ( 'NONE', ( -19.43581021992248381, 124.5763273985873241, 178.2048886345954486 ) ) ; +#21718 = CARTESIAN_POINT ( 'NONE', ( -35.94216947274806984, 191.5529916554748127, 103.8979322272315500 ) ) ; +#21719 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; +#21722 = EDGE_LOOP ( 'NONE', ( #14595, #28720, #12344, #36687, #3777 ) ) ; +#21721 = PLANE ( 'NONE', #3765 ) ; +#21720 = CARTESIAN_POINT ( 'NONE', ( -2.622304094908183725, 208.9737167940518816, 73.45181557642186476 ) ) ; +#21723 = EDGE_CURVE ( 'NONE', #18841, #23325, #24045, .T. ) ; +#21724 = ORIENTED_EDGE ( 'NONE', *, *, #38522, .F. ) ; +#21725 = CARTESIAN_POINT ( 'NONE', ( -3.704309072947313375, 175.3139521501252034, 100.3006306135645644 ) ) ; +#21726 = VERTEX_POINT ( 'NONE', #33217 ) ; +#21727 = CONICAL_SURFACE ( 'NONE', #10635, 5.250000000012835955, 0.7853981634113290644 ) ; +#21728 = ORIENTED_EDGE ( 'NONE', *, *, #18453, .T. ) ; +#21730 = AXIS2_PLACEMENT_3D ( 'NONE', #4857, #14487, #39405 ) ; +#21729 = FACE_OUTER_BOUND ( 'NONE', #39327, .T. ) ; +#21731 = VECTOR ( 'NONE', #33800, 1000.000000000000000 ) ; +#21732 = DIRECTION ( 'NONE', ( -0.0005884949961238380989, 0.2249510543439045829, -0.9743698870671267942 ) ) ; +#21733 = CARTESIAN_POINT ( 'NONE', ( -41.28986358703587456, 120.5685454323574817, 90.59221360106587895 ) ) ; +#21734 = CARTESIAN_POINT ( 'NONE', ( 12.64209925790531308, 131.0231129754641302, 89.89439459407216759 ) ) ; +#21735 = FACE_OUTER_BOUND ( 'NONE', #20091, .T. ) ; +#21736 = ORIENTED_EDGE ( 'NONE', *, *, #16040, .F. ) ; +#21737 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#21738 = ORIENTED_EDGE ( 'NONE', *, *, #14077, .F. ) ; +#21739 = CARTESIAN_POINT ( 'NONE', ( 5.659153654835778369, 124.3673852322629187, 88.36203164978959990 ) ) ; +#21740 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#21741 = FACE_BOUND ( 'NONE', #1501, .T. ) ; +#21742 = CARTESIAN_POINT ( 'NONE', ( 16.22247671335948382, 122.0701589875174164, 174.5870958018068109 ) ) ; +#21743 = ORIENTED_EDGE ( 'NONE', *, *, #7077, .T. ) ; +#21744 = DIRECTION ( 'NONE', ( -0.0005884949961189823910, 0.2249510543439030286, -0.9743698870671271273 ) ) ; +#21745 = CARTESIAN_POINT ( 'NONE', ( 1.079159667266636147, 188.6661133437667672, 103.2092760790662425 ) ) ; +#21746 = LINE ( 'NONE', #12726, #34841 ) ; +#21747 = CARTESIAN_POINT ( 'NONE', ( -23.36581923842090092, 181.0107737450888976, 104.5356085457618889 ) ) ; +#21748 = EDGE_CURVE ( 'NONE', #15091, #24326, #23526, .T. ) ; +#21749 = ORIENTED_EDGE ( 'NONE', *, *, #31281, .T. ) ; +#21750 = CARTESIAN_POINT ( 'NONE', ( 1.969467697532000017, 189.5457934668000064, 105.8936626681000064 ) ) ; +#21751 = EDGE_CURVE ( 'NONE', #35446, #37130, #20240, .T. ) ; +#21752 = CARTESIAN_POINT ( 'NONE', ( -35.95405601968204223, 218.5902260770999987, 76.08021997845068540 ) ) ; +#21753 = CARTESIAN_POINT ( 'NONE', ( 36.13112569603666202, 191.5149598075008726, 103.8458137197516038 ) ) ; +#21754 = CARTESIAN_POINT ( 'NONE', ( 5.770779297447407252, 149.0005910511659408, 94.04893340636374433 ) ) ; +#21755 = AXIS2_PLACEMENT_3D ( 'NONE', #2306, #5360, #2898 ) ; +#21756 = ORIENTED_EDGE ( 'NONE', *, *, #9943, .F. ) ; +#21757 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #642, #37859 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21758 = CONICAL_SURFACE ( 'NONE', #11979, 22.50000000000906653, 0.7853981633972855203 ) ; +#21759 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#21760 = FACE_OUTER_BOUND ( 'NONE', #9084, .T. ) ; +#21761 = AXIS2_PLACEMENT_3D ( 'NONE', #27036, #8207, #39468 ) ; +#21762 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #108, #9725, #28329, #28139, #37926, #6234, #22604, #12567, #19102, #19505 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999849565, 0.3750000000000334732, 0.4375000000000577871, 0.5000000000000820455, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21763 = ORIENTED_EDGE ( 'NONE', *, *, #6190, .T. ) ; +#21764 = CARTESIAN_POINT ( 'NONE', ( 35.54494089926004108, 209.7096602146001487, 73.03703587511542139 ) ) ; +#21765 = VERTEX_POINT ( 'NONE', #14234 ) ; +#21767 = DIRECTION ( 'NONE', ( 0.7933533411653341805, -0.5930537057989598848, -0.1373964268091485141 ) ) ; +#21766 = CARTESIAN_POINT ( 'NONE', ( 36.21922981210563108, 191.9874384596776338, 104.3789711234515210 ) ) ; +#21768 = EDGE_LOOP ( 'NONE', ( #525, #25332, #11070, #11223 ) ) ; +#21769 = ORIENTED_EDGE ( 'NONE', *, *, #9876, .F. ) ; +#21770 = ADVANCED_FACE ( 'NONE', ( #29777 ), #31995, .F. ) ; +#21771 = ORIENTED_EDGE ( 'NONE', *, *, #17556, .T. ) ; +#21772 = CARTESIAN_POINT ( 'NONE', ( 2.665066171023000141, 208.9435558216999880, 75.81117239588000700 ) ) ; +#21773 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#21774 = CARTESIAN_POINT ( 'NONE', ( 12.63839252860180906, 184.0139321654835101, 102.6414058913664178 ) ) ; +#21775 = VERTEX_POINT ( 'NONE', #27936 ) ; +#21776 = ORIENTED_EDGE ( 'NONE', *, *, #28633, .F. ) ; +#21777 = DIRECTION ( 'NONE', ( -0.0006039748319387963508, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#21778 = LINE ( 'NONE', #27534, #28290 ) ; +#21779 = CARTESIAN_POINT ( 'NONE', ( 13.50311538254501009, 187.4520168550668302, 105.7007522453218797 ) ) ; +#21780 = CARTESIAN_POINT ( 'NONE', ( -34.95487770220995571, 225.9002260770353985, 76.07961649987865371 ) ) ; +#21781 = AXIS2_PLACEMENT_3D ( 'NONE', #1164, #13643, #19960 ) ; +#21782 = VERTEX_POINT ( 'NONE', #6224 ) ; +#21783 = ADVANCED_FACE ( 'NONE', ( #31383 ), #12560, .F. ) ; +#21784 = VERTEX_POINT ( 'NONE', #2773 ) ; +#21785 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#21786 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.271205595054999941E-14, 1.000000000000000000 ) ) ; +#21787 = CIRCLE ( 'NONE', #9378, 8.000001494568982352 ) ; +#21788 = CARTESIAN_POINT ( 'NONE', ( -27.41912080593000312, 124.8060542353999978, 88.82539917399999752 ) ) ; +#21789 = EDGE_CURVE ( 'NONE', #18192, #37405, #11127, .T. ) ; +#21790 = EDGE_LOOP ( 'NONE', ( #17967, #29334, #3376, #27711 ) ) ; +#21791 = AXIS2_PLACEMENT_3D ( 'NONE', #23836, #34813, #18881 ) ; +#21792 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#21793 = FACE_OUTER_BOUND ( 'NONE', #31329, .T. ) ; +#21794 = ORIENTED_EDGE ( 'NONE', *, *, #251, .T. ) ; +#21795 = EDGE_CURVE ( 'NONE', #33611, #39608, #12631, .T. ) ; +#21796 = CARTESIAN_POINT ( 'NONE', ( 20.50137524228200192, 192.1862632329211067, 106.4093414499090926 ) ) ; +#21797 = EDGE_CURVE ( 'NONE', #8652, #4634, #5927, .T. ) ; +#21798 = FACE_OUTER_BOUND ( 'NONE', #493, .T. ) ; +#21799 = EDGE_CURVE ( 'NONE', #4109, #978, #40166, .T. ) ; +#21800 = EDGE_CURVE ( 'NONE', #33315, #25840, #25369, .T. ) ; +#21801 = CARTESIAN_POINT ( 'NONE', ( -44.79353637294777002, 181.5138299656995287, 101.5857470109101399 ) ) ; +#21802 = CARTESIAN_POINT ( 'NONE', ( -39.74908053984227507, 182.4717680925825789, 106.9353792437991473 ) ) ; +#21803 = ORIENTED_EDGE ( 'NONE', *, *, #31766, .T. ) ; +#21804 = FACE_OUTER_BOUND ( 'NONE', #22631, .T. ) ; +#21805 = CARTESIAN_POINT ( 'NONE', ( 35.46133700181365356, 82.39441720660606450, 284.2611062593159659 ) ) ; +#21806 = CARTESIAN_POINT ( 'NONE', ( -37.83887613609999789, 119.2344500291000031, 87.17227830417002110 ) ) ; +#21807 = CARTESIAN_POINT ( 'NONE', ( 36.18573331279999650, 112.9861525913999998, 89.60135871797001528 ) ) ; +#21808 = VERTEX_POINT ( 'NONE', #21594 ) ; +#21809 = AXIS2_PLACEMENT_3D ( 'NONE', #37673, #22355, #34778 ) ; +#21810 = AXIS2_PLACEMENT_3D ( 'NONE', #39037, #11046, #14728 ) ; +#21811 = CARTESIAN_POINT ( 'NONE', ( 15.75161875086000052, 144.6230676373999984, 95.85461094414999650 ) ) ; +#21812 = ORIENTED_EDGE ( 'NONE', *, *, #31118, .F. ) ; +#21813 = CARTESIAN_POINT ( 'NONE', ( -38.01550421529999824, 118.9002399435000115, 90.44667324955001675 ) ) ; +#21814 = AXIS2_PLACEMENT_3D ( 'NONE', #15986, #38069, #6185 ) ; +#21815 = EDGE_LOOP ( 'NONE', ( #12178, #36565, #30928, #1282, #23818, #30066 ) ) ; +#21816 = CARTESIAN_POINT ( 'NONE', ( 20.00185907575961153, 191.2197610873820963, 106.8662960061243155 ) ) ; +#21817 = CARTESIAN_POINT ( 'NONE', ( 6.937632354211411504E-13, 155.6803346353071618, 98.67347229716645529 ) ) ; +#21818 = CARTESIAN_POINT ( 'NONE', ( 23.36940079100686063, 177.7945392694463749, 100.6858723966742843 ) ) ; +#21819 = CARTESIAN_POINT ( 'NONE', ( -38.11718854129877343, 118.8155790694493561, 90.29079743518840928 ) ) ; +#21820 = ORIENTED_EDGE ( 'NONE', *, *, #37517, .F. ) ; +#21821 = ORIENTED_EDGE ( 'NONE', *, *, #18892, .T. ) ; +#21822 = CARTESIAN_POINT ( 'NONE', ( 0.8006758311543553663, 189.0100522499311637, 105.7387579588670263 ) ) ; +#21823 = CARTESIAN_POINT ( 'NONE', ( -37.54767055407849341, 212.5463739241209851, 75.74784908760784674 ) ) ; +#21824 = EDGE_CURVE ( 'NONE', #24048, #20022, #6794, .T. ) ; +#21825 = VERTEX_POINT ( 'NONE', #25062 ) ; +#21826 = CARTESIAN_POINT ( 'NONE', ( 6.271009700395496544, 163.8321258783347787, 97.98591366900288335 ) ) ; +#21827 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21828 = EDGE_LOOP ( 'NONE', ( #20692, #6035, #602, #3636, #27877, #27849 ) ) ; +#21829 = PLANE ( 'NONE', #5241 ) ; +#21830 = ADVANCED_FACE ( 'NONE', ( #16426 ), #6821, .F. ) ; +#21831 = CARTESIAN_POINT ( 'NONE', ( 18.60795789290834179, 125.1298367273077616, 178.8296990479766748 ) ) ; +#21832 = CARTESIAN_POINT ( 'NONE', ( 45.54775444177381871, 116.6087611523222023, 153.3386251583491742 ) ) ; +#21833 = ORIENTED_EDGE ( 'NONE', *, *, #33030, .F. ) ; +#21834 = CARTESIAN_POINT ( 'NONE', ( 28.20349900165999912, 125.2316176986000045, 88.71892600564000020 ) ) ; +#21835 = VECTOR ( 'NONE', #24291, 1000.000000000000000 ) ; +#21836 = ADVANCED_FACE ( 'NONE', ( #35222 ), #22989, .F. ) ; +#21837 = CARTESIAN_POINT ( 'NONE', ( 3.677495930535071622, 167.8566700076929692, 101.3370465724240574 ) ) ; +#21838 = CARTESIAN_POINT ( 'NONE', ( -25.35785070895000004, 191.5893649937000021, 106.2870274426000066 ) ) ; +#21839 = CONICAL_SURFACE ( 'NONE', #33580, 4.999999999914826354, 0.7853981634347277918 ) ; +#21840 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825913618700161, 0.0005734119025369202160 ) ) ; +#21841 = EDGE_CURVE ( 'NONE', #16912, #19220, #19294, .T. ) ; +#21842 = EDGE_CURVE ( 'NONE', #21943, #33199, #698, .T. ) ; +#21843 = VERTEX_POINT ( 'NONE', #22393 ) ; +#21844 = CARTESIAN_POINT ( 'NONE', ( -40.69155169351290624, 119.9027463543584275, 92.49074896885643682 ) ) ; +#21845 = ADVANCED_FACE ( 'NONE', ( #28717 ), #33353, .F. ) ; +#21846 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921576300, -0.2249510932971602595 ) ) ; +#21847 = CARTESIAN_POINT ( 'NONE', ( 36.76307291026488855, 191.6283014451216502, 104.3440614356115077 ) ) ; +#21848 = CARTESIAN_POINT ( 'NONE', ( -38.93740081958814159, 183.0561992808241882, 105.0172067937131999 ) ) ; +#21849 = ORIENTED_EDGE ( 'NONE', *, *, #19376, .F. ) ; +#21850 = LINE ( 'NONE', #34291, #23168 ) ; +#21851 = CARTESIAN_POINT ( 'NONE', ( 2.712710242590048448, 205.4139694218411591, 76.23344288180996386 ) ) ; +#21852 = CARTESIAN_POINT ( 'NONE', ( -42.83084823883022807, 121.2593020781266659, 90.75261808358531823 ) ) ; +#21853 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; +#21854 = CARTESIAN_POINT ( 'NONE', ( -36.20721311647999840, 191.7525047693000033, 104.2843089044999942 ) ) ; +#21855 = CARTESIAN_POINT ( 'NONE', ( -25.50393605561328414, 190.9794142776714807, 106.3251602599453776 ) ) ; +#21856 = LOCAL_TIME ( 14, 25, 27.00000000000000000, #9388 ) ; +#21857 = DIRECTION ( 'NONE', ( -0.0005884949961234174284, 0.2249510543439059151, -0.9743698870671263501 ) ) ; +#21858 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; +#21859 = DIRECTION ( 'NONE', ( -0.0005884949961242895607, 0.2249510543439076360, -0.9743698870671260170 ) ) ; +#21860 = VECTOR ( 'NONE', #27562, 999.9999999999998863 ) ; +#21861 = VECTOR ( 'NONE', #32739, 1000.000000000000227 ) ; +#21862 = CARTESIAN_POINT ( 'NONE', ( -13.50000077922901731, 184.9627595935803868, 102.3630947892575307 ) ) ; +#21863 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -5.029100735414826696E-18, -0.0006039748319369899615 ) ) ; +#21864 = CARTESIAN_POINT ( 'NONE', ( 38.06830324738000115, 190.8197764434999897, 106.3743150780999969 ) ) ; +#21865 = CARTESIAN_POINT ( 'NONE', ( 37.18465032402060189, 191.0618976901199915, 106.3215651414160163 ) ) ; +#21866 = AXIS2_PLACEMENT_3D ( 'NONE', #15471, #30618, #31209 ) ; +#21867 = VERTEX_POINT ( 'NONE', #10325 ) ; +#21868 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22941, #13726, #35368, #32338 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21870 = ORIENTED_EDGE ( 'NONE', *, *, #36786, .F. ) ; +#21869 = CARTESIAN_POINT ( 'NONE', ( 36.15716616049000010, 191.3344399890999910, 106.7319169443999982 ) ) ; +#21871 = ORIENTED_EDGE ( 'NONE', *, *, #13506, .F. ) ; +#21872 = VERTEX_POINT ( 'NONE', #22593 ) ; +#21873 = ORIENTED_EDGE ( 'NONE', *, *, #1903, .F. ) ; +#21874 = CARTESIAN_POINT ( 'NONE', ( -5.145159818766837034, 135.0788229529110538, 90.84143235571785624 ) ) ; +#21875 = CARTESIAN_POINT ( 'NONE', ( 20.00192081821563761, 126.7670151487632353, 91.98617178303544506 ) ) ; +#21876 = ADVANCED_FACE ( 'NONE', ( #16027 ), #28521, .F. ) ; +#21878 = ADVANCED_FACE ( 'NONE', ( #16232 ), #13184, .T. ) ; +#21877 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35946, #7144, #25982, #1827, #35334, #1414 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 4 ), + ( 0.000000000000000000, 0.3333323949805780950, 0.6666648884538761699, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21879 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.271205131337281593E-14, 1.000000000000000000 ) ) ; +#21880 = CARTESIAN_POINT ( 'NONE', ( 45.26991834669612302, 123.8840750961899744, 93.35648333539963062 ) ) ; +#21881 = ADVANCED_FACE ( 'NONE', ( #38500 ), #28784, .F. ) ; +#21882 = ORIENTED_EDGE ( 'NONE', *, *, #18835, .T. ) ; +#21883 = CARTESIAN_POINT ( 'NONE', ( 36.35031782592000127, 191.7402427641999907, 104.2390283135000004 ) ) ; +#21884 = PLANE ( 'NONE', #22779 ) ; +#21885 = CARTESIAN_POINT ( 'NONE', ( -36.27950425524976907, 191.8188495074159334, 104.4051415298545180 ) ) ; +#21886 = CARTESIAN_POINT ( 'NONE', ( -20.16657163988445589, 151.9255956737779343, 94.91094380485814952 ) ) ; +#21887 = EDGE_LOOP ( 'NONE', ( #37743, #24594, #22818, #6339, #20005, #26368, #2075, #4454, #29160, #28382, #13810, #20949 ) ) ; +#21888 = EDGE_CURVE ( 'NONE', #34680, #17164, #7224, .T. ) ; +#21889 = CARTESIAN_POINT ( 'NONE', ( -21.44693686545786449, 130.1487540525002657, 89.71308199639462089 ) ) ; +#21890 = CARTESIAN_POINT ( 'NONE', ( 36.11364262193256280, 191.5260145455536929, 103.8483746271915322 ) ) ; +#21891 = CARTESIAN_POINT ( 'NONE', ( -3.537752371395798789, 168.4800613451581910, 98.55175200207808928 ) ) ; +#21892 = CARTESIAN_POINT ( 'NONE', ( -21.50774950077886061, 213.7117741840153826, 76.07152960608476633 ) ) ; +#21893 = VECTOR ( 'NONE', #32844, 1000.000000000000000 ) ; +#21894 = EDGE_CURVE ( 'NONE', #34518, #17427, #3956, .T. ) ; +#21895 = ORIENTED_EDGE ( 'NONE', *, *, #39911, .T. ) ; +#21896 = CARTESIAN_POINT ( 'NONE', ( 15.66818115446893422, 137.9078187121401697, 94.21874166949204721 ) ) ; +#21897 = CARTESIAN_POINT ( 'NONE', ( 2.281943726123000005, 189.4781187019000015, 103.5431292473000013 ) ) ; +#21898 = AXIS2_PLACEMENT_3D ( 'NONE', #4712, #17171, #7174 ) ; +#21899 = AXIS2_PLACEMENT_3D ( 'NONE', #27556, #2384, #39984 ) ; +#21900 = CARTESIAN_POINT ( 'NONE', ( -29.94659852602001138, 103.6131156703197576, 89.78587174324022158 ) ) ; +#21901 = AXIS2_PLACEMENT_3D ( 'NONE', #28307, #13171, #22772 ) ; +#21902 = EDGE_LOOP ( 'NONE', ( #31963, #28548, #16928, #17404 ) ) ; +#21903 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#21904 = ORIENTED_EDGE ( 'NONE', *, *, #10986, .F. ) ; +#21905 = EDGE_CURVE ( 'NONE', #3990, #24029, #34816, .T. ) ; +#21906 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11956, #21571, #39533, #17449, #26889, #4987, #23815, #21364, #11327, #8272, #30147 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000203171, 0.6250000000000158762, 0.6875000000000135447, 0.7500000000000111022, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21907 = LINE ( 'NONE', #15557, #37174 ) ; +#21908 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540931611, 160.6260167145983360, 97.25887387932731087 ) ) ; +#21909 = CARTESIAN_POINT ( 'NONE', ( -25.99154556069859012, 196.5784392978119968, 103.8908015619487060 ) ) ; +#21910 = CARTESIAN_POINT ( 'NONE', ( -37.20408499829227367, 178.1325612192622430, 136.7211859319445466 ) ) ; +#21911 = CARTESIAN_POINT ( 'NONE', ( 30.01356315559810639, 141.5423698496542499, 27.80511976906114668 ) ) ; +#21912 = DIRECTION ( 'NONE', ( -0.1305262607518133389, 0.9660168937933039102, 0.2231014481353405798 ) ) ; +#21913 = CARTESIAN_POINT ( 'NONE', ( -1.871327295256297152, 189.6068325900267553, 105.9136324549362058 ) ) ; +#21914 = ORIENTED_EDGE ( 'NONE', *, *, #22278, .T. ) ; +#21915 = CARTESIAN_POINT ( 'NONE', ( -25.49166333918160987, 196.1181869037000070, 103.6951339686000040 ) ) ; +#21916 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620728018, 0.0004744508866335444284 ) ) ; +#21917 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673393900, 153.8082236412882366, 95.66734676454734654 ) ) ; +#21919 = FACE_OUTER_BOUND ( 'NONE', #32813, .T. ) ; +#21918 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971565680 ) ) ; +#21920 = ORIENTED_EDGE ( 'NONE', *, *, #31525, .F. ) ; +#21921 = ORIENTED_EDGE ( 'NONE', *, *, #16594, .F. ) ; +#21922 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #373, #18758, #9796, #22271 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 2.705159532099978906E-07, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21923 = CONICAL_SURFACE ( 'NONE', #27805, 22.50000000000898837, 0.7853981633973132759 ) ; +#21924 = ADVANCED_FACE ( 'NONE', ( #35015 ), #20274, .F. ) ; +#21925 = LINE ( 'NONE', #18815, #36981 ) ; +#21926 = EDGE_CURVE ( 'NONE', #33981, #38943, #16620, .T. ) ; +#21927 = CIRCLE ( 'NONE', #4264, 58.90509898146415679 ) ; +#21928 = ADVANCED_FACE ( 'NONE', ( #1094 ), #31314, .T. ) ; +#21929 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18225, #2900, #6168, #36653, #39704, #15385 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21930 = ORIENTED_EDGE ( 'NONE', *, *, #13900, .F. ) ; +#21931 = LINE ( 'NONE', #25203, #36089 ) ; +#21932 = DIRECTION ( 'NONE', ( -0.0006039748319367822284, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#21933 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250614502, 179.6252109630515577, 101.6466942236997824 ) ) ; +#21934 = CARTESIAN_POINT ( 'NONE', ( 30.66227699762960412, 129.7971910029650644, 89.60044452426214434 ) ) ; +#21935 = CARTESIAN_POINT ( 'NONE', ( -31.70535868460997619, 226.4002260771022463, 73.57765341574507545 ) ) ; +#21936 = ORIENTED_EDGE ( 'NONE', *, *, #147, .F. ) ; +#21937 = ADVANCED_FACE ( 'NONE', ( #24993 ), #12492, .F. ) ; +#21938 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#21939 = ORIENTED_EDGE ( 'NONE', *, *, #34450, .F. ) ; +#21940 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971566235 ) ) ; +#21941 = CARTESIAN_POINT ( 'NONE', ( 20.89466079040630575, 182.4265417833274796, 104.8357029080749783 ) ) ; +#21942 = EDGE_CURVE ( 'NONE', #4210, #27010, #27870, .T. ) ; +#21943 = VERTEX_POINT ( 'NONE', #21917 ) ; +#21944 = DIRECTION ( 'NONE', ( -0.0004161288024422820394, -0.5299192578930420616, -0.8480479980230526404 ) ) ; +#21945 = CARTESIAN_POINT ( 'NONE', ( 0.9088675734344845436, 188.6359493924010167, 103.2024150330645398 ) ) ; +#21946 = FACE_OUTER_BOUND ( 'NONE', #15815, .T. ) ; +#21947 = VERTEX_POINT ( 'NONE', #5963 ) ; +#21948 = CARTESIAN_POINT ( 'NONE', ( -19.42038588717154113, 126.1613205632184673, 176.0264188615619503 ) ) ; +#21949 = CARTESIAN_POINT ( 'NONE', ( -30.11526512126999933, 126.4563218505000179, 91.68818888923999566 ) ) ; +#21950 = VECTOR ( 'NONE', #23323, 1000.000000000000114 ) ; +#21951 = EDGE_CURVE ( 'NONE', #585, #38693, #29705, .T. ) ; +#21952 = DIRECTION ( 'NONE', ( 0.6087614883550946931, -0.7730004026499608383, -0.1785492307423600933 ) ) ; +#21953 = DIRECTION ( 'NONE', ( -0.5987319960703951782, -0.8009494346596170988, 0.000000000000000000 ) ) ; +#21954 = DIRECTION ( 'NONE', ( 0.6087614115774877543, -0.7730004600455409047, -0.1785492440296705396 ) ) ; +#21955 = AXIS2_PLACEMENT_3D ( 'NONE', #28114, #33613, #27526 ) ; +#21956 = EDGE_LOOP ( 'NONE', ( #2720, #5469, #35806, #8328 ) ) ; +#21957 = CARTESIAN_POINT ( 'NONE', ( 25.99886678296517672, 118.8155665066540934, 87.25209012101137773 ) ) ; +#21958 = VECTOR ( 'NONE', #38503, 1000.000000000000114 ) ; +#21959 = CARTESIAN_POINT ( 'NONE', ( 15.34881605426699025, 136.8304653680823435, 91.23345309747541876 ) ) ; +#21960 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540930012, 174.4013312751985438, 100.4391564142062094 ) ) ; +#21961 = ORIENTED_EDGE ( 'NONE', *, *, #38672, .F. ) ; +#21962 = CARTESIAN_POINT ( 'NONE', ( 16.43146722802687520, 121.9169648965784774, 177.7564454048611253 ) ) ; +#21963 = CARTESIAN_POINT ( 'NONE', ( 3.061557430615667652, 191.9759150222000130, 101.9195982364086888 ) ) ; +#21965 = CARTESIAN_POINT ( 'NONE', ( -2.768682643724713621, 190.8910486004296558, 106.6325679542271985 ) ) ; +#21964 = FACE_OUTER_BOUND ( 'NONE', #36506, .T. ) ; +#21966 = EDGE_LOOP ( 'NONE', ( #35019, #10147, #6139, #13024 ) ) ; +#21967 = ORIENTED_EDGE ( 'NONE', *, *, #28298, .T. ) ; +#21968 = CARTESIAN_POINT ( 'NONE', ( -40.05779377713677292, 77.14301703112144537, 290.6649606259057919 ) ) ; +#21969 = CIRCLE ( 'NONE', #23962, 2.000000000040191850 ) ; +#21970 = CARTESIAN_POINT ( 'NONE', ( -35.95814990381343534, 192.2304528612855847, 104.4264063346583669 ) ) ; +#21971 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#21972 = FACE_OUTER_BOUND ( 'NONE', #35230, .T. ) ; +#21973 = EDGE_CURVE ( 'NONE', #1318, #6960, #31413, .T. ) ; +#21974 = VERTEX_POINT ( 'NONE', #31724 ) ; +#21975 = EDGE_CURVE ( 'NONE', #7592, #22581, #27505, .T. ) ; +#21976 = VECTOR ( 'NONE', #22072, 1000.000000000000114 ) ; +#21977 = AXIS2_PLACEMENT_3D ( 'NONE', #29340, #7244, #20690 ) ; +#21978 = ORIENTED_EDGE ( 'NONE', *, *, #26637, .F. ) ; +#21979 = CARTESIAN_POINT ( 'NONE', ( -36.55077531636867150, 265.2798088768021785, 205.0571533001752584 ) ) ; +#21980 = LINE ( 'NONE', #31373, #1088 ) ; +#21981 = DIRECTION ( 'NONE', ( -0.0006039748319382907873, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#21982 = CARTESIAN_POINT ( 'NONE', ( 35.72740534132000079, 192.3407274401000109, 104.0317702792000034 ) ) ; +#21983 = ORIENTED_EDGE ( 'NONE', *, *, #5580, .T. ) ; +#21984 = AXIS2_PLACEMENT_3D ( 'NONE', #31473, #19777, #32086 ) ; +#21985 = ORIENTED_EDGE ( 'NONE', *, *, #10778, .F. ) ; +#21986 = ORIENTED_EDGE ( 'NONE', *, *, #34582, .F. ) ; +#21987 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#21988 = AXIS2_PLACEMENT_3D ( 'NONE', #17328, #997, #1203 ) ; +#21989 = EDGE_CURVE ( 'NONE', #4671, #14541, #3307, .T. ) ; +#21990 = LINE ( 'NONE', #28128, #29847 ) ; +#21991 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3525, #9289, #9083, #37090, #34205, #30961, #474, #40145, #12156, #3334, #21572, #12751, #28302, #77, #266 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999998769318, 0.1874999999998715194, 0.2499999999998661071, 0.3749999999998618883, 0.4374999999998645528, 0.4687499999998658851, 0.4999999999998672173, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#21992 = CARTESIAN_POINT ( 'NONE', ( -26.40419816585999868, 122.8758340463000138, 88.03691424743999505 ) ) ; +#21993 = EDGE_LOOP ( 'NONE', ( #803, #39747, #21416, #28854 ) ) ; +#21994 = LINE ( 'NONE', #102, #5592 ) ; +#21995 = CARTESIAN_POINT ( 'NONE', ( 15.50029467073742140, 160.6294874787857623, 97.24095194441136414 ) ) ; +#21996 = ORIENTED_EDGE ( 'NONE', *, *, #8536, .F. ) ; +#21997 = CARTESIAN_POINT ( 'NONE', ( 3.608102626577426086, 174.7005586332282121, 102.9883855544077420 ) ) ; +#21998 = CARTESIAN_POINT ( 'NONE', ( -20.49970532888763941, 191.4139234226054498, 104.3698659823340478 ) ) ; +#21999 = ADVANCED_FACE ( 'NONE', ( #19020 ), #28154, .F. ) ; +#22000 = CARTESIAN_POINT ( 'NONE', ( -39.13061847294451923, 119.0370893851462029, 89.74140283572911869 ) ) ; +#22001 = CARTESIAN_POINT ( 'NONE', ( -18.96075656525927400, 149.0999870379767742, 180.7331665572989721 ) ) ; +#22002 = AXIS2_PLACEMENT_3D ( 'NONE', #12857, #31871, #38931 ) ; +#22003 = EDGE_LOOP ( 'NONE', ( #35332, #20160, #16930, #27223 ) ) ; +#22004 = CARTESIAN_POINT ( 'NONE', ( 3.882702611521182234, 148.0331269957187317, 129.7473673645792474 ) ) ; +#22005 = ORIENTED_EDGE ( 'NONE', *, *, #35981, .T. ) ; +#22006 = VERTEX_POINT ( 'NONE', #19215 ) ; +#22007 = CARTESIAN_POINT ( 'NONE', ( 13.55367387944097146, 148.0748368286854486, 93.83050549129562512 ) ) ; +#22008 = AXIS2_PLACEMENT_3D ( 'NONE', #11252, #17572, #39859 ) ; +#22009 = CARTESIAN_POINT ( 'NONE', ( -37.43252112508000096, 118.7416284442000176, 87.16657656499999973 ) ) ; +#22010 = CIRCLE ( 'NONE', #29823, 6.000000367552694058 ) ; +#22011 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927783543234, 0.0005734119022076374994 ) ) ; +#22012 = ORIENTED_EDGE ( 'NONE', *, *, #6393, .T. ) ; +#22013 = CYLINDRICAL_SURFACE ( 'NONE', #10856, 4.999999999999990230 ) ; +#22014 = ORIENTED_EDGE ( 'NONE', *, *, #30553, .F. ) ; +#22015 = AXIS2_PLACEMENT_3D ( 'NONE', #36698, #10610, #33623 ) ; +#22016 = ADVANCED_FACE ( 'NONE', ( #28252 ), #2891, .F. ) ; +#22017 = CARTESIAN_POINT ( 'NONE', ( -25.50922756583905837, 191.3757872987501969, 104.3640622938216183 ) ) ; +#22018 = ADVANCED_FACE ( 'NONE', ( #40100 ), #4631, .F. ) ; +#22019 = EDGE_LOOP ( 'NONE', ( #19531, #21986, #14193, #1572, #5838, #31487, #15239, #37234, #19212, #6207 ) ) ; +#22020 = CARTESIAN_POINT ( 'NONE', ( 11.42879460937821179, 158.6506707231792745, 96.27341295134117161 ) ) ; +#22021 = CARTESIAN_POINT ( 'NONE', ( -32.35856811579363068, 153.0051697192221241, 291.5780876995356721 ) ) ; +#22022 = CARTESIAN_POINT ( 'NONE', ( -31.99382095406631876, 162.7703235776980080, 188.0763422140252317 ) ) ; +#22023 = CARTESIAN_POINT ( 'NONE', ( -20.97965385745949618, 158.7746864580521731, 96.32161813573080167 ) ) ; +#22024 = EDGE_CURVE ( 'NONE', #31599, #7038, #6358, .T. ) ; +#22025 = CARTESIAN_POINT ( 'NONE', ( -16.11981483134459836, 151.5072451357098373, 180.2250316836445165 ) ) ; +#22026 = ADVANCED_FACE ( 'NONE', ( #3473 ), #39219, .F. ) ; +#22027 = CARTESIAN_POINT ( 'NONE', ( -35.65904030449263473, 114.4088988627134285, 90.28932200601107638 ) ) ; +#22028 = ORIENTED_EDGE ( 'NONE', *, *, #37027, .T. ) ; +#22029 = ORIENTED_EDGE ( 'NONE', *, *, #23760, .F. ) ; +#22030 = CARTESIAN_POINT ( 'NONE', ( 5.666806155083023988, 187.7449703091009781, 103.5069947386187295 ) ) ; +#22031 = CARTESIAN_POINT ( 'NONE', ( -22.50007685686057002, 158.5507592289326340, 96.61294483226545537 ) ) ; +#22032 = DIRECTION ( 'NONE', ( -0.0005884949961224831714, 0.2249510543439058596, -0.9743698870671263501 ) ) ; +#22033 = AXIS2_PLACEMENT_3D ( 'NONE', #2342, #14612, #36890 ) ; +#22034 = ORIENTED_EDGE ( 'NONE', *, *, #28386, .F. ) ; +#22035 = CARTESIAN_POINT ( 'NONE', ( 22.78080448403245839, 154.4094593426142978, 95.28739704982865533 ) ) ; +#22036 = ORIENTED_EDGE ( 'NONE', *, *, #21047, .T. ) ; +#22037 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927775716107, 0.0005734119022078446905 ) ) ; +#22038 = VECTOR ( 'NONE', #21002, 1000.000000000000000 ) ; +#22039 = CARTESIAN_POINT ( 'NONE', ( 13.76437287132129406, 125.3330071257134364, 174.7699841520732775 ) ) ; +#22040 = VERTEX_POINT ( 'NONE', #34164 ) ; +#22041 = CARTESIAN_POINT ( 'NONE', ( 28.25636536875000004, 125.5795385150000101, 89.14486926956999469 ) ) ; +#22042 = CARTESIAN_POINT ( 'NONE', ( 3.706555699605236676, 167.8627247553967550, 101.3085851372709811 ) ) ; +#22043 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; +#22044 = CARTESIAN_POINT ( 'NONE', ( -23.94751279123330079, 115.2659257769921481, 90.28224853685935614 ) ) ; +#22045 = CARTESIAN_POINT ( 'NONE', ( 43.77049507405610740, 121.6642732591545695, 90.64092531184280688 ) ) ; +#22046 = VERTEX_POINT ( 'NONE', #9640 ) ; +#22047 = LINE ( 'NONE', #34476, #5658 ) ; +#22048 = CARTESIAN_POINT ( 'NONE', ( 37.34715196620786060, 164.6396645750260745, 198.2231758344085506 ) ) ; +#22049 = CARTESIAN_POINT ( 'NONE', ( 42.65317302408573141, 111.7419529267020692, 132.5528259335349617 ) ) ; +#22050 = CARTESIAN_POINT ( 'NONE', ( -31.65770855640243653, 226.4002260771000010, 152.4718672074029087 ) ) ; +#22051 = VERTEX_POINT ( 'NONE', #34546 ) ; +#22052 = ORIENTED_EDGE ( 'NONE', *, *, #1898, .T. ) ; +#22053 = CARTESIAN_POINT ( 'NONE', ( 38.27279269694903263, 118.8579677785462536, 90.24548094119661812 ) ) ; +#22054 = CARTESIAN_POINT ( 'NONE', ( 19.33664095386789938, 148.6211264722984708, 180.7044371687416344 ) ) ; +#22055 = CARTESIAN_POINT ( 'NONE', ( 0.05451946023377000211, 0.000000000000000000, 90.26775191081999594 ) ) ; +#22056 = CARTESIAN_POINT ( 'NONE', ( -26.20112490964000074, 189.6309950977999961, 106.5274262965999981 ) ) ; +#22057 = ORIENTED_EDGE ( 'NONE', *, *, #18390, .T. ) ; +#22058 = EDGE_CURVE ( 'NONE', #27090, #2067, #3092, .T. ) ; +#22059 = AXIS2_PLACEMENT_3D ( 'NONE', #16619, #19885, #32381 ) ; +#22060 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1073, #13757, #13561, #30067, #2057, #11867, #17568, #30256, #5099, #2259, #24352, #4338, #14527, #36799, #1275, #26247, #39447, #33317, #27222, #17765, #2467, #35600, #14737 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 2, 1, 1, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.06249999999999558686, 0.09374999999999338030, 0.1249999999999911737, 0.2500000000000386913, 0.3750000000000862088, 0.4375000000001109113, 0.4687500000001164624, 0.4843750000001117439, 0.5000000000001070255, 0.6250000000000861533, 0.6875000000000701661, 0.7500000000000540679, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22061 = AXIS2_PLACEMENT_3D ( 'NONE', #12112, #6912, #777 ) ; +#22062 = CARTESIAN_POINT ( 'NONE', ( -3.668404232153524180, 126.2395570190490162, 91.36559546079023164 ) ) ; +#22063 = EDGE_CURVE ( 'NONE', #15187, #23240, #28059, .T. ) ; +#22064 = CARTESIAN_POINT ( 'NONE', ( -25.49166336760104912, 196.1181869298516744, 103.6951339797178804 ) ) ; +#22065 = DIRECTION ( 'NONE', ( -0.0002393070161718421224, -0.2243351686125209798, 0.9745120188359627234 ) ) ; +#22066 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#22067 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#22068 = CARTESIAN_POINT ( 'NONE', ( -24.42625686036400268, 103.6131156702357998, 89.78253759510907628 ) ) ; +#22069 = CARTESIAN_POINT ( 'NONE', ( 36.67680368011099290, 191.6489404259000366, 104.3309255465679968 ) ) ; +#22070 = ADVANCED_FACE ( 'NONE', ( #15954 ), #28448, .T. ) ; +#22071 = ADVANCED_FACE ( 'NONE', ( #13308 ), #14422, .T. ) ; +#22072 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927772634805, -0.0005734119022076526783 ) ) ; +#22073 = VERTEX_POINT ( 'NONE', #28845 ) ; +#22074 = EDGE_CURVE ( 'NONE', #20022, #23754, #10252, .T. ) ; +#22075 = ORIENTED_EDGE ( 'NONE', *, *, #7223, .T. ) ; +#22076 = FACE_OUTER_BOUND ( 'NONE', #32819, .T. ) ; +#22077 = EDGE_CURVE ( 'NONE', #28425, #20406, #13509, .T. ) ; +#22078 = CARTESIAN_POINT ( 'NONE', ( 20.08575548181600823, 126.7829121113273345, 91.90359369817805657 ) ) ; +#22079 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825876548734466, 0.0005734119033856171967 ) ) ; +#22080 = DIRECTION ( 'NONE', ( 2.341876692568676009E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#22081 = EDGE_LOOP ( 'NONE', ( #38490, #8718, #39894, #19197 ) ) ; +#22082 = CARTESIAN_POINT ( 'NONE', ( 35.40134743638000003, 113.4209880517999949, 87.10124724256999684 ) ) ; +#22083 = CARTESIAN_POINT ( 'NONE', ( 5.668111417358427495, 126.1276375062645485, 91.85037204208205708 ) ) ; +#22084 = CARTESIAN_POINT ( 'NONE', ( 3.667423414729225062, 126.3906643772000962, 90.71184782943855396 ) ) ; +#22085 = DIRECTION ( 'NONE', ( 0.6086215548477215131, 0.7730393818215735013, 0.1788572534946829551 ) ) ; +#22086 = CARTESIAN_POINT ( 'NONE', ( -36.74108571740404727, 191.5886187954329785, 104.3865692648879531 ) ) ; +#22087 = ORIENTED_EDGE ( 'NONE', *, *, #4068, .F. ) ; +#22088 = DIRECTION ( 'NONE', ( 0.0006039748319388624871, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#22089 = CARTESIAN_POINT ( 'NONE', ( -45.92426925958796602, 185.3756982569226182, 105.5675847568430896 ) ) ; +#22090 = DIRECTION ( 'NONE', ( -0.0002393071182785117045, -0.2252352986010040525, 0.9743043687658490271 ) ) ; +#22091 = CIRCLE ( 'NONE', #40334, 2.499999999967561948 ) ; +#22092 = PLANE ( 'NONE', #20353 ) ; +#22093 = ORIENTED_EDGE ( 'NONE', *, *, #9685, .F. ) ; +#22094 = ORIENTED_EDGE ( 'NONE', *, *, #9508, .F. ) ; +#22095 = LINE ( 'NONE', #6729, #14165 ) ; +#22096 = EDGE_CURVE ( 'NONE', #7038, #37452, #19626, .T. ) ; +#22097 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 82.27946979429628982, 310.0857197240630967 ) ) ; +#22098 = CARTESIAN_POINT ( 'NONE', ( 16.16729401867695515, 152.0078996042194603, 180.9416867539977716 ) ) ; +#22099 = EDGE_LOOP ( 'NONE', ( #39515, #10749, #27096, #35496 ) ) ; +#22100 = CYLINDRICAL_SURFACE ( 'NONE', #913, 6.000000000000008882 ) ; +#22101 = VERTEX_POINT ( 'NONE', #22719 ) ; +#22102 = CARTESIAN_POINT ( 'NONE', ( -15.94440735842906776, 121.4348066503545311, 176.4336059028145769 ) ) ; +#22103 = DIRECTION ( 'NONE', ( 1.868163743354593614E-15, 0.9743700557921585181, 0.2249510932971562072 ) ) ; +#22104 = EDGE_CURVE ( 'NONE', #14237, #29278, #7228, .T. ) ; +#22105 = CARTESIAN_POINT ( 'NONE', ( 25.17621027598018202, 212.3493493770845930, 75.54347298572716340 ) ) ; +#22106 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457974481995, -32.89481530046831637, 142.2936922234670760 ) ) ; +#22107 = DIRECTION ( 'NONE', ( 0.0004161288024568093728, 0.5299192578742120130, 0.8480479980348188951 ) ) ; +#22108 = EDGE_CURVE ( 'NONE', #12555, #16493, #19814, .T. ) ; +#22109 = CARTESIAN_POINT ( 'NONE', ( -20.89286847790088331, 136.3261294211067138, 91.13890976780785991 ) ) ; +#22110 = CARTESIAN_POINT ( 'NONE', ( -2.826855781103999821, 209.1896615391999887, 73.20597810447000597 ) ) ; +#22111 = FACE_OUTER_BOUND ( 'NONE', #1430, .T. ) ; +#22112 = ORIENTED_EDGE ( 'NONE', *, *, #8590, .T. ) ; +#22113 = EDGE_CURVE ( 'NONE', #8275, #25353, #35289, .T. ) ; +#22114 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#22115 = AXIS2_PLACEMENT_3D ( 'NONE', #1345, #32637, #17071 ) ; +#22116 = CARTESIAN_POINT ( 'NONE', ( -20.49852834234505039, 173.9502348336490059, 102.3906403256567756 ) ) ; +#22117 = DIRECTION ( 'NONE', ( 0.7075227875440994740, -0.1589708073325998561, 0.6885780910846993619 ) ) ; +#22118 = AXIS2_PLACEMENT_3D ( 'NONE', #30294, #18005, #2291 ) ; +#22119 = AXIS2_PLACEMENT_3D ( 'NONE', #3078, #6739, #25781 ) ; +#22120 = CARTESIAN_POINT ( 'NONE', ( 3.667815738790128677, 185.3461555468956590, 105.0070005413519993 ) ) ; +#22121 = ORIENTED_EDGE ( 'NONE', *, *, #38887, .T. ) ; +#22122 = EDGE_CURVE ( 'NONE', #7673, #10087, #35145, .T. ) ; +#22123 = ORIENTED_EDGE ( 'NONE', *, *, #35578, .T. ) ; +#22124 = DIRECTION ( 'NONE', ( -0.0005884949961195158185, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#22125 = CARTESIAN_POINT ( 'NONE', ( 21.26485671578026171, 115.6496691380893935, 87.25494085142716472 ) ) ; +#22126 = LINE ( 'NONE', #9648, #5651 ) ; +#22127 = ORIENTED_EDGE ( 'NONE', *, *, #1191, .T. ) ; +#22128 = CARTESIAN_POINT ( 'NONE', ( 44.24596348240854837, 122.9115719264381710, 88.00256960708196630 ) ) ; +#22129 = LINE ( 'NONE', #3696, #25093 ) ; +#22130 = DIRECTION ( 'NONE', ( -0.7072735235945706300, -0.6508952239913728954, -0.2758615054829884894 ) ) ; +#22131 = CARTESIAN_POINT ( 'NONE', ( -38.37334322435999923, 118.8333358913999973, 87.72073648586000161 ) ) ; +#22132 = LINE ( 'NONE', #10056, #12441 ) ; +#22133 = FACE_OUTER_BOUND ( 'NONE', #9908, .T. ) ; +#22134 = ORIENTED_EDGE ( 'NONE', *, *, #38008, .T. ) ; +#22135 = CARTESIAN_POINT ( 'NONE', ( 16.57457763302071641, 122.6753833417943582, 173.8792011210641704 ) ) ; +#22136 = ORIENTED_EDGE ( 'NONE', *, *, #34487, .T. ) ; +#22137 = FACE_OUTER_BOUND ( 'NONE', #9752, .T. ) ; +#22138 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #28785, #35688 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22139 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749091804, 179.1800746286054675, 103.5747911656487190 ) ) ; +#22140 = ORIENTED_EDGE ( 'NONE', *, *, #811, .F. ) ; +#22141 = AXIS2_PLACEMENT_3D ( 'NONE', #33780, #12927, #31132 ) ; +#22142 = LINE ( 'NONE', #19652, #12811 ) ; +#22143 = CARTESIAN_POINT ( 'NONE', ( 0.7458232703635604421, 188.6195839535141374, 103.1987352477761135 ) ) ; +#22144 = DIRECTION ( 'NONE', ( 0.6087614115774629964, 0.7729348350621531027, 0.1788331191967995615 ) ) ; +#22145 = AXIS2_PLACEMENT_3D ( 'NONE', #16738, #10630, #23097 ) ; +#22146 = VECTOR ( 'NONE', #29098, 1000.000000000000227 ) ; +#22147 = ORIENTED_EDGE ( 'NONE', *, *, #37892, .T. ) ; +#22148 = ORIENTED_EDGE ( 'NONE', *, *, #10800, .F. ) ; +#22149 = CARTESIAN_POINT ( 'NONE', ( 20.29162647263515495, 118.1107816779753250, 87.54680495799553341 ) ) ; +#22150 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#22151 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14064, #7916, #30208, #23669, #17100, #2409, #26542, #8543, #11608, #36123, #2204, #36539, #32855, #35698, #4645, #14879, #1579, #14677, #27166, #27373 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999344136, 0.1874999999998909761, 0.2187499999998807898, 0.2343749999998846756, 0.2499999999998885891, 0.4999999999998846478, 0.6249999999998738787, 0.6874999999998608891, 0.7187499999998606670, 0.7343749999998657740, 0.7499999999998708811, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22152 = EDGE_LOOP ( 'NONE', ( #10522, #27181, #36450, #33156 ) ) ; +#22153 = CIRCLE ( 'NONE', #29323, 2.000000000468127315 ) ; +#22154 = LINE ( 'NONE', #22359, #36259 ) ; +#22155 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#22156 = CARTESIAN_POINT ( 'NONE', ( -25.61730414488999941, 120.5278807943000032, 90.18495103081001218 ) ) ; +#22157 = ADVANCED_FACE ( 'NONE', ( #38241 ), #34650, .F. ) ; +#22158 = ADVANCED_FACE ( 'NONE', ( #35539 ), #6607, .T. ) ; +#22159 = VERTEX_POINT ( 'NONE', #1426 ) ; +#22160 = EDGE_CURVE ( 'NONE', #9253, #16546, #33086, .T. ) ; +#22161 = ADVANCED_FACE ( 'NONE', ( #19622 ), #4487, .T. ) ; +#22162 = DIRECTION ( 'NONE', ( 3.469446951953609456E-15, 0.9743700557921587402, 0.2249510932971554578 ) ) ; +#22163 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2255194953558363191, 0.9742386449830560124 ) ) ; +#22164 = ORIENTED_EDGE ( 'NONE', *, *, #13068, .F. ) ; +#22165 = ADVANCED_FACE ( 'NONE', ( #4697 ), #28645, .T. ) ; +#22166 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37247, #3282, #21720, #31511 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22167 = DIRECTION ( 'NONE', ( -0.0005884939472035798308, 0.2255194584528803226, -0.9742384859642908568 ) ) ; +#22168 = CARTESIAN_POINT ( 'NONE', ( -20.16511123273965111, 137.5482785908162668, 94.32836982820661831 ) ) ; +#22170 = CARTESIAN_POINT ( 'NONE', ( -3.169891427924896199, 127.3945816957879060, 89.06620843884485339 ) ) ; +#22169 = CARTESIAN_POINT ( 'NONE', ( 36.06387094376011504, 192.3198907774919633, 104.3778220165794721 ) ) ; +#22171 = ORIENTED_EDGE ( 'NONE', *, *, #18623, .F. ) ; +#22172 = EDGE_CURVE ( 'NONE', #37452, #31429, #32121, .T. ) ; +#22173 = CIRCLE ( 'NONE', #31950, 9.500000000012004620 ) ; +#22174 = ORIENTED_EDGE ( 'NONE', *, *, #1879, .T. ) ; +#22175 = CARTESIAN_POINT ( 'NONE', ( 28.26008709311996370, 125.3597192996346052, 90.11688057617377012 ) ) ; +#22176 = AXIS2_PLACEMENT_3D ( 'NONE', #28777, #3816, #22454 ) ; +#22177 = VECTOR ( 'NONE', #32712, 1000.000000000000114 ) ; +#22178 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971546806 ) ) ; +#22179 = ORIENTED_EDGE ( 'NONE', *, *, #36767, .T. ) ; +#22180 = CIRCLE ( 'NONE', #16911, 59.40509898823096790 ) ; +#22181 = VERTEX_POINT ( 'NONE', #4076 ) ; +#22182 = CARTESIAN_POINT ( 'NONE', ( -19.44534333246823721, 148.3822623830060365, 180.6034369735336895 ) ) ; +#22183 = CARTESIAN_POINT ( 'NONE', ( 14.12655386339156394, 193.2440397236847218, 28.36825712431430802 ) ) ; +#22184 = CARTESIAN_POINT ( 'NONE', ( 40.67331120850102621, 184.3716013758660779, 104.7596565505194803 ) ) ; +#22185 = CARTESIAN_POINT ( 'NONE', ( -2.300492219183000397, 191.0298810790000061, 106.1837422966000020 ) ) ; +#22186 = ORIENTED_EDGE ( 'NONE', *, *, #6042, .T. ) ; +#22187 = EDGE_LOOP ( 'NONE', ( #14126, #26471, #19642, #32766 ) ) ; +#22188 = CARTESIAN_POINT ( 'NONE', ( -6.028075236889769428, 177.1156665047246008, 103.6258451396837899 ) ) ; +#22189 = DIRECTION ( 'NONE', ( 0.7069397808360943225, -0.6508952239913948778, -0.2767156548816978590 ) ) ; +#22190 = CARTESIAN_POINT ( 'NONE', ( -25.86047652274000086, 121.2837808580000001, 87.84016125891000115 ) ) ; +#22191 = ORIENTED_EDGE ( 'NONE', *, *, #13742, .F. ) ; +#22192 = ORIENTED_EDGE ( 'NONE', *, *, #7573, .T. ) ; +#22193 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #4609, #7676, #38956, #10966, #23429, #35871, #7809 ), + ( #38479, #16803, #1473, #7609, #13960, #10499, #10089 ), + ( #29097, #28890, #1266, #26036, #19473, #20279, #867 ), + ( #13551, #16994, #3929, #32166, #29296, #38884, #38284 ), + ( #669, #31969, #35801, #13351, #1068, #25841, #35591 ), + ( #7397, #38090, #20070, #10901, #34988, #3731, #26240 ), + ( #4531, #29497, #13163, #23369, #16206, #26436, #22567 ), + ( #32559, #22965, #7001, #35390, #28689, #35197, #25642 ), + ( #16597, #16403, #10297, #22765, #19862, #7202, #19669 ), + ( #13751, #4125, #32364, #4333, #38676, #10695, #23159 ), + ( #36639, #17610, #14173, #32950, #8646, #4947, #20897 ), + ( #20695, #5137, #30301, #8442, #17407, #2101, #30108 ), + ( #39899, #21107, #14572, #11707, #14973, #29902, #8013 ), + ( #30519, #1893, #14365, #33559, #11289, #14781, #36223 ), + ( #33360, #11908, #5551, #27057, #24396, #23770, #5351 ), + ( #32758, #26847, #2504, #39287, #27476, #36843, #8846 ), + ( #17202, #23559, #4742, #1688, #27263, #29704, #23980 ), + ( #39693, #8230, #26644, #36013, #11497, #39086, #36437 ), + ( #11094, #17806, #20478, #24187, #39488, #33149, #2297 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 3, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 3, 4 ), + ( -0.009999996581309438665, -1.380576915403000099E-13, 0.006245672222069000197, 0.01249582094693999987, 0.02499611839667999907, 0.03749641584643000070, 0.04999671329618000232, 0.09999790309516000397, 0.1499990928940999890, 0.2000002826931999989, 0.3000001540364999886, 0.4000000253798999816, 0.5999997680666000477, 0.7999995107534000338, 0.9999996581169999788 ), + ( 0.1755984787945999992, 0.8244285363540999612, 0.8309168369296949797 ), + .UNSPECIFIED. ) ; +#22194 = CARTESIAN_POINT ( 'NONE', ( -20.51998460911297784, 211.0905570173818546, 73.57089872868714053 ) ) ; +#22195 = ORIENTED_EDGE ( 'NONE', *, *, #16047, .F. ) ; +#22196 = FACE_OUTER_BOUND ( 'NONE', #5122, .T. ) ; +#22197 = CARTESIAN_POINT ( 'NONE', ( 14.74285125918311756, 136.4206760581051867, 93.70497248843004456 ) ) ; +#22198 = ORIENTED_EDGE ( 'NONE', *, *, #24939, .T. ) ; +#22199 = LINE ( 'NONE', #9930, #22955 ) ; +#22200 = CIRCLE ( 'NONE', #14343, 2.249999999984614973 ) ; +#22201 = VECTOR ( 'NONE', #10919, 1000.000000000000114 ) ; +#22202 = CARTESIAN_POINT ( 'NONE', ( -1.931781717180999891, 189.4344389325000009, 106.0157167347000069 ) ) ; +#22203 = CARTESIAN_POINT ( 'NONE', ( -0.02845919973435177830, 93.66652340833722690, 291.5585611238757906 ) ) ; +#22204 = VECTOR ( 'NONE', #5996, 1000.000000000000227 ) ; +#22205 = ORIENTED_EDGE ( 'NONE', *, *, #20008, .F. ) ; +#22206 = CARTESIAN_POINT ( 'NONE', ( 22.78224836617404137, 153.4848041862170476, 97.81073271791672141 ) ) ; +#22207 = CIRCLE ( 'NONE', #37202, 2.500000000048662407 ) ; +#22208 = EDGE_CURVE ( 'NONE', #20878, #15252, #3883, .T. ) ; +#22209 = DIRECTION ( 'NONE', ( 0.0008702530711002103318, -0.2253087760482092305, 0.9742870203873447155 ) ) ; +#22210 = EDGE_CURVE ( 'NONE', #37005, #29453, #29044, .T. ) ; +#22211 = CARTESIAN_POINT ( 'NONE', ( -26.00138850119475364, 118.1173731751006102, 87.28355378449504087 ) ) ; +#22212 = VECTOR ( 'NONE', #32705, 1000.000000000000000 ) ; +#22213 = DIRECTION ( 'NONE', ( 3.251597278533251339E-13, 0.9743700556678254188, 0.2249510938357014433 ) ) ; +#22214 = CARTESIAN_POINT ( 'NONE', ( 44.97084429314561049, 114.9968340379079166, 129.9902062988158491 ) ) ; +#22215 = ORIENTED_EDGE ( 'NONE', *, *, #33538, .T. ) ; +#22216 = FACE_OUTER_BOUND ( 'NONE', #18166, .T. ) ; +#22217 = ORIENTED_EDGE ( 'NONE', *, *, #28578, .F. ) ; +#22218 = CARTESIAN_POINT ( 'NONE', ( -13.73975480766844370, 125.4641165520392576, 174.2036076464545999 ) ) ; +#22219 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39933, #33591, #20932, #5585, #27292, #40328, #12333, #12523, #30334, #21554, #24630, #31150 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999997571942, 0.3749999999996513345, 0.4374999999996138089, 0.4687499999996104783, 0.4843749999996179723, 0.4999999999996255218, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22220 = CARTESIAN_POINT ( 'NONE', ( -38.00039891565000261, 118.8907101337000114, 90.44953021773000046 ) ) ; +#22221 = ORIENTED_EDGE ( 'NONE', *, *, #24428, .F. ) ; +#22222 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#22223 = CARTESIAN_POINT ( 'NONE', ( 35.04645051036200698, 220.4002260771000294, 75.53733736045835201 ) ) ; +#22224 = EDGE_LOOP ( 'NONE', ( #2442, #29288, #7803, #33837 ) ) ; +#22225 = CARTESIAN_POINT ( 'NONE', ( 11.62516440745127788, 158.5902278274764399, 96.25934000436126325 ) ) ; +#22226 = CARTESIAN_POINT ( 'NONE', ( -28.94629671773198965, 110.6131156702000027, 90.28526767713175616 ) ) ; +#22227 = CARTESIAN_POINT ( 'NONE', ( -32.70191599978576136, 163.2145672798008889, 188.5682430650827826 ) ) ; +#22228 = CARTESIAN_POINT ( 'NONE', ( -3.535839359701232087, 174.6735602432432586, 103.0605886135060700 ) ) ; +#22229 = FACE_BOUND ( 'NONE', #6205, .T. ) ; +#22230 = ORIENTED_EDGE ( 'NONE', *, *, #34985, .F. ) ; +#22231 = EDGE_LOOP ( 'NONE', ( #32155, #32182, #21369, #5369 ) ) ; +#22233 = AXIS2_PLACEMENT_3D ( 'NONE', #16684, #19356, #22846 ) ; +#22232 = CARTESIAN_POINT ( 'NONE', ( -6.036160832484147143, 177.5628022570028861, 100.8450471008263065 ) ) ; +#22234 = EDGE_CURVE ( 'NONE', #11287, #38686, #18449, .T. ) ; +#22235 = DIRECTION ( 'NONE', ( -0.6771712326826390127, 0.7358254695422518088, 0.000000000000000000 ) ) ; +#22236 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31823, #19519, #16449, #28939, #32214, #10945, #4780, #23406, #29745, #13797, #35845, #29940, #38717, #32989, #11542, #23811 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 4 ), + ( 6.245004513516505540E-17, 0.002671159371488287821, 0.004006739057232330467, 0.005342318742976373547, 0.006677898428720415759, 0.008013478114464457971, 0.009349057800208501051, 0.01068463748595254413 ), + .UNSPECIFIED. ) ; +#22237 = CIRCLE ( 'NONE', #4571, 6.000000000011024071 ) ; +#22238 = EDGE_LOOP ( 'NONE', ( #16712, #3894 ) ) ; +#22239 = CARTESIAN_POINT ( 'NONE', ( -23.36251194011130039, 135.0730551530189700, 91.06624837206607026 ) ) ; +#22240 = AXIS2_PLACEMENT_3D ( 'NONE', #11428, #23918, #14716 ) ; +#22241 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524656274, 149.3470289647502511, 130.0514119197545142 ) ) ; +#22242 = VERTEX_POINT ( 'NONE', #9340 ) ; +#22243 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#22244 = CARTESIAN_POINT ( 'NONE', ( 37.46412981905668005, 124.0392836328241088, 91.34593135885953075 ) ) ; +#22245 = ORIENTED_EDGE ( 'NONE', *, *, #21258, .T. ) ; +#22246 = CARTESIAN_POINT ( 'NONE', ( 10.03596943923905549, 167.8233964549057760, 101.4708580514027148 ) ) ; +#22247 = LINE ( 'NONE', #34872, #13998 ) ; +#22248 = CARTESIAN_POINT ( 'NONE', ( 15.50147165590422205, 151.4095604219332643, 97.16497155034561217 ) ) ; +#22249 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567345 ) ) ; +#22250 = DIRECTION ( 'NONE', ( 0.6068733047655823221, 0.7745082036644093115, 0.1784428043363773253 ) ) ; +#22251 = ORIENTED_EDGE ( 'NONE', *, *, #10944, .F. ) ; +#22252 = CARTESIAN_POINT ( 'NONE', ( 20.48673967653602901, 211.0896571907997554, 75.54495990469186495 ) ) ; +#22253 = CARTESIAN_POINT ( 'NONE', ( 0.6537733827144348586, 189.0019688857385347, 103.6874789632729659 ) ) ; +#22254 = CARTESIAN_POINT ( 'NONE', ( -2.801236327734337284, 190.0641490399931115, 106.6132946571331956 ) ) ; +#22255 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927876389700, -0.0005734119022052573504 ) ) ; +#22256 = ORIENTED_EDGE ( 'NONE', *, *, #24089, .T. ) ; +#22257 = ADVANCED_FACE ( 'NONE', ( #6853 ), #23586, .T. ) ; +#22258 = DIRECTION ( 'NONE', ( 0.9914447795421099663, -0.1270909273343945323, -0.02975139169821508847 ) ) ; +#22259 = EDGE_CURVE ( 'NONE', #7826, #6999, #6645, .T. ) ; +#22260 = CARTESIAN_POINT ( 'NONE', ( 2.879337540444164567, 205.2605563912295850, 76.16820990527092761 ) ) ; +#22261 = FACE_OUTER_BOUND ( 'NONE', #23537, .T. ) ; +#22262 = AXIS2_PLACEMENT_3D ( 'NONE', #9522, #107, #24269 ) ; +#22263 = AXIS2_PLACEMENT_3D ( 'NONE', #21637, #9357, #34466 ) ; +#22264 = CARTESIAN_POINT ( 'NONE', ( -26.04096242281000073, 189.6189556054999912, 106.3534993234000012 ) ) ; +#22265 = ORIENTED_EDGE ( 'NONE', *, *, #9480, .F. ) ; +#22266 = VECTOR ( 'NONE', #35647, 1000.000000000000000 ) ; +#22267 = AXIS2_PLACEMENT_3D ( 'NONE', #35087, #7290, #7096 ) ; +#22268 = CARTESIAN_POINT ( 'NONE', ( 42.51832847222295442, 128.8459892653891075, 92.45259438658834483 ) ) ; +#22269 = CARTESIAN_POINT ( 'NONE', ( -12.63633278542094196, 136.6784457103040040, 94.29417180125015818 ) ) ; +#22270 = ORIENTED_EDGE ( 'NONE', *, *, #27854, .F. ) ; +#22271 = CARTESIAN_POINT ( 'NONE', ( 28.26067382423566698, 125.1347711400599110, 91.09124888412546284 ) ) ; +#22272 = CARTESIAN_POINT ( 'NONE', ( -22.49999922076901981, 174.5126133868815543, 99.95592377105238313 ) ) ; +#22273 = LINE ( 'NONE', #25142, #35883 ) ; +#22274 = CARTESIAN_POINT ( 'NONE', ( 37.96499314393000191, 190.9636352775000034, 106.2831835281999986 ) ) ; +#22275 = CARTESIAN_POINT ( 'NONE', ( 36.76977172392000170, 191.5398167378999972, 106.2267418912000068 ) ) ; +#22276 = EDGE_LOOP ( 'NONE', ( #10510, #22804, #26285, #16568, #33344, #30163 ) ) ; +#22277 = CARTESIAN_POINT ( 'NONE', ( -28.46737701140902033, 184.1209660424817400, 102.1777913196515755 ) ) ; +#22278 = EDGE_CURVE ( 'NONE', #315, #14670, #4661, .T. ) ; +#22279 = LINE ( 'NONE', #31472, #11844 ) ; +#22280 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#22281 = ORIENTED_EDGE ( 'NONE', *, *, #38976, .F. ) ; +#22282 = CARTESIAN_POINT ( 'NONE', ( -30.72295198953211326, 177.7251950676070749, 100.7025732852349762 ) ) ; +#22283 = ORIENTED_EDGE ( 'NONE', *, *, #21842, .T. ) ; +#22284 = CONICAL_SURFACE ( 'NONE', #35962, 6.000000000029579006, 0.7853981634430682313 ) ; +#22285 = VECTOR ( 'NONE', #40299, 1000.000000000000000 ) ; +#22286 = CARTESIAN_POINT ( 'NONE', ( 25.99904971602028425, 120.7769186021849066, 87.52076664421943519 ) ) ; +#22287 = CARTESIAN_POINT ( 'NONE', ( -36.70588856729196436, 191.6013385684930483, 104.3872917547991932 ) ) ; +#22288 = ORIENTED_EDGE ( 'NONE', *, *, #11539, .T. ) ; +#22289 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; +#22290 = EDGE_CURVE ( 'NONE', #26621, #1901, #30206, .T. ) ; +#22291 = AXIS2_PLACEMENT_3D ( 'NONE', #18930, #3392, #6461 ) ; +#22292 = AXIS2_PLACEMENT_3D ( 'NONE', #19348, #24718, #9360 ) ; +#22293 = LINE ( 'NONE', #16728, #20071 ) ; +#22294 = CARTESIAN_POINT ( 'NONE', ( -22.49952074149951997, 137.4671135675431515, 177.5661851824280291 ) ) ; +#22295 = LINE ( 'NONE', #15928, #25613 ) ; +#22296 = ORIENTED_EDGE ( 'NONE', *, *, #7686, .T. ) ; +#22297 = EDGE_CURVE ( 'NONE', #8771, #15381, #9902, .T. ) ; +#22298 = CARTESIAN_POINT ( 'NONE', ( -26.00898928064792059, 209.7096528057114710, 76.07444037909847623 ) ) ; +#22299 = LINE ( 'NONE', #18590, #944 ) ; +#22300 = LINE ( 'NONE', #4057, #18177 ) ; +#22301 = CARTESIAN_POINT ( 'NONE', ( -35.81913783262000095, 191.4997546378000095, 103.7576553867999962 ) ) ; +#22302 = EDGE_CURVE ( 'NONE', #3973, #15609, #6013, .T. ) ; +#22303 = ORIENTED_EDGE ( 'NONE', *, *, #36111, .F. ) ; +#22304 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#22305 = ORIENTED_EDGE ( 'NONE', *, *, #34996, .T. ) ; +#22306 = EDGE_CURVE ( 'NONE', #19810, #22776, #37691, .T. ) ; +#22307 = ADVANCED_FACE ( 'NONE', ( #18864 ), #11869, .F. ) ; +#22308 = CARTESIAN_POINT ( 'NONE', ( -28.53208073851174476, 125.2791694434640135, 88.59312828080875590 ) ) ; +#22309 = ADVANCED_FACE ( 'NONE', ( #678 ), #5956, .T. ) ; +#22310 = CARTESIAN_POINT ( 'NONE', ( 25.53747175047978857, 190.9172658757476313, 106.2799836673595024 ) ) ; +#22311 = CARTESIAN_POINT ( 'NONE', ( -13.36410657841409488, 181.7648119164822162, 101.6247081824262040 ) ) ; +#22312 = CARTESIAN_POINT ( 'NONE', ( -22.49967939491756752, 153.8038087509543743, 95.68807059495395606 ) ) ; +#22313 = CIRCLE ( 'NONE', #24927, 1.999999997455631284 ) ; +#22314 = CARTESIAN_POINT ( 'NONE', ( 15.50029467790899496, 185.7974155947267718, 103.0514270424844483 ) ) ; +#22315 = AXIS2_PLACEMENT_3D ( 'NONE', #34197, #2394, #37480 ) ; +#22316 = CARTESIAN_POINT ( 'NONE', ( -2.288621054235000063, 209.3634523597000054, 73.69906321377999348 ) ) ; +#22317 = CARTESIAN_POINT ( 'NONE', ( 38.48555382640000033, 118.5484835161000063, 89.80748669179000387 ) ) ; +#22318 = ORIENTED_EDGE ( 'NONE', *, *, #13693, .T. ) ; +#22319 = CARTESIAN_POINT ( 'NONE', ( -22.50000097842500679, 160.7375465425423897, 96.77263313290113445 ) ) ; +#22320 = CARTESIAN_POINT ( 'NONE', ( 24.63900929408691454, 117.2586415609094814, 170.8533154267458940 ) ) ; +#22321 = DIRECTION ( 'NONE', ( 1.397458901295144550E-11, 0.9743043966640304587, 0.2252353050503839715 ) ) ; +#22322 = CARTESIAN_POINT ( 'NONE', ( 16.28891463809603124, 132.2249801446032791, 155.9597679450893679 ) ) ; +#22323 = ORIENTED_EDGE ( 'NONE', *, *, #2690, .T. ) ; +#22324 = EDGE_LOOP ( 'NONE', ( #27997, #33336, #13820, #26675 ) ) ; +#22325 = EDGE_CURVE ( 'NONE', #2286, #36964, #16808, .T. ) ; +#22326 = ORIENTED_EDGE ( 'NONE', *, *, #21789, .T. ) ; +#22327 = CARTESIAN_POINT ( 'NONE', ( 23.68458193633980713, 135.2968916886795228, 91.38751720632359365 ) ) ; +#22328 = LINE ( 'NONE', #26803, #4293 ) ; +#22329 = DIRECTION ( 'NONE', ( -0.0004271987741244301384, 0.7071067811864831798, -0.7071066521404663074 ) ) ; +#22330 = ORIENTED_EDGE ( 'NONE', *, *, #33198, .F. ) ; +#22331 = ORIENTED_EDGE ( 'NONE', *, *, #18163, .T. ) ; +#22332 = FACE_OUTER_BOUND ( 'NONE', #4174, .T. ) ; +#22333 = CARTESIAN_POINT ( 'NONE', ( 12.31247077724877315, 134.4456542776592585, 93.59261989489698408 ) ) ; +#22334 = CARTESIAN_POINT ( 'NONE', ( 25.50773797008787369, 191.9759150222000130, 101.9060413058080030 ) ) ; +#22335 = CARTESIAN_POINT ( 'NONE', ( 29.40663682764231268, 130.8456206841377707, 89.84325200762386032 ) ) ; +#22336 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; +#22337 = ORIENTED_EDGE ( 'NONE', *, *, #37899, .F. ) ; +#22338 = CARTESIAN_POINT ( 'NONE', ( -19.21678146528146058, 125.2620815843974924, 178.3530915497297258 ) ) ; +#22339 = EDGE_CURVE ( 'NONE', #10264, #11480, #7614, .T. ) ; +#22340 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24173, #33540, #18198, #27649, #5946, #37033, #21703, #36625, #12477, #36421, #33749, #30504 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999995047295, 0.3749999999992678079, 0.4374999999991787680, 0.4687499999991626698, 0.4843749999991739386, 0.4999999999991850963, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22341 = VERTEX_POINT ( 'NONE', #25849 ) ; +#22342 = CARTESIAN_POINT ( 'NONE', ( -20.54149002962999049, 176.5964826137828254, 28.07869762585763240 ) ) ; +#22343 = DIRECTION ( 'NONE', ( -0.9999998176028267460, -3.062651553416717956E-09, 0.0006039820470873916896 ) ) ; +#22344 = AXIS2_PLACEMENT_3D ( 'NONE', #24212, #2323, #33380 ) ; +#22345 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; +#22346 = ORIENTED_EDGE ( 'NONE', *, *, #33159, .T. ) ; +#22347 = CONICAL_SURFACE ( 'NONE', #4687, 6.499999999933947947, 0.7853981634770059728 ) ; +#22348 = VERTEX_POINT ( 'NONE', #10309 ) ; +#22349 = ADVANCED_FACE ( 'NONE', ( #35205 ), #29103, .T. ) ; +#22350 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988408924259, 150.9961524914645850, 94.51313162284453995 ) ) ; +#22351 = CARTESIAN_POINT ( 'NONE', ( 2.922156723524788724, 190.2869223753070855, 103.5823562725477842 ) ) ; +#22352 = FACE_OUTER_BOUND ( 'NONE', #32967, .T. ) ; +#22353 = EDGE_CURVE ( 'NONE', #35918, #7067, #10505, .T. ) ; +#22354 = VERTEX_POINT ( 'NONE', #22308 ) ; +#22355 = DIRECTION ( 'NONE', ( -0.0005884949961266395689, 0.2249510543439048882, -0.9743698870671267942 ) ) ; +#22356 = CARTESIAN_POINT ( 'NONE', ( -25.50046849319145537, 118.1130939482222857, 89.11646148004645340 ) ) ; +#22357 = ORIENTED_EDGE ( 'NONE', *, *, #29121, .T. ) ; +#22358 = EDGE_CURVE ( 'NONE', #30585, #8959, #25778, .T. ) ; +#22359 = CARTESIAN_POINT ( 'NONE', ( 59.75594728249464538, 30.15273947196611815, 149.3573573250752133 ) ) ; +#22360 = CARTESIAN_POINT ( 'NONE', ( 36.13530173960303671, 191.5119209504615867, 103.8451096219701810 ) ) ; +#22361 = CARTESIAN_POINT ( 'NONE', ( -27.04885921334999921, 123.0440198693000013, 91.29407312176999767 ) ) ; +#22362 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29806, #1998, #14468, #21004, #7912, #36119, #33249, #2405, #1785, #5451 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.0008906419405732026156, 0.2506679814554299002, 0.5004453209702866001, 0.7502226604851433001, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22363 = VERTEX_POINT ( 'NONE', #18597 ) ; +#22364 = CARTESIAN_POINT ( 'NONE', ( -6.036264379393829316, 136.7917950106709100, 93.80320213086851311 ) ) ; +#22365 = LINE ( 'NONE', #21960, #34535 ) ; +#22366 = DIRECTION ( 'NONE', ( -0.0006039748319391913256, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#22367 = EDGE_LOOP ( 'NONE', ( #37923, #24761, #30421, #17831 ) ) ; +#22368 = FACE_OUTER_BOUND ( 'NONE', #16813, .T. ) ; +#22369 = CARTESIAN_POINT ( 'NONE', ( -22.49970497327230490, 184.8490926230421962, 102.8554404399357622 ) ) ; +#22370 = AXIS2_PLACEMENT_3D ( 'NONE', #4923, #23536, #14145 ) ; +#22372 = CARTESIAN_POINT ( 'NONE', ( -17.08965732320790920, 121.5613976340063118, 176.7749525043521146 ) ) ; +#22371 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825929013683355, 0.0005734119021813978553 ) ) ; +#22373 = AXIS2_PLACEMENT_3D ( 'NONE', #12382, #5646, #2786 ) ; +#22374 = ORIENTED_EDGE ( 'NONE', *, *, #8756, .F. ) ; +#22375 = LINE ( 'NONE', #21968, #18620 ) ; +#22376 = DIRECTION ( 'NONE', ( 0.0005884949961246576473, -0.2249510543439054155, 0.9743698870671265722 ) ) ; +#22377 = VERTEX_POINT ( 'NONE', #15937 ) ; +#22378 = EDGE_LOOP ( 'NONE', ( #20547, #3879, #36071, #13685 ) ) ; +#22379 = PLANE ( 'NONE', #20443 ) ; +#22380 = CARTESIAN_POINT ( 'NONE', ( -25.51388077191477066, 211.0902258580313742, 75.57405363378009611 ) ) ; +#22381 = CARTESIAN_POINT ( 'NONE', ( 13.51095425345201129, 187.6707999454940818, 106.0508869016509266 ) ) ; +#22382 = CARTESIAN_POINT ( 'NONE', ( 20.50147081996105314, 160.1804844985509817, 99.18687942156120130 ) ) ; +#22383 = ORIENTED_EDGE ( 'NONE', *, *, #5138, .F. ) ; +#22384 = EDGE_CURVE ( 'NONE', #13079, #17036, #20937, .T. ) ; +#22385 = VERTEX_POINT ( 'NONE', #28045 ) ; +#22386 = EDGE_CURVE ( 'NONE', #33385, #37452, #16995, .T. ) ; +#22387 = ORIENTED_EDGE ( 'NONE', *, *, #11824, .F. ) ; +#22388 = CYLINDRICAL_SURFACE ( 'NONE', #35635, 6.000000000000011546 ) ; +#22389 = EDGE_CURVE ( 'NONE', #9503, #734, #30128, .T. ) ; +#22390 = CARTESIAN_POINT ( 'NONE', ( -12.63767699504066577, 177.1899956602251507, 101.0812418388079834 ) ) ; +#22391 = CARTESIAN_POINT ( 'NONE', ( -23.36763934512021734, 134.2409834847225625, 93.73796057560730333 ) ) ; +#22392 = ADVANCED_FACE ( 'NONE', ( #34930 ), #6538, .T. ) ; +#22393 = CARTESIAN_POINT ( 'NONE', ( 18.99670475096374034, 148.1889770648965623, 184.7135872576050986 ) ) ; +#22394 = ORIENTED_EDGE ( 'NONE', *, *, #27339, .T. ) ; +#22395 = ORIENTED_EDGE ( 'NONE', *, *, #12285, .T. ) ; +#22396 = CARTESIAN_POINT ( 'NONE', ( -25.49121842733731569, 191.8361208170296379, 104.4329317390898950 ) ) ; +#22397 = ORIENTED_EDGE ( 'NONE', *, *, #23667, .F. ) ; +#22398 = AXIS2_PLACEMENT_3D ( 'NONE', #15962, #10047, #6757 ) ; +#22399 = EDGE_CURVE ( 'NONE', #7245, #39006, #11688, .T. ) ; +#22400 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; +#22401 = ORIENTED_EDGE ( 'NONE', *, *, #36264, .F. ) ; +#22402 = CARTESIAN_POINT ( 'NONE', ( -31.05248204746864005, 158.9539887611892652, 186.6368167519732424 ) ) ; +#22403 = EDGE_CURVE ( 'NONE', #26164, #8671, #26817, .T. ) ; +#22404 = AXIS2_PLACEMENT_3D ( 'NONE', #14914, #39835, #32897 ) ; +#22405 = CARTESIAN_POINT ( 'NONE', ( -2.813165966022999953, 190.9564557362000130, 106.6949844788999968 ) ) ; +#22406 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218859315, 87.27946979429613350, 297.5295786860743874 ) ) ; +#22407 = ORIENTED_EDGE ( 'NONE', *, *, #912, .F. ) ; +#22408 = DIRECTION ( 'NONE', ( -0.7072735235946167043, -0.6508952239913153859, -0.2758615054830065305 ) ) ; +#22409 = CARTESIAN_POINT ( 'NONE', ( 33.29944284160863077, 84.12354575840004145, 284.1448177430615374 ) ) ; +#22410 = CARTESIAN_POINT ( 'NONE', ( -25.66804413620193159, 118.1146252066666733, 87.61661746274521079 ) ) ; +#22411 = LINE ( 'NONE', #9529, #32041 ) ; +#22412 = EDGE_CURVE ( 'NONE', #23623, #20699, #1007, .T. ) ; +#22413 = LINE ( 'NONE', #3972, #3013 ) ; +#22414 = ORIENTED_EDGE ( 'NONE', *, *, #13872, .T. ) ; +#22415 = CARTESIAN_POINT ( 'NONE', ( -45.03708708209951084, 124.0713768683079081, 93.45577792510331960 ) ) ; +#22416 = LINE ( 'NONE', #19115, #32470 ) ; +#22417 = ORIENTED_EDGE ( 'NONE', *, *, #3386, .F. ) ; +#22418 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12027, #36966, #8968, #21443 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22419 = AXIS2_PLACEMENT_3D ( 'NONE', #37897, #25646, #22371 ) ; +#22420 = ORIENTED_EDGE ( 'NONE', *, *, #40087, .T. ) ; +#22421 = DIRECTION ( 'NONE', ( -0.0006039748319380815363, -1.388651635424563573E-14, -0.9999998176071845934 ) ) ; +#22422 = DIRECTION ( 'NONE', ( 0.0005121997063476214180, 0.5299192642332222203, 0.8480479414785353498 ) ) ; +#22423 = CARTESIAN_POINT ( 'NONE', ( -3.657007565168505003, 174.7046328845856920, 102.9436394089264155 ) ) ; +#22424 = VERTEX_POINT ( 'NONE', #8783 ) ; +#22425 = DIRECTION ( 'NONE', ( -1.214306433183758024E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#22426 = VERTEX_POINT ( 'NONE', #36378 ) ; +#22427 = ORIENTED_EDGE ( 'NONE', *, *, #26991, .F. ) ; +#22428 = CARTESIAN_POINT ( 'NONE', ( 39.73175645750271912, 182.5347700109205675, 106.6535420028259438 ) ) ; +#22429 = LINE ( 'NONE', #26102, #39350 ) ; +#22430 = AXIS2_PLACEMENT_3D ( 'NONE', #10283, #7790, #35568 ) ; +#22431 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#22432 = EDGE_CURVE ( 'NONE', #9285, #21583, #30042, .T. ) ; +#22433 = EDGE_LOOP ( 'NONE', ( #2934, #23995, #11375, #19393 ) ) ; +#22434 = CARTESIAN_POINT ( 'NONE', ( 8.046776635720599202, 151.4387294071806593, 94.61044745561473235 ) ) ; +#22435 = EDGE_CURVE ( 'NONE', #32876, #23127, #33596, .T. ) ; +#22436 = CARTESIAN_POINT ( 'NONE', ( 21.85504115049297980, 129.9621995019233225, 89.81490981051685196 ) ) ; +#22437 = EDGE_CURVE ( 'NONE', #3193, #3978, #17704, .T. ) ; +#22438 = ORIENTED_EDGE ( 'NONE', *, *, #8596, .F. ) ; +#22439 = DIRECTION ( 'NONE', ( 0.5988683521957592903, -0.8008474865655358377, 0.000000000000000000 ) ) ; +#22440 = CARTESIAN_POINT ( 'NONE', ( 30.07009376554507440, 174.7970070534087768, 102.5555909528905261 ) ) ; +#22441 = CARTESIAN_POINT ( 'NONE', ( 25.99332206926874278, 209.7096538831000032, 78.04280567916214295 ) ) ; +#22442 = ORIENTED_EDGE ( 'NONE', *, *, #25126, .T. ) ; +#22443 = CARTESIAN_POINT ( 'NONE', ( 28.20672708967000020, 125.3940403962999994, 88.92763624988999993 ) ) ; +#22444 = EDGE_CURVE ( 'NONE', #5073, #81, #15117, .T. ) ; +#22445 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#22446 = CARTESIAN_POINT ( 'NONE', ( -21.82845865523656315, 182.3067054805563316, 104.3206871860773504 ) ) ; +#22447 = CARTESIAN_POINT ( 'NONE', ( 3.755182731601074408, 175.3075123181448305, 100.3502401767937613 ) ) ; +#22448 = DIRECTION ( 'NONE', ( -0.0006039748319379876444, -1.544770086762009064E-14, -0.9999998176071845934 ) ) ; +#22449 = ORIENTED_EDGE ( 'NONE', *, *, #2888, .T. ) ; +#22451 = EDGE_CURVE ( 'NONE', #520, #20878, #15078, .T. ) ; +#22450 = CARTESIAN_POINT ( 'NONE', ( 22.49999736296386743, 160.7435420377399282, 96.74666379507640102 ) ) ; +#22452 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971519328 ) ) ; +#22453 = AXIS2_PLACEMENT_3D ( 'NONE', #5090, #2250, #30060 ) ; +#22454 = DIRECTION ( 'NONE', ( 0.5968393679912002980, 0.8023607473050164973, 0.000000000000000000 ) ) ; +#22455 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37855, #9054, #6170, #15768, #34372, #3488 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 4 ), + ( 0.000000000000000000, 0.3333281889657515595, 0.6666640818021849491, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22456 = CARTESIAN_POINT ( 'NONE', ( 12.63717152284372958, 130.1526461680852265, 92.50424807167719621 ) ) ; +#22457 = ORIENTED_EDGE ( 'NONE', *, *, #37909, .T. ) ; +#22458 = VECTOR ( 'NONE', #876, 1000.000000000000000 ) ; +#22459 = CARTESIAN_POINT ( 'NONE', ( 38.36940859710925622, 118.9353376627760071, 90.24631930852783057 ) ) ; +#22460 = DIRECTION ( 'NONE', ( 0.0005884949961264727102, -0.2249510543439039167, 0.9743698870671270162 ) ) ; +#22461 = PLANE ( 'NONE', #17621 ) ; +#22462 = EDGE_CURVE ( 'NONE', #30098, #23829, #37775, .T. ) ; +#22463 = AXIS2_PLACEMENT_3D ( 'NONE', #26707, #14022, #22832 ) ; +#22464 = CARTESIAN_POINT ( 'NONE', ( -26.00373707785711730, 190.8838294880926014, 106.8165467415037142 ) ) ; +#22465 = ORIENTED_EDGE ( 'NONE', *, *, #22614, .F. ) ; +#22466 = CARTESIAN_POINT ( 'NONE', ( 20.48791368134620683, 201.8041646541999796, 85.15356383073336133 ) ) ; +#22467 = CARTESIAN_POINT ( 'NONE', ( -12.63793912156016042, 182.0618459091404873, 102.2059974569859975 ) ) ; +#22468 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29227, #400, #25767, #10018 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22469 = CARTESIAN_POINT ( 'NONE', ( -43.75033814667176557, 185.4897723175090221, 107.5113483461213661 ) ) ; +#22470 = FACE_OUTER_BOUND ( 'NONE', #38561, .T. ) ; +#22471 = CARTESIAN_POINT ( 'NONE', ( -22.78255965921956161, 158.2257193261845316, 98.76172871125201880 ) ) ; +#22472 = CARTESIAN_POINT ( 'NONE', ( 0.5441254074100964067, 211.4999999999614602, 73.05817544432547095 ) ) ; +#22473 = CARTESIAN_POINT ( 'NONE', ( 35.09291703857000044, 217.7719116314000019, 152.4718672074000381 ) ) ; +#22474 = CARTESIAN_POINT ( 'NONE', ( 36.08518882432319685, 192.3722560605559977, 106.3999998832000102 ) ) ; +#22475 = CARTESIAN_POINT ( 'NONE', ( 3.820232418934266239, 143.6044667692935093, 95.59131969296058173 ) ) ; +#22476 = CARTESIAN_POINT ( 'NONE', ( 4.034499240732137615, 175.2435454650998850, 100.6217987443006194 ) ) ; +#22477 = EDGE_LOOP ( 'NONE', ( #35181, #40188 ) ) ; +#22478 = EDGE_LOOP ( 'NONE', ( #17870, #20844, #4227, #12674 ) ) ; +#22479 = CARTESIAN_POINT ( 'NONE', ( -2.946865378000000035, 209.3288521576999983, 76.09373086713999612 ) ) ; +#22480 = VECTOR ( 'NONE', #32937, 1000.000000000000000 ) ; +#22481 = CARTESIAN_POINT ( 'NONE', ( 20.50029254611199292, 184.8549113859068029, 102.8308091169877798 ) ) ; +#22482 = VECTOR ( 'NONE', #4835, 1000.000000000000227 ) ; +#22483 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 77.27946979429643193, 322.5967026918629017 ) ) ; +#22484 = CARTESIAN_POINT ( 'NONE', ( 39.05648265166797017, 127.5103312055594955, 92.14632397477382142 ) ) ; +#22485 = ORIENTED_EDGE ( 'NONE', *, *, #25991, .T. ) ; +#22486 = CARTESIAN_POINT ( 'NONE', ( -39.69261857620511336, 119.4152473592345842, 89.81183687744525912 ) ) ; +#22487 = EDGE_CURVE ( 'NONE', #39445, #7666, #13120, .T. ) ; +#22488 = CIRCLE ( 'NONE', #5501, 51.90509899263581417 ) ; +#22489 = EDGE_CURVE ( 'NONE', #39132, #33799, #31455, .T. ) ; +#22490 = ORIENTED_EDGE ( 'NONE', *, *, #19643, .F. ) ; +#22491 = VECTOR ( 'NONE', #25154, 1000.000000000000000 ) ; +#22492 = CARTESIAN_POINT ( 'NONE', ( -23.36013446842593666, 174.6767834003346138, 103.0763367099988415 ) ) ; +#22493 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#22494 = LINE ( 'NONE', #28417, #16471 ) ; +#22495 = LINE ( 'NONE', #18776, #12749 ) ; +#22496 = CARTESIAN_POINT ( 'NONE', ( -45.19483343799229402, 186.0262136949233138, 106.1956750743143090 ) ) ; +#22497 = ADVANCED_FACE ( 'NONE', ( #6292 ), #34295, .T. ) ; +#22498 = DIRECTION ( 'NONE', ( -0.7865509479255973213, -0.6175253892086901564, 0.000000000000000000 ) ) ; +#22499 = CARTESIAN_POINT ( 'NONE', ( 2.943104451508621544, 209.7096517725655644, 76.05672380837390278 ) ) ; +#22500 = ORIENTED_EDGE ( 'NONE', *, *, #4915, .F. ) ; +#22501 = ORIENTED_EDGE ( 'NONE', *, *, #34092, .T. ) ; +#22502 = FACE_OUTER_BOUND ( 'NONE', #17811, .T. ) ; +#22503 = CARTESIAN_POINT ( 'NONE', ( 92.50187971282166188, 221.8453154663451699, 201.2060978135920379 ) ) ; +#22504 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#22505 = FACE_OUTER_BOUND ( 'NONE', #3954, .T. ) ; +#22506 = EDGE_LOOP ( 'NONE', ( #33423, #24128, #32697, #36474 ) ) ; +#22507 = CARTESIAN_POINT ( 'NONE', ( 44.87746509354383306, 179.5854585350990362, 137.0276591108483331 ) ) ; +#22508 = VERTEX_POINT ( 'NONE', #7097 ) ; +#22509 = VECTOR ( 'NONE', #34885, 1000.000000000000000 ) ; +#22510 = EDGE_CURVE ( 'NONE', #39608, #9539, #13451, .T. ) ; +#22511 = CARTESIAN_POINT ( 'NONE', ( -20.00025820447960001, 138.1823733798348428, 91.56700283718186029 ) ) ; +#22512 = CARTESIAN_POINT ( 'NONE', ( 19.99933118494021755, 196.5785306413737601, 103.8628508136982731 ) ) ; +#22513 = VECTOR ( 'NONE', #7554, 1000.000000000000000 ) ; +#22514 = LINE ( 'NONE', #34932, #12980 ) ; +#22515 = DIRECTION ( 'NONE', ( -0.0006039748319384964604, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#22516 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999904787, 132.9679238121919980, 90.36185680185722902 ) ) ; +#22517 = CARTESIAN_POINT ( 'NONE', ( 20.48137660469177490, 206.5183323763784529, 74.84160177721973639 ) ) ; +#22518 = CARTESIAN_POINT ( 'NONE', ( -37.90890821973000158, 190.8183704905999889, 106.4200881177000184 ) ) ; +#22519 = EDGE_LOOP ( 'NONE', ( #18086, #1048, #27230, #11555 ) ) ; +#22520 = EDGE_CURVE ( 'NONE', #19730, #35236, #20166, .T. ) ; +#22521 = CARTESIAN_POINT ( 'NONE', ( 38.29593043767467719, 218.5902260770999987, 76.03537484722993156 ) ) ; +#22522 = CARTESIAN_POINT ( 'NONE', ( -36.54104006138566518, 191.4170194552398812, 106.3917187889346252 ) ) ; +#22523 = DIRECTION ( 'NONE', ( -0.0005884949961228156962, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#22524 = CARTESIAN_POINT ( 'NONE', ( -28.52494644200928064, 186.7521494213145559, 105.8641958179564568 ) ) ; +#22525 = VERTEX_POINT ( 'NONE', #4828 ) ; +#22526 = ORIENTED_EDGE ( 'NONE', *, *, #12787, .F. ) ; +#22527 = EDGE_CURVE ( 'NONE', #35660, #9503, #762, .T. ) ; +#22528 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #26053, #22782, #29315, #4142 ), + ( #38495, #9705, #10109, #7016 ), + ( #19489, #35216, #25252, #10514 ), + ( #37702, #28710, #879, #484 ), + ( #19686, #22982, #29113, #31983 ), + ( #19882, #19084, #1086, #22185 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 4 ), + ( 4, 4 ), + ( -0.01985735277108999913, 0.000000000000000000, 1.000000000000000000, 1.019994027157999916 ), + ( -2.955566845425000168E-05, 0.9999999395687999559 ), + .UNSPECIFIED. ) ; +#22529 = ORIENTED_EDGE ( 'NONE', *, *, #21130, .T. ) ; +#22530 = CARTESIAN_POINT ( 'NONE', ( 26.00081424259415641, 120.1020648120652510, 90.44388058125247198 ) ) ; +#22531 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#22532 = ADVANCED_FACE ( 'NONE', ( #22663 ), #32065, .F. ) ; +#22533 = ORIENTED_EDGE ( 'NONE', *, *, #39876, .T. ) ; +#22534 = ORIENTED_EDGE ( 'NONE', *, *, #6847, .T. ) ; +#22535 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; +#22536 = CARTESIAN_POINT ( 'NONE', ( -20.16352061881138980, 211.0884378490691802, 75.92576696064729447 ) ) ; +#22537 = CARTESIAN_POINT ( 'NONE', ( -3.669581222327467973, 184.0117732734406104, 102.6507570783573300 ) ) ; +#22538 = AXIS2_PLACEMENT_3D ( 'NONE', #12796, #19109, #31601 ) ; +#22539 = AXIS2_PLACEMENT_3D ( 'NONE', #18492, #39775, #34436 ) ; +#22540 = CYLINDRICAL_SURFACE ( 'NONE', #37359, 2.000000000000014655 ) ; +#22541 = ORIENTED_EDGE ( 'NONE', *, *, #35, .T. ) ; +#22542 = FACE_OUTER_BOUND ( 'NONE', #14695, .T. ) ; +#22543 = ORIENTED_EDGE ( 'NONE', *, *, #6944, .F. ) ; +#22544 = DIRECTION ( 'NONE', ( -0.0006039748319395907457, -1.314021223879979801E-14, -0.9999998176071847045 ) ) ; +#22545 = CIRCLE ( 'NONE', #4888, 7.499999999880614610 ) ; +#22546 = CARTESIAN_POINT ( 'NONE', ( -2.455126040769211038, 209.0000001767654965, 74.29847181561608238 ) ) ; +#22547 = ORIENTED_EDGE ( 'NONE', *, *, #36883, .T. ) ; +#22548 = CARTESIAN_POINT ( 'NONE', ( -19.99861762737637960, 193.7273908560958944, 106.6527233798307179 ) ) ; +#22549 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#22550 = LINE ( 'NONE', #28870, #1849 ) ; +#22551 = ORIENTED_EDGE ( 'NONE', *, *, #23458, .F. ) ; +#22552 = ORIENTED_EDGE ( 'NONE', *, *, #5745, .T. ) ; +#22553 = CYLINDRICAL_SURFACE ( 'NONE', #3501, 2.000000000000001332 ) ; +#22554 = CARTESIAN_POINT ( 'NONE', ( 24.53499375125008797, 104.1131156705585283, 90.25296631813145609 ) ) ; +#22555 = VERTEX_POINT ( 'NONE', #19959 ) ; +#22556 = CARTESIAN_POINT ( 'NONE', ( -24.42746480797000430, 103.6131156702000027, 87.78253795972000262 ) ) ; +#22557 = CARTESIAN_POINT ( 'NONE', ( -45.38028798438312350, 123.7560755211207351, 91.33058355487838753 ) ) ; +#22558 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#22559 = ORIENTED_EDGE ( 'NONE', *, *, #1013, .F. ) ; +#22560 = CARTESIAN_POINT ( 'NONE', ( -13.46995280217765156, 158.2275496627099756, 98.75652669741377565 ) ) ; +#22561 = CARTESIAN_POINT ( 'NONE', ( 3.882702609166361896, 148.9606115483820190, 129.9617790688332093 ) ) ; +#22562 = ORIENTED_EDGE ( 'NONE', *, *, #2682, .T. ) ; +#22563 = AXIS2_PLACEMENT_3D ( 'NONE', #30689, #30270, #2477 ) ; +#22564 = AXIS2_PLACEMENT_3D ( 'NONE', #3919, #25426, #10288 ) ; +#22565 = ORIENTED_EDGE ( 'NONE', *, *, #4320, .F. ) ; +#22566 = AXIS2_PLACEMENT_3D ( 'NONE', #24159, #24769, #9220 ) ; +#22567 = CARTESIAN_POINT ( 'NONE', ( 26.00644222260579852, 120.1782714929480136, 90.46828040459247688 ) ) ; +#22568 = CARTESIAN_POINT ( 'NONE', ( -28.46570037481142990, 129.9682353502039405, 92.24140578106545263 ) ) ; +#22569 = LINE ( 'NONE', #31971, #28342 ) ; +#22570 = AXIS2_PLACEMENT_3D ( 'NONE', #9412, #31698, #22088 ) ; +#22572 = CARTESIAN_POINT ( 'NONE', ( 75.33446582941786573, 196.6730905574605970, 189.2244420380926329 ) ) ; +#22571 = CARTESIAN_POINT ( 'NONE', ( 20.48191743768403228, 208.0778533060426412, 76.14482956145043602 ) ) ; +#22573 = EDGE_CURVE ( 'NONE', #3283, #15358, #29485, .T. ) ; +#22574 = ORIENTED_EDGE ( 'NONE', *, *, #10110, .T. ) ; +#22575 = CARTESIAN_POINT ( 'NONE', ( -1.212289009923044114, 143.4874838728126747, 158.5684238127680317 ) ) ; +#22576 = CARTESIAN_POINT ( 'NONE', ( -35.93776389612042976, 192.3429967070654811, 104.4165159352158696 ) ) ; +#22577 = CARTESIAN_POINT ( 'NONE', ( 1.222756636386816087, 143.4873526228519722, 158.5689915630758549 ) ) ; +#22578 = ORIENTED_EDGE ( 'NONE', *, *, #39679, .T. ) ; +#22579 = EDGE_CURVE ( 'NONE', #30603, #16409, #23251, .T. ) ; +#22580 = EDGE_CURVE ( 'NONE', #19924, #27113, #33045, .T. ) ; +#22581 = VERTEX_POINT ( 'NONE', #6394 ) ; +#22582 = EDGE_CURVE ( 'NONE', #30526, #11064, #15751, .T. ) ; +#22583 = CARTESIAN_POINT ( 'NONE', ( -25.02288988185319596, 182.0930031294805644, 101.7075183579726598 ) ) ; +#22584 = ADVANCED_FACE ( 'NONE', ( #9280 ), #5308, .F. ) ; +#22585 = CARTESIAN_POINT ( 'NONE', ( -20.24826303546999995, 118.4645066319000080, 90.03000659637000069 ) ) ; +#22586 = CARTESIAN_POINT ( 'NONE', ( 16.67763860462360981, 127.2204759592696917, 176.3528348589679524 ) ) ; +#22587 = LINE ( 'NONE', #38106, #6527 ) ; +#22588 = ORIENTED_EDGE ( 'NONE', *, *, #14387, .F. ) ; +#22589 = VERTEX_POINT ( 'NONE', #8116 ) ; +#22590 = DIRECTION ( 'NONE', ( 0.0006039748319392047697, 1.158053700410192562E-15, 0.9999998176071845934 ) ) ; +#22591 = CARTESIAN_POINT ( 'NONE', ( -1.208148773261155995, 135.9313244140174675, 177.2163779120750178 ) ) ; +#22592 = CARTESIAN_POINT ( 'NONE', ( -28.42925635489000413, 114.0103269030000064, 152.4718672074000381 ) ) ; +#22593 = CARTESIAN_POINT ( 'NONE', ( 37.31693588142861273, 172.3309151562380919, 164.9673944986862466 ) ) ; +#22594 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#22595 = ORIENTED_EDGE ( 'NONE', *, *, #31268, .T. ) ; +#22596 = CARTESIAN_POINT ( 'NONE', ( -3.334859686512663401, 127.9467318872441126, 92.10164337879916729 ) ) ; +#22597 = VERTEX_POINT ( 'NONE', #20576 ) ; +#22598 = AXIS2_PLACEMENT_3D ( 'NONE', #38747, #4805, #7472 ) ; +#22599 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38586, #13069, #25546, #7109 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999992929003319597 ), + .UNSPECIFIED. ) ; +#22600 = CIRCLE ( 'NONE', #16035, 5.499999999795470274 ) ; +#22601 = ORIENTED_EDGE ( 'NONE', *, *, #14997, .F. ) ; +#22602 = PLANE ( 'NONE', #7197 ) ; +#22603 = ORIENTED_EDGE ( 'NONE', *, *, #24909, .T. ) ; +#22604 = CARTESIAN_POINT ( 'NONE', ( -5.666787700381098247, 187.4723117046142988, 105.7482843246638282 ) ) ; +#22605 = CARTESIAN_POINT ( 'NONE', ( -3.069700939255000094, 190.9031832800000075, 106.9453286978999955 ) ) ; +#22606 = CARTESIAN_POINT ( 'NONE', ( -3.669581222364402873, 126.6894591277509221, 89.41685568663245931 ) ) ; +#22607 = ORIENTED_EDGE ( 'NONE', *, *, #11562, .T. ) ; +#22608 = CARTESIAN_POINT ( 'NONE', ( 12.63943526405000028, 181.6152899278259838, 104.1402435540826730 ) ) ; +#22609 = CARTESIAN_POINT ( 'NONE', ( -25.43620862700356966, 117.4588632744077898, 87.78297971315110715 ) ) ; +#22610 = CARTESIAN_POINT ( 'NONE', ( 22.78193024035000391, 158.2317512724935114, 98.73560148591467112 ) ) ; +#22611 = CARTESIAN_POINT ( 'NONE', ( 13.49868479949546618, 123.8375716773093984, 91.19048863502061408 ) ) ; +#22612 = CARTESIAN_POINT ( 'NONE', ( -42.34690063467109411, 120.8447378157120511, 90.65661607257399623 ) ) ; +#22613 = ORIENTED_EDGE ( 'NONE', *, *, #12208, .T. ) ; +#22614 = EDGE_CURVE ( 'NONE', #9290, #30211, #8186, .T. ) ; +#22616 = EDGE_CURVE ( 'NONE', #15817, #33167, #14056, .T. ) ; +#22615 = CARTESIAN_POINT ( 'NONE', ( 5.669508483227596152, 188.3446291069645611, 103.1322831256426866 ) ) ; +#22617 = VECTOR ( 'NONE', #12814, 1000.000000000000227 ) ; +#22618 = VECTOR ( 'NONE', #2975, 1000.000000000000000 ) ; +#22619 = CARTESIAN_POINT ( 'NONE', ( -35.56297588777000129, 113.0122100763999953, 90.16589942257002122 ) ) ; +#22621 = ORIENTED_EDGE ( 'NONE', *, *, #9351, .F. ) ; +#22620 = EDGE_CURVE ( 'NONE', #33611, #7238, #3727, .T. ) ; +#22622 = EDGE_LOOP ( 'NONE', ( #36695, #32709, #8697, #37340 ) ) ; +#22624 = AXIS2_PLACEMENT_3D ( 'NONE', #30977, #8909, #18075 ) ; +#22623 = CARTESIAN_POINT ( 'NONE', ( 9.448122968319339066, 159.6991011598222769, 96.51665850995770768 ) ) ; +#22625 = EDGE_CURVE ( 'NONE', #28895, #16043, #16918, .T. ) ; +#22626 = CARTESIAN_POINT ( 'NONE', ( -28.34217563707975174, 125.1610136493592762, 88.56573566053803859 ) ) ; +#22627 = CIRCLE ( 'NONE', #27872, 1.999999999928235628 ) ; +#22628 = CARTESIAN_POINT ( 'NONE', ( -3.769492941842434774, 174.7312905648006733, 102.8344854120291245 ) ) ; +#22629 = ORIENTED_EDGE ( 'NONE', *, *, #33466, .F. ) ; +#22630 = CARTESIAN_POINT ( 'NONE', ( -37.15110916248943340, 71.94901889567350395, 323.0119659613925478 ) ) ; +#22631 = EDGE_LOOP ( 'NONE', ( #21756, #34823, #25870, #2646 ) ) ; +#22632 = ORIENTED_EDGE ( 'NONE', *, *, #312, .T. ) ; +#22633 = EDGE_CURVE ( 'NONE', #11054, #5530, #20861, .T. ) ; +#22634 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323826078921479493, 0.0005734118987168501961 ) ) ; +#22635 = FACE_OUTER_BOUND ( 'NONE', #31264, .T. ) ; +#22636 = CARTESIAN_POINT ( 'NONE', ( 29.41435563321591218, 160.9614827452744237, 187.1157519457187561 ) ) ; +#22637 = EDGE_LOOP ( 'NONE', ( #12723, #19264, #6322, #18047 ) ) ; +#22638 = EDGE_LOOP ( 'NONE', ( #3688, #28044, #24547, #38908, #39780, #2941, #36531, #29560, #23120 ) ) ; +#22639 = DIRECTION ( 'NONE', ( -0.1305261967116597976, -0.9660514608154224803, -0.2229517594197838737 ) ) ; +#22640 = CARTESIAN_POINT ( 'NONE', ( 36.18171820146000073, 191.5958956560999980, 103.9695318283999939 ) ) ; +#22641 = DIRECTION ( 'NONE', ( 0.0006039748319379437342, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#22642 = DIRECTION ( 'NONE', ( 0.6087614883550945821, -0.7730004026499607273, -0.1785492307423600655 ) ) ; +#22643 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#22644 = LINE ( 'NONE', #1149, #28161 ) ; +#22645 = ORIENTED_EDGE ( 'NONE', *, *, #23912, .F. ) ; +#22646 = FACE_OUTER_BOUND ( 'NONE', #12756, .T. ) ; +#22647 = CARTESIAN_POINT ( 'NONE', ( -20.51779757010343985, 207.7035150799023882, 76.57867102927539804 ) ) ; +#22648 = CARTESIAN_POINT ( 'NONE', ( -20.00029466087617180, 160.7280592933503556, 96.77210435901376684 ) ) ; +#22649 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7850, #26678, #29741, #1724 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22650 = CARTESIAN_POINT ( 'NONE', ( 16.59040448417249891, 121.5622698803751121, 177.2309519810485767 ) ) ; +#22651 = CARTESIAN_POINT ( 'NONE', ( -18.76885123896627050, 125.8224625306723112, 175.1047239809785765 ) ) ; +#22652 = AXIS2_PLACEMENT_3D ( 'NONE', #19803, #7344, #10641 ) ; +#22653 = VERTEX_POINT ( 'NONE', #36006 ) ; +#22654 = CARTESIAN_POINT ( 'NONE', ( -23.36589107377781005, 134.9158523539519194, 90.81477344275025132 ) ) ; +#22655 = DIRECTION ( 'NONE', ( 0.0005884965073584763964, -0.2249510525036909903, 0.9743698874910607932 ) ) ; +#22656 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749903839, 135.0525466846722225, 91.33453887330247767 ) ) ; +#22657 = AXIS2_PLACEMENT_3D ( 'NONE', #25959, #38000, #16510 ) ; +#22658 = CARTESIAN_POINT ( 'NONE', ( 3.168077512235829563, 183.4518822370066289, 105.0831384053979036 ) ) ; +#22659 = VECTOR ( 'NONE', #7084, 1000.000000000000000 ) ; +#22660 = CARTESIAN_POINT ( 'NONE', ( 38.38896709011299180, 118.9510566342067506, 90.24663272979658757 ) ) ; +#22661 = DIRECTION ( 'NONE', ( -7.428452990058934869E-11, 0.9743700557754537694, 0.2249510933695120507 ) ) ; +#22662 = CARTESIAN_POINT ( 'NONE', ( -3.871848511230478351, 168.4194807666234794, 98.88106509990059578 ) ) ; +#22663 = FACE_OUTER_BOUND ( 'NONE', #31172, .T. ) ; +#22664 = CARTESIAN_POINT ( 'NONE', ( 25.50065687296894978, 121.1891575091324285, 90.18200499751846166 ) ) ; +#22665 = EDGE_CURVE ( 'NONE', #267, #10675, #20997, .T. ) ; +#22666 = VERTEX_POINT ( 'NONE', #21710 ) ; +#22667 = ADVANCED_FACE ( 'NONE', ( #40289 ), #30710, .T. ) ; +#22668 = EDGE_CURVE ( 'NONE', #9147, #16362, #37944, .T. ) ; +#22669 = ADVANCED_FACE ( 'NONE', ( #11900 ), #5338, .F. ) ; +#22670 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023851578 ) ) ; +#22671 = CARTESIAN_POINT ( 'NONE', ( -45.38741881364221342, 124.3872433421413177, 88.42275326155656501 ) ) ; +#22672 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#22673 = CARTESIAN_POINT ( 'NONE', ( 5.667731215173129833, 181.6143669964321248, 104.1442412133662998 ) ) ; +#22674 = EDGE_CURVE ( 'NONE', #5859, #19656, #12099, .T. ) ; +#22675 = AXIS2_PLACEMENT_3D ( 'NONE', #21394, #12981, #12771 ) ; +#22676 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772234801672, 136.6775772631780796, 180.9814965275865575 ) ) ; +#22677 = CARTESIAN_POINT ( 'NONE', ( 36.06506691458749714, 192.7090436111730014, 106.3601754007769813 ) ) ; +#22678 = CARTESIAN_POINT ( 'NONE', ( -10.44543797371702532, 134.9177046684737888, 90.80749218586807103 ) ) ; +#22679 = VECTOR ( 'NONE', #28608, 1000.000000000000114 ) ; +#22680 = CARTESIAN_POINT ( 'NONE', ( 21.00183496203274913, 175.6226406432039084, 103.0937819539236671 ) ) ; +#22681 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #36906, #13863, #17865, #19978 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.022641250864768203, 3.265663285694688334 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9950844102104468014, 0.9950844102104468014, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#22682 = CONICAL_SURFACE ( 'NONE', #472, 8.000002017059829384, 0.7853981633973110554 ) ; +#22683 = ORIENTED_EDGE ( 'NONE', *, *, #28570, .F. ) ; +#22684 = EDGE_CURVE ( 'NONE', #23777, #4523, #15503, .T. ) ; +#22685 = CARTESIAN_POINT ( 'NONE', ( -2.620903370884999806, 209.1091071886999941, 75.80136619622000183 ) ) ; +#22686 = CARTESIAN_POINT ( 'NONE', ( 35.59944106830731414, 113.9908721492990082, 87.24628312167284605 ) ) ; +#22687 = FACE_OUTER_BOUND ( 'NONE', #11881, .T. ) ; +#22688 = VERTEX_POINT ( 'NONE', #13101 ) ; +#22689 = DIRECTION ( 'NONE', ( -0.1305262373691798983, 0.9659583596717404852, 0.2233547598295697878 ) ) ; +#22690 = EDGE_LOOP ( 'NONE', ( #35774, #27533, #5006, #40146 ) ) ; +#22691 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; +#22692 = CARTESIAN_POINT ( 'NONE', ( 3.689590423171785094, 168.4639776339773221, 98.70304694460136830 ) ) ; +#22693 = PLANE ( 'NONE', #36660 ) ; +#22694 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#22695 = CARTESIAN_POINT ( 'NONE', ( 22.99270477044632344, 214.0899081099834689, 76.04459013870678064 ) ) ; +#22696 = CARTESIAN_POINT ( 'NONE', ( -30.06912398756719895, 176.8608841570483605, 103.2369763308513058 ) ) ; +#22697 = CARTESIAN_POINT ( 'NONE', ( -3.537750984983824232, 137.3463269818849426, 91.36396247942009552 ) ) ; +#22698 = VERTEX_POINT ( 'NONE', #16157 ) ; +#22699 = CARTESIAN_POINT ( 'NONE', ( 15.95616423589712340, 121.8747789553152785, 174.5819126748912709 ) ) ; +#22700 = CARTESIAN_POINT ( 'NONE', ( -5.407053729055359526, 177.7320116765900195, 100.6888568555215357 ) ) ; +#22701 = DIRECTION ( 'NONE', ( -0.0005884949961249829080, 0.2249510543439062205, -0.9743698870671264611 ) ) ; +#22702 = VERTEX_POINT ( 'NONE', #31304 ) ; +#22703 = AXIS2_PLACEMENT_3D ( 'NONE', #7222, #4148, #29322 ) ; +#22704 = CARTESIAN_POINT ( 'NONE', ( -36.71895117216000415, 191.7004588050999985, 104.5481094693000017 ) ) ; +#22705 = ORIENTED_EDGE ( 'NONE', *, *, #24582, .F. ) ; +#22706 = DIRECTION ( 'NONE', ( -0.5669487081581161547, -0.8237530954830113439, 0.000000000000000000 ) ) ; +#22707 = ORIENTED_EDGE ( 'NONE', *, *, #16137, .T. ) ; +#22708 = CARTESIAN_POINT ( 'NONE', ( -20.61224116156940411, 136.5556511042426280, 91.19172679136488568 ) ) ; +#22709 = EDGE_CURVE ( 'NONE', #11864, #7059, #4018, .T. ) ; +#22710 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422003068, 160.0671381723056754, 99.67809115075311865 ) ) ; +#22711 = EDGE_CURVE ( 'NONE', #1023, #33655, #15168, .T. ) ; +#22712 = FACE_OUTER_BOUND ( 'NONE', #3198, .T. ) ; +#22713 = DIRECTION ( 'NONE', ( 0.6087613186456907188, 0.7730177010543248795, 0.1784749023741044327 ) ) ; +#22714 = CARTESIAN_POINT ( 'NONE', ( -2.574763605953999779, 208.8764647145999902, 73.51762046848000409 ) ) ; +#22715 = CARTESIAN_POINT ( 'NONE', ( -37.29184647923000284, 190.5495719324999868, 106.6204670725000057 ) ) ; +#22716 = ORIENTED_EDGE ( 'NONE', *, *, #14390, .F. ) ; +#22717 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452350121, 0.1781166614240802804 ) ) ; +#22718 = CARTESIAN_POINT ( 'NONE', ( 42.97429946896744468, 67.83849343097567441, 322.0145824706445978 ) ) ; +#22719 = CARTESIAN_POINT ( 'NONE', ( 18.99767128196905830, 125.6058446513852118, 175.3475295528536151 ) ) ; +#22720 = LINE ( 'NONE', #16551, #1679 ) ; +#22721 = EDGE_LOOP ( 'NONE', ( #29116, #8030, #8526, #19612, #23456, #12561, #39244, #78, #6598, #27343, #14736 ) ) ; +#22722 = VERTEX_POINT ( 'NONE', #10241 ) ; +#22723 = ORIENTED_EDGE ( 'NONE', *, *, #1156, .T. ) ; +#22724 = CARTESIAN_POINT ( 'NONE', ( -43.94721011010098266, 112.7011882844193309, 88.77749572683383406 ) ) ; +#22725 = CONICAL_SURFACE ( 'NONE', #16171, 2.749999999892358549, 0.7853981634430725611 ) ; +#22726 = CARTESIAN_POINT ( 'NONE', ( 21.84918941357979705, 115.3422797856098185, 87.25458792911985029 ) ) ; +#22727 = CYLINDRICAL_SURFACE ( 'NONE', #39607, 1.999999999999989342 ) ; +#22728 = ORIENTED_EDGE ( 'NONE', *, *, #6864, .T. ) ; +#22729 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31098, #37427, #12092, #22098 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0005629175158857319377, 0.0007039624576953972413 ), + .UNSPECIFIED. ) ; +#22730 = AXIS2_PLACEMENT_3D ( 'NONE', #36739, #8750, #21212 ) ; +#22731 = ORIENTED_EDGE ( 'NONE', *, *, #14402, .T. ) ; +#22732 = DIRECTION ( 'NONE', ( 0.7075229215369458480, 9.360719863062603953E-05, 0.7066903895890456200 ) ) ; +#22733 = EDGE_CURVE ( 'NONE', #21947, #20205, #2326, .T. ) ; +#22734 = CARTESIAN_POINT ( 'NONE', ( -32.88044542039068574, 158.6959831765299214, 186.6567934753981888 ) ) ; +#22735 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971559574 ) ) ; +#22736 = CARTESIAN_POINT ( 'NONE', ( 25.50773797003102317, 191.9759150222000130, 101.9060413058080314 ) ) ; +#22737 = CARTESIAN_POINT ( 'NONE', ( 12.63493752644979118, 130.4235786262125032, 90.26909773778339741 ) ) ; +#22738 = CARTESIAN_POINT ( 'NONE', ( 19.98232544185748694, 209.7096131673859816, 76.04619115725449774 ) ) ; +#22739 = ORIENTED_EDGE ( 'NONE', *, *, #18771, .T. ) ; +#22740 = CARTESIAN_POINT ( 'NONE', ( -19.46367776224865409, 126.2483085376569250, 175.9816896695615753 ) ) ; +#22741 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28296, #3931, #21962, #16207 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0001033949579707245088, 0.0007867618316233762534 ), + .UNSPECIFIED. ) ; +#22742 = ORIENTED_EDGE ( 'NONE', *, *, #38840, .T. ) ; +#22743 = CARTESIAN_POINT ( 'NONE', ( -24.53639859075814300, 116.1139236424685208, 89.78257310409678382 ) ) ; +#22744 = CARTESIAN_POINT ( 'NONE', ( -6.316814198236529343, 180.2143825551339376, 27.02657698885747095 ) ) ; +#22745 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498900431, 132.2978364233248953, 93.26432363101957890 ) ) ; +#22746 = CYLINDRICAL_SURFACE ( 'NONE', #10575, 3.000000000000000888 ) ; +#22747 = ORIENTED_EDGE ( 'NONE', *, *, #33672, .F. ) ; +#22748 = FACE_OUTER_BOUND ( 'NONE', #39529, .T. ) ; +#22749 = FACE_OUTER_BOUND ( 'NONE', #8597, .T. ) ; +#22750 = FACE_OUTER_BOUND ( 'NONE', #8239, .T. ) ; +#22751 = CARTESIAN_POINT ( 'NONE', ( 8.470678308075262564, 161.4201748467667983, 97.42774225087779882 ) ) ; +#22752 = ORIENTED_EDGE ( 'NONE', *, *, #17567, .F. ) ; +#22753 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825926232611000, 0.0005734119022436430946 ) ) ; +#22754 = CARTESIAN_POINT ( 'NONE', ( 13.47018477901269051, 157.8313129290910695, 98.99086971718068639 ) ) ; +#22755 = ORIENTED_EDGE ( 'NONE', *, *, #10579, .F. ) ; +#22756 = CARTESIAN_POINT ( 'NONE', ( 41.04524146634799564, 219.5549399801000163, 73.53371387614997445 ) ) ; +#22757 = AXIS2_PLACEMENT_3D ( 'NONE', #8973, #17935, #8563 ) ; +#22758 = ORIENTED_EDGE ( 'NONE', *, *, #40274, .T. ) ; +#22759 = ADVANCED_FACE ( 'NONE', ( #19801 ), #29848, .F. ) ; +#22760 = EDGE_CURVE ( 'NONE', #30934, #23210, #28838, .T. ) ; +#22761 = DIRECTION ( 'NONE', ( 0.9999998268364571619, 0.0001323821501201892905, -0.0005734126106023100652 ) ) ; +#22762 = AXIS2_PLACEMENT_3D ( 'NONE', #2938, #40346, #34606 ) ; +#22763 = LINE ( 'NONE', #28100, #7799 ) ; +#22764 = VERTEX_POINT ( 'NONE', #16745 ) ; +#22765 = CARTESIAN_POINT ( 'NONE', ( 26.00448138516999919, 120.3035362655000000, 90.49060283839000363 ) ) ; +#22766 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#22767 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24732, #37185, #15695, #3221, #9781, #9578, #12629, #38184, #16101, #25735, #25129, #28780, #27998, #18743, #22660, #28196, #28385, #165, #22459, #22053, #34689, #31050 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999992953414, 0.1874999999989522270, 0.2187499999987793931, 0.2343749999986751154, 0.2421874999986851629, 0.2499999999986952104, 0.3749999999991081578, 0.4374999999992994493, 0.4687499999994137467, 0.4843749999994504396, 0.4999999999994870770, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22769 = CARTESIAN_POINT ( 'NONE', ( -37.29428432633125112, 118.1868522465356364, 122.8630558711557796 ) ) ; +#22768 = CARTESIAN_POINT ( 'NONE', ( 25.49183423580130636, 211.0903769678246817, 75.54322026927223988 ) ) ; +#22770 = ORIENTED_EDGE ( 'NONE', *, *, #40315, .T. ) ; +#22771 = ORIENTED_EDGE ( 'NONE', *, *, #27117, .T. ) ; +#22772 = DIRECTION ( 'NONE', ( -0.6087613186456907188, 0.7729176985478710682, 0.1789074850089337476 ) ) ; +#22773 = CARTESIAN_POINT ( 'NONE', ( 28.46393509008022349, 182.0672870871918576, 102.1824291507762865 ) ) ; +#22774 = CARTESIAN_POINT ( 'NONE', ( -35.94659742851874284, 109.6131156826799895, 89.78949559170979455 ) ) ; +#22775 = ORIENTED_EDGE ( 'NONE', *, *, #12540, .T. ) ; +#22776 = VERTEX_POINT ( 'NONE', #13897 ) ; +#22777 = CARTESIAN_POINT ( 'NONE', ( 38.57548057532000030, 119.2480769345999931, 90.41779171121000047 ) ) ; +#22778 = CARTESIAN_POINT ( 'NONE', ( -35.55125210787799972, 114.2871942515880335, 87.28925635746423950 ) ) ; +#22779 = AXIS2_PLACEMENT_3D ( 'NONE', #18580, #6324, #3250 ) ; +#22780 = ADVANCED_FACE ( 'NONE', ( #20634 ), #7955, .F. ) ; +#22781 = CARTESIAN_POINT ( 'NONE', ( 5.673401637569556399, 187.6316643536460731, 105.9943968491383970 ) ) ; +#22782 = CARTESIAN_POINT ( 'NONE', ( -2.813782933366999917, 190.8795050674000038, 106.6764022065000006 ) ) ; +#22783 = CARTESIAN_POINT ( 'NONE', ( 36.14124483135999810, 192.1045279321999999, 104.3956236366000212 ) ) ; +#22784 = ORIENTED_EDGE ( 'NONE', *, *, #28431, .T. ) ; +#22785 = ORIENTED_EDGE ( 'NONE', *, *, #34582, .T. ) ; +#22786 = AXIS2_PLACEMENT_3D ( 'NONE', #19793, #13682, #34729 ) ; +#22787 = VERTEX_POINT ( 'NONE', #35528 ) ; +#22788 = CARTESIAN_POINT ( 'NONE', ( -6.034872611388630403, 176.9126535083784688, 103.3009512934358582 ) ) ; +#22789 = VECTOR ( 'NONE', #30345, 1000.000000000000000 ) ; +#22790 = CARTESIAN_POINT ( 'NONE', ( -37.22290639677533619, 126.0669666328596321, 91.85916804901101784 ) ) ; +#22791 = CARTESIAN_POINT ( 'NONE', ( 22.49999745837402543, 174.5192442765713849, 99.92720223818444936 ) ) ; +#22792 = VERTEX_POINT ( 'NONE', #20014 ) ; +#22793 = ORIENTED_EDGE ( 'NONE', *, *, #22297, .F. ) ; +#22794 = CARTESIAN_POINT ( 'NONE', ( 20.33358726661999683, 174.4467126026231085, 100.2570000595842430 ) ) ; +#22795 = ORIENTED_EDGE ( 'NONE', *, *, #17871, .F. ) ; +#22796 = EDGE_CURVE ( 'NONE', #11205, #39755, #20214, .T. ) ; +#22797 = DIRECTION ( 'NONE', ( 2.893731969398355670E-13, -0.9743700559028483088, -0.2249510928177059499 ) ) ; +#22798 = ORIENTED_EDGE ( 'NONE', *, *, #26926, .F. ) ; +#22799 = CARTESIAN_POINT ( 'NONE', ( -30.07353167211553213, 135.0567859791754302, 91.04548219668697584 ) ) ; +#22800 = EDGE_CURVE ( 'NONE', #1699, #38902, #21390, .T. ) ; +#22801 = CARTESIAN_POINT ( 'NONE', ( -30.07185925050806574, 137.2385153804196705, 91.86824398011344783 ) ) ; +#22802 = CARTESIAN_POINT ( 'NONE', ( 34.29562917979933445, 218.5902260770999987, 75.53779083768952773 ) ) ; +#22803 = EDGE_LOOP ( 'NONE', ( #4046, #21507, #2153, #10405 ) ) ; +#22804 = ORIENTED_EDGE ( 'NONE', *, *, #14621, .F. ) ; +#22806 = EDGE_CURVE ( 'NONE', #24313, #13948, #9638, .T. ) ; +#22805 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#22807 = EDGE_CURVE ( 'NONE', #23218, #37942, #39850, .T. ) ; +#22808 = CARTESIAN_POINT ( 'NONE', ( 24.33241291692780806, 117.2920445016514748, 170.8609620625155117 ) ) ; +#22809 = CARTESIAN_POINT ( 'NONE', ( -20.49588020594338644, 118.8154963149322754, 94.28014888055585629 ) ) ; +#22810 = EDGE_CURVE ( 'NONE', #15150, #32498, #39636, .T. ) ; +#22811 = CIRCLE ( 'NONE', #30633, 2.500000000019892532 ) ; +#22812 = EDGE_CURVE ( 'NONE', #38645, #8802, #24287, .T. ) ; +#22813 = CYLINDRICAL_SURFACE ( 'NONE', #21977, 4.999999999999990230 ) ; +#22814 = ORIENTED_EDGE ( 'NONE', *, *, #38791, .T. ) ; +#22815 = VECTOR ( 'NONE', #39575, 1000.000000000000000 ) ; +#22816 = CARTESIAN_POINT ( 'NONE', ( 25.50043875868088961, 117.7861551627153744, 89.75251609159239763 ) ) ; +#22817 = CARTESIAN_POINT ( 'NONE', ( -37.21824319516999680, 117.1596748030000015, 89.86351461361999782 ) ) ; +#22818 = ORIENTED_EDGE ( 'NONE', *, *, #8255, .F. ) ; +#22819 = CARTESIAN_POINT ( 'NONE', ( -23.20480341064914498, 151.8084575254806339, 205.6165954981223081 ) ) ; +#22820 = EDGE_LOOP ( 'NONE', ( #22147, #28418, #26932, #23121 ) ) ; +#22821 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971564570 ) ) ; +#22822 = CARTESIAN_POINT ( 'NONE', ( 26.03550245107076933, 190.8511564191358900, 106.7775725292634945 ) ) ; +#22823 = DIRECTION ( 'NONE', ( 0.7855779781279682572, 0.6187626687837376460, 0.000000000000000000 ) ) ; +#22824 = ORIENTED_EDGE ( 'NONE', *, *, #30432, .T. ) ; +#22825 = CARTESIAN_POINT ( 'NONE', ( 30.07038983360635243, 136.6834034282913422, 94.27269756974730797 ) ) ; +#22826 = ORIENTED_EDGE ( 'NONE', *, *, #10656, .T. ) ; +#22827 = ORIENTED_EDGE ( 'NONE', *, *, #5577, .F. ) ; +#22828 = CARTESIAN_POINT ( 'NONE', ( 1.837866333389163609, 189.4578565298617718, 105.8682861792007373 ) ) ; +#22829 = CARTESIAN_POINT ( 'NONE', ( 36.05352243695643466, 118.8155708862894642, 87.24600886790115339 ) ) ; +#22830 = VERTEX_POINT ( 'NONE', #4433 ) ; +#22831 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178587041921E-05, -0.0002331579774917524482 ) ) ; +#22832 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319372081030 ) ) ; +#22833 = CARTESIAN_POINT ( 'NONE', ( -26.00152628985659575, 118.5828354757999961, 87.28353789566725141 ) ) ; +#22834 = CARTESIAN_POINT ( 'NONE', ( 36.36406131881000192, 191.7312092642999914, 104.2373321830999942 ) ) ; +#22835 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559296 ) ) ; +#22836 = AXIS2_PLACEMENT_3D ( 'NONE', #7377, #37513, #4509 ) ; +#22837 = CARTESIAN_POINT ( 'NONE', ( 37.28741399843698900, 124.9789241431960392, 93.24647550195996359 ) ) ; +#22838 = DIRECTION ( 'NONE', ( 0.0005884949961194453454, -0.2249510543439075527, 0.9743698870671261281 ) ) ; +#22839 = ORIENTED_EDGE ( 'NONE', *, *, #26416, .F. ) ; +#22840 = CARTESIAN_POINT ( 'NONE', ( 25.83247327863999843, 120.7394249123999970, 87.68326996205000512 ) ) ; +#22841 = EDGE_CURVE ( 'NONE', #16282, #28951, #10153, .T. ) ; +#22842 = VECTOR ( 'NONE', #6193, 1000.000000000000000 ) ; +#22843 = CARTESIAN_POINT ( 'NONE', ( -20.51745969899640087, 207.4083551867479116, 77.09396086730279762 ) ) ; +#22844 = VECTOR ( 'NONE', #24344, 1000.000000000000000 ) ; +#22845 = CARTESIAN_POINT ( 'NONE', ( -7.985938709523869861, 131.0204239720261512, 89.90626579571295451 ) ) ; +#22846 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#22847 = DIRECTION ( 'NONE', ( -0.7871416011357068587, 0.6167723240884886993, 0.000000000000000000 ) ) ; +#22848 = ORIENTED_EDGE ( 'NONE', *, *, #18916, .F. ) ; +#22849 = CARTESIAN_POINT ( 'NONE', ( 45.29398665750001385, 181.0941504656715608, 101.9475978871965651 ) ) ; +#22850 = ADVANCED_FACE ( 'NONE', ( #25940 ), #3825, .F. ) ; +#22851 = CARTESIAN_POINT ( 'NONE', ( 0.7809376719035407977, 189.0122013254281512, 103.6875910670326277 ) ) ; +#22852 = CARTESIAN_POINT ( 'NONE', ( -2.676356233750540881, 189.7677746538298607, 106.5447958017762176 ) ) ; +#22853 = EDGE_CURVE ( 'NONE', #16029, #36719, #37976, .T. ) ; +#22854 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; +#22855 = CARTESIAN_POINT ( 'NONE', ( -25.87511576118999912, 191.6567917961000092, 104.0339623576000179 ) ) ; +#22856 = LINE ( 'NONE', #7289, #2985 ) ; +#22857 = FACE_OUTER_BOUND ( 'NONE', #29568, .T. ) ; +#22858 = EDGE_CURVE ( 'NONE', #21490, #35342, #754, .T. ) ; +#22859 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #30447, #36149, #11418, #21037 ), + ( #36763, #5889, #20618, #17536 ), + ( #27190, #17736, #26978, #14899 ), + ( #40030, #39415, #5479, #8978 ), + ( #5694, #24520, #36978, #23903 ), + ( #20828, #33280, #5272, #30231 ), + ( #17939, #14708, #2437, #39620 ), + ( #24112, #27402, #39823, #8773 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.05582231594939000147, 0.000000000000000000, 0.3333333892231000184, 0.6666666942443999488, 1.000000000000000000, 1.059484521436000026 ), + ( -0.2890760154095999845, 1.289073967883000105 ), + .UNSPECIFIED. ) ; +#22860 = CARTESIAN_POINT ( 'NONE', ( 3.596286182869788295, 141.6796019413746706, 182.7901370451803587 ) ) ; +#22861 = LINE ( 'NONE', #7293, #30445 ) ; +#22862 = ORIENTED_EDGE ( 'NONE', *, *, #30002, .T. ) ; +#22863 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23716, #21060, #5299, #5498 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22864 = CARTESIAN_POINT ( 'NONE', ( -22.78329764787637046, 154.4034317766920310, 95.31352365236099899 ) ) ; +#22865 = AXIS2_PLACEMENT_3D ( 'NONE', #29426, #13677, #3856 ) ; +#22866 = VECTOR ( 'NONE', #17011, 1000.000000000000114 ) ; +#22867 = ORIENTED_EDGE ( 'NONE', *, *, #14007, .T. ) ; +#22868 = DIRECTION ( 'NONE', ( 0.0006039712449778905342, 0.000000000000000000, 0.9999998176093508606 ) ) ; +#22869 = CARTESIAN_POINT ( 'NONE', ( 5.666581507162372411, 181.3641253286114079, 104.3006101419990870 ) ) ; +#22870 = AXIS2_PLACEMENT_3D ( 'NONE', #20796, #39388, #39793 ) ; +#22871 = CARTESIAN_POINT ( 'NONE', ( -15.10535409822645647, 135.6520233040683934, 94.05869708244797778 ) ) ; +#22872 = CARTESIAN_POINT ( 'NONE', ( 36.06465037923999972, 192.5956917412999871, 105.6705187376000197 ) ) ; +#22873 = CIRCLE ( 'NONE', #26150, 2.500000000008382628 ) ; +#22874 = CARTESIAN_POINT ( 'NONE', ( -5.666930955406936476, 130.1424768347354188, 92.50234736738113384 ) ) ; +#22875 = CARTESIAN_POINT ( 'NONE', ( 35.68143157579000047, 192.6396356641000409, 106.7375437715000004 ) ) ; +#22876 = ORIENTED_EDGE ( 'NONE', *, *, #13824, .F. ) ; +#22877 = CARTESIAN_POINT ( 'NONE', ( -5.669593981664322158, 181.2570474460025309, 104.3730823857091394 ) ) ; +#22878 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#22879 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178582675974E-05, -0.0002331579774919535406 ) ) ; +#22880 = CARTESIAN_POINT ( 'NONE', ( 12.31735795870903161, 136.6817491452135016, 94.27986305550896873 ) ) ; +#22881 = ORIENTED_EDGE ( 'NONE', *, *, #1186, .F. ) ; +#22882 = PLANE ( 'NONE', #5022 ) ; +#22883 = VERTEX_POINT ( 'NONE', #13055 ) ; +#22884 = CARTESIAN_POINT ( 'NONE', ( -23.36043049209896694, 136.7895015923607787, 93.81313601547243763 ) ) ; +#22885 = ORIENTED_EDGE ( 'NONE', *, *, #13324, .T. ) ; +#22886 = DIRECTION ( 'NONE', ( 0.6983012566254244158, 0.000000000000000000, 0.7158039920225042207 ) ) ; +#22887 = ADVANCED_FACE ( 'NONE', ( #6900 ), #36333, .F. ) ; +#22888 = ADVANCED_FACE ( 'NONE', ( #17906 ), #26334, .F. ) ; +#22889 = CARTESIAN_POINT ( 'NONE', ( -45.58302259763831188, 185.8574834039084180, 105.8703329252015806 ) ) ; +#22890 = EDGE_CURVE ( 'NONE', #22006, #1429, #13044, .T. ) ; +#22891 = FACE_OUTER_BOUND ( 'NONE', #16650, .T. ) ; +#22892 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; +#22893 = ORIENTED_EDGE ( 'NONE', *, *, #23111, .T. ) ; +#22894 = AXIS2_PLACEMENT_3D ( 'NONE', #16287, #10773, #20983 ) ; +#22895 = DIRECTION ( 'NONE', ( -0.7855473026356900590, -0.6188014303620735790, 0.0004744508866335530478 ) ) ; +#22896 = AXIS2_PLACEMENT_3D ( 'NONE', #28765, #743, #22835 ) ; +#22897 = CARTESIAN_POINT ( 'NONE', ( -8.271967253109403728, 188.3426927931979264, 103.1403358607322360 ) ) ; +#22898 = CARTESIAN_POINT ( 'NONE', ( -3.419728389424999904, 127.6373404636000117, 89.37896439713999541 ) ) ; +#22899 = EDGE_CURVE ( 'NONE', #25549, #30903, #21682, .T. ) ; +#22900 = VECTOR ( 'NONE', #11453, 999.9999999999998863 ) ; +#22901 = CONICAL_SURFACE ( 'NONE', #1337, 2.502995680536484802, 0.7853981633384532479 ) ; +#22902 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#22903 = VERTEX_POINT ( 'NONE', #11601 ) ; +#22904 = ORIENTED_EDGE ( 'NONE', *, *, #11536, .F. ) ; +#22905 = CARTESIAN_POINT ( 'NONE', ( 13.55514511692094537, 147.5124591927943811, 96.26643020890679736 ) ) ; +#22906 = EDGE_CURVE ( 'NONE', #32161, #30285, #35903, .T. ) ; +#22907 = CARTESIAN_POINT ( 'NONE', ( -18.92878511345999826, 158.4511806311000157, 97.78514868614999500 ) ) ; +#22908 = CARTESIAN_POINT ( 'NONE', ( -12.64562993050861550, 181.6872450680611450, 101.6064063805796280 ) ) ; +#22909 = CARTESIAN_POINT ( 'NONE', ( 10.88293107966285334, 124.3679198336539571, 88.35892229760115413 ) ) ; +#22910 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #22203, #303, #6836, #35235 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.137875966956430229, 6.279468620546222901 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.3333333333333335369, 0.3333333333333335369, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#22911 = CARTESIAN_POINT ( 'NONE', ( 25.67924018176999823, 190.7157574210999940, 106.3544759560000017 ) ) ; +#22912 = ADVANCED_FACE ( 'NONE', ( #24286 ), #12584, .T. ) ; +#22913 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24127, #27207, #26792, #17757, #11653, #20425, #10846, #20219, #23315, #17150, #14727, #8588, #17957, #21059, #35744, #17343, #26999 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000044131, 0.1875000000000067446, 0.2500000000000090483, 0.3750000000000066058, 0.5000000000000042188, 0.6250000000000018874, 0.7499999999999993339, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22914 = CARTESIAN_POINT ( 'NONE', ( 20.48181612770335391, 206.0037509564070319, 75.48930600427006254 ) ) ; +#22915 = CARTESIAN_POINT ( 'NONE', ( -37.94564516765999684, 190.8198141665000094, 106.4202611438000048 ) ) ; +#22916 = ORIENTED_EDGE ( 'NONE', *, *, #29669, .T. ) ; +#22917 = CYLINDRICAL_SURFACE ( 'NONE', #1566, 4.999999999999990230 ) ; +#22918 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 77.27946979429611929, 297.5967072516830854 ) ) ; +#22919 = CARTESIAN_POINT ( 'NONE', ( 3.334663831449610871, 126.1666046699075281, 91.68664002808421287 ) ) ; +#22920 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#22921 = EDGE_LOOP ( 'NONE', ( #6094, #21495, #13808, #26111 ) ) ; +#22922 = AXIS2_PLACEMENT_3D ( 'NONE', #23853, #36309, #7690 ) ; +#22923 = AXIS2_PLACEMENT_3D ( 'NONE', #15635, #19093, #27735 ) ; +#22924 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37607, #18986, #36810, #21688, #6126, #33928 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.1624460549302637891, 0.5812230274651318807, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22925 = ORIENTED_EDGE ( 'NONE', *, *, #6295, .T. ) ; +#22926 = CARTESIAN_POINT ( 'NONE', ( -26.00760980898482799, 207.8686442861051376, 77.29275028086965449 ) ) ; +#22927 = VECTOR ( 'NONE', #38737, 1000.000000000000114 ) ; +#22928 = CIRCLE ( 'NONE', #22292, 29.99999999998092548 ) ; +#22929 = CARTESIAN_POINT ( 'NONE', ( -45.30371984282656683, 124.3227729409930618, 91.46136974178453727 ) ) ; +#22930 = ORIENTED_EDGE ( 'NONE', *, *, #4883, .F. ) ; +#22931 = CARTESIAN_POINT ( 'NONE', ( -25.91302099857000130, 130.1559280140999988, 92.53977237774999764 ) ) ; +#22932 = CARTESIAN_POINT ( 'NONE', ( -39.69437836998564251, 161.5619712970498085, 197.5056430804474985 ) ) ; +#22933 = CARTESIAN_POINT ( 'NONE', ( -38.39048845847000280, 118.6206116153999943, 89.90268112204999795 ) ) ; +#22934 = CARTESIAN_POINT ( 'NONE', ( -3.503019623547876993, 184.0485918194861767, 102.4881131396436444 ) ) ; +#22935 = CARTESIAN_POINT ( 'NONE', ( 28.47525309053320797, 130.3504702658399879, 92.80840815248680542 ) ) ; +#22936 = ORIENTED_EDGE ( 'NONE', *, *, #40229, .T. ) ; +#22937 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26248, #13562, #33157, #36232 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#22938 = FACE_OUTER_BOUND ( 'NONE', #21722, .T. ) ; +#22939 = ORIENTED_EDGE ( 'NONE', *, *, #26674, .F. ) ; +#22940 = EDGE_CURVE ( 'NONE', #38457, #34802, #27592, .T. ) ; +#22941 = CARTESIAN_POINT ( 'NONE', ( -3.169881913554984720, 185.9062129263137138, 102.5746722649703315 ) ) ; +#22942 = ADVANCED_FACE ( 'NONE', ( #5657 ), #6639, .F. ) ; +#22943 = DIRECTION ( 'NONE', ( -4.452505765293227325E-11, -0.9743700387726779155, -0.2249511670165995070 ) ) ; +#22944 = CARTESIAN_POINT ( 'NONE', ( 46.36049362162751919, 125.3570268543407167, 88.90797177416244779 ) ) ; +#22945 = ORIENTED_EDGE ( 'NONE', *, *, #38289, .T. ) ; +#22946 = ORIENTED_EDGE ( 'NONE', *, *, #34601, .F. ) ; +#22947 = CARTESIAN_POINT ( 'NONE', ( -0.4374722634361999929, 188.8708576324000035, 103.5226396815999976 ) ) ; +#22948 = CARTESIAN_POINT ( 'NONE', ( 25.50924790716773671, 191.9759150222000130, 104.4060408498541079 ) ) ; +#22949 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971577060 ) ) ; +#22950 = ORIENTED_EDGE ( 'NONE', *, *, #20945, .T. ) ; +#22951 = AXIS2_PLACEMENT_3D ( 'NONE', #3444, #34716, #3852 ) ; +#22952 = FACE_OUTER_BOUND ( 'NONE', #5163, .T. ) ; +#22953 = LINE ( 'NONE', #35382, #11523 ) ; +#22954 = VERTEX_POINT ( 'NONE', #8946 ) ; +#22955 = VECTOR ( 'NONE', #31802, 1000.000000000000000 ) ; +#22956 = VECTOR ( 'NONE', #31620, 1000.000000000000000 ) ; +#22957 = CARTESIAN_POINT ( 'NONE', ( 21.46414478492309996, 116.1138660754223508, 89.75506028734766062 ) ) ; +#22958 = EDGE_LOOP ( 'NONE', ( #2871, #24111, #33755, #3343 ) ) ; +#22959 = DIRECTION ( 'NONE', ( 0.7933530821293307556, 0.5932640870757668328, 0.1364866662427073885 ) ) ; +#22960 = CARTESIAN_POINT ( 'NONE', ( 2.544461030880475594, 209.0000001909309901, 73.61327617014224245 ) ) ; +#22961 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; +#22962 = LINE ( 'NONE', #32359, #3420 ) ; +#22963 = EDGE_CURVE ( 'NONE', #40341, #27102, #38626, .T. ) ; +#22964 = EDGE_LOOP ( 'NONE', ( #38339, #29236, #20870, #26626 ) ) ; +#22965 = CARTESIAN_POINT ( 'NONE', ( 25.66875014887000006, 120.3200521089000006, 90.15167757061000486 ) ) ; +#22966 = CARTESIAN_POINT ( 'NONE', ( -25.51388077191477066, 211.0902258580313742, 75.57405363378009611 ) ) ; +#22968 = LINE ( 'NONE', #13556, #30528 ) ; +#22967 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988445790169, 150.9961524914176607, 94.51313162276940716 ) ) ; +#22969 = CARTESIAN_POINT ( 'NONE', ( -14.13846548020544880, 164.5254833472192217, 152.7619685177316740 ) ) ; +#22970 = VERTEX_POINT ( 'NONE', #27757 ) ; +#22971 = DIRECTION ( 'NONE', ( 0.0005884949961249829080, -0.2249510543439062205, 0.9743698870671264611 ) ) ; +#22972 = FACE_OUTER_BOUND ( 'NONE', #5332, .T. ) ; +#22973 = CARTESIAN_POINT ( 'NONE', ( -8.473620771760185022, 151.0652496779955811, 95.04735290400581960 ) ) ; +#22974 = ORIENTED_EDGE ( 'NONE', *, *, #39996, .F. ) ; +#22975 = ORIENTED_EDGE ( 'NONE', *, *, #13794, .F. ) ; +#22976 = FACE_OUTER_BOUND ( 'NONE', #10291, .T. ) ; +#22978 = AXIS2_PLACEMENT_3D ( 'NONE', #39826, #21655, #17942 ) ; +#22977 = FACE_OUTER_BOUND ( 'NONE', #12357, .T. ) ; +#22979 = AXIS2_PLACEMENT_3D ( 'NONE', #22516, #31918, #19419 ) ; +#22980 = CYLINDRICAL_SURFACE ( 'NONE', #4971, 2.000000000000001332 ) ; +#22981 = CARTESIAN_POINT ( 'NONE', ( -45.41309877574845899, 123.7966584769246197, 93.36316325758346579 ) ) ; +#22982 = CARTESIAN_POINT ( 'NONE', ( -2.814039094922999862, 190.9184237906999897, 106.6856330288999999 ) ) ; +#22983 = ORIENTED_EDGE ( 'NONE', *, *, #39523, .F. ) ; +#22984 = ORIENTED_EDGE ( 'NONE', *, *, #13764, .T. ) ; +#22985 = ORIENTED_EDGE ( 'NONE', *, *, #11675, .T. ) ; +#22986 = EDGE_CURVE ( 'NONE', #32426, #206, #11213, .T. ) ; +#22987 = CARTESIAN_POINT ( 'NONE', ( -16.53460274203917635, 121.8354022778151204, 177.5673403339679055 ) ) ; +#22988 = ADVANCED_FACE ( 'NONE', ( #24891 ), #36001, .F. ) ; +#22989 = CYLINDRICAL_SURFACE ( 'NONE', #35935, 2.000000000000000000 ) ; +#22990 = ORIENTED_EDGE ( 'NONE', *, *, #21049, .T. ) ; +#22991 = ORIENTED_EDGE ( 'NONE', *, *, #39052, .T. ) ; +#22992 = CARTESIAN_POINT ( 'NONE', ( 29.05382570111806118, 110.6131156702000027, 87.75023660053001606 ) ) ; +#22993 = CARTESIAN_POINT ( 'NONE', ( -37.92915657618366509, 117.8950347885309498, 89.71597331060294778 ) ) ; +#22994 = ORIENTED_EDGE ( 'NONE', *, *, #4472, .F. ) ; +#22995 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#22996 = VERTEX_POINT ( 'NONE', #32014 ) ; +#22997 = FACE_OUTER_BOUND ( 'NONE', #25774, .T. ) ; +#22998 = CARTESIAN_POINT ( 'NONE', ( -2.752073334482000089, 190.2672676434999914, 106.5277000906000069 ) ) ; +#22999 = CARTESIAN_POINT ( 'NONE', ( 36.43736767128643095, 111.7645015433333384, 175.7443402496501790 ) ) ; +#23000 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391903498 ) ) ; +#23001 = ORIENTED_EDGE ( 'NONE', *, *, #32837, .T. ) ; +#23002 = CARTESIAN_POINT ( 'NONE', ( -13.49823529424112145, 160.0636115298041204, 99.69358428540749628 ) ) ; +#23003 = VECTOR ( 'NONE', #4252, 1000.000000000000114 ) ; +#23004 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12456, #15914, #37798, #6115, #9205, #18574, #31079, #15529, #12871, #25347, #3639 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998192557, 0.3749999999997322697, 0.4374999999996888045, 0.4687499999996911915, 0.4999999999996935784, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23005 = CARTESIAN_POINT ( 'NONE', ( 22.20627172700715590, 213.9926456290793908, 73.04509205071391875 ) ) ; +#23006 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 82.27946979429631824, 312.5857197240630967 ) ) ; +#23007 = VECTOR ( 'NONE', #5458, 1000.000000000000000 ) ; +#23008 = LINE ( 'NONE', #35242, #31110 ) ; +#23009 = EDGE_LOOP ( 'NONE', ( #21343, #14892, #24855, #37297, #24074, #31994, #6631 ) ) ; +#23010 = CARTESIAN_POINT ( 'NONE', ( 22.99212157941825296, 211.0902260771000272, 76.05077210604348181 ) ) ; +#23011 = CARTESIAN_POINT ( 'NONE', ( -36.71662452048000347, 115.6901090825000011, 89.59692734496999833 ) ) ; +#23012 = VERTEX_POINT ( 'NONE', #35040 ) ; +#23013 = ORIENTED_EDGE ( 'NONE', *, *, #7875, .T. ) ; +#23014 = PLANE ( 'NONE', #31680 ) ; +#23015 = EDGE_CURVE ( 'NONE', #24868, #35038, #4762, .T. ) ; +#23016 = CARTESIAN_POINT ( 'NONE', ( -4.076917671009580246, 159.1898768710711636, 28.07643227829938226 ) ) ; +#23017 = CARTESIAN_POINT ( 'NONE', ( 25.86949214255275820, 190.8731965187743356, 106.6117107760572082 ) ) ; +#23018 = LINE ( 'NONE', #19526, #19435 ) ; +#23019 = VERTEX_POINT ( 'NONE', #16250 ) ; +#23020 = ORIENTED_EDGE ( 'NONE', *, *, #7319, .T. ) ; +#23021 = CARTESIAN_POINT ( 'NONE', ( -2.935493006219376255, 190.8915656532114724, 106.8042233182557652 ) ) ; +#23022 = ORIENTED_EDGE ( 'NONE', *, *, #1139, .T. ) ; +#23023 = ORIENTED_EDGE ( 'NONE', *, *, #14443, .F. ) ; +#23024 = CARTESIAN_POINT ( 'NONE', ( -6.031620047117566052, 177.7903949882438042, 100.7027583919079063 ) ) ; +#23025 = EDGE_CURVE ( 'NONE', #11556, #14938, #3751, .T. ) ; +#23026 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#23027 = ORIENTED_EDGE ( 'NONE', *, *, #40327, .F. ) ; +#23028 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39505, #38689, #39098, #32962 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23029 = ORIENTED_EDGE ( 'NONE', *, *, #5337, .F. ) ; +#23030 = CARTESIAN_POINT ( 'NONE', ( -39.35358084013989810, 182.6251433340804624, 104.9179412529496176 ) ) ; +#23032 = EDGE_CURVE ( 'NONE', #12363, #20529, #36686, .T. ) ; +#23031 = CARTESIAN_POINT ( 'NONE', ( -18.98875009441257333, 125.3860450160050277, 176.2394239049030773 ) ) ; +#23033 = FACE_OUTER_BOUND ( 'NONE', #15723, .T. ) ; +#23035 = AXIS2_PLACEMENT_3D ( 'NONE', #2008, #26551, #7925 ) ; +#23034 = CARTESIAN_POINT ( 'NONE', ( 36.52937954486999672, 191.8776055557000007, 104.5091987639000166 ) ) ; +#23036 = ADVANCED_FACE ( 'NONE', ( #33355 ), #4853, .F. ) ; +#23037 = CARTESIAN_POINT ( 'NONE', ( 19.99998068445589894, 192.4505593463679531, 103.8661183637674696 ) ) ; +#23038 = EDGE_CURVE ( 'NONE', #5670, #18015, #6220, .T. ) ; +#23039 = AXIS2_PLACEMENT_3D ( 'NONE', #33595, #17441, #15005 ) ; +#23040 = DIRECTION ( 'NONE', ( 0.0002393071182782299474, 0.2252352986010034697, -0.9743043687658493601 ) ) ; +#23041 = FACE_OUTER_BOUND ( 'NONE', #27153, .T. ) ; +#23042 = CARTESIAN_POINT ( 'NONE', ( 13.76428958129024060, 149.7303430849056554, 179.8030703196882882 ) ) ; +#23043 = EDGE_LOOP ( 'NONE', ( #40372, #1657, #3864, #23703 ) ) ; +#23044 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501099214, 179.0628333271199892, 104.0826189413407548 ) ) ; +#23045 = CARTESIAN_POINT ( 'NONE', ( 25.43413852155488186, 117.4589139984525588, 87.75225533617421547 ) ) ; +#23046 = CARTESIAN_POINT ( 'NONE', ( 3.778874383621917854, 175.3021472085679591, 100.3732877819419684 ) ) ; +#23047 = CARTESIAN_POINT ( 'NONE', ( 45.75915549074260014, 185.6501889555703713, 105.6243901609633724 ) ) ; +#23048 = ORIENTED_EDGE ( 'NONE', *, *, #12349, .F. ) ; +#23049 = LINE ( 'NONE', #19948, #3686 ) ; +#23050 = CARTESIAN_POINT ( 'NONE', ( 1.081957969975081646, 189.0686000648533422, 103.7038781678739525 ) ) ; +#23051 = CARTESIAN_POINT ( 'NONE', ( 13.55514511693098889, 164.0767501412786942, 100.0905987950646931 ) ) ; +#23052 = CARTESIAN_POINT ( 'NONE', ( -21.44693694427656538, 176.9185168219783009, 100.5107344958116897 ) ) ; +#23053 = CARTESIAN_POINT ( 'NONE', ( -26.12919643628000088, 191.8854903158000127, 103.7978481772000094 ) ) ; +#23054 = CARTESIAN_POINT ( 'NONE', ( 77.66418106072950422, 192.0495531737880697, 194.3144031859467020 ) ) ; +#23055 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#23056 = ADVANCED_FACE ( 'NONE', ( #39484 ), #3466, .F. ) ; +#23057 = CARTESIAN_POINT ( 'NONE', ( 13.50147201673213893, 151.4095814229721668, 97.16618435358425643 ) ) ; +#23058 = ORIENTED_EDGE ( 'NONE', *, *, #37153, .T. ) ; +#23059 = AXIS2_PLACEMENT_3D ( 'NONE', #2566, #30577, #24657 ) ; +#23060 = CARTESIAN_POINT ( 'NONE', ( -3.589080270976114040, 149.3464402625973548, 130.0539584792211940 ) ) ; +#23061 = VECTOR ( 'NONE', #7669, 1000.000000000000114 ) ; +#23062 = ORIENTED_EDGE ( 'NONE', *, *, #29580, .F. ) ; +#23063 = CARTESIAN_POINT ( 'NONE', ( 22.34487381648171933, 115.6781641173579374, 87.75408369845331435 ) ) ; +#23064 = CARTESIAN_POINT ( 'NONE', ( 46.36186659599525228, 124.8321406060005216, 91.18150140577510854 ) ) ; +#23065 = ADVANCED_FACE ( 'NONE', ( #2884 ), #40293, .F. ) ; +#23066 = CARTESIAN_POINT ( 'NONE', ( -25.49061850948251262, 191.6070706629876668, 105.4250562708838004 ) ) ; +#23067 = CARTESIAN_POINT ( 'NONE', ( 36.06505478249000163, 192.7057421003999877, 106.3400883135000043 ) ) ; +#23068 = CARTESIAN_POINT ( 'NONE', ( -39.68966533330124946, 159.7604222978274322, 205.3090076836404876 ) ) ; +#23069 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26081, #6844, #2097, #5131, #22612, #25692 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.0006561535229017134967, 0.001312307045803426993 ), + .UNSPECIFIED. ) ; +#23070 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672435848, 137.9484336565874116, 94.05843294792771303 ) ) ; +#23071 = CARTESIAN_POINT ( 'NONE', ( 13.50718655633492382, 188.3455032986072979, 103.1278069412195748 ) ) ; +#23072 = VERTEX_POINT ( 'NONE', #18602 ) ; +#23073 = CARTESIAN_POINT ( 'NONE', ( -2.954012872169000214, 209.1419319052000105, 76.14255845111000554 ) ) ; +#23074 = ADVANCED_FACE ( 'NONE', ( #12486 ), #2735, .T. ) ; +#23075 = CARTESIAN_POINT ( 'NONE', ( -16.40936930839530916, 122.6519308020210985, 174.4724684896352187 ) ) ; +#23076 = CARTESIAN_POINT ( 'NONE', ( 4.035676232316198764, 143.6517845923164600, 95.38087260498555509 ) ) ; +#23077 = ORIENTED_EDGE ( 'NONE', *, *, #21233, .T. ) ; +#23078 = LINE ( 'NONE', #28808, #6249 ) ; +#23079 = CARTESIAN_POINT ( 'NONE', ( 25.50040748627628773, 118.8155663766999481, 89.75240507814876878 ) ) ; +#23080 = EDGE_CURVE ( 'NONE', #6360, #6247, #24987, .T. ) ; +#23081 = ORIENTED_EDGE ( 'NONE', *, *, #40041, .F. ) ; +#23082 = ADVANCED_FACE ( 'NONE', ( #10445 ), #7151, .F. ) ; +#23083 = EDGE_CURVE ( 'NONE', #20264, #8681, #2091, .T. ) ; +#23084 = CARTESIAN_POINT ( 'NONE', ( -38.54565956053704667, 119.1564759897554211, 90.30561907418552892 ) ) ; +#23085 = CARTESIAN_POINT ( 'NONE', ( 23.39706652104787565, 115.1133789070304090, 87.25365305013352213 ) ) ; +#23086 = ORIENTED_EDGE ( 'NONE', *, *, #26544, .F. ) ; +#23087 = CARTESIAN_POINT ( 'NONE', ( 36.25669640222992030, 191.9251549171964655, 106.3935000725031728 ) ) ; +#23088 = VECTOR ( 'NONE', #6054, 1000.000000000000000 ) ; +#23089 = CARTESIAN_POINT ( 'NONE', ( -37.20408499833268223, 118.8543451041053629, 123.0175147492476100 ) ) ; +#23090 = VECTOR ( 'NONE', #26860, 1000.000000000000227 ) ; +#23091 = CARTESIAN_POINT ( 'NONE', ( -19.40198027091592081, 124.9165765156423760, 177.8474014814652264 ) ) ; +#23092 = CARTESIAN_POINT ( 'NONE', ( -36.06983547239383370, 77.73424611234590031, 291.5803292120234573 ) ) ; +#23093 = EDGE_LOOP ( 'NONE', ( #26696, #3112, #7837, #39360 ) ) ; +#23094 = CARTESIAN_POINT ( 'NONE', ( 15.94070853784563013, 152.8278484770639523, 181.6213642978358109 ) ) ; +#23095 = VECTOR ( 'NONE', #9554, 1000.000000000000114 ) ; +#23096 = CARTESIAN_POINT ( 'NONE', ( -30.07125580757959682, 177.2369646589789056, 101.0604468351817928 ) ) ; +#23097 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927789794472, 0.0005734119022071577400 ) ) ; +#23098 = CARTESIAN_POINT ( 'NONE', ( -20.51815631801374096, 205.9571214413596181, 75.54984696095283425 ) ) ; +#23099 = ORIENTED_EDGE ( 'NONE', *, *, #18103, .F. ) ; +#23100 = DIRECTION ( 'NONE', ( 0.0005884949961259727845, -0.2249510543439064703, 0.9743698870671262391 ) ) ; +#23101 = CARTESIAN_POINT ( 'NONE', ( 37.88844529860523380, 117.7436133799949403, 89.67204850642481517 ) ) ; +#23102 = CARTESIAN_POINT ( 'NONE', ( 32.37225758321823577, 137.6347993665977185, 94.48777941942033465 ) ) ; +#23103 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13928, #10061, #26012, #16776 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23104 = DIRECTION ( 'NONE', ( -0.0006039748319344481579, 1.110223022795018804E-14, -0.9999998176071845934 ) ) ; +#23105 = CARTESIAN_POINT ( 'NONE', ( 20.00171108015191024, 119.7153632178993377, 90.35824133875276232 ) ) ; +#23106 = CARTESIAN_POINT ( 'NONE', ( -3.535970564801350857, 118.9425530769304515, 90.19402121340442591 ) ) ; +#23107 = DIRECTION ( 'NONE', ( -0.7933535594326887042, 0.5932204071694016090, 0.1366736194488628042 ) ) ; +#23108 = CARTESIAN_POINT ( 'NONE', ( 38.13650326794999756, 118.9089952261000036, 90.39651201712000272 ) ) ; +#23109 = CIRCLE ( 'NONE', #33546, 5.500000000058693495 ) ; +#23110 = ORIENTED_EDGE ( 'NONE', *, *, #4929, .T. ) ; +#23111 = EDGE_CURVE ( 'NONE', #11548, #22377, #26254, .T. ) ; +#23112 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#23113 = EDGE_CURVE ( 'NONE', #25308, #32551, #817, .T. ) ; +#23114 = LINE ( 'NONE', #38432, #27430 ) ; +#23115 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24790, #15175, #15368, #33557 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23116 = CARTESIAN_POINT ( 'NONE', ( -16.11981483100024448, 123.6845644636535582, 173.7931095965155635 ) ) ; +#23117 = ADVANCED_FACE ( 'NONE', ( #29038 ), #1634, .F. ) ; +#23118 = AXIS2_PLACEMENT_3D ( 'NONE', #13306, #16355, #3683 ) ; +#23120 = ORIENTED_EDGE ( 'NONE', *, *, #20051, .T. ) ; +#23119 = CARTESIAN_POINT ( 'NONE', ( -13.46215051151162889, 153.7291600434821532, 98.23113887026609348 ) ) ; +#23121 = ORIENTED_EDGE ( 'NONE', *, *, #4499, .F. ) ; +#23122 = EDGE_CURVE ( 'NONE', #20440, #31162, #14725, .T. ) ; +#23123 = EDGE_LOOP ( 'NONE', ( #32960, #32955, #25274, #14447 ) ) ; +#23124 = CARTESIAN_POINT ( 'NONE', ( -26.00789644338852469, 208.0210118655040787, 76.93397401140359193 ) ) ; +#23125 = EDGE_CURVE ( 'NONE', #20950, #29253, #21469, .T. ) ; +#23126 = DIRECTION ( 'NONE', ( 0.0005884949961251158311, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#23127 = VERTEX_POINT ( 'NONE', #37781 ) ; +#23128 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825857840055654, 0.0005734119038270033821 ) ) ; +#23129 = ADVANCED_FACE ( 'NONE', ( #3033 ), #9792, .T. ) ; +#23130 = CARTESIAN_POINT ( 'NONE', ( -20.45366101552173532, 211.0901972962080322, 75.63591788811629613 ) ) ; +#23131 = CARTESIAN_POINT ( 'NONE', ( -38.09076243749999691, 119.2798029714000023, 87.30615167818000089 ) ) ; +#23132 = FACE_OUTER_BOUND ( 'NONE', #3519, .T. ) ; +#23133 = VERTEX_POINT ( 'NONE', #34303 ) ; +#23134 = CARTESIAN_POINT ( 'NONE', ( 19.54487014920338339, 148.9873530275860958, 183.1261089886357638 ) ) ; +#23135 = DIRECTION ( 'NONE', ( 0.0005884949961260158274, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#23136 = DIRECTION ( 'NONE', ( 0.0006039748319392047697, 1.154386647790520729E-15, 0.9999998176071845934 ) ) ; +#23137 = CARTESIAN_POINT ( 'NONE', ( 39.01778814463001055, 209.7096538831000032, 28.07991271570000080 ) ) ; +#23138 = VECTOR ( 'NONE', #35951, 1000.000000000000227 ) ; +#23139 = ADVANCED_FACE ( 'NONE', ( #18968 ), #6298, .T. ) ; +#23140 = ORIENTED_EDGE ( 'NONE', *, *, #23260, .T. ) ; +#23141 = CARTESIAN_POINT ( 'NONE', ( -1.852762058314000093, 189.5547784236999860, 103.8460018853999998 ) ) ; +#23142 = PLANE ( 'NONE', #9456 ) ; +#23143 = VECTOR ( 'NONE', #17542, 1000.000000000000114 ) ; +#23144 = AXIS2_PLACEMENT_3D ( 'NONE', #11218, #23692, #4860 ) ; +#23145 = CARTESIAN_POINT ( 'NONE', ( -5.668107859749786925, 185.2316718754979377, 105.5024628770674866 ) ) ; +#23146 = CIRCLE ( 'NONE', #39441, 1.650000000000002798 ) ; +#23147 = VERTEX_POINT ( 'NONE', #40239 ) ; +#23148 = CARTESIAN_POINT ( 'NONE', ( -40.55516615315095663, 184.2569486434040869, 105.2953989892096445 ) ) ; +#23149 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319417801836 ) ) ; +#23150 = VERTEX_POINT ( 'NONE', #28204 ) ; +#23151 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #22808, #32209, #4165, #16643 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.6245186104307177688, 0.8013624142894875124 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973955533075615776, 0.9973955533075615776, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#23152 = ORIENTED_EDGE ( 'NONE', *, *, #2682, .F. ) ; +#23153 = VERTEX_POINT ( 'NONE', #9584 ) ; +#23154 = CARTESIAN_POINT ( 'NONE', ( 39.81119971704559646, 75.02554102933939362, 323.6757538848392528 ) ) ; +#23155 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048996748, 130.3419545077892678, 92.84535593381433216 ) ) ; +#23156 = ORIENTED_EDGE ( 'NONE', *, *, #9047, .F. ) ; +#23157 = DIRECTION ( 'NONE', ( -0.0005884949961212082581, 0.2249510543439042498, -0.9743698870671267942 ) ) ; +#23158 = VERTEX_POINT ( 'NONE', #22064 ) ; +#23159 = CARTESIAN_POINT ( 'NONE', ( 26.01546616514680466, 120.4365795122199927, 90.52613441020730534 ) ) ; +#23160 = ADVANCED_FACE ( 'NONE', ( #24742 ), #34706, .F. ) ; +#23161 = CARTESIAN_POINT ( 'NONE', ( 77.76841782105992706, 192.2294772166672772, 194.3560228188070766 ) ) ; +#23162 = EDGE_CURVE ( 'NONE', #3220, #6135, #860, .T. ) ; +#23163 = EDGE_CURVE ( 'NONE', #28309, #35551, #24311, .T. ) ; +#23165 = DIRECTION ( 'NONE', ( -0.5989082241854613020, 0.8008175873178838833, 0.0003617255600147346959 ) ) ; +#23164 = FACE_OUTER_BOUND ( 'NONE', #5215, .T. ) ; +#23166 = ORGANIZATION ( '未', '未', '' ) ; +#23167 = CARTESIAN_POINT ( 'NONE', ( 76.10777906859902942, 155.6827192487123455, 98.62805563715404844 ) ) ; +#23168 = VECTOR ( 'NONE', #31452, 1000.000000000000227 ) ; +#23169 = CONICAL_SURFACE ( 'NONE', #34871, 2.499987184277071339, 0.7853981634084753471 ) ; +#23170 = VERTEX_POINT ( 'NONE', #13651 ) ; +#23171 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567345 ) ) ; +#23172 = EDGE_CURVE ( 'NONE', #19831, #8063, #24794, .T. ) ; +#23173 = LINE ( 'NONE', #7617, #16856 ) ; +#23174 = ORIENTED_EDGE ( 'NONE', *, *, #18399, .T. ) ; +#23175 = DIRECTION ( 'NONE', ( 0.0004161288024526961808, 0.5299192578740949955, 0.8480479980348919478 ) ) ; +#23176 = EDGE_CURVE ( 'NONE', #16772, #25128, #33951, .T. ) ; +#23177 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923101038, 127.7447309815698873, 89.13696229017300254 ) ) ; +#23178 = CARTESIAN_POINT ( 'NONE', ( -45.37018052505393939, 124.2011127489164153, 91.76099384493524269 ) ) ; +#23179 = CARTESIAN_POINT ( 'NONE', ( 3.534232527368997623, 141.9351730801645033, 92.41913181349261208 ) ) ; +#23180 = EDGE_LOOP ( 'NONE', ( #22731, #33258, #29216, #36451 ) ) ; +#23181 = VERTEX_POINT ( 'NONE', #28792 ) ; +#23182 = CYLINDRICAL_SURFACE ( 'NONE', #20013, 2.000000000000001332 ) ; +#23183 = VERTEX_POINT ( 'NONE', #38579 ) ; +#23184 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #16162, #819, #29246, #32506 ), + ( #25986, #16944, #19618, #28640 ), + ( #23108, #615, #22317, #28840 ), + ( #19211, #13303, #35341, #3680 ), + ( #31721, #4071, #4481, #13106 ), + ( #16543, #29445, #25591, #29040 ), + ( #1016, #38033, #19421, #31920 ), + ( #7551, #3878, #16352, #26190 ), + ( #4278, #25789, #38236, #10447 ), + ( #35534, #7346, #10247, #19807 ), + ( #16752, #1218, #13700, #38628 ), + ( #8385, #23714, #29854, #36169 ), + ( #35952, #38823, #30462, #30248 ), + ( #14314, #20843, #7962, #36586 ), + ( #17554, #7750, #30058, #11441 ), + ( #39431, #2457, #5298, #5088 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.001700366337021999965, 0.000000000000000000, 0.005170675847449000308, 0.01037958123234999919, 0.02079739200211999997, 0.04163301354170000079, 0.06246863508127999814, 0.08330425662085999550, 0.1249754996999000028, 0.1666467427790999933, 0.3333317150958000075, 0.6666652572568999569, 1.000000000000000000, 1.177776354664000102 ), + ( -0.2624929596591999981, 1.257088294254000038 ), + .UNSPECIFIED. ) ; +#23185 = CYLINDRICAL_SURFACE ( 'NONE', #33693, 2.000000000000001332 ) ; +#23186 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27238, #10655, #36726, #36107, #5443, #20578, #33046, #8325, #15069, #1992 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23187 = EDGE_LOOP ( 'NONE', ( #17764, #29911, #37086, #2062, #11202, #40221, #30269 ) ) ; +#23188 = CARTESIAN_POINT ( 'NONE', ( -28.94629671773198965, 110.6131156702000027, 90.28526767713175616 ) ) ; +#23189 = CARTESIAN_POINT ( 'NONE', ( 3.081029741328818794, 190.8867177225405669, 106.8190053092809819 ) ) ; +#23190 = VERTEX_POINT ( 'NONE', #26141 ) ; +#23191 = LINE ( 'NONE', #35622, #27566 ) ; +#23192 = AXIS2_PLACEMENT_3D ( 'NONE', #26030, #34588, #13158 ) ; +#23193 = AXIS2_PLACEMENT_3D ( 'NONE', #9979, #16096, #22452 ) ; +#23194 = CARTESIAN_POINT ( 'NONE', ( -41.39426888469423460, 120.3350051359701638, 90.19625819200398098 ) ) ; +#23195 = CARTESIAN_POINT ( 'NONE', ( 43.23122282123772919, 179.1331515733938886, 148.2643789950020619 ) ) ; +#23196 = EDGE_LOOP ( 'NONE', ( #10813, #8369, #15787, #29732 ) ) ; +#23197 = AXIS2_PLACEMENT_3D ( 'NONE', #37209, #24548, #6505 ) ; +#23198 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#23199 = CARTESIAN_POINT ( 'NONE', ( -3.668404232393724929, 183.5617789225002809, 104.5994755552988096 ) ) ; +#23200 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425197144, 137.5181437524809667, 94.48855197221574542 ) ) ; +#23201 = ORIENTED_EDGE ( 'NONE', *, *, #10574, .T. ) ; +#23202 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825928107556782, 0.0005734119021999202568 ) ) ; +#23203 = EDGE_CURVE ( 'NONE', #14712, #22688, #1369, .T. ) ; +#23204 = EDGE_CURVE ( 'NONE', #33391, #28841, #36716, .T. ) ; +#23206 = CARTESIAN_POINT ( 'NONE', ( -38.08615123650999834, 118.2522031968999983, 89.85284521143999825 ) ) ; +#23205 = CARTESIAN_POINT ( 'NONE', ( -15.49970618492638508, 127.6313525092815411, 89.64145404642985682 ) ) ; +#23207 = ORIENTED_EDGE ( 'NONE', *, *, #1928, .F. ) ; +#23208 = CARTESIAN_POINT ( 'NONE', ( 31.79421365038999880, 226.4002260771000010, 73.53930126516999621 ) ) ; +#23209 = CARTESIAN_POINT ( 'NONE', ( 38.57409235987329055, 118.4658207127237688, 89.66260175151403189 ) ) ; +#23210 = VERTEX_POINT ( 'NONE', #10997 ) ; +#23211 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825852464688619, 0.0005734119039458779104 ) ) ; +#23212 = CARTESIAN_POINT ( 'NONE', ( 46.08267618988084280, 184.7865884867546242, 107.4179575081553253 ) ) ; +#23213 = CARTESIAN_POINT ( 'NONE', ( 45.33187901993595403, 106.2369563754977122, 169.3368253429517836 ) ) ; +#23214 = PLANE ( 'NONE', #8011 ) ; +#23215 = CARTESIAN_POINT ( 'NONE', ( 3.168112933839599688, 185.2356858264948301, 105.4949491227606870 ) ) ; +#23216 = ORIENTED_EDGE ( 'NONE', *, *, #36784, .T. ) ; +#23217 = CIRCLE ( 'NONE', #38874, 6.000000000000007994 ) ; +#23218 = VERTEX_POINT ( 'NONE', #2404 ) ; +#23219 = CARTESIAN_POINT ( 'NONE', ( -42.72426501338485849, 120.8886262355579220, 91.39497110141761027 ) ) ; +#23220 = ORIENTED_EDGE ( 'NONE', *, *, #8420, .F. ) ; +#23221 = VERTEX_POINT ( 'NONE', #36534 ) ; +#23222 = CARTESIAN_POINT ( 'NONE', ( -8.048542123008331828, 160.5967930229313367, 99.81338747665230926 ) ) ; +#23223 = VECTOR ( 'NONE', #19015, 1000.000000000000114 ) ; +#23224 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510153906202348, 0.9743700737782995391 ) ) ; +#23225 = AXIS2_PLACEMENT_3D ( 'NONE', #32891, #33288, #33495 ) ; +#23226 = AXIS2_PLACEMENT_3D ( 'NONE', #12608, #31640, #25512 ) ; +#23227 = ORIENTED_EDGE ( 'NONE', *, *, #17729, .F. ) ; +#23228 = CARTESIAN_POINT ( 'NONE', ( 25.50040748627628773, 118.8155663766999481, 89.75240507814876878 ) ) ; +#23229 = CARTESIAN_POINT ( 'NONE', ( -2.480274637552000172, 211.0000000000000000, 32.65999473746001058 ) ) ; +#23230 = CARTESIAN_POINT ( 'NONE', ( 44.87323697063200001, 186.3386389082236860, 107.7764265916358113 ) ) ; +#23231 = CARTESIAN_POINT ( 'NONE', ( 19.99963753331764593, 193.2798873410197871, 103.4435829895760577 ) ) ; +#23232 = ORIENTED_EDGE ( 'NONE', *, *, #5904, .F. ) ; +#23233 = DIRECTION ( 'NONE', ( 0.0005884949961270922233, -0.2249510543439054433, 0.9743698870671265722 ) ) ; +#23234 = CARTESIAN_POINT ( 'NONE', ( -23.36030038340052428, 176.7386739072689181, 103.0361307674479150 ) ) ; +#23235 = ORIENTED_EDGE ( 'NONE', *, *, #25080, .F. ) ; +#23236 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 77.27946979429631824, 312.5857197240631535 ) ) ; +#23237 = CARTESIAN_POINT ( 'NONE', ( 14.29930377595062652, 176.1145857943713793, 103.0403539068457235 ) ) ; +#23238 = FACE_OUTER_BOUND ( 'NONE', #33314, .T. ) ; +#23239 = CARTESIAN_POINT ( 'NONE', ( 36.04796026496615724, 209.7096538831000032, 78.03673292965207509 ) ) ; +#23240 = VERTEX_POINT ( 'NONE', #35906 ) ; +#23241 = CARTESIAN_POINT ( 'NONE', ( -22.99592550276514658, 134.9153278805555090, 90.81446795239106962 ) ) ; +#23242 = DIRECTION ( 'NONE', ( -0.1305262304084799929, 0.9659442311576372786, 0.2234158576928528539 ) ) ; +#23243 = CARTESIAN_POINT ( 'NONE', ( 31.32891649726831673, 135.2306215998971481, 90.85444841302377483 ) ) ; +#23244 = EDGE_CURVE ( 'NONE', #24812, #13325, #21003, .T. ) ; +#23245 = CARTESIAN_POINT ( 'NONE', ( 23.68470177377144381, 137.2456318144843976, 91.83741932284023335 ) ) ; +#23246 = CARTESIAN_POINT ( 'NONE', ( -25.63353067346999836, 191.3682931014000133, 104.2390837140000031 ) ) ; +#23247 = AXIS2_PLACEMENT_3D ( 'NONE', #6455, #2613, #18515 ) ; +#23248 = CARTESIAN_POINT ( 'NONE', ( 19.70863784699480448, 149.1560517737245561, 182.9541186021026817 ) ) ; +#23249 = CIRCLE ( 'NONE', #5584, 2.000000003652215419 ) ; +#23250 = CARTESIAN_POINT ( 'NONE', ( 25.67500669693000503, 191.2493216073000042, 104.1755163559000010 ) ) ; +#23251 = LINE ( 'NONE', #14258, #17047 ) ; +#23252 = CARTESIAN_POINT ( 'NONE', ( -28.46728868143000213, 182.0597503762595579, 102.2150741956516384 ) ) ; +#23253 = ORIENTED_EDGE ( 'NONE', *, *, #17357, .F. ) ; +#23254 = CONICAL_SURFACE ( 'NONE', #2988, 6.500001087336274352, 0.7853982191638021471 ) ; +#23255 = EDGE_CURVE ( 'NONE', #1872, #10112, #4641, .T. ) ; +#23256 = ADVANCED_FACE ( 'NONE', ( #20377 ), #27368, .T. ) ; +#23257 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178587041921E-05, 0.0002331579774917524482 ) ) ; +#23258 = DIRECTION ( 'NONE', ( -0.1305262373691799260, -0.9659798014921964215, -0.2232620085624539286 ) ) ; +#23259 = CARTESIAN_POINT ( 'NONE', ( 19.98483764167631094, 211.0849390754169974, 73.04592155476974824 ) ) ; +#23260 = EDGE_CURVE ( 'NONE', #30446, #21872, #24290, .T. ) ; +#23261 = FACE_OUTER_BOUND ( 'NONE', #24205, .T. ) ; +#23262 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#23263 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1988, #11996, #2787, #11377 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23264 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971530430 ) ) ; +#23265 = CARTESIAN_POINT ( 'NONE', ( 22.81058210632548366, 115.1133384263758472, 90.25400781920090765 ) ) ; +#23266 = ORIENTED_EDGE ( 'NONE', *, *, #24197, .F. ) ; +#23267 = ORIENTED_EDGE ( 'NONE', *, *, #31288, .F. ) ; +#23268 = CARTESIAN_POINT ( 'NONE', ( 25.49921019565536184, 118.1133140256443426, 87.75227232668940758 ) ) ; +#23269 = DIRECTION ( 'NONE', ( -0.1706442583057901363, -1.252691005673331975E-14, -0.9853327037641991248 ) ) ; +#23270 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596097999, 128.5887768395806177, 89.32567453967637050 ) ) ; +#23271 = FACE_OUTER_BOUND ( 'NONE', #35863, .T. ) ; +#23272 = CIRCLE ( 'NONE', #16744, 4.500000000010161649 ) ; +#23273 = ORIENTED_EDGE ( 'NONE', *, *, #20085, .F. ) ; +#23274 = CARTESIAN_POINT ( 'NONE', ( 6.035686183114718162, 177.4040666397187067, 100.9383125970363864 ) ) ; +#23275 = CARTESIAN_POINT ( 'NONE', ( 3.535839194698592980, 136.6870853775678825, 94.28644726325400427 ) ) ; +#23276 = VECTOR ( 'NONE', #14837, 1000.000000000000114 ) ; +#23277 = EDGE_LOOP ( 'NONE', ( #36277, #2341, #26409, #1190 ) ) ; +#23278 = VECTOR ( 'NONE', #12801, 1000.000000000000000 ) ; +#23279 = CARTESIAN_POINT ( 'NONE', ( 25.99332526491797069, 209.7096538831000032, 78.04280567724204332 ) ) ; +#23280 = VERTEX_POINT ( 'NONE', #12209 ) ; +#23281 = CYLINDRICAL_SURFACE ( 'NONE', #1387, 2.000000000000014655 ) ; +#23282 = VECTOR ( 'NONE', #29483, 999.9999999999998863 ) ; +#23283 = CARTESIAN_POINT ( 'NONE', ( -5.668109638568584074, 127.9100376797824907, 92.26561629879442705 ) ) ; +#23284 = CARTESIAN_POINT ( 'NONE', ( -13.49823340920320724, 160.0628909777703655, 99.69670533858855777 ) ) ; +#23285 = DIRECTION ( 'NONE', ( -0.0005884949961232824453, 0.2249510543439075805, -0.9743698870671260170 ) ) ; +#23286 = AXIS2_PLACEMENT_3D ( 'NONE', #13489, #20000, #38416 ) ; +#23287 = CYLINDRICAL_SURFACE ( 'NONE', #21561, 2.000000000000011546 ) ; +#23288 = CARTESIAN_POINT ( 'NONE', ( -25.49994355703909932, 120.2054709989172778, 89.98570258340846806 ) ) ; +#23289 = ORIENTED_EDGE ( 'NONE', *, *, #26264, .F. ) ; +#23290 = ORIENTED_EDGE ( 'NONE', *, *, #23083, .F. ) ; +#23291 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971546806 ) ) ; +#23292 = CARTESIAN_POINT ( 'NONE', ( -30.07072815488413653, 177.4736756012406431, 100.9125331478477676 ) ) ; +#23293 = CARTESIAN_POINT ( 'NONE', ( 28.34940426444671147, 125.4854830354149300, 88.94851520771482001 ) ) ; +#23294 = ADVANCED_FACE ( 'NONE', ( #30616 ), #8659, .F. ) ; +#23295 = CARTESIAN_POINT ( 'NONE', ( -13.46391575659845685, 154.4039982810205629, 95.30803284751881677 ) ) ; +#23296 = EDGE_LOOP ( 'NONE', ( #21453, #164, #39762, #8365 ) ) ; +#23297 = CARTESIAN_POINT ( 'NONE', ( 30.06878009202964463, 135.2977368468020813, 91.38385643107594092 ) ) ; +#23298 = CARTESIAN_POINT ( 'NONE', ( -20.49970531958900821, 174.4001369415014437, 100.4419005551936834 ) ) ; +#23299 = CARTESIAN_POINT ( 'NONE', ( 37.71311666782268190, 212.3970731212147598, 75.53572676091057758 ) ) ; +#23300 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#23301 = EDGE_CURVE ( 'NONE', #5782, #15583, #30568, .T. ) ; +#23302 = CARTESIAN_POINT ( 'NONE', ( -20.49970532896238495, 138.0793279496801631, 92.05657955325195019 ) ) ; +#23303 = CARTESIAN_POINT ( 'NONE', ( -21.21320613303312541, 183.0566203626299284, 103.8092442496014485 ) ) ; +#23304 = CARTESIAN_POINT ( 'NONE', ( 5.696483686681999892, 174.3879284816999871, 152.4718672074000381 ) ) ; +#23305 = EDGE_CURVE ( 'NONE', #20475, #23972, #36426, .T. ) ; +#23306 = CIRCLE ( 'NONE', #30505, 16.50000000000598277 ) ; +#23307 = EDGE_CURVE ( 'NONE', #32767, #133, #13860, .T. ) ; +#23308 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15685, #2432, #21231, #3009, #24516, #21032, #39818, #15496, #11834, #27784 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.002297953239941401965, 0.2517230612339881879, 0.5011481692280349565, 0.7505732772220816695, 0.9999983852161284936 ), + .UNSPECIFIED. ) ; +#23309 = DIRECTION ( 'NONE', ( 0.0006039748319377573598, 1.390293078070570268E-14, 0.9999998176071845934 ) ) ; +#23310 = AXIS2_PLACEMENT_3D ( 'NONE', #28395, #12856, #25335 ) ; +#23311 = EDGE_CURVE ( 'NONE', #15935, #12175, #37871, .T. ) ; +#23312 = CARTESIAN_POINT ( 'NONE', ( 26.14898090114000340, 191.6041293664000023, 107.0269310404000151 ) ) ; +#23313 = EDGE_CURVE ( 'NONE', #25599, #14004, #9538, .T. ) ; +#23314 = LINE ( 'NONE', #7961, #38779 ) ; +#23315 = CARTESIAN_POINT ( 'NONE', ( 26.45759199812077611, 122.9297683075388079, 88.01751430407519194 ) ) ; +#23316 = ORIENTED_EDGE ( 'NONE', *, *, #23872, .T. ) ; +#23317 = VECTOR ( 'NONE', #7015, 1000.000000000000114 ) ; +#23318 = DIRECTION ( 'NONE', ( 7.677760455955688654E-18, -1.000000000000000000, 1.271205131337280331E-14 ) ) ; +#23319 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7071067167009886800, 0.7071068456721004702 ) ) ; +#23320 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29536, #23403, #20318, #4576 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.003244958643172611134 ), + .UNSPECIFIED. ) ; +#23321 = CARTESIAN_POINT ( 'NONE', ( -21.10693792752578801, 183.2696801607907844, 102.3189169904713509 ) ) ; +#23322 = CARTESIAN_POINT ( 'NONE', ( -28.47139460624499208, 181.8099728549552481, 101.8153497139206962 ) ) ; +#23324 = ORIENTED_EDGE ( 'NONE', *, *, #22510, .F. ) ; +#23323 = DIRECTION ( 'NONE', ( -0.7066795771589046149, 3.237673907669277066E-09, 0.7075337272713659864 ) ) ; +#23325 = VERTEX_POINT ( 'NONE', #38148 ) ; +#23326 = ORIENTED_EDGE ( 'NONE', *, *, #19543, .F. ) ; +#23327 = ORIENTED_EDGE ( 'NONE', *, *, #25414, .F. ) ; +#23328 = CYLINDRICAL_SURFACE ( 'NONE', #23530, 6.000000000000001776 ) ; +#23329 = CARTESIAN_POINT ( 'NONE', ( -21.21399091017794802, 175.8930158889867528, 100.7869902896899816 ) ) ; +#23330 = ORIENTED_EDGE ( 'NONE', *, *, #36386, .T. ) ; +#23331 = FACE_BOUND ( 'NONE', #34421, .T. ) ; +#23332 = EDGE_CURVE ( 'NONE', #8868, #25286, #35046, .T. ) ; +#23333 = CARTESIAN_POINT ( 'NONE', ( -38.64958770352021844, 161.8984352577749348, 192.4743989663406012 ) ) ; +#23334 = CARTESIAN_POINT ( 'NONE', ( -24.42595486541198824, 109.6131156702000027, 90.28253750392424593 ) ) ; +#23335 = DIRECTION ( 'NONE', ( -0.0002393071182782278061, -0.2252352986010052738, 0.9743043687658489160 ) ) ; +#23336 = CARTESIAN_POINT ( 'NONE', ( -36.18523557502999921, 114.4326857091000136, 87.90963942732001613 ) ) ; +#23337 = ORIENTED_EDGE ( 'NONE', *, *, #34942, .F. ) ; +#23338 = CARTESIAN_POINT ( 'NONE', ( 17.92694799460988975, 127.4246020651061997, 177.6516979807273628 ) ) ; +#23339 = CONICAL_SURFACE ( 'NONE', #3096, 5.003076031389202427, 0.7853570728742632623 ) ; +#23340 = CARTESIAN_POINT ( 'NONE', ( 16.56083148683698170, 121.8447191377824907, 177.5628756867482423 ) ) ; +#23341 = CARTESIAN_POINT ( 'NONE', ( 38.29593043761780535, 218.5902260770999987, 76.03537484717311656 ) ) ; +#23342 = CARTESIAN_POINT ( 'NONE', ( -25.98973257537553749, 191.3166157958662836, 106.8934875062374203 ) ) ; +#23343 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561239 ) ) ; +#23344 = CARTESIAN_POINT ( 'NONE', ( -5.668109638568660458, 185.2323518255123815, 105.4995176905214294 ) ) ; +#23345 = ORIENTED_EDGE ( 'NONE', *, *, #2888, .F. ) ; +#23346 = VERTEX_POINT ( 'NONE', #29350 ) ; +#23347 = CARTESIAN_POINT ( 'NONE', ( -2.325334792972999942, 189.9234775223999918, 103.8041889634999961 ) ) ; +#23348 = CARTESIAN_POINT ( 'NONE', ( 22.50176470574469079, 160.0679787287287752, 99.67284943499184635 ) ) ; +#23349 = CARTESIAN_POINT ( 'NONE', ( 28.47525309053320797, 130.3504702658399879, 92.80840815248680542 ) ) ; +#23350 = CARTESIAN_POINT ( 'NONE', ( 26.00081424259415641, 120.1020648120652510, 90.44388058125247198 ) ) ; +#23351 = EDGE_CURVE ( 'NONE', #34249, #26229, #28868, .T. ) ; +#23352 = ORIENTED_EDGE ( 'NONE', *, *, #16427, .T. ) ; +#23353 = VERTEX_POINT ( 'NONE', #22819 ) ; +#23354 = CARTESIAN_POINT ( 'NONE', ( -2.448596876244000242, 209.1869211169000096, 75.60179039185000249 ) ) ; +#23355 = DIRECTION ( 'NONE', ( 1.249000902710531491E-14, -1.000000000000000000, 0.000000000000000000 ) ) ; +#23356 = ORIENTED_EDGE ( 'NONE', *, *, #34317, .T. ) ; +#23357 = ORIENTED_EDGE ( 'NONE', *, *, #39821, .F. ) ; +#23358 = EDGE_CURVE ( 'NONE', #32563, #24177, #4175, .T. ) ; +#23359 = ADVANCED_FACE ( 'NONE', ( #31619 ), #16062, .F. ) ; +#23360 = ORIENTED_EDGE ( 'NONE', *, *, #7098, .F. ) ; +#23361 = EDGE_LOOP ( 'NONE', ( #34712, #40279, #9476, #26234 ) ) ; +#23362 = CARTESIAN_POINT ( 'NONE', ( -28.16705420941000071, 186.9743051542000103, 105.9152683551999985 ) ) ; +#23363 = CARTESIAN_POINT ( 'NONE', ( -6.037441369385896373, 137.2416971194969335, 91.85446235641137491 ) ) ; +#23364 = EDGE_CURVE ( 'NONE', #315, #27892, #36061, .T. ) ; +#23365 = EDGE_LOOP ( 'NONE', ( #18191, #26575, #36629, #8451 ) ) ; +#23366 = CARTESIAN_POINT ( 'NONE', ( -5.670680073181483039, 181.8822695513912322, 101.9131439626678883 ) ) ; +#23367 = ORIENTED_EDGE ( 'NONE', *, *, #5666, .T. ) ; +#23368 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19764, #10794, #26144, #25943 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.01233348531029615849, 0.01329655828663948471 ), + .UNSPECIFIED. ) ; +#23369 = CARTESIAN_POINT ( 'NONE', ( 26.00143615033000088, 120.1794630026000021, 90.46342538870999306 ) ) ; +#23370 = AXIS2_PLACEMENT_3D ( 'NONE', #5267, #23285, #26364 ) ; +#23371 = CARTESIAN_POINT ( 'NONE', ( 30.05202369937001805, 184.7526529595380964, 104.8540442476633956 ) ) ; +#23372 = VECTOR ( 'NONE', #27667, 1000.000000000000227 ) ; +#23374 = FACE_OUTER_BOUND ( 'NONE', #17239, .T. ) ; +#23373 = CARTESIAN_POINT ( 'NONE', ( 25.49182901039327831, 209.7089661076149127, 75.54314178666862745 ) ) ; +#23375 = VERTEX_POINT ( 'NONE', #17244 ) ; +#23376 = VERTEX_POINT ( 'NONE', #39140 ) ; +#23377 = CARTESIAN_POINT ( 'NONE', ( -36.14255531305040137, 191.9341410994068156, 104.4181006106035738 ) ) ; +#23378 = VERTEX_POINT ( 'NONE', #35850 ) ; +#23379 = CARTESIAN_POINT ( 'NONE', ( -36.63447688325992857, 117.3726060988748827, 87.28991059808527098 ) ) ; +#23380 = DIRECTION ( 'NONE', ( 0.1632030863883311977, -0.3417424275059330885, 0.9255143790539803739 ) ) ; +#23381 = LINE ( 'NONE', #39100, #9793 ) ; +#23382 = VERTEX_POINT ( 'NONE', #17453 ) ; +#23383 = ORIENTED_EDGE ( 'NONE', *, *, #36111, .T. ) ; +#23384 = LINE ( 'NONE', #35821, #27941 ) ; +#23385 = ORIENTED_EDGE ( 'NONE', *, *, #29539, .F. ) ; +#23386 = CARTESIAN_POINT ( 'NONE', ( -35.46684749371900836, 192.2358989730090286, 106.9510738220610051 ) ) ; +#23387 = EDGE_CURVE ( 'NONE', #21784, #40324, #783, .T. ) ; +#23388 = ADVANCED_FACE ( 'NONE', ( #7857 ), #8064, .F. ) ; +#23389 = CIRCLE ( 'NONE', #14261, 55.00273826250365516 ) ; +#23390 = EDGE_CURVE ( 'NONE', #18545, #4424, #21057, .T. ) ; +#23391 = ORIENTED_EDGE ( 'NONE', *, *, #27586, .T. ) ; +#23392 = ADVANCED_FACE ( 'NONE', ( #20528 ), #2347, .F. ) ; +#23393 = CARTESIAN_POINT ( 'NONE', ( 2.897488417982000186, 190.8910880237999947, 106.6291566765000169 ) ) ; +#23394 = ORIENTED_EDGE ( 'NONE', *, *, #25585, .F. ) ; +#23395 = CARTESIAN_POINT ( 'NONE', ( 39.51558108783103762, 119.2344049514255317, 89.72500211528681291 ) ) ; +#23396 = DIRECTION ( 'NONE', ( 0.0005884949961209496759, -0.2249510543439030841, 0.9743698870671270162 ) ) ; +#23397 = CARTESIAN_POINT ( 'NONE', ( 31.79177573931936962, 115.2378407561303391, 176.5461501322318725 ) ) ; +#23398 = CARTESIAN_POINT ( 'NONE', ( 10.03596943924900486, 143.5399299914239180, 95.86457705213388181 ) ) ; +#23399 = EDGE_CURVE ( 'NONE', #18000, #3485, #17347, .T. ) ; +#23400 = ORIENTED_EDGE ( 'NONE', *, *, #18608, .T. ) ; +#23401 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31327, #13319, #22934, #22537 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23402 = CARTESIAN_POINT ( 'NONE', ( 44.90853464007773965, 181.5172347420035237, 101.5323552624301016 ) ) ; +#23403 = CARTESIAN_POINT ( 'NONE', ( -12.63329150945545365, 131.0198790336825141, 89.90887378819283526 ) ) ; +#23404 = EDGE_CURVE ( 'NONE', #36508, #25569, #11511, .T. ) ; +#23405 = ORIENTED_EDGE ( 'NONE', *, *, #3840, .T. ) ; +#23406 = CARTESIAN_POINT ( 'NONE', ( 33.32721009243029897, 80.97613274184595866, 288.9672004084912373 ) ) ; +#23408 = CARTESIAN_POINT ( 'NONE', ( -36.62475089482000357, 116.6800463140000090, 90.15487809088000404 ) ) ; +#23407 = CARTESIAN_POINT ( 'NONE', ( -40.80866763255103535, 127.3612606829378535, 89.59438440199370746 ) ) ; +#23409 = EDGE_CURVE ( 'NONE', #1228, #32479, #10607, .T. ) ; +#23410 = VECTOR ( 'NONE', #2269, 1000.000000000000000 ) ; +#23411 = EDGE_LOOP ( 'NONE', ( #30888, #1264, #34125, #24004 ) ) ; +#23412 = VERTEX_POINT ( 'NONE', #5602 ) ; +#23413 = CARTESIAN_POINT ( 'NONE', ( 14.70300188629267168, 151.6530204554825048, 27.72645225616384934 ) ) ; +#23414 = CARTESIAN_POINT ( 'NONE', ( 37.28954786541507360, 191.0747319291052975, 106.2969461956769095 ) ) ; +#23415 = AXIS2_PLACEMENT_3D ( 'NONE', #5183, #1937, #36470 ) ; +#23416 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082098698, 139.6633459290210055, 297.5876476292032180 ) ) ; +#23417 = ORIENTED_EDGE ( 'NONE', *, *, #4129, .T. ) ; +#23418 = ORIENTED_EDGE ( 'NONE', *, *, #31125, .F. ) ; +#23419 = FACE_OUTER_BOUND ( 'NONE', #27851, .T. ) ; +#23420 = EDGE_LOOP ( 'NONE', ( #7585, #37284, #40123, #11060, #21936, #8976, #28289, #40063, #30772, #26901, #16979, #38072, #22094 ) ) ; +#23421 = ORIENTED_EDGE ( 'NONE', *, *, #22384, .T. ) ; +#23422 = CARTESIAN_POINT ( 'NONE', ( -13.46973633630999956, 173.3942358358999911, 152.4718672074000381 ) ) ; +#23423 = FACE_OUTER_BOUND ( 'NONE', #27605, .T. ) ; +#23424 = FACE_OUTER_BOUND ( 'NONE', #35187, .T. ) ; +#23425 = ORIENTED_EDGE ( 'NONE', *, *, #21342, .F. ) ; +#23426 = EDGE_LOOP ( 'NONE', ( #13889, #32125, #23597, #1141 ) ) ; +#23427 = CARTESIAN_POINT ( 'NONE', ( 14.31745512424952516, 177.1967911514969956, 100.5533783294099663 ) ) ; +#23428 = CARTESIAN_POINT ( 'NONE', ( 3.062765380279557359, 191.9759150222000130, 103.9195978716434610 ) ) ; +#23429 = CARTESIAN_POINT ( 'NONE', ( 26.00024017384605557, 120.0658609975274231, 90.40786069970178573 ) ) ; +#23430 = CARTESIAN_POINT ( 'NONE', ( -25.66867234669999931, 120.7997677173000000, 87.89940608527000165 ) ) ; +#23431 = ORIENTED_EDGE ( 'NONE', *, *, #11032, .F. ) ; +#23432 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971560961 ) ) ; +#23433 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#23434 = ORIENTED_EDGE ( 'NONE', *, *, #23244, .F. ) ; +#23435 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1209, #16934, #23101, #10437, #7543, #32702, #10237, #35523, #20010, #35129, #38027, #7143, #4473, #29029, #19798, #1413, #14302, #39832, #1826, #5288 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 1, 1, 1, 1, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999978351, 0.3749999999999983902, 0.4374999999999962252, 0.4687499999999926170, 0.4843749999999907296, 0.4921874999999897859, 0.4960937499999917843, 0.4980468749999927280, 0.4999999999999937272, 0.7499999999999967804, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23436 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825968346491471, 0.0005734119012694825638 ) ) ; +#23437 = CARTESIAN_POINT ( 'NONE', ( 25.49918375113658087, 117.7860527769602470, 87.75221892551610381 ) ) ; +#23438 = ADVANCED_FACE ( 'NONE', ( #35204 ), #6669, .F. ) ; +#23439 = EDGE_CURVE ( 'NONE', #13145, #34776, #28501, .T. ) ; +#23440 = FACE_OUTER_BOUND ( 'NONE', #2974, .T. ) ; +#23441 = PLANE ( 'NONE', #13114 ) ; +#23442 = ORIENTED_EDGE ( 'NONE', *, *, #5392, .T. ) ; +#23443 = FACE_OUTER_BOUND ( 'NONE', #29876, .T. ) ; +#23444 = VECTOR ( 'NONE', #33271, 1000.000000000000000 ) ; +#23445 = CARTESIAN_POINT ( 'NONE', ( -15.99798258269242623, 173.8482551488953050, 102.8774467584792802 ) ) ; +#23446 = PLANE ( 'NONE', #3841 ) ; +#23447 = VECTOR ( 'NONE', #32836, 1000.000000000000114 ) ; +#23448 = ORIENTED_EDGE ( 'NONE', *, *, #9148, .F. ) ; +#23449 = CARTESIAN_POINT ( 'NONE', ( 5.666342389540173663, 185.9093800082626160, 102.5669869859405026 ) ) ; +#23450 = VECTOR ( 'NONE', #22167, 1000.000000000000000 ) ; +#23451 = CARTESIAN_POINT ( 'NONE', ( -26.00800983458967508, 191.5260122442129216, 103.8858970416150385 ) ) ; +#23452 = CARTESIAN_POINT ( 'NONE', ( 17.31813039954455036, 152.9213809402095023, 180.9051047961254142 ) ) ; +#23453 = AXIS2_PLACEMENT_3D ( 'NONE', #22907, #29032, #7341 ) ; +#23454 = CARTESIAN_POINT ( 'NONE', ( -2.453916141853501820, 205.5673811402000126, 76.30169882352981858 ) ) ; +#23455 = LINE ( 'NONE', #32066, #31084 ) ; +#23456 = ORIENTED_EDGE ( 'NONE', *, *, #32310, .T. ) ; +#23457 = CARTESIAN_POINT ( 'NONE', ( 1.447658035571013802, 152.0519508787176335, 130.6788418760813784 ) ) ; +#23458 = EDGE_CURVE ( 'NONE', #16326, #13844, #2115, .T. ) ; +#23459 = CARTESIAN_POINT ( 'NONE', ( -35.94504593274000825, 192.5960943757999928, 104.9593749602999964 ) ) ; +#23460 = DIRECTION ( 'NONE', ( -0.0005559617608505201727, 0.3907311284922885264, -0.9205046855576908271 ) ) ; +#23461 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#23462 = CARTESIAN_POINT ( 'NONE', ( -23.35635573182313607, 131.0183818788550241, 89.91503395410319399 ) ) ; +#23463 = DIRECTION ( 'NONE', ( 0.6087613505916590340, -0.7729391287937367183, -0.1788147678616013314 ) ) ; +#23464 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988446460639, 156.3551877982853000, 95.75036263590625651 ) ) ; +#23465 = CARTESIAN_POINT ( 'NONE', ( -38.37333053086418744, 118.8333496579262487, 87.72072121845931747 ) ) ; +#23466 = ORIENTED_EDGE ( 'NONE', *, *, #4929, .F. ) ; +#23467 = CARTESIAN_POINT ( 'NONE', ( 5.659893952243699289, 181.0147214850249782, 104.5189528120545646 ) ) ; +#23468 = PLANE ( 'NONE', #17021 ) ; +#23469 = CIRCLE ( 'NONE', #7145, 8.999999999999998224 ) ; +#23470 = CARTESIAN_POINT ( 'NONE', ( 12.31694666161969387, 134.8454845476107096, 93.34277599105703871 ) ) ; +#23471 = ORIENTED_EDGE ( 'NONE', *, *, #30924, .F. ) ; +#23472 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490506714044, 156.2427122712157086, 96.23754757944949745 ) ) ; +#23473 = AXIS2_PLACEMENT_3D ( 'NONE', #26437, #32560, #20281 ) ; +#23474 = CARTESIAN_POINT ( 'NONE', ( 3.725419649892127261, 136.7247895207366355, 94.10044209311497809 ) ) ; +#23475 = AXIS2_PLACEMENT_3D ( 'NONE', #20271, #11090, #1681 ) ; +#23476 = ORIENTED_EDGE ( 'NONE', *, *, #6613, .F. ) ; +#23477 = LINE ( 'NONE', #20817, #23444 ) ; +#23478 = ORIENTED_EDGE ( 'NONE', *, *, #5294, .F. ) ; +#23479 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; +#23480 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#23481 = CARTESIAN_POINT ( 'NONE', ( -12.63532332570012073, 130.1618938156200613, 92.53889310033923721 ) ) ; +#23482 = ADVANCED_FACE ( 'NONE', ( #16602 ), #35376, .F. ) ; +#23483 = EDGE_CURVE ( 'NONE', #326, #36696, #20391, .T. ) ; +#23484 = CARTESIAN_POINT ( 'NONE', ( 37.39851594842701132, 107.7137877614669179, 168.6499130571439196 ) ) ; +#23485 = CARTESIAN_POINT ( 'NONE', ( -5.670177853320987893, 124.7093853677813513, 88.91838017179868814 ) ) ; +#23486 = ORIENTED_EDGE ( 'NONE', *, *, #18512, .F. ) ; +#23487 = CARTESIAN_POINT ( 'NONE', ( 39.04493984371202941, 209.7096538830999748, 73.03492191715572801 ) ) ; +#23488 = DIRECTION ( 'NONE', ( 0.7933533416835718555, -0.5930537051408170113, -0.1373964266575322390 ) ) ; +#23489 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#23490 = ORIENTED_EDGE ( 'NONE', *, *, #28837, .T. ) ; +#23491 = CARTESIAN_POINT ( 'NONE', ( -45.39809028288159709, 124.1809289841894213, 92.62646527380597661 ) ) ; +#23492 = ORIENTED_EDGE ( 'NONE', *, *, #31520, .F. ) ; +#23493 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#23494 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18006, #21518, #2499, #11491, #27655, #18601, #40292, #36837, #31111, #30515, #15172, #14776, #8842, #40092 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999997961075, 0.3749999999997057354, 0.4374999999996544986, 0.4687499999996283528, 0.4843749999996272981, 0.4999999999996261879, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23495 = FACE_OUTER_BOUND ( 'NONE', #28415, .T. ) ; +#23496 = CARTESIAN_POINT ( 'NONE', ( -28.68341338983000455, 124.5116353150000066, 91.63388613658000281 ) ) ; +#23497 = CIRCLE ( 'NONE', #35232, 7.999999999999992895 ) ; +#23498 = CARTESIAN_POINT ( 'NONE', ( -25.84608708632153551, 211.0902257898999892, 73.23808610911966355 ) ) ; +#23499 = CARTESIAN_POINT ( 'NONE', ( -21.21281380558005125, 182.9066539643694966, 104.4588199671594850 ) ) ; +#23500 = VECTOR ( 'NONE', #30252, 1000.000000000000000 ) ; +#23501 = AXIS2_PLACEMENT_3D ( 'NONE', #33703, #14723, #20635 ) ; +#23502 = CARTESIAN_POINT ( 'NONE', ( -28.46708276391288450, 184.0084905153442492, 102.6649762630933651 ) ) ; +#23503 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971552357 ) ) ; +#23504 = ADVANCED_FACE ( 'NONE', ( #39498 ), #17208, .F. ) ; +#23505 = CARTESIAN_POINT ( 'NONE', ( 37.58195705592999758, 118.7990928048999990, 87.12052553435999869 ) ) ; +#23506 = LINE ( 'NONE', #1834, #23138 ) ; +#23507 = CARTESIAN_POINT ( 'NONE', ( 3.188030641335061421, 183.7439365961982674, 102.0716281244637145 ) ) ; +#23508 = ORIENTED_EDGE ( 'NONE', *, *, #34130, .T. ) ; +#23509 = CARTESIAN_POINT ( 'NONE', ( 39.01961099994073123, 121.1792603210347608, 123.5275808920352603 ) ) ; +#23510 = CARTESIAN_POINT ( 'NONE', ( -14.78424370841450042, 128.6742020487672278, 91.93439134535178425 ) ) ; +#23511 = CARTESIAN_POINT ( 'NONE', ( -36.35641993181373266, 191.5958320935953623, 106.4146220668809377 ) ) ; +#23512 = CARTESIAN_POINT ( 'NONE', ( 35.40748609300000282, 112.8223810538000009, 87.09901120572000366 ) ) ; +#23513 = CARTESIAN_POINT ( 'NONE', ( 39.01510395514510776, 128.3961366480688184, 92.35085356743662999 ) ) ; +#23514 = ORIENTED_EDGE ( 'NONE', *, *, #3666, .F. ) ; +#23515 = ORIENTED_EDGE ( 'NONE', *, *, #21338, .T. ) ; +#23516 = EDGE_LOOP ( 'NONE', ( #20463, #35722, #8666, #32007 ) ) ; +#23517 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#23518 = EDGE_CURVE ( 'NONE', #40179, #32617, #20359, .T. ) ; +#23519 = DIRECTION ( 'NONE', ( 0.0005884965073590145944, -0.2249510525036911290, 0.9743698874910607932 ) ) ; +#23520 = CARTESIAN_POINT ( 'NONE', ( 5.664340955981074011, 123.7792148246779078, 91.23079828286975612 ) ) ; +#23521 = EDGE_LOOP ( 'NONE', ( #15742, #10041, #21204, #20617 ) ) ; +#23522 = EDGE_LOOP ( 'NONE', ( #34953, #25604, #28967, #32335 ) ) ; +#23523 = FACE_BOUND ( 'NONE', #2100, .T. ) ; +#23524 = CIRCLE ( 'NONE', #30073, 6.000000000043544723 ) ; +#23525 = ADVANCED_FACE ( 'NONE', ( #29711 ), #1693, .F. ) ; +#23526 = CIRCLE ( 'NONE', #37890, 2.749999999927908334 ) ; +#23527 = CARTESIAN_POINT ( 'NONE', ( -13.49083856689536987, 187.6673735495426740, 106.0664666259349644 ) ) ; +#23528 = ORIENTED_EDGE ( 'NONE', *, *, #25536, .T. ) ; +#23529 = CARTESIAN_POINT ( 'NONE', ( -19.40383092080755745, 125.3891650183175841, 175.7828678101702167 ) ) ; +#23530 = AXIS2_PLACEMENT_3D ( 'NONE', #25998, #13914, #10459 ) ; +#23531 = EDGE_LOOP ( 'NONE', ( #5699, #24354, #36298, #13488 ) ) ; +#23532 = CYLINDRICAL_SURFACE ( 'NONE', #16826, 10.00000000000000533 ) ; +#23533 = EDGE_CURVE ( 'NONE', #26865, #3241, #25221, .T. ) ; +#23534 = ADVANCED_FACE ( 'NONE', ( #18221 ), #39701, .T. ) ; +#23535 = LINE ( 'NONE', #7988, #31325 ) ; +#23536 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 1.005820108796730516E-17, 0.0006039748319389842430 ) ) ; +#23537 = EDGE_LOOP ( 'NONE', ( #38278, #14215, #24186, #40210 ) ) ; +#23538 = CARTESIAN_POINT ( 'NONE', ( -0.4376709669680989845, 188.6085996256109922, 103.1929362358850142 ) ) ; +#23539 = EDGE_CURVE ( 'NONE', #17164, #29960, #28636, .T. ) ; +#23540 = CARTESIAN_POINT ( 'NONE', ( 0.9451061190988069294, 189.0447137624019831, 103.7056411191770025 ) ) ; +#23541 = DIRECTION ( 'NONE', ( 0.5988683521957626210, -0.8008474865655332842, 0.000000000000000000 ) ) ; +#23542 = ORIENTED_EDGE ( 'NONE', *, *, #21570, .T. ) ; +#23543 = CARTESIAN_POINT ( 'NONE', ( -22.19951751066730239, 122.8658642608983484, 176.1889355587336752 ) ) ; +#23544 = ORIENTED_EDGE ( 'NONE', *, *, #27221, .F. ) ; +#23545 = EDGE_LOOP ( 'NONE', ( #14331, #2912, #4902, #25402 ) ) ; +#23546 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37364, #33476, #40419, #33273, #24314, #33885, #5263, #9165, #8763, #27782, #34084, #2429, #17728, #27182, #30221, #39614, #12230, #24720, #11626, #21229 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000069666, 0.1875000000000091038, 0.2187500000000237033, 0.2500000000000383027, 0.3750000000000381362, 0.5000000000000378586, 0.6250000000000376366, 0.7500000000000373035, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23547 = ORIENTED_EDGE ( 'NONE', *, *, #34529, .F. ) ; +#23548 = CARTESIAN_POINT ( 'NONE', ( -38.46044104337040181, 118.4609804511839286, 89.70916240556151422 ) ) ; +#23549 = VERTEX_POINT ( 'NONE', #5773 ) ; +#23550 = CARTESIAN_POINT ( 'NONE', ( -28.17025018105144341, 187.6480004385370819, 102.9918920620223730 ) ) ; +#23551 = CARTESIAN_POINT ( 'NONE', ( -27.38562835820999908, 187.4256067411000117, 105.8479368917000158 ) ) ; +#23552 = FACE_OUTER_BOUND ( 'NONE', #4583, .T. ) ; +#23553 = AXIS2_PLACEMENT_3D ( 'NONE', #15642, #25471, #34234 ) ; +#23554 = ADVANCED_FACE ( 'NONE', ( #28995 ), #4647, .T. ) ; +#23555 = ORIENTED_EDGE ( 'NONE', *, *, #1459, .T. ) ; +#23556 = CARTESIAN_POINT ( 'NONE', ( -20.49839850487972726, 118.3474708296278664, 89.78013583511243212 ) ) ; +#23557 = ORIENTED_EDGE ( 'NONE', *, *, #19851, .T. ) ; +#23558 = CIRCLE ( 'NONE', #14398, 5.499999999656736804 ) ; +#23559 = CARTESIAN_POINT ( 'NONE', ( 27.41836671908999890, 124.2890015699999964, 91.06748153460000594 ) ) ; +#23560 = CONICAL_SURFACE ( 'NONE', #38549, 5.999999999815444518, 0.7853981633778843729 ) ; +#23561 = DIRECTION ( 'NONE', ( -0.0005884949961187637075, 0.2249510543439065258, -0.9743698870671262391 ) ) ; +#23563 = CARTESIAN_POINT ( 'NONE', ( 22.50029346826671173, 138.3995272081080259, 92.10453246904701530 ) ) ; +#23562 = CARTESIAN_POINT ( 'NONE', ( 17.03084806954877095, 121.4891440001390492, 177.4761730266376105 ) ) ; +#23564 = ORIENTED_EDGE ( 'NONE', *, *, #17746, .T. ) ; +#23565 = ORIENTED_EDGE ( 'NONE', *, *, #36480, .T. ) ; +#23566 = CARTESIAN_POINT ( 'NONE', ( -36.19139248826387245, 191.8884328938771944, 104.4137272565322831 ) ) ; +#23567 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17498, #5655, #29801, #2604, #33453, #24489 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23568 = EDGE_LOOP ( 'NONE', ( #24480, #38730, #24513, #2111 ) ) ; +#23569 = CARTESIAN_POINT ( 'NONE', ( 39.15547825205999999, 119.6286442269999952, 90.46801798868999356 ) ) ; +#23570 = DIRECTION ( 'NONE', ( 0.6068735732728635091, 0.7743428331745977333, 0.1791581501750993122 ) ) ; +#23571 = EDGE_CURVE ( 'NONE', #29762, #39475, #32150, .T. ) ; +#23572 = CARTESIAN_POINT ( 'NONE', ( 40.93334977941019304, 181.3867412422068526, 104.5835422556928052 ) ) ; +#23573 = CARTESIAN_POINT ( 'NONE', ( -37.46426832607435387, 111.9935766244044117, 150.7713156516942945 ) ) ; +#23574 = ORIENTED_EDGE ( 'NONE', *, *, #1047, .F. ) ; +#23575 = EDGE_CURVE ( 'NONE', #37873, #19980, #11004, .T. ) ; +#23576 = EDGE_LOOP ( 'NONE', ( #33563, #2513, #24349, #3099 ) ) ; +#23577 = ORIENTED_EDGE ( 'NONE', *, *, #3338, .F. ) ; +#23578 = CARTESIAN_POINT ( 'NONE', ( -12.63691346781947722, 177.4392416099184686, 100.9254952946230901 ) ) ; +#23579 = CARTESIAN_POINT ( 'NONE', ( -2.771263523205826029, 193.9703421779226176, 102.7697054433951678 ) ) ; +#23580 = VECTOR ( 'NONE', #2222, 999.9999999999998863 ) ; +#23581 = ADVANCED_FACE ( 'NONE', ( #10403 ), #29411, .T. ) ; +#23582 = CARTESIAN_POINT ( 'NONE', ( 27.36069733113999902, 124.7149260091999992, 88.77129815678000568 ) ) ; +#23583 = EDGE_CURVE ( 'NONE', #23937, #22722, #13853, .T. ) ; +#23584 = ORIENTED_EDGE ( 'NONE', *, *, #20245, .T. ) ; +#23585 = CARTESIAN_POINT ( 'NONE', ( -35.96364602615999928, 192.3236677699999859, 106.4340467460000212 ) ) ; +#23586 = CONICAL_SURFACE ( 'NONE', #7905, 6.000000000067895023, 0.7853981634347139140 ) ; +#23587 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3322, #28682, #28285, #21753, #22360, #34194, #6990, #15994, #6192, #25228, #461, #65, #28486, #13149, #19462, #18644, #37677, #31151, #3124, #25027, #37476, #6387, #18848, #31350, #13345, #25832, #32700, #17138, #39228 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 1, 2, 2, 1, 1, 2, 2, 1, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.03125000000016738694, 0.04687500000023392399, 0.06250000000030046798, 0.09375000000043354209, 0.1093750000005237893, 0.1250000000006140366, 0.1875000000007510381, 0.2187500000008107681, 0.2343750000008530954, 0.2500000000008953949, 0.3750000000012715939, 0.4375000000014597212, 0.4687500000015364376, 0.4843750000015764612, 0.4921875000015817347, 0.4960937500015843993, 0.5000000000015870638, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23588 = AXIS2_PLACEMENT_3D ( 'NONE', #23270, #13665, #20181 ) ; +#23589 = CONICAL_SURFACE ( 'NONE', #3326, 2.503100863752302896, 0.7853981633869029366 ) ; +#23590 = CARTESIAN_POINT ( 'NONE', ( 3.075358835610300101, 190.8616699574176039, 106.8060003944983833 ) ) ; +#23591 = VERTEX_POINT ( 'NONE', #14682 ) ; +#23592 = FACE_OUTER_BOUND ( 'NONE', #486, .T. ) ; +#23593 = CARTESIAN_POINT ( 'NONE', ( -2.851221542150457200, 209.7096659646922774, 76.06022685436926167 ) ) ; +#23594 = CARTESIAN_POINT ( 'NONE', ( 22.50147045824727599, 137.9496250995102855, 94.05327224295773192 ) ) ; +#23595 = CARTESIAN_POINT ( 'NONE', ( -15.03362232203068771, 151.2943605774707407, 177.4366870137986609 ) ) ; +#23596 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23071, #19972, #35303, #38777, #19169, #34702, #977, #13660, #4444, #19771, #10210 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000003837486, 0.3750000000005756506, 0.4375000000006891709, 0.4687500000006858403, 0.5000000000006824541, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23597 = ORIENTED_EDGE ( 'NONE', *, *, #13981, .F. ) ; +#23598 = DIRECTION ( 'NONE', ( -0.0005884949961238158727, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#23599 = CARTESIAN_POINT ( 'NONE', ( 22.66453919972767039, 213.5901743387830152, 75.54496024088506090 ) ) ; +#23600 = ORIENTED_EDGE ( 'NONE', *, *, #7268, .T. ) ; +#23601 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14489, #11412, #23898, #8359, #15253, #106, #12987, #18687, #10123, #9518, #3552, #7028, #28921, #15833, #9924, #892, #28722, #25875, #38318, #34431, #28526, #700, #13188, #10329, #29518, #35826, #4970, #22993, #7631, #26067, #8040, #38701, #14198, #7835, #20306, #39112, #20499, #35417 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 1, 1, 1, 1, 2, 2, 2, 2, 1, 1, 1, 1, 2, 2, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999995608790, 0.1874999999993424704, 0.2187499999992332522, 0.2343749999991789901, 0.2421874999991508737, 0.2460937499991381339, 0.2480468749991304178, 0.2490234374991269484, 0.2499999999991234789, 0.3749999999991580069, 0.4374999999991762700, 0.4687499999991853739, 0.4843749999991859845, 0.4921874999991874278, 0.4960937499991910360, 0.4980468749991939781, 0.4999999999991968647, 0.6249999999993025579, 0.6874999999993643973, 0.7187499999993987032, 0.7343749999994065858, 0.7421874999994167998, 0.7499999999994269029, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23602 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#23603 = AXIS2_PLACEMENT_3D ( 'NONE', #12512, #25215, #31338 ) ; +#23605 = DIRECTION ( 'NONE', ( 0.0005884949961214528541, -0.2249510543439078303, 0.9743698870671260170 ) ) ; +#23604 = CARTESIAN_POINT ( 'NONE', ( 2.463364856792551905, 209.5677208948551993, 75.55701285043443249 ) ) ; +#23606 = AXIS2_PLACEMENT_3D ( 'NONE', #21848, #34288, #37573 ) ; +#23607 = ORIENTED_EDGE ( 'NONE', *, *, #15506, .F. ) ; +#23608 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749390117, 179.6299767372342160, 101.6260513916748920 ) ) ; +#23609 = AXIS2_PLACEMENT_3D ( 'NONE', #20581, #10991, #30401 ) ; +#23610 = ORIENTED_EDGE ( 'NONE', *, *, #138, .F. ) ; +#23611 = EDGE_CURVE ( 'NONE', #33199, #20733, #7960, .T. ) ; +#23612 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319380788258 ) ) ; +#23613 = EDGE_CURVE ( 'NONE', #34462, #23591, #21612, .T. ) ; +#23614 = DIRECTION ( 'NONE', ( -0.0005884949961279498272, 0.2249510543439066645, -0.9743698870671262391 ) ) ; +#23615 = CARTESIAN_POINT ( 'NONE', ( -24.42625685282789405, 109.6131156702000027, 89.78253759522658584 ) ) ; +#23616 = ADVANCED_BREP_SHAPE_REPRESENTATION ( 'MID360+\X2\76f8673a652f67b6\X0\6.24', ( #1957, #11396 ), #2275 ) ; +#23617 = EDGE_CURVE ( 'NONE', #9198, #36415, #13204, .T. ) ; +#23618 = DIRECTION ( 'NONE', ( -2.530387804365254516E-14, -0.9743700557921585181, -0.2249510932971561239 ) ) ; +#23619 = ORIENTED_EDGE ( 'NONE', *, *, #23518, .T. ) ; +#23620 = EDGE_CURVE ( 'NONE', #27747, #14927, #32857, .T. ) ; +#23621 = VERTEX_POINT ( 'NONE', #36126 ) ; +#23622 = CARTESIAN_POINT ( 'NONE', ( -3.233962871607205081, 183.4879531415897418, 102.0164083997212146 ) ) ; +#23623 = VERTEX_POINT ( 'NONE', #20593 ) ; +#23624 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #39429, #36993, #12057, #11439 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.016443151784193422, 3.056089401325539079 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9998690188640146914, 0.9998690188640146914, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#23625 = ORIENTED_EDGE ( 'NONE', *, *, #6042, .F. ) ; +#23626 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455648834120, -31.54510897440487938, 136.4474729010643159 ) ) ; +#23627 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25477, #709, #3770, #16438 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23628 = CARTESIAN_POINT ( 'NONE', ( 2.877595496360000116, 208.9474331168999868, 73.28391261951000502 ) ) ; +#23629 = ORIENTED_EDGE ( 'NONE', *, *, #32407, .T. ) ; +#23630 = EDGE_CURVE ( 'NONE', #37866, #15089, #33057, .T. ) ; +#23631 = ORIENTED_EDGE ( 'NONE', *, *, #25585, .T. ) ; +#23632 = CARTESIAN_POINT ( 'NONE', ( -0.4361371085228029076, 189.0000000148081654, 105.7376017109280184 ) ) ; +#23633 = FACE_OUTER_BOUND ( 'NONE', #39737, .T. ) ; +#23634 = CARTESIAN_POINT ( 'NONE', ( -35.54692679333999905, 192.3064933894999911, 104.0386506509999975 ) ) ; +#23635 = CARTESIAN_POINT ( 'NONE', ( 37.09773084145999889, 191.6304407382999955, 104.5058401963000136 ) ) ; +#23636 = CARTESIAN_POINT ( 'NONE', ( -25.66777027296999947, 120.6958994388000121, 87.87614527869999392 ) ) ; +#23637 = EDGE_CURVE ( 'NONE', #7336, #17805, #19710, .T. ) ; +#23638 = ORIENTED_EDGE ( 'NONE', *, *, #687, .T. ) ; +#23639 = CARTESIAN_POINT ( 'NONE', ( 1.752039179668189783, 151.6655327357930219, 130.5892088565730091 ) ) ; +#23640 = CYLINDRICAL_SURFACE ( 'NONE', #35202, 2.500000000000003997 ) ; +#23641 = ORIENTED_EDGE ( 'NONE', *, *, #33196, .F. ) ; +#23642 = CARTESIAN_POINT ( 'NONE', ( -20.51827374288739847, 208.4342764294943606, 75.91696062898481046 ) ) ; +#23643 = CARTESIAN_POINT ( 'NONE', ( 25.49921019565536184, 118.1133140256443426, 87.75227232668940758 ) ) ; +#23644 = VECTOR ( 'NONE', #19788, 999.9999999999998863 ) ; +#23645 = CARTESIAN_POINT ( 'NONE', ( 3.046672840563001472, 207.8686389444187341, 77.27521480613795291 ) ) ; +#23646 = ORIENTED_EDGE ( 'NONE', *, *, #33311, .T. ) ; +#23647 = CONICAL_SURFACE ( 'NONE', #33404, 2.499999999873558476, 0.7853981633651732075 ) ; +#23648 = ADVANCED_FACE ( 'NONE', ( #3190 ), #24702, .F. ) ; +#23649 = CARTESIAN_POINT ( 'NONE', ( 14.24259403095196319, 124.1280741090887574, 175.6403682132716426 ) ) ; +#23650 = AXIS2_PLACEMENT_3D ( 'NONE', #30564, #36685, #8698 ) ; +#23651 = FACE_OUTER_BOUND ( 'NONE', #16843, .T. ) ; +#23652 = FACE_OUTER_BOUND ( 'NONE', #3352, .T. ) ; +#23653 = ORIENTED_EDGE ( 'NONE', *, *, #14137, .T. ) ; +#23654 = CARTESIAN_POINT ( 'NONE', ( 20.00004282447493864, 191.5259056233101091, 103.8580927373495371 ) ) ; +#23655 = ORIENTED_EDGE ( 'NONE', *, *, #28982, .T. ) ; +#23656 = CARTESIAN_POINT ( 'NONE', ( -26.12791299326000072, 191.8330791879999992, 103.7958756749000031 ) ) ; +#23657 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31814, #3970, #19512, #23005, #6841, #38137, #7240, #4374, #16245, #7437, #19110, #13201, #26276, #25689, #16443, #1112, #31603, #10539 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999893419, 0.2499999999999786837, 0.3749999999999680256, 0.4374999999999676370, 0.4999999999999672484, 0.6249999999999790168, 0.6874999999999849010, 0.7499999999999907851, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23658 = CARTESIAN_POINT ( 'NONE', ( -9.584790827646999745, 188.0427815642999860, 103.3283854050000201 ) ) ; +#23659 = CARTESIAN_POINT ( 'NONE', ( 25.43225731411000012, 191.0569328349000102, 104.3863169934000013 ) ) ; +#23660 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#23661 = FACE_OUTER_BOUND ( 'NONE', #9692, .T. ) ; +#23662 = ORIENTED_EDGE ( 'NONE', *, *, #38392, .T. ) ; +#23663 = DIRECTION ( 'NONE', ( -0.0002393071182776102175, -0.2252352986010028590, 0.9743043687658493601 ) ) ; +#23664 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#23665 = CARTESIAN_POINT ( 'NONE', ( 20.00025828646017345, 174.5279639952516106, 99.93388581131628712 ) ) ; +#23666 = CARTESIAN_POINT ( 'NONE', ( 22.50034184233011914, 153.8097659799650501, 95.66226703669086362 ) ) ; +#23667 = EDGE_CURVE ( 'NONE', #20961, #5945, #24373, .T. ) ; +#23668 = CARTESIAN_POINT ( 'NONE', ( 19.46082156961019294, 125.9120791161117410, 177.4132114498032422 ) ) ; +#23669 = CARTESIAN_POINT ( 'NONE', ( 32.48294317935824438, 176.0008788113808009, 100.2663086607479244 ) ) ; +#23670 = LINE ( 'NONE', #20589, #33487 ) ; +#23671 = EDGE_CURVE ( 'NONE', #36559, #29017, #15844, .T. ) ; +#23672 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418800025, 218.5902260770999987, 73.08022052563953253 ) ) ; +#23673 = AXIS2_PLACEMENT_3D ( 'NONE', #40407, #9149, #40205 ) ; +#23674 = EDGE_CURVE ( 'NONE', #23190, #18594, #6454, .T. ) ; +#23675 = CARTESIAN_POINT ( 'NONE', ( -1.458415328219441198, 152.0517121881307503, 130.6798743971081365 ) ) ; +#23676 = CARTESIAN_POINT ( 'NONE', ( -38.80490438818794274, 119.2275004425862335, 87.75208274189962765 ) ) ; +#23677 = VERTEX_POINT ( 'NONE', #20510 ) ; +#23678 = EDGE_LOOP ( 'NONE', ( #39418, #7264, #16945, #15104 ) ) ; +#23679 = AXIS2_PLACEMENT_3D ( 'NONE', #10133, #12573, #37527 ) ; +#23680 = CARTESIAN_POINT ( 'NONE', ( 25.99207700458055825, 210.6299893049999810, 76.04276577997849529 ) ) ; +#23681 = CARTESIAN_POINT ( 'NONE', ( -38.87088589341672673, 169.4517328299331780, 182.9034801424807029 ) ) ; +#23682 = EDGE_CURVE ( 'NONE', #16249, #4337, #34938, .T. ) ; +#23683 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12750, #19068, #3736, #34598 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23684 = ORIENTED_EDGE ( 'NONE', *, *, #21383, .F. ) ; +#23685 = LINE ( 'NONE', #8138, #20609 ) ; +#23686 = ORIENTED_EDGE ( 'NONE', *, *, #4685, .T. ) ; +#23687 = EDGE_CURVE ( 'NONE', #33799, #17057, #9992, .T. ) ; +#23688 = CARTESIAN_POINT ( 'NONE', ( -16.89653939414543871, 151.9703269149406424, 184.0152534838730958 ) ) ; +#23689 = CARTESIAN_POINT ( 'NONE', ( 25.61835187867219688, 116.5980403540922765, 87.25231144943825257 ) ) ; +#23690 = VERTEX_POINT ( 'NONE', #27297 ) ; +#23691 = CARTESIAN_POINT ( 'NONE', ( 36.06505478217123795, 192.7057421143160525, 106.3400883098223915 ) ) ; +#23692 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; +#23693 = LINE ( 'NONE', #32685, #8370 ) ; +#23694 = CARTESIAN_POINT ( 'NONE', ( -15.49970618492638508, 127.6313525092815411, 89.64145404642985682 ) ) ; +#23695 = CARTESIAN_POINT ( 'NONE', ( 21.70190315701263017, 123.1837599801819465, 176.5257127422096914 ) ) ; +#23696 = ORIENTED_EDGE ( 'NONE', *, *, #19041, .T. ) ; +#23697 = ADVANCED_FACE ( 'NONE', ( #5591 ), #2536, .T. ) ; +#23698 = CARTESIAN_POINT ( 'NONE', ( -39.71429903588311561, 169.1766066404292985, 164.5230398149320763 ) ) ; +#23699 = CARTESIAN_POINT ( 'NONE', ( 12.63704034694744571, 181.8935201937362933, 101.9167722821602098 ) ) ; +#23700 = AXIS2_PLACEMENT_3D ( 'NONE', #31319, #20976, #36300 ) ; +#23701 = DIRECTION ( 'NONE', ( -0.7066903926851150208, 0.000000000000000000, 0.7075229246367624736 ) ) ; +#23702 = CARTESIAN_POINT ( 'NONE', ( 23.69388335781209776, 131.0246890999723632, 89.88804818403849595 ) ) ; +#23703 = ORIENTED_EDGE ( 'NONE', *, *, #26396, .F. ) ; +#23704 = VECTOR ( 'NONE', #36904, 1000.000000000000000 ) ; +#23705 = CARTESIAN_POINT ( 'NONE', ( -43.00650784327562093, 120.7113638011818750, 92.29910861957030477 ) ) ; +#23706 = CARTESIAN_POINT ( 'NONE', ( -2.436970328474767467, 191.4135392062999870, 104.3588452339995882 ) ) ; +#23707 = CARTESIAN_POINT ( 'NONE', ( -28.27925241266000000, 125.3242495368999982, 91.03020751606000260 ) ) ; +#23708 = AXIS2_PLACEMENT_3D ( 'NONE', #10750, #35257, #19532 ) ; +#23709 = CARTESIAN_POINT ( 'NONE', ( -25.77711092217260358, 212.2744629154549045, 73.07407281147119704 ) ) ; +#23710 = CARTESIAN_POINT ( 'NONE', ( -25.90152905792492177, 209.7106500049521003, 73.18271116922589670 ) ) ; +#23711 = CARTESIAN_POINT ( 'NONE', ( 25.89011449699999901, 191.5660806957999966, 106.7678315448000035 ) ) ; +#23712 = CARTESIAN_POINT ( 'NONE', ( 37.73510322196000288, 118.9927959184999935, 87.11919898040000021 ) ) ; +#23713 = CARTESIAN_POINT ( 'NONE', ( 39.06517727473992352, 190.5638640950986655, 106.5323238486747073 ) ) ; +#23714 = CARTESIAN_POINT ( 'NONE', ( 38.47096800405999772, 118.8680569848000061, 90.10415460253000219 ) ) ; +#23715 = VERTEX_POINT ( 'NONE', #12740 ) ; +#23716 = CARTESIAN_POINT ( 'NONE', ( 25.51044001015309703, 191.4790671403759745, 106.3785283636754855 ) ) ; +#23717 = CARTESIAN_POINT ( 'NONE', ( -6.035968311314003465, 136.6786235697017844, 94.29340140767534706 ) ) ; +#23718 = DIRECTION ( 'NONE', ( -0.9914447795421099663, -0.1272537940605282525, -0.02904687618140097335 ) ) ; +#23719 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971537369 ) ) ; +#23720 = EDGE_CURVE ( 'NONE', #1984, #34777, #28490, .T. ) ; +#23721 = EDGE_CURVE ( 'NONE', #14927, #3624, #15215, .T. ) ; +#23723 = EDGE_LOOP ( 'NONE', ( #36651, #1378, #15050, #38477 ) ) ; +#23722 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971580945 ) ) ; +#23724 = ORIENTED_EDGE ( 'NONE', *, *, #25133, .T. ) ; +#23725 = ORIENTED_EDGE ( 'NONE', *, *, #35422, .T. ) ; +#23726 = ORIENTED_EDGE ( 'NONE', *, *, #1177, .T. ) ; +#23727 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421684034, 185.2348895838669591, 105.4885254536207100 ) ) ; +#23728 = VECTOR ( 'NONE', #4335, 1000.000000000000000 ) ; +#23729 = CARTESIAN_POINT ( 'NONE', ( 19.99941580399983110, 118.1025156334579265, 87.25545403306659864 ) ) ; +#23730 = LINE ( 'NONE', #29869, #13530 ) ; +#23731 = CIRCLE ( 'NONE', #32873, 9.999999999987895904 ) ; +#23732 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21801, #12378, #31193, #27346 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23733 = VERTEX_POINT ( 'NONE', #663 ) ; +#23734 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561239 ) ) ; +#23735 = AXIS2_PLACEMENT_3D ( 'NONE', #14590, #11514, #31335 ) ; +#23736 = CARTESIAN_POINT ( 'NONE', ( -39.64444090039871327, 161.8176364200976707, 196.2252754037533293 ) ) ; +#23737 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 183.4515543678114966, 105.0773313099630855 ) ) ; +#23738 = CARTESIAN_POINT ( 'NONE', ( -35.56060160276999937, 113.4209612089999979, 87.40543740024000385 ) ) ; +#23739 = ORIENTED_EDGE ( 'NONE', *, *, #36822, .T. ) ; +#23740 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; +#23741 = CARTESIAN_POINT ( 'NONE', ( 3.665000663723704477, 187.4035791409591809, 102.9162352551000339 ) ) ; +#23742 = CARTESIAN_POINT ( 'NONE', ( -20.50629817461280169, 199.8811588058565007, 94.82707092103487412 ) ) ; +#23743 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#23744 = CARTESIAN_POINT ( 'NONE', ( 28.18739088310087482, 186.6040837889091506, 105.2826068624289064 ) ) ; +#23745 = CARTESIAN_POINT ( 'NONE', ( -19.37711623718722009, 148.6588772883655736, 183.3364165269119042 ) ) ; +#23746 = ORIENTED_EDGE ( 'NONE', *, *, #10455, .F. ) ; +#23747 = ORIENTED_EDGE ( 'NONE', *, *, #18898, .F. ) ; +#23748 = EDGE_CURVE ( 'NONE', #32876, #6189, #13471, .T. ) ; +#23749 = CARTESIAN_POINT ( 'NONE', ( -1.067684965441970002, 188.6609290045259968, 103.2053738198000019 ) ) ; +#23750 = CARTESIAN_POINT ( 'NONE', ( 0.5998483646439000117, 188.7533020767000096, 103.3645834587000110 ) ) ; +#23751 = CARTESIAN_POINT ( 'NONE', ( 21.70855119580487269, 123.2009557436313401, 176.5136632602473981 ) ) ; +#23752 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4686, #10640, #29442, #17143 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.006242663039495804055, 0.006951143884268293910 ), + .UNSPECIFIED. ) ; +#23753 = ORIENTED_EDGE ( 'NONE', *, *, #14997, .T. ) ; +#23754 = VERTEX_POINT ( 'NONE', #37081 ) ; +#23755 = CARTESIAN_POINT ( 'NONE', ( 1.447658035571013802, 152.0519508787176335, 130.6788418760813784 ) ) ; +#23756 = EDGE_LOOP ( 'NONE', ( #9751, #26169, #30290, #38746 ) ) ; +#23757 = VERTEX_POINT ( 'NONE', #9477 ) ; +#23758 = CIRCLE ( 'NONE', #13974, 5.499999999852380306 ) ; +#23759 = CIRCLE ( 'NONE', #15266, 9.500000000017017499 ) ; +#23760 = EDGE_CURVE ( 'NONE', #23378, #37138, #20778, .T. ) ; +#23761 = ORIENTED_EDGE ( 'NONE', *, *, #22711, .T. ) ; +#23762 = VERTEX_POINT ( 'NONE', #18448 ) ; +#23763 = AXIS2_PLACEMENT_3D ( 'NONE', #32328, #35976, #23128 ) ; +#23764 = CARTESIAN_POINT ( 'NONE', ( 20.80638670441944527, 212.3488676199132783, 73.54615486076477282 ) ) ; +#23765 = FACE_OUTER_BOUND ( 'NONE', #1884, .T. ) ; +#23766 = LINE ( 'NONE', #36219, #38907 ) ; +#23767 = ORIENTED_EDGE ( 'NONE', *, *, #31292, .F. ) ; +#23768 = LINE ( 'NONE', #7807, #37578 ) ; +#23769 = ORIENTED_EDGE ( 'NONE', *, *, #18563, .T. ) ; +#23770 = CARTESIAN_POINT ( 'NONE', ( 26.49585351857600202, 122.3650666170340031, 90.96953248081020149 ) ) ; +#23771 = CARTESIAN_POINT ( 'NONE', ( 40.11622567341476753, 89.23467188456967847, 291.5343147401541160 ) ) ; +#23772 = EDGE_CURVE ( 'NONE', #23677, #29062, #35791, .T. ) ; +#23773 = EDGE_CURVE ( 'NONE', #31566, #26136, #25636, .T. ) ; +#23775 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#23774 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672095143, 184.4039562885918713, 104.7835373820076939 ) ) ; +#23776 = EDGE_CURVE ( 'NONE', #32811, #6019, #36053, .T. ) ; +#23777 = VERTEX_POINT ( 'NONE', #10491 ) ; +#23778 = VERTEX_POINT ( 'NONE', #26233 ) ; +#23779 = VERTEX_POINT ( 'NONE', #16985 ) ; +#23780 = CARTESIAN_POINT ( 'NONE', ( 39.13448785807999997, 118.7961619415000030, 89.51920029467000006 ) ) ; +#23781 = CARTESIAN_POINT ( 'NONE', ( -36.51709733199022168, 117.1641781026797275, 87.28983970377757373 ) ) ; +#23782 = CARTESIAN_POINT ( 'NONE', ( -15.94449010895081642, 152.1461032928982036, 184.5535245782780294 ) ) ; +#23783 = CARTESIAN_POINT ( 'NONE', ( -27.47748879306896086, 186.9397151897404683, 105.3937141543796230 ) ) ; +#23784 = CARTESIAN_POINT ( 'NONE', ( 36.42566904746000489, 191.8206917416999886, 104.3689174806000040 ) ) ; +#23785 = CIRCLE ( 'NONE', #32930, 5.999999999963008257 ) ; +#23786 = VECTOR ( 'NONE', #20610, 1000.000000000000114 ) ; +#23787 = ORIENTED_EDGE ( 'NONE', *, *, #28113, .T. ) ; +#23788 = ORIENTED_EDGE ( 'NONE', *, *, #13646, .F. ) ; +#23789 = CARTESIAN_POINT ( 'NONE', ( -0.9403779577023761993, 189.0417799565218218, 103.6973547697631659 ) ) ; +#23790 = CARTESIAN_POINT ( 'NONE', ( -2.937969491697683733, 193.8169247291332340, 102.7046841998142241 ) ) ; +#23791 = CIRCLE ( 'NONE', #17899, 2.500000000100818021 ) ; +#23792 = CARTESIAN_POINT ( 'NONE', ( 27.59710228827999856, 124.5605221792999941, 88.39323889937000445 ) ) ; +#23793 = ORIENTED_EDGE ( 'NONE', *, *, #32762, .F. ) ; +#23794 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 3.370379598151327408E-34, -0.0006039748319386880390 ) ) ; +#23795 = CARTESIAN_POINT ( 'NONE', ( 3.062734419220130455, 191.5259964270285025, 103.8683342040099831 ) ) ; +#23796 = CARTESIAN_POINT ( 'NONE', ( 2.730912326449253413, 190.9537264196661113, 106.4728235569722585 ) ) ; +#23797 = ORIENTED_EDGE ( 'NONE', *, *, #24400, .T. ) ; +#23798 = CARTESIAN_POINT ( 'NONE', ( -20.51922277227172131, 207.6016423443957422, 74.06967515246797973 ) ) ; +#23799 = CARTESIAN_POINT ( 'NONE', ( 28.70699186420280569, 148.4355579229025750, 96.47039304610791532 ) ) ; +#23800 = CARTESIAN_POINT ( 'NONE', ( 20.18580386471265697, 152.8943896618027338, 94.93918149854322053 ) ) ; +#23801 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#23802 = EDGE_CURVE ( 'NONE', #30783, #15846, #1675, .T. ) ; +#23803 = ORIENTED_EDGE ( 'NONE', *, *, #19147, .T. ) ; +#23804 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38460, #38864, #1451, #32151, #32346, #35778 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23805 = DIRECTION ( 'NONE', ( 0.6087611434179115433, -0.7728348325624404547, -0.1792657018023851023 ) ) ; +#23806 = CARTESIAN_POINT ( 'NONE', ( 40.95827073235999904, 112.8424141243000065, 152.4718672074000381 ) ) ; +#23807 = EDGE_CURVE ( 'NONE', #39104, #28131, #20268, .T. ) ; +#23808 = AXIS2_PLACEMENT_3D ( 'NONE', #3566, #16045, #19313 ) ; +#23809 = AXIS2_PLACEMENT_3D ( 'NONE', #8775, #30848, #15501 ) ; +#23810 = ORIENTED_EDGE ( 'NONE', *, *, #24059, .F. ) ; +#23811 = CARTESIAN_POINT ( 'NONE', ( 31.79629795468130027, 77.14301703112144537, 291.5393397680163616 ) ) ; +#23812 = AXIS2_PLACEMENT_3D ( 'NONE', #15856, #28352, #321 ) ; +#23813 = EDGE_CURVE ( 'NONE', #10234, #13401, #9321, .T. ) ; +#23814 = EDGE_CURVE ( 'NONE', #9576, #3624, #9136, .T. ) ; +#23816 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250907130, 179.1753088543010222, 103.5954339977679126 ) ) ; +#23815 = CARTESIAN_POINT ( 'NONE', ( 13.80919085533496116, 135.4028283656384986, 90.90478696006167070 ) ) ; +#23817 = EDGE_CURVE ( 'NONE', #33081, #7841, #39476, .T. ) ; +#23818 = ORIENTED_EDGE ( 'NONE', *, *, #1179, .F. ) ; +#23819 = ORIENTED_EDGE ( 'NONE', *, *, #9836, .T. ) ; +#23820 = EDGE_CURVE ( 'NONE', #14260, #9552, #18808, .T. ) ; +#23821 = VERTEX_POINT ( 'NONE', #32941 ) ; +#23822 = CARTESIAN_POINT ( 'NONE', ( -1.208357120606557533, 136.1559913323450246, 176.2419420377342760 ) ) ; +#23823 = LINE ( 'NONE', #5192, #17644 ) ; +#23824 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568733 ) ) ; +#23825 = ORIENTED_EDGE ( 'NONE', *, *, #7366, .T. ) ; +#23826 = ORIENTED_EDGE ( 'NONE', *, *, #8732, .F. ) ; +#23827 = DIRECTION ( 'NONE', ( -1.001359783477163956E-17, 0.9743043966640315690, 0.2252353050503800580 ) ) ; +#23828 = ORIENTED_EDGE ( 'NONE', *, *, #21751, .F. ) ; +#23829 = VERTEX_POINT ( 'NONE', #14357 ) ; +#23830 = FACE_OUTER_BOUND ( 'NONE', #29749, .T. ) ; +#23831 = CARTESIAN_POINT ( 'NONE', ( 3.044162729732000194, 208.9211496470000213, 73.11923083157999770 ) ) ; +#23832 = CARTESIAN_POINT ( 'NONE', ( -2.851224489384554861, 209.7096574326964458, 76.06022722088786736 ) ) ; +#23833 = ORIENTED_EDGE ( 'NONE', *, *, #28034, .T. ) ; +#23834 = ORIENTED_EDGE ( 'NONE', *, *, #31018, .T. ) ; +#23835 = DIRECTION ( 'NONE', ( 0.7072262180194089920, 0.6509452856072081017, 0.2758646619118033660 ) ) ; +#23836 = CARTESIAN_POINT ( 'NONE', ( -40.80866763254666552, 127.3612606828822891, 89.59438440209265764 ) ) ; +#23837 = CARTESIAN_POINT ( 'NONE', ( -35.65792458881000471, 191.9570647582000049, 104.0584178364000110 ) ) ; +#23838 = CARTESIAN_POINT ( 'NONE', ( 36.58238559271000412, 191.1514690895999991, 103.6232305048999933 ) ) ; +#23839 = VERTEX_POINT ( 'NONE', #18202 ) ; +#23840 = DIRECTION ( 'NONE', ( -0.0005884949961261976481, 0.2255194585872562218, -0.9742384859325514679 ) ) ; +#23841 = AXIS2_PLACEMENT_3D ( 'NONE', #12576, #37531, #27564 ) ; +#23842 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319394906738 ) ) ; +#23843 = ORIENTED_EDGE ( 'NONE', *, *, #13946, .F. ) ; +#23844 = CARTESIAN_POINT ( 'NONE', ( -20.49973909911777881, 191.9757886370473443, 104.4339460251406706 ) ) ; +#23845 = CARTESIAN_POINT ( 'NONE', ( -76.10925030609094222, 156.2249461908077421, 96.27941314734424338 ) ) ; +#23846 = CARTESIAN_POINT ( 'NONE', ( -15.49892152445502269, 185.4935632634996807, 104.3684056661689397 ) ) ; +#23847 = ORIENTED_EDGE ( 'NONE', *, *, #9641, .F. ) ; +#23848 = VECTOR ( 'NONE', #19644, 1000.000000000000114 ) ; +#23849 = DIRECTION ( 'NONE', ( -0.0005884949961209497843, 0.2249510543439031118, -0.9743698870671271273 ) ) ; +#23850 = DIRECTION ( 'NONE', ( 0.9999998268369121313, 0.0001323825517318003638, -0.0005734117245120936733 ) ) ; +#23851 = VECTOR ( 'NONE', #8396, 1000.000000000000000 ) ; +#23852 = CARTESIAN_POINT ( 'NONE', ( 24.12246166080794652, 148.1961369715741341, 202.2538559978290493 ) ) ; +#23853 = CARTESIAN_POINT ( 'NONE', ( 30.07038801304316777, 174.6845315262252143, 103.0427758964743816 ) ) ; +#23854 = ORIENTED_EDGE ( 'NONE', *, *, #14824, .T. ) ; +#23855 = LINE ( 'NONE', #30189, #25730 ) ; +#23856 = LINE ( 'NONE', #33442, #1650 ) ; +#23857 = CARTESIAN_POINT ( 'NONE', ( -15.99970515225999179, 151.9770228117144484, 94.74935186622352035 ) ) ; +#23858 = EDGE_CURVE ( 'NONE', #11457, #13536, #33754, .T. ) ; +#23859 = ORIENTED_EDGE ( 'NONE', *, *, #24909, .F. ) ; +#23860 = CARTESIAN_POINT ( 'NONE', ( 20.48555995111231809, 211.0898943587194481, 73.54694346759191603 ) ) ; +#23861 = CARTESIAN_POINT ( 'NONE', ( -12.60649365401999944, 165.2216646563843199, 152.9217693939943388 ) ) ; +#23862 = CARTESIAN_POINT ( 'NONE', ( 36.11364262193256280, 191.5260145455536929, 103.8483746271915322 ) ) ; +#23863 = CARTESIAN_POINT ( 'NONE', ( -24.55651442736381895, 213.0895335167360543, 73.57320146239435132 ) ) ; +#23864 = EDGE_CURVE ( 'NONE', #14925, #17057, #36004, .T. ) ; +#23865 = CARTESIAN_POINT ( 'NONE', ( 5.674687014606257129, 130.3475820607916660, 92.82156578849662765 ) ) ; +#23866 = DIRECTION ( 'NONE', ( -0.0006039748319388143485, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#23867 = ORIENTED_EDGE ( 'NONE', *, *, #38295, .F. ) ; +#23868 = EDGE_CURVE ( 'NONE', #24000, #28951, #27652, .T. ) ; +#23869 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2117, #20916, #23179, #5569 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23870 = CIRCLE ( 'NONE', #6225, 2.250000000025557778 ) ; +#23871 = DIRECTION ( 'NONE', ( -0.0005884949961229519804, 0.2249510543439058041, -0.9743698870671265722 ) ) ; +#23872 = EDGE_CURVE ( 'NONE', #32617, #8891, #37828, .T. ) ; +#23873 = AXIS2_PLACEMENT_3D ( 'NONE', #34484, #25326, #15310 ) ; +#23874 = CARTESIAN_POINT ( 'NONE', ( 23.39351881373000097, 163.2729245447999915, 152.4718672074000381 ) ) ; +#23876 = AXIS2_PLACEMENT_3D ( 'NONE', #592, #12671, #793 ) ; +#23875 = CARTESIAN_POINT ( 'NONE', ( 20.31643133402063128, 211.0882409943167204, 73.38274506984599554 ) ) ; +#23877 = CARTESIAN_POINT ( 'NONE', ( 13.50046316317049566, 187.7460073498711495, 103.5025028263219014 ) ) ; +#23878 = DIRECTION ( 'NONE', ( 0.7856637149787866203, -0.6186538021912836305, 0.000000000000000000 ) ) ; +#23879 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#23880 = VECTOR ( 'NONE', #6601, 1000.000000000000000 ) ; +#23881 = CARTESIAN_POINT ( 'NONE', ( 28.70581487418796129, 148.8854600315911796, 94.52165327196804867 ) ) ; +#23882 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39913, #11714, #30730, #8862 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23883 = DIRECTION ( 'NONE', ( 0.0005884949961246697904, -0.2249510543439056376, 0.9743698870671265722 ) ) ; +#23884 = ORIENTED_EDGE ( 'NONE', *, *, #31664, .T. ) ; +#23885 = ORIENTED_EDGE ( 'NONE', *, *, #21797, .F. ) ; +#23886 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971570121 ) ) ; +#23887 = CARTESIAN_POINT ( 'NONE', ( 3.755190925667593937, 144.1654378765031765, 93.16053287089553692 ) ) ; +#23888 = FACE_BOUND ( 'NONE', #31684, .T. ) ; +#23889 = EDGE_LOOP ( 'NONE', ( #38914, #5634, #26775, #30644 ) ) ; +#23890 = LINE ( 'NONE', #17722, #1763 ) ; +#23891 = CARTESIAN_POINT ( 'NONE', ( -6.272775217941449988, 148.2033965809511074, 96.43792127017829330 ) ) ; +#23892 = VERTEX_POINT ( 'NONE', #21709 ) ; +#23893 = CARTESIAN_POINT ( 'NONE', ( 0.04503145192458000295, 271.9029643395999756, 74.55847715811999876 ) ) ; +#23894 = LINE ( 'NONE', #33883, #13155 ) ; +#23895 = ORIENTED_EDGE ( 'NONE', *, *, #13788, .T. ) ; +#23896 = DIRECTION ( 'NONE', ( 0.0006039748319382907873, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#23897 = CARTESIAN_POINT ( 'NONE', ( 3.535852102820259191, 167.8277681301466941, 101.4758341492079410 ) ) ; +#23898 = CARTESIAN_POINT ( 'NONE', ( -36.07906380798383594, 114.1210279025020640, 89.76624208691289653 ) ) ; +#23899 = CARTESIAN_POINT ( 'NONE', ( -77.80691370946981067, 191.9356020547612900, 194.2498739115223145 ) ) ; +#23900 = CONICAL_SURFACE ( 'NONE', #9536, 6.000002063501014504, 0.7853981633766364823 ) ; +#23901 = DIRECTION ( 'NONE', ( -0.6087614115774880874, -0.7729348350621346730, -0.1788331191967951483 ) ) ; +#23902 = ORIENTED_EDGE ( 'NONE', *, *, #16273, .T. ) ; +#23903 = CARTESIAN_POINT ( 'NONE', ( 38.96275200744000244, 119.0759358096000113, 87.81759083996999493 ) ) ; +#23904 = DIRECTION ( 'NONE', ( -9.819286345289026293E-14, -0.9743700557546187691, -0.2249510934597585554 ) ) ; +#23905 = DIRECTION ( 'NONE', ( 0.0005884949961232365835, -0.2249510543439025012, 0.9743698870671272383 ) ) ; +#23906 = ADVANCED_FACE ( 'NONE', ( #27855 ), #17140, .F. ) ; +#23907 = VECTOR ( 'NONE', #30157, 1000.000000000000114 ) ; +#23909 = ORIENTED_EDGE ( 'NONE', *, *, #19418, .F. ) ; +#23908 = EDGE_CURVE ( 'NONE', #5720, #13097, #30907, .T. ) ; +#23910 = CARTESIAN_POINT ( 'NONE', ( 16.56210604780206097, 152.2139753621886200, 181.5173256375959454 ) ) ; +#23911 = VERTEX_POINT ( 'NONE', #15745 ) ; +#23912 = EDGE_CURVE ( 'NONE', #4266, #39205, #2141, .T. ) ; +#23913 = CONICAL_SURFACE ( 'NONE', #6258, 59.40509992922268623, 0.7853981633972876297 ) ; +#23914 = ORIENTED_EDGE ( 'NONE', *, *, #15038, .F. ) ; +#23915 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#23916 = EDGE_CURVE ( 'NONE', #36914, #8, #12690, .T. ) ; +#23917 = CARTESIAN_POINT ( 'NONE', ( -42.90458491324071133, 121.0778554138752696, 91.06191244779695637 ) ) ; +#23918 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#23919 = CARTESIAN_POINT ( 'NONE', ( -38.93661188361225811, 190.9636370701329042, 106.3296290494274814 ) ) ; +#23920 = CARTESIAN_POINT ( 'NONE', ( -26.01494426630450008, 211.0902259182902014, 73.07465174665132679 ) ) ; +#23921 = ADVANCED_FACE ( 'NONE', ( #29440 ), #29033, .T. ) ; +#23922 = FACE_OUTER_BOUND ( 'NONE', #36068, .T. ) ; +#23923 = CARTESIAN_POINT ( 'NONE', ( -20.89285664280696864, 129.6089482465050366, 89.58812326051432251 ) ) ; +#23924 = CARTESIAN_POINT ( 'NONE', ( 19.98232544185748694, 209.7096131673859816, 76.04619115725449774 ) ) ; +#23925 = EDGE_CURVE ( 'NONE', #7306, #11263, #38818, .T. ) ; +#23926 = CARTESIAN_POINT ( 'NONE', ( 38.31866179960999830, 118.8458981293999983, 87.57078246666000609 ) ) ; +#23927 = CARTESIAN_POINT ( 'NONE', ( 37.43095215650283336, 132.6072067203139966, 336.9709689194860402 ) ) ; +#23928 = DIRECTION ( 'NONE', ( 0.9999998355993788834, 0.000000000000000000, -0.0005734119072321743841 ) ) ; +#23929 = ORIENTED_EDGE ( 'NONE', *, *, #8601, .T. ) ; +#23930 = CARTESIAN_POINT ( 'NONE', ( -19.99823416869160653, 118.9403737594142854, 90.20346087292679726 ) ) ; +#23931 = CARTESIAN_POINT ( 'NONE', ( -34.02805798185369213, 127.1714145380894934, 297.5790971239380269 ) ) ; +#23932 = AXIS2_PLACEMENT_3D ( 'NONE', #10168, #19733, #34862 ) ; +#23933 = CARTESIAN_POINT ( 'NONE', ( 35.67229871239999994, 112.8254580524999966, 87.36424608503999423 ) ) ; +#23934 = CIRCLE ( 'NONE', #18033, 22.00000000001089973 ) ; +#23936 = ORIENTED_EDGE ( 'NONE', *, *, #18850, .F. ) ; +#23935 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178587041921E-05, 0.0002331579774917524482 ) ) ; +#23937 = VERTEX_POINT ( 'NONE', #13100 ) ; +#23938 = ORIENTED_EDGE ( 'NONE', *, *, #11278, .F. ) ; +#23939 = DIRECTION ( 'NONE', ( -3.469446951775313086E-15, 0.9743700557921582961, 0.2249510932971566790 ) ) ; +#23940 = ORIENTED_EDGE ( 'NONE', *, *, #4323, .F. ) ; +#23941 = CARTESIAN_POINT ( 'NONE', ( 26.80352412410122653, 110.6131156702000027, 87.25159563508790939 ) ) ; +#23942 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971541810 ) ) ; +#23943 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2525, #17829, #21344, #24416 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23944 = AXIS2_PLACEMENT_3D ( 'NONE', #9922, #19298, #3359 ) ; +#23945 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37345, #31616, #37538, #12806 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999992928476323373 ), + .UNSPECIFIED. ) ; +#23946 = VERTEX_POINT ( 'NONE', #20012 ) ; +#23947 = CARTESIAN_POINT ( 'NONE', ( 41.04524146633079340, 217.7719116456999870, 73.53371387620883581 ) ) ; +#23948 = LINE ( 'NONE', #8612, #31917 ) ; +#23949 = CARTESIAN_POINT ( 'NONE', ( -20.35105629446761810, 205.4136997713417827, 76.24793642633174784 ) ) ; +#23950 = CARTESIAN_POINT ( 'NONE', ( -37.98047323488999893, 118.5895443490000076, 87.61478617256000234 ) ) ; +#23951 = ORIENTED_EDGE ( 'NONE', *, *, #32216, .T. ) ; +#23952 = LINE ( 'NONE', #11882, #17297 ) ; +#23953 = ORIENTED_EDGE ( 'NONE', *, *, #7348, .T. ) ; +#23954 = LINE ( 'NONE', #11067, #18777 ) ; +#23955 = CARTESIAN_POINT ( 'NONE', ( -6.678738644527168193E-14, 150.3212993284946606, 97.43624128390267458 ) ) ; +#23956 = FACE_OUTER_BOUND ( 'NONE', #10553, .T. ) ; +#23957 = ORIENTED_EDGE ( 'NONE', *, *, #36264, .T. ) ; +#23958 = CARTESIAN_POINT ( 'NONE', ( -45.30254285283432836, 123.8728708323052530, 93.41010951591879063 ) ) ; +#23959 = CARTESIAN_POINT ( 'NONE', ( 0.6024761863935000905, 188.6227430405999996, 103.2008371842000116 ) ) ; +#23960 = DIRECTION ( 'NONE', ( 0.7730662169443226484, 0.5272861007345267526, 0.3526159273084130130 ) ) ; +#23961 = CARTESIAN_POINT ( 'NONE', ( -36.15565225323541654, 190.9881546654719955, 106.8454183269966933 ) ) ; +#23962 = AXIS2_PLACEMENT_3D ( 'NONE', #12179, #6028, #30583 ) ; +#23963 = EDGE_CURVE ( 'NONE', #18635, #36684, #35396, .T. ) ; +#23964 = ORIENTED_EDGE ( 'NONE', *, *, #12189, .F. ) ; +#23965 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319697732, 89.77447388934736239, 291.5295797804315612 ) ) ; +#23966 = EDGE_CURVE ( 'NONE', #35463, #17707, #3424, .T. ) ; +#23967 = VECTOR ( 'NONE', #33518, 1000.000000000000000 ) ; +#23968 = EDGE_LOOP ( 'NONE', ( #19877, #15138, #26985, #18783 ) ) ; +#23969 = AXIS2_PLACEMENT_3D ( 'NONE', #23457, #22670, #17295 ) ; +#23970 = AXIS2_PLACEMENT_3D ( 'NONE', #28312, #28120, #10918 ) ; +#23971 = EDGE_LOOP ( 'NONE', ( #36611, #1590, #2759 ) ) ; +#23972 = VERTEX_POINT ( 'NONE', #4475 ) ; +#23973 = CARTESIAN_POINT ( 'NONE', ( -28.52670407937950969, 187.4270078119665754, 102.9410870260050928 ) ) ; +#23974 = DIRECTION ( 'NONE', ( -0.0004161288024659176468, -0.5299192578491020988, -0.8480479980505092330 ) ) ; +#23975 = DIRECTION ( 'NONE', ( -0.1305262051638081122, -0.9660383184132187440, -0.2230086929312311284 ) ) ; +#23976 = CARTESIAN_POINT ( 'NONE', ( -25.50905134446982814, 211.0902258593999932, 74.90585137389213344 ) ) ; +#23977 = ORIENTED_EDGE ( 'NONE', *, *, #19678, .F. ) ; +#23978 = LINE ( 'NONE', #26434, #10829 ) ; +#23979 = ORIENTED_EDGE ( 'NONE', *, *, #18634, .F. ) ; +#23980 = CARTESIAN_POINT ( 'NONE', ( 27.65543316470899526, 123.9742713734289907, 91.34205566895781203 ) ) ; +#23981 = CARTESIAN_POINT ( 'NONE', ( -35.46040159328508423, 192.0851836084571573, 103.9436889710039509 ) ) ; +#23983 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#23982 = LINE ( 'NONE', #23562, #30402 ) ; +#23984 = VERTEX_POINT ( 'NONE', #1010 ) ; +#23985 = ADVANCED_FACE ( 'NONE', ( #13497 ), #32109, .F. ) ; +#23986 = ORIENTED_EDGE ( 'NONE', *, *, #34992, .F. ) ; +#23987 = AXIS2_PLACEMENT_3D ( 'NONE', #27367, #33861, #15272 ) ; +#23988 = ORIENTED_EDGE ( 'NONE', *, *, #13200, .F. ) ; +#23989 = CARTESIAN_POINT ( 'NONE', ( 39.08959358783000226, 118.7615907617999937, 89.51972163240000668 ) ) ; +#23990 = CARTESIAN_POINT ( 'NONE', ( 12.50955560414800338, 154.7292631241200809, 156.6833918255910874 ) ) ; +#23991 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19240, #35171, #25413, #7183 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 1.364025899357880227E-07, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#23992 = CARTESIAN_POINT ( 'NONE', ( 25.99211731546482795, 209.7096512574500480, 76.04280604205342797 ) ) ; +#23993 = CARTESIAN_POINT ( 'NONE', ( 19.99976926757112849, 160.7481248081381295, 96.75239270071580222 ) ) ; +#23994 = ORIENTED_EDGE ( 'NONE', *, *, #14905, .F. ) ; +#23995 = ORIENTED_EDGE ( 'NONE', *, *, #1816, .T. ) ; +#23996 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319388572829 ) ) ; +#23997 = CARTESIAN_POINT ( 'NONE', ( 15.69892041351113932, 187.1166384466105796, 102.8427215779686605 ) ) ; +#23998 = ORIENTED_EDGE ( 'NONE', *, *, #14355, .T. ) ; +#23999 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#24000 = VERTEX_POINT ( 'NONE', #39027 ) ; +#24001 = ADVANCED_FACE ( 'NONE', ( #23922 ), #8023, .F. ) ; +#24002 = CARTESIAN_POINT ( 'NONE', ( 2.633415369384000115, 190.2731404274000226, 106.2916909573000055 ) ) ; +#24003 = EDGE_CURVE ( 'NONE', #28125, #33123, #19103, .T. ) ; +#24004 = ORIENTED_EDGE ( 'NONE', *, *, #7077, .F. ) ; +#24005 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049171541, 157.6243160761467266, 99.14398654756077178 ) ) ; +#24006 = CARTESIAN_POINT ( 'NONE', ( -22.99922046160000022, 115.1130721137993191, 90.28167579205376114 ) ) ; +#24007 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971550137 ) ) ; +#24008 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825940092507032, 0.0005734119019213044762 ) ) ; +#24009 = AXIS2_PLACEMENT_3D ( 'NONE', #31336, #3495, #8869 ) ; +#24010 = ORIENTED_EDGE ( 'NONE', *, *, #34309, .T. ) ; +#24011 = CARTESIAN_POINT ( 'NONE', ( 25.99161516108275904, 205.5538991746897750, 75.22020848238861390 ) ) ; +#24012 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#24013 = AXIS2_PLACEMENT_3D ( 'NONE', #10600, #32856, #26543 ) ; +#24014 = CARTESIAN_POINT ( 'NONE', ( 58.66975477332916711, 246.4867810014529823, 202.1076182964096120 ) ) ; +#24015 = VERTEX_POINT ( 'NONE', #26787 ) ; +#24016 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#24017 = ORIENTED_EDGE ( 'NONE', *, *, #22063, .T. ) ; +#24019 = CARTESIAN_POINT ( 'NONE', ( 2.546554931011165923, 207.4083916550792424, 77.08013917139633975 ) ) ; +#24018 = CARTESIAN_POINT ( 'NONE', ( 24.01770307888959621, 118.3486789263952517, 189.6358675532988229 ) ) ; +#24020 = VERTEX_POINT ( 'NONE', #8379 ) ; +#24021 = ORIENTED_EDGE ( 'NONE', *, *, #12194, .T. ) ; +#24022 = ADVANCED_FACE ( 'NONE', ( #17953 ), #14553, .F. ) ; +#24023 = ORIENTED_EDGE ( 'NONE', *, *, #29904, .T. ) ; +#24024 = CARTESIAN_POINT ( 'NONE', ( 2.923530179117999950, 209.0467129328000055, 76.04238949198999364 ) ) ; +#24025 = LINE ( 'NONE', #14623, #38546 ) ; +#24026 = CARTESIAN_POINT ( 'NONE', ( 44.18542131443735599, 185.8340086539333527, 107.6130707359650671 ) ) ; +#24027 = CARTESIAN_POINT ( 'NONE', ( 12.64087841763192976, 177.6494266093880583, 100.7817535531127220 ) ) ; +#24028 = ORIENTED_EDGE ( 'NONE', *, *, #26538, .T. ) ; +#24029 = VERTEX_POINT ( 'NONE', #39232 ) ; +#24030 = CARTESIAN_POINT ( 'NONE', ( -14.16859886990510731, 176.0439122282943458, 102.8701808096547126 ) ) ; +#24031 = ORIENTED_EDGE ( 'NONE', *, *, #24145, .F. ) ; +#24032 = ORIENTED_EDGE ( 'NONE', *, *, #39168, .F. ) ; +#24033 = DIRECTION ( 'NONE', ( -0.0006039748319385906776, -1.894780628693970208E-14, -0.9999998176071844824 ) ) ; +#24034 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498896523, 176.3880814481161678, 103.4433606027125876 ) ) ; +#24035 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319697732, 89.77447388934736239, 291.5295797804315612 ) ) ; +#24036 = VERTEX_POINT ( 'NONE', #8169 ) ; +#24037 = EDGE_CURVE ( 'NONE', #39966, #8486, #30861, .T. ) ; +#24038 = CONICAL_SURFACE ( 'NONE', #9677, 10.00000000001786482, 0.7853981633973029508 ) ; +#24039 = EDGE_LOOP ( 'NONE', ( #22824, #5348, #32212, #15507 ) ) ; +#24040 = FACE_OUTER_BOUND ( 'NONE', #35745, .T. ) ; +#24041 = CARTESIAN_POINT ( 'NONE', ( 22.99270477044632344, 214.0899081099834689, 76.04459013870678064 ) ) ; +#24042 = CARTESIAN_POINT ( 'NONE', ( -35.89237578347999857, 192.0714260180999986, 104.3144186237000213 ) ) ; +#24043 = FACE_OUTER_BOUND ( 'NONE', #2419, .T. ) ; +#24044 = ORIENTED_EDGE ( 'NONE', *, *, #37060, .F. ) ; +#24045 = LINE ( 'NONE', #8089, #15049 ) ; +#24046 = AXIS2_PLACEMENT_3D ( 'NONE', #6858, #16068, #31421 ) ; +#24047 = ADVANCED_FACE ( 'NONE', ( #15703 ), #6043, .F. ) ; +#24048 = VERTEX_POINT ( 'NONE', #6102 ) ; +#24049 = FACE_OUTER_BOUND ( 'NONE', #12968, .T. ) ; +#24050 = CYLINDRICAL_SURFACE ( 'NONE', #38250, 4.000000000000000000 ) ; +#24051 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; +#24052 = ORIENTED_EDGE ( 'NONE', *, *, #19999, .F. ) ; +#24053 = CARTESIAN_POINT ( 'NONE', ( 0.8403833798046884684, 188.6282387687823530, 103.2006762577494499 ) ) ; +#24054 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39908, #5359, #8653, #18017, #18223, #30727, #27878, #2719, #27671, #33970, #5971, #22125, #829, #3097, #34368, #22726, #19026, #15961, #31517, #38046 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999693301, 0.1874999999999585332, 0.2187499999999572564, 0.2343749999999562295, 0.2499999999999552025, 0.4999999999999809042, 0.6249999999999945599, 0.6875000000000004441, 0.7187500000000023315, 0.7343750000000032196, 0.7500000000000041078, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24055 = EDGE_CURVE ( 'NONE', #19089, #9253, #10083, .T. ) ; +#24056 = CARTESIAN_POINT ( 'NONE', ( -14.42530073247155720, 176.7775577408967536, 100.6450012727129604 ) ) ; +#24057 = ADVANCED_FACE ( 'NONE', ( #10140 ), #34758, .T. ) ; +#24058 = LINE ( 'NONE', #27342, #36632 ) ; +#24059 = EDGE_CURVE ( 'NONE', #40319, #24779, #7048, .T. ) ; +#24060 = ORIENTED_EDGE ( 'NONE', *, *, #25588, .F. ) ; +#24061 = CARTESIAN_POINT ( 'NONE', ( -21.09366915965894052, 182.9316659667568672, 101.8987661775678646 ) ) ; +#24062 = EDGE_CURVE ( 'NONE', #37119, #3824, #14934, .T. ) ; +#24063 = CARTESIAN_POINT ( 'NONE', ( 2.243807508789410932, 189.9164095999701942, 103.9478535516479525 ) ) ; +#24064 = CARTESIAN_POINT ( 'NONE', ( 27.20828230392673319, 188.6004222997412967, 103.1783301543543558 ) ) ; +#24065 = ORIENTED_EDGE ( 'NONE', *, *, #8155, .F. ) ; +#24066 = CARTESIAN_POINT ( 'NONE', ( -38.36106832263448752, 118.8212171802660606, 87.72011982685570786 ) ) ; +#24067 = VERTEX_POINT ( 'NONE', #16052 ) ; +#24068 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #12722, #2732, #34568, #31538 ), + .UNSPECIFIED., .F., .F. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.944787670326749243E-14, 1.570060973614819666 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8049111466635345824, 0.8049111466635345824, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#24069 = CARTESIAN_POINT ( 'NONE', ( -5.668109638568818553, 183.4491308723886789, 105.0878286196073645 ) ) ; +#24070 = CARTESIAN_POINT ( 'NONE', ( -12.63810009328765815, 175.3544237672228121, 100.1411543447596983 ) ) ; +#24071 = CARTESIAN_POINT ( 'NONE', ( 25.37978428000000264, 192.2113631761999955, 104.5397008112999941 ) ) ; +#24072 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #40067, #34128, #37415, #30487 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 1.247272850135699217E-05, 0.0003357035447835687012 ), + .UNSPECIFIED. ) ; +#24073 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474974874276943, 155.7928101624827946, 98.18628735359691007 ) ) ; +#24074 = ORIENTED_EDGE ( 'NONE', *, *, #3760, .T. ) ; +#24075 = VECTOR ( 'NONE', #1552, 1000.000000000000000 ) ; +#24076 = VECTOR ( 'NONE', #35210, 1000.000000000000114 ) ; +#24077 = DIRECTION ( 'NONE', ( -0.6087614810001763521, 0.7729390313185928729, 0.1788147452386053549 ) ) ; +#24078 = CARTESIAN_POINT ( 'NONE', ( 19.99866638146631104, 191.9758059840616227, 106.9124836309507884 ) ) ; +#24079 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971574562 ) ) ; +#24080 = CARTESIAN_POINT ( 'NONE', ( -3.763919581963022676, 137.3023230737443896, 91.58620352610245163 ) ) ; +#24081 = CARTESIAN_POINT ( 'NONE', ( -19.99970941558080284, 118.1131156714892114, 90.27986793006986943 ) ) ; +#24082 = CARTESIAN_POINT ( 'NONE', ( -25.99970180910912632, 119.7153706046975543, 90.38600776144058102 ) ) ; +#24083 = CARTESIAN_POINT ( 'NONE', ( -25.49004383460846057, 191.2291505275362340, 106.3759092483763737 ) ) ; +#24084 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#24085 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#24086 = ORIENTED_EDGE ( 'NONE', *, *, #6659, .T. ) ; +#24087 = FACE_OUTER_BOUND ( 'NONE', #21021, .T. ) ; +#24088 = CARTESIAN_POINT ( 'NONE', ( -32.08517628747592454, 135.8679722276884263, 91.03989294943069410 ) ) ; +#24089 = EDGE_CURVE ( 'NONE', #726, #21825, #19317, .T. ) ; +#24090 = ORIENTED_EDGE ( 'NONE', *, *, #1269, .F. ) ; +#24091 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684796025, 217.7719116314000019, 75.57961659102821272 ) ) ; +#24092 = CARTESIAN_POINT ( 'NONE', ( 22.95436083522999837, 211.0902260770999987, 13.53038997162000001 ) ) ; +#24093 = EDGE_LOOP ( 'NONE', ( #5194, #3986 ) ) ; +#24094 = LINE ( 'NONE', #2218, #38544 ) ; +#24095 = VECTOR ( 'NONE', #14940, 1000.000000000000114 ) ; +#24096 = EDGE_CURVE ( 'NONE', #25840, #20231, #18313, .T. ) ; +#24097 = CARTESIAN_POINT ( 'NONE', ( 16.23669227365375178, 152.0555296727118559, 181.0551735875241093 ) ) ; +#24098 = DIRECTION ( 'NONE', ( 0.0006039748319390980842, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#24099 = FACE_OUTER_BOUND ( 'NONE', #4547, .T. ) ; +#24100 = VERTEX_POINT ( 'NONE', #3174 ) ; +#24101 = CARTESIAN_POINT ( 'NONE', ( 30.77384432821773075, 154.8931025985799863, 195.9769581536852741 ) ) ; +#24102 = EDGE_CURVE ( 'NONE', #34936, #28826, #6155, .T. ) ; +#24103 = AXIS2_PLACEMENT_3D ( 'NONE', #5275, #23489, #11420 ) ; +#24104 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#24105 = CONICAL_SURFACE ( 'NONE', #19494, 2.999999999919165550, 0.7853981633921003347 ) ; +#24106 = CARTESIAN_POINT ( 'NONE', ( -46.25578703409212267, 126.0671570396426659, 91.86466764140388364 ) ) ; +#24107 = DIRECTION ( 'NONE', ( -0.7856637153356348380, 0.6186538017381019161, 0.000000000000000000 ) ) ; +#24108 = VECTOR ( 'NONE', #810, 1000.000000000000227 ) ; +#24109 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142367503004439, 137.4659008082804519, 177.5714312369109393 ) ) ; +#24110 = EDGE_CURVE ( 'NONE', #30170, #711, #18160, .T. ) ; +#24111 = ORIENTED_EDGE ( 'NONE', *, *, #39031, .F. ) ; +#24112 = CARTESIAN_POINT ( 'NONE', ( 37.94196629854999969, 119.2238566698000000, 87.13002152622999574 ) ) ; +#24113 = CARTESIAN_POINT ( 'NONE', ( 17.99676327751970106, 132.8602135917551266, 90.82840093810243332 ) ) ; +#24114 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#24115 = ORIENTED_EDGE ( 'NONE', *, *, #13162, .F. ) ; +#24116 = CARTESIAN_POINT ( 'NONE', ( 32.66389061773956826, 141.7118122376935219, 282.5421777876526335 ) ) ; +#24117 = CARTESIAN_POINT ( 'NONE', ( -42.69612883678725268, 120.9011579166986223, 92.53537271405176057 ) ) ; +#24118 = DIRECTION ( 'NONE', ( -0.0009686424659220636531, 0.2252351993847904188, -0.9743039395844949047 ) ) ; +#24119 = CARTESIAN_POINT ( 'NONE', ( 16.16561595000348817, 152.0060889837787386, 180.9382316808850533 ) ) ; +#24120 = LINE ( 'NONE', #17950, #38721 ) ; +#24121 = CARTESIAN_POINT ( 'NONE', ( 33.53687168153876996, 218.5902260770998282, 61.03824646354980388 ) ) ; +#24122 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927769952488, 0.0005734119022077144778 ) ) ; +#24123 = FACE_OUTER_BOUND ( 'NONE', #2476, .T. ) ; +#24124 = VECTOR ( 'NONE', #17524, 1000.000000000000000 ) ; +#24125 = CARTESIAN_POINT ( 'NONE', ( 37.92873555815999964, 118.8137886041999991, 87.34311561645002087 ) ) ; +#24126 = PERSON_AND_ORGANIZATION_ROLE ( 'creator' ) ; +#24127 = CARTESIAN_POINT ( 'NONE', ( 25.99904971602028425, 120.7769186021849066, 87.52076664421943519 ) ) ; +#24128 = ORIENTED_EDGE ( 'NONE', *, *, #34145, .F. ) ; +#24129 = CARTESIAN_POINT ( 'NONE', ( 36.06237287903013566, 191.9759150222000130, 101.8996665707920073 ) ) ; +#24130 = DIRECTION ( 'NONE', ( -0.0006039748319386903158, 0.000000000000000000, -0.9999998176071845934 ) ) ; +#24131 = VECTOR ( 'NONE', #3414, 1000.000000000000114 ) ; +#24132 = CARTESIAN_POINT ( 'NONE', ( -25.67411030247916415, 190.9010662205137692, 106.4782255816775347 ) ) ; +#24133 = CARTESIAN_POINT ( 'NONE', ( 35.93711133181000150, 112.8285350512999941, 87.62948096434999457 ) ) ; +#24134 = AXIS2_PLACEMENT_3D ( 'NONE', #8848, #14974, #9039 ) ; +#24135 = ORIENTED_EDGE ( 'NONE', *, *, #9842, .T. ) ; +#24136 = CONICAL_SURFACE ( 'NONE', #28051, 48.00000000001370637, 0.7853981633973088350 ) ; +#24137 = CARTESIAN_POINT ( 'NONE', ( 23.72254622402000024, 114.0103269029000188, 152.4718672074000381 ) ) ; +#24138 = EDGE_LOOP ( 'NONE', ( #34148, #22414, #36933, #2564 ) ) ; +#24139 = EDGE_LOOP ( 'NONE', ( #27326, #31180, #9795, #11329 ) ) ; +#24140 = ORIENTED_EDGE ( 'NONE', *, *, #1500, .F. ) ; +#24141 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#24142 = ORIENTED_EDGE ( 'NONE', *, *, #3690, .F. ) ; +#24143 = CARTESIAN_POINT ( 'NONE', ( 47.95581608532123141, 138.8991522261716227, 291.4101743701981491 ) ) ; +#24144 = ADVANCED_FACE ( 'NONE', ( #27616 ), #27424, .F. ) ; +#24145 = EDGE_CURVE ( 'NONE', #18171, #11951, #37393, .T. ) ; +#24146 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37043, #37239, #9241, #6151 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24147 = CARTESIAN_POINT ( 'NONE', ( -31.65770855151000518, 220.4002260771000010, 152.4718672074000381 ) ) ; +#24148 = EDGE_CURVE ( 'NONE', #36888, #23778, #38310, .T. ) ; +#24149 = EDGE_CURVE ( 'NONE', #2542, #9013, #17361, .T. ) ; +#24150 = ORIENTED_EDGE ( 'NONE', *, *, #15459, .F. ) ; +#24151 = CARTESIAN_POINT ( 'NONE', ( -39.81773669046000208, 119.3672490520999929, 89.66199800214000959 ) ) ; +#24152 = CARTESIAN_POINT ( 'NONE', ( -37.62184588523724926, 212.3970731564136543, 75.58122719057897143 ) ) ; +#24153 = CARTESIAN_POINT ( 'NONE', ( 0.03597117087481289943, -13.74990928990362882, 59.55738949995932785 ) ) ; +#24154 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386905326 ) ) ; +#24155 = VERTEX_POINT ( 'NONE', #26624 ) ; +#24156 = EDGE_CURVE ( 'NONE', #31711, #32274, #40013, .T. ) ; +#24157 = DIRECTION ( 'NONE', ( 0.0005559617637900415204, -0.3907311284895835235, 0.9205046855588372434 ) ) ; +#24158 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971560961 ) ) ; +#24159 = CARTESIAN_POINT ( 'NONE', ( 76.10748482110098223, 155.7951947758797644, 98.14087069364009608 ) ) ; +#24160 = CARTESIAN_POINT ( 'NONE', ( 35.90288022432931569, 114.9671451721747388, 90.24610039920314364 ) ) ; +#24161 = CARTESIAN_POINT ( 'NONE', ( -4.472258755436127942, 188.0486996950087644, 103.0700877984231454 ) ) ; +#24162 = CARTESIAN_POINT ( 'NONE', ( -19.44498994767157996, 147.7083494500389236, 183.5267648320292437 ) ) ; +#24163 = EDGE_CURVE ( 'NONE', #711, #14055, #4748, .T. ) ; +#24164 = ORIENTED_EDGE ( 'NONE', *, *, #2807, .T. ) ; +#24165 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24166 = CARTESIAN_POINT ( 'NONE', ( 0.5626196048780000014, 189.0076182214000369, 103.6939729820999929 ) ) ; +#24167 = DIRECTION ( 'NONE', ( -0.6087614115774880874, -0.7729348350621346730, -0.1788331191967949541 ) ) ; +#24168 = CARTESIAN_POINT ( 'NONE', ( -35.47623439677231261, 192.3170613116924983, 106.9314473276327959 ) ) ; +#24169 = CIRCLE ( 'NONE', #33264, 2.499999996677015446 ) ; +#24170 = AXIS2_PLACEMENT_3D ( 'NONE', #17232, #17027, #38707 ) ; +#24171 = ORIENTED_EDGE ( 'NONE', *, *, #3811, .F. ) ; +#24172 = ORIENTED_EDGE ( 'NONE', *, *, #32675, .T. ) ; +#24173 = CARTESIAN_POINT ( 'NONE', ( -4.036264725700203115, 136.7920597759830628, 93.80205530682346193 ) ) ; +#24174 = VERTEX_POINT ( 'NONE', #7588 ) ; +#24175 = VECTOR ( 'NONE', #21052, 1000.000000000000000 ) ; +#24176 = ADVANCED_FACE ( 'NONE', ( #22750 ), #35991, .F. ) ; +#24177 = VERTEX_POINT ( 'NONE', #32152 ) ; +#24178 = CARTESIAN_POINT ( 'NONE', ( -25.49994349231765867, 120.2054710424039712, 89.98570239460282494 ) ) ; +#24179 = ORIENTED_EDGE ( 'NONE', *, *, #11828, .T. ) ; +#24180 = CARTESIAN_POINT ( 'NONE', ( 22.64037623556000156, 154.1096148157000130, 95.47483195632999298 ) ) ; +#24181 = CARTESIAN_POINT ( 'NONE', ( -42.17438498177038042, 189.1974161214382377, 108.4895825446868827 ) ) ; +#24182 = CARTESIAN_POINT ( 'NONE', ( -43.55091172764321072, 114.1088728472908542, 121.9228533734347906 ) ) ; +#24183 = CARTESIAN_POINT ( 'NONE', ( 38.86524458869443066, 78.89674437744240265, 287.2041492525814874 ) ) ; +#24184 = ORIENTED_EDGE ( 'NONE', *, *, #9933, .T. ) ; +#24185 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700561807847604, -0.2249510916138314776 ) ) ; +#24186 = ORIENTED_EDGE ( 'NONE', *, *, #32627, .T. ) ; +#24187 = CARTESIAN_POINT ( 'NONE', ( 28.53099798254000063, 124.6121974830000028, 91.48367005413001607 ) ) ; +#24188 = CARTESIAN_POINT ( 'NONE', ( -35.95482889959664163, 191.5453567879722527, 103.8962766636049651 ) ) ; +#24189 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21407, #8728, #21606, #5846 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24191 = CARTESIAN_POINT ( 'NONE', ( -25.59112167743846911, 177.7878761659546569, 100.7140007254543121 ) ) ; +#24190 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24192 = ORIENTED_EDGE ( 'NONE', *, *, #8651, .F. ) ; +#24193 = VECTOR ( 'NONE', #32874, 1000.000000000000114 ) ; +#24194 = AXIS2_PLACEMENT_3D ( 'NONE', #13573, #13179, #32186 ) ; +#24195 = VERTEX_POINT ( 'NONE', #16386 ) ; +#24196 = VECTOR ( 'NONE', #23262, 1000.000000000000000 ) ; +#24197 = EDGE_CURVE ( 'NONE', #3422, #31634, #29548, .T. ) ; +#24198 = EDGE_CURVE ( 'NONE', #28275, #844, #4104, .T. ) ; +#24199 = EDGE_LOOP ( 'NONE', ( #6705, #40214, #22541, #33617 ) ) ; +#24200 = CARTESIAN_POINT ( 'NONE', ( 38.81343184944000058, 119.1356832321999946, 90.12174961364000580 ) ) ; +#24201 = DIRECTION ( 'NONE', ( 0.0005559617453743673698, -0.3907311284892681091, 0.9205046855589822385 ) ) ; +#24202 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597321 ) ) ; +#24203 = DIRECTION ( 'NONE', ( 0.0005884949961199763876, -0.2249510543439082189, 0.9743698870671259060 ) ) ; +#24204 = CARTESIAN_POINT ( 'NONE', ( 12.63559769525019760, 130.7554039043622538, 90.06174994595149030 ) ) ; +#24205 = EDGE_LOOP ( 'NONE', ( #18331, #29373, #28482, #850 ) ) ; +#24206 = EDGE_CURVE ( 'NONE', #30170, #36211, #24375, .T. ) ; +#24207 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3621, #26134, #32457, #32652, #33452, #14053 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.005654176964698274729, 0.006914021989763599434, 0.008173867014828924138 ), + .UNSPECIFIED. ) ; +#24208 = ORIENTED_EDGE ( 'NONE', *, *, #7816, .T. ) ; +#24209 = FACE_OUTER_BOUND ( 'NONE', #21272, .T. ) ; +#24210 = CARTESIAN_POINT ( 'NONE', ( 6.035675884397954327, 136.7933931256889650, 93.79627993537543773 ) ) ; +#24211 = FACE_OUTER_BOUND ( 'NONE', #14615, .T. ) ; +#24212 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250102911, 179.6252109630355562, 101.6466942236733502 ) ) ; +#24213 = ORIENTED_EDGE ( 'NONE', *, *, #27348, .F. ) ; +#24214 = EDGE_CURVE ( 'NONE', #34239, #4201, #16498, .T. ) ; +#24215 = ORIENTED_EDGE ( 'NONE', *, *, #2167, .T. ) ; +#24216 = CARTESIAN_POINT ( 'NONE', ( 36.04645032798080706, 209.7096537570166390, 75.53673338561257822 ) ) ; +#24217 = CARTESIAN_POINT ( 'NONE', ( 1.805080888245589099, 188.6616185568467188, 106.3070958968081925 ) ) ; +#24218 = DIRECTION ( 'NONE', ( 0.0005884949961248703678, -0.2249510543439058319, 0.9743698870671263501 ) ) ; +#24219 = CIRCLE ( 'NONE', #7843, 30.49999999999569411 ) ; +#24220 = EDGE_CURVE ( 'NONE', #33804, #24048, #39356, .T. ) ; +#24221 = CIRCLE ( 'NONE', #7199, 4.500000040450174765 ) ; +#24222 = CARTESIAN_POINT ( 'NONE', ( 39.72066838923261400, 121.2692008855572539, 123.5482992136137597 ) ) ; +#24223 = CARTESIAN_POINT ( 'NONE', ( -19.28798288393075921, 116.9568857464341960, 189.5000423914045484 ) ) ; +#24224 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386880390 ) ) ; +#24225 = VECTOR ( 'NONE', #31932, 1000.000000000000114 ) ; +#24226 = ORIENTED_EDGE ( 'NONE', *, *, #21053, .T. ) ; +#24227 = AXIS2_PLACEMENT_3D ( 'NONE', #24281, #8941, #21613 ) ; +#24228 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #12095, #34147 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 0.9772821279367359670 ), + .UNSPECIFIED. ) ; +#24229 = CARTESIAN_POINT ( 'NONE', ( 45.36643772893244630, 116.4348306688925589, 122.4284095013975815 ) ) ; +#24230 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319390483193 ) ) ; +#24231 = ORIENTED_EDGE ( 'NONE', *, *, #28609, .T. ) ; +#24232 = CARTESIAN_POINT ( 'NONE', ( -13.50000076883903510, 154.4042507776735818, 95.30811371979322644 ) ) ; +#24233 = ORIENTED_EDGE ( 'NONE', *, *, #3498, .F. ) ; +#24234 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #16832, #35624, #20933, #2740 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.589500645051687755, 4.589514308577216539 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999844423337, 0.9999999999844423337, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#24236 = LINE ( 'NONE', #27520, #26587 ) ; +#24235 = CARTESIAN_POINT ( 'NONE', ( 1.447658035601137039, 144.9407251426815719, 129.0349007182437049 ) ) ; +#24237 = ORIENTED_EDGE ( 'NONE', *, *, #22810, .F. ) ; +#24238 = EDGE_LOOP ( 'NONE', ( #690, #10119, #30981, #6405 ) ) ; +#24239 = ORIENTED_EDGE ( 'NONE', *, *, #28787, .F. ) ; +#24240 = CARTESIAN_POINT ( 'NONE', ( 2.892746630442000200, 209.4404812580999931, 75.94847571316999790 ) ) ; +#24241 = FACE_OUTER_BOUND ( 'NONE', #15627, .T. ) ; +#24242 = FACE_OUTER_BOUND ( 'NONE', #11899, .T. ) ; +#24243 = ORIENTED_EDGE ( 'NONE', *, *, #10483, .T. ) ; +#24244 = ADVANCED_FACE ( 'NONE', ( #11272 ), #36205, .F. ) ; +#24245 = ORIENTED_EDGE ( 'NONE', *, *, #9599, .T. ) ; +#24246 = CARTESIAN_POINT ( 'NONE', ( -19.46367937371129742, 126.2449231135791052, 175.9963188856066267 ) ) ; +#24247 = ORIENTED_EDGE ( 'NONE', *, *, #24102, .T. ) ; +#24248 = ORIENTED_EDGE ( 'NONE', *, *, #39169, .F. ) ; +#24250 = AXIS2_PLACEMENT_3D ( 'NONE', #28137, #29132, #26265 ) ; +#24249 = CARTESIAN_POINT ( 'NONE', ( -19.46394794124172023, 125.6806896231740751, 178.4345049239138064 ) ) ; +#24251 = AXIS2_PLACEMENT_3D ( 'NONE', #12110, #24598, #12303 ) ; +#24252 = CARTESIAN_POINT ( 'NONE', ( -20.16658013707266761, 191.4887187421555836, 104.0448208598989339 ) ) ; +#24253 = DIRECTION ( 'NONE', ( -0.0005884949961217841863, 0.2249510543439059707, -0.9743698870671263501 ) ) ; +#24254 = ORIENTED_EDGE ( 'NONE', *, *, #11636, .T. ) ; +#24255 = ORIENTED_EDGE ( 'NONE', *, *, #3997, .T. ) ; +#24256 = AXIS2_PLACEMENT_3D ( 'NONE', #7926, #8346, #8553 ) ; +#24257 = ORIENTED_EDGE ( 'NONE', *, *, #23358, .T. ) ; +#24258 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#24259 = AXIS2_PLACEMENT_3D ( 'NONE', #14799, #27283, #11725 ) ; +#24260 = CARTESIAN_POINT ( 'NONE', ( -8.608366704199914565, 290.9053179400343083, 213.0407505633107803 ) ) ; +#24261 = CARTESIAN_POINT ( 'NONE', ( -35.86721096416999899, 191.4607620390000022, 103.7475147376000137 ) ) ; +#24262 = ORIENTED_EDGE ( 'NONE', *, *, #5493, .F. ) ; +#24263 = CARTESIAN_POINT ( 'NONE', ( -25.67606946964000159, 121.0254811276000027, 87.95152064859000518 ) ) ; +#24264 = ORIENTED_EDGE ( 'NONE', *, *, #13873, .T. ) ; +#24265 = CARTESIAN_POINT ( 'NONE', ( -24.95545957861278197, 159.0476773995373208, 180.5017353223074110 ) ) ; +#24266 = CARTESIAN_POINT ( 'NONE', ( 39.75749670546768044, 190.3327792175265074, 106.6496084232941683 ) ) ; +#24267 = ORIENTED_EDGE ( 'NONE', *, *, #38380, .T. ) ; +#24268 = CARTESIAN_POINT ( 'NONE', ( 2.923899559741844456, 190.2918927302490317, 103.5835027169823377 ) ) ; +#24269 = DIRECTION ( 'NONE', ( 2.610758831345079531E-13, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#24270 = CARTESIAN_POINT ( 'NONE', ( -16.00004089843094590, 126.6464682493123917, 88.90122559946476599 ) ) ; +#24271 = CARTESIAN_POINT ( 'NONE', ( 15.89469151744206421, 128.5927809666073927, 173.0004654942144384 ) ) ; +#24272 = EDGE_CURVE ( 'NONE', #37342, #27638, #10805, .T. ) ; +#24273 = FACE_OUTER_BOUND ( 'NONE', #13374, .T. ) ; +#24274 = CARTESIAN_POINT ( 'NONE', ( 39.60379206711759537, 77.57075965540369111, 291.0398443752740718 ) ) ; +#24275 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #13159, #16001 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24276 = VERTEX_POINT ( 'NONE', #23268 ) ; +#24277 = CARTESIAN_POINT ( 'NONE', ( -10.43102010142666636, 177.7899709888353073, 100.7052528220414445 ) ) ; +#24278 = ORIENTED_EDGE ( 'NONE', *, *, #35605, .T. ) ; +#24279 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#24280 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24281 = CARTESIAN_POINT ( 'NONE', ( 1.447658035571013802, 152.0519508787176335, 130.6788418760813784 ) ) ; +#24282 = VECTOR ( 'NONE', #2836, 1000.000000000000114 ) ; +#24283 = LINE ( 'NONE', #20579, #31759 ) ; +#24284 = ORIENTED_EDGE ( 'NONE', *, *, #38013, .T. ) ; +#24285 = EDGE_CURVE ( 'NONE', #34119, #2177, #11525, .T. ) ; +#24286 = FACE_OUTER_BOUND ( 'NONE', #26697, .T. ) ; +#24287 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5708, #18110, #22466, #7498 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24288 = LINE ( 'NONE', #24491, #13534 ) ; +#24289 = EDGE_CURVE ( 'NONE', #36914, #7388, #16713, .T. ) ; +#24290 = LINE ( 'NONE', #1575, #38657 ) ; +#24291 = DIRECTION ( 'NONE', ( 0.0005884949961258157921, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24292 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#24293 = LINE ( 'NONE', #20795, #21544 ) ; +#24294 = DIRECTION ( 'NONE', ( 0.0005884949961260158274, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24295 = LINE ( 'NONE', #14472, #32520 ) ; +#24296 = EDGE_CURVE ( 'NONE', #32946, #14369, #37375, .T. ) ; +#24297 = ADVANCED_FACE ( 'NONE', ( #1183 ), #19762, .F. ) ; +#24298 = PLANE ( 'NONE', #5614 ) ; +#24299 = ORIENTED_EDGE ( 'NONE', *, *, #1638, .F. ) ; +#24300 = ADVANCED_FACE ( 'NONE', ( #21631 ), #30899, .F. ) ; +#24301 = CARTESIAN_POINT ( 'NONE', ( -18.25047883358543643, 148.8013935164445058, 179.6016233685625707 ) ) ; +#24302 = PLANE ( 'NONE', #2778 ) ; +#24303 = FACE_OUTER_BOUND ( 'NONE', #16760, .T. ) ; +#24304 = ORIENTED_EDGE ( 'NONE', *, *, #38211, .T. ) ; +#24305 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501101346, 132.2930706491314936, 93.28496646302122031 ) ) ; +#24306 = CARTESIAN_POINT ( 'NONE', ( -17.34531841451655509, 148.6239897228831239, 177.2780028082611068 ) ) ; +#24307 = AXIS2_PLACEMENT_3D ( 'NONE', #11934, #18633, #30738 ) ; +#24308 = ORIENTED_EDGE ( 'NONE', *, *, #25037, .T. ) ; +#24309 = CARTESIAN_POINT ( 'NONE', ( -38.06878942637000307, 119.2569487920000029, 87.30466660982000349 ) ) ; +#24310 = AXIS2_PLACEMENT_3D ( 'NONE', #2388, #15457, #27951 ) ; +#24311 = CIRCLE ( 'NONE', #39947, 40.00000000000000000 ) ; +#24312 = CARTESIAN_POINT ( 'NONE', ( -3.868308320181239601, 143.6108898970049950, 95.54847815645690901 ) ) ; +#24313 = VERTEX_POINT ( 'NONE', #11613 ) ; +#24314 = CARTESIAN_POINT ( 'NONE', ( 36.19426920368436384, 191.0813240488200790, 106.8190525720156359 ) ) ; +#24315 = CARTESIAN_POINT ( 'NONE', ( -44.78361369234769285, 123.5315818933150638, 88.22160218664450326 ) ) ; +#24316 = FACE_OUTER_BOUND ( 'NONE', #38110, .T. ) ; +#24317 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8770, #40028, #24724, #6279 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 6.123799525086606188, 7.674909438896238001 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8093550745305059246, 0.8093550745305059246, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#24318 = CARTESIAN_POINT ( 'NONE', ( 30.07151994636415893, 176.9016356171800055, 103.2549657627566262 ) ) ; +#24319 = CARTESIAN_POINT ( 'NONE', ( 13.47345847663963880, 153.8080446478709575, 95.66732164731912746 ) ) ; +#24320 = VERTEX_POINT ( 'NONE', #5254 ) ; +#24321 = ORIENTED_EDGE ( 'NONE', *, *, #17228, .F. ) ; +#24322 = CARTESIAN_POINT ( 'NONE', ( 15.10888617544567047, 175.7086446263182609, 103.2882499569403336 ) ) ; +#24323 = LINE ( 'NONE', #7737, #39467 ) ; +#24324 = CARTESIAN_POINT ( 'NONE', ( 40.77345084030530842, 111.1478968208657818, 141.5557280835205631 ) ) ; +#24325 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23897, #7728, #20194, #4667, #39008, #6082, #34471, #30639, #2633, #21837, #22042, #28184, #31039, #18731, #3008, #3205, #37365 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999997805367, 0.1874999999996615485, 0.2187499999996115052, 0.2343749999996013744, 0.2421874999995963229, 0.2499999999995912714, 0.3749999999996251332, 0.4374999999996631583, 0.4999999999997011280, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24326 = VERTEX_POINT ( 'NONE', #8551 ) ; +#24327 = DIRECTION ( 'NONE', ( 0.0008702530711002103318, -0.2253087760482092305, 0.9742870203873447155 ) ) ; +#24328 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16947, #1424, #20025, #16164 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24329 = CARTESIAN_POINT ( 'NONE', ( -43.76721067839228141, 120.3817750124939323, 91.13402268011530794 ) ) ; +#24330 = CARTESIAN_POINT ( 'NONE', ( 25.88694336884159242, 211.8813746531136815, 73.04286901727219572 ) ) ; +#24331 = CARTESIAN_POINT ( 'NONE', ( -13.84340190164384232, 129.1309658598411829, 155.2542762368457261 ) ) ; +#24332 = LINE ( 'NONE', #36381, #36488 ) ; +#24333 = EDGE_CURVE ( 'NONE', #39651, #14192, #21014, .T. ) ; +#24334 = CARTESIAN_POINT ( 'NONE', ( -2.436970329118646639, 191.4135392062368908, 104.3588452342733603 ) ) ; +#24335 = VECTOR ( 'NONE', #38258, 1000.000000000000000 ) ; +#24336 = LINE ( 'NONE', #18157, #12201 ) ; +#24337 = EDGE_CURVE ( 'NONE', #24627, #30524, #31559, .T. ) ; +#24338 = VECTOR ( 'NONE', #27105, 1000.000000000000000 ) ; +#24339 = CARTESIAN_POINT ( 'NONE', ( 37.94419046432000187, 119.2344160205999941, 87.12639605929000197 ) ) ; +#24340 = DATE_TIME_ROLE ( 'classification_date' ) ; +#24341 = CARTESIAN_POINT ( 'NONE', ( 20.50145991744662055, 186.5915574767782061, 105.2843683661653102 ) ) ; +#24342 = EDGE_CURVE ( 'NONE', #29960, #22046, #32800, .T. ) ; +#24343 = CARTESIAN_POINT ( 'NONE', ( 20.00201742172724551, 173.8530216436687965, 102.8568040933565300 ) ) ; +#24344 = DIRECTION ( 'NONE', ( 1.447458112927613770E-19, 1.000000000000000000, -1.271205603797056623E-14 ) ) ; +#24345 = LINE ( 'NONE', #36392, #37860 ) ; +#24346 = ADVANCED_FACE ( 'NONE', ( #37745 ), #3790, .T. ) ; +#24348 = ORIENTED_EDGE ( 'NONE', *, *, #8399, .F. ) ; +#24347 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178662923876E-05, -0.0002331579774918193435 ) ) ; +#24349 = ORIENTED_EDGE ( 'NONE', *, *, #27585, .T. ) ; +#24350 = EDGE_LOOP ( 'NONE', ( #36220, #36823, #2136, #11360, #15113, #9612, #31030 ) ) ; +#24351 = EDGE_CURVE ( 'NONE', #37430, #33415, #37003, .T. ) ; +#24352 = CARTESIAN_POINT ( 'NONE', ( -2.384008221771502622, 189.5405707719284010, 103.4132521871697747 ) ) ; +#24353 = EDGE_CURVE ( 'NONE', #14192, #23280, #284, .T. ) ; +#24354 = ORIENTED_EDGE ( 'NONE', *, *, #6295, .F. ) ; +#24355 = CARTESIAN_POINT ( 'NONE', ( 16.14434960479602310, 151.5098951869622965, 180.2135683096460639 ) ) ; +#24356 = DIRECTION ( 'NONE', ( 0.7855473026356902810, 0.6188014303620730239, -0.0004744508866335444284 ) ) ; +#24357 = ORIENTED_EDGE ( 'NONE', *, *, #3115, .T. ) ; +#24358 = CARTESIAN_POINT ( 'NONE', ( 40.54493957013273331, 217.7719115632999944, 73.03401595487400755 ) ) ; +#24359 = CARTESIAN_POINT ( 'NONE', ( -23.36173672920000044, 135.2906635721360828, 91.41449412993499379 ) ) ; +#24360 = DIRECTION ( 'NONE', ( 1.766515445929712010E-15, 0.9743043966640313469, 0.2252353050503801690 ) ) ; +#24361 = DIRECTION ( 'NONE', ( -0.0005884949961244972938, 0.2249510543439076637, -0.9743698870671260170 ) ) ; +#24362 = CARTESIAN_POINT ( 'NONE', ( 17.33255171641533110, 121.2645175805946138, 177.4250592562015925 ) ) ; +#24363 = CIRCLE ( 'NONE', #33456, 1.749999999939591433 ) ; +#24364 = VERTEX_POINT ( 'NONE', #4596 ) ; +#24365 = DIRECTION ( 'NONE', ( 0.5634794340701355653, -0.8261300910752492621, 0.000000000000000000 ) ) ; +#24366 = FACE_OUTER_BOUND ( 'NONE', #6160, .T. ) ; +#24367 = VECTOR ( 'NONE', #7082, 1000.000000000000000 ) ; +#24368 = CARTESIAN_POINT ( 'NONE', ( 13.50000077932746834, 151.9719590241109870, 94.73025978658517943 ) ) ; +#24369 = FACE_OUTER_BOUND ( 'NONE', #29930, .T. ) ; +#24370 = VERTEX_POINT ( 'NONE', #38542 ) ; +#24371 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173120816, 138.0805213879916664, 92.05262725620852393 ) ) ; +#24372 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33076, #5063, #29830, #39408 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24373 = CIRCLE ( 'NONE', #5393, 3.000000000000005773 ) ; +#24374 = CARTESIAN_POINT ( 'NONE', ( 1.111562947836880255, 189.0855455024050400, 103.7202029498749880 ) ) ; +#24375 = LINE ( 'NONE', #4927, #32203 ) ; +#24376 = CARTESIAN_POINT ( 'NONE', ( -42.83084823883022807, 121.2593020781266659, 90.75261808358531823 ) ) ; +#24377 = EDGE_LOOP ( 'NONE', ( #27310, #11450, #30392, #7442 ) ) ; +#24378 = ORIENTED_EDGE ( 'NONE', *, *, #35132, .F. ) ; +#24379 = CARTESIAN_POINT ( 'NONE', ( 20.49908935505346719, 194.2769733015968541, 102.8866291927022303 ) ) ; +#24380 = ORIENTED_EDGE ( 'NONE', *, *, #4265, .T. ) ; +#24381 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9585, #24341, #18363, #3426 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24382 = EDGE_CURVE ( 'NONE', #36231, #38065, #11150, .T. ) ; +#24383 = EDGE_CURVE ( 'NONE', #39292, #38824, #35423, .T. ) ; +#24384 = EDGE_LOOP ( 'NONE', ( #5556, #10142, #39912, #8024 ) ) ; +#24385 = CARTESIAN_POINT ( 'NONE', ( -25.50098454281350158, 121.6303684359623389, 88.26205429894362453 ) ) ; +#24386 = EDGE_CURVE ( 'NONE', #37113, #25434, #12904, .T. ) ; +#24387 = ORIENTED_EDGE ( 'NONE', *, *, #28442, .F. ) ; +#24388 = CARTESIAN_POINT ( 'NONE', ( -35.93912355882999776, 192.8585610955000220, 106.5512944815999958 ) ) ; +#24389 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927765820594, 0.0005734119022078099960 ) ) ; +#24390 = CARTESIAN_POINT ( 'NONE', ( 21.17088928811812920, 192.5990385700442573, 28.42526875025830435 ) ) ; +#24391 = EDGE_CURVE ( 'NONE', #13040, #3283, #20130, .T. ) ; +#24392 = VERTEX_POINT ( 'NONE', #1954 ) ; +#24393 = CARTESIAN_POINT ( 'NONE', ( -5.671868782401078946, 181.7830489082147380, 101.7543586301373040 ) ) ; +#24394 = AXIS2_PLACEMENT_3D ( 'NONE', #19271, #31168, #31775 ) ; +#24395 = ORIENTED_EDGE ( 'NONE', *, *, #36164, .T. ) ; +#24396 = CARTESIAN_POINT ( 'NONE', ( 26.49433430397300171, 122.3661283948670047, 90.96806730438009936 ) ) ; +#24397 = CARTESIAN_POINT ( 'NONE', ( -21.70206937734006303, 182.6897195680310233, 102.1853773300410779 ) ) ; +#24399 = CARTESIAN_POINT ( 'NONE', ( 38.15045221970718359, 118.4868570840783377, 87.66883015867043127 ) ) ; +#24398 = PLANE ( 'NONE', #27828 ) ; +#24400 = EDGE_CURVE ( 'NONE', #7852, #10957, #40157, .T. ) ; +#24401 = CONICAL_SURFACE ( 'NONE', #13920, 2.500000073598442896, 0.7853981634226060438 ) ; +#24402 = EDGE_LOOP ( 'NONE', ( #13856, #32936, #17461, #36139 ) ) ; +#24403 = ORIENTED_EDGE ( 'NONE', *, *, #37203, .F. ) ; +#24404 = CARTESIAN_POINT ( 'NONE', ( -13.46279686986694202, 157.6279356061011185, 99.13124279942860539 ) ) ; +#24405 = ADVANCED_FACE ( 'NONE', ( #8708 ), #8046, .F. ) ; +#24406 = LINE ( 'NONE', #8863, #35680 ) ; +#24407 = CARTESIAN_POINT ( 'NONE', ( -45.27486310239934397, 116.8517531720308540, 123.7677792994715560 ) ) ; +#24408 = CARTESIAN_POINT ( 'NONE', ( 12.63563601333813224, 130.7300475903418544, 90.07759431230093128 ) ) ; +#24409 = CARTESIAN_POINT ( 'NONE', ( -12.63881457583079992, 135.0847523732418836, 91.07654686071646211 ) ) ; +#24410 = ORIENTED_EDGE ( 'NONE', *, *, #24296, .T. ) ; +#24411 = ORIENTED_EDGE ( 'NONE', *, *, #22160, .T. ) ; +#24412 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; +#24413 = DIRECTION ( 'NONE', ( -0.0005884949961247568518, 0.2249510543439060262, -0.9743698870671264611 ) ) ; +#24414 = VERTEX_POINT ( 'NONE', #36074 ) ; +#24415 = EDGE_LOOP ( 'NONE', ( #12028, #5722, #32080, #35449 ) ) ; +#24416 = CARTESIAN_POINT ( 'NONE', ( -3.537737212824113353, 144.2088358181959222, 92.94829169108382416 ) ) ; +#24417 = AXIS2_PLACEMENT_3D ( 'NONE', #38198, #13653, #22672 ) ; +#24418 = CARTESIAN_POINT ( 'NONE', ( -17.00047812746342402, 136.5658759208817230, 181.4646850263357010 ) ) ; +#24419 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39705, #30314, #39914, #33572 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24420 = CIRCLE ( 'NONE', #10039, 2.500000000000002220 ) ; +#24421 = CARTESIAN_POINT ( 'NONE', ( 3.068920026728427786, 190.7403886567750817, 106.7700806275786647 ) ) ; +#24422 = DIRECTION ( 'NONE', ( 0.0005884949961219227473, -0.2249510543439028620, 0.9743698870671272383 ) ) ; +#24423 = AXIS2_PLACEMENT_3D ( 'NONE', #39457, #20873, #11469 ) ; +#24424 = CARTESIAN_POINT ( 'NONE', ( -36.45697978980704335, 190.7486664167910249, 106.7916551997199690 ) ) ; +#24425 = CARTESIAN_POINT ( 'NONE', ( -4.036264725720115187, 167.9338357148002387, 100.9917020970990791 ) ) ; +#24426 = CARTESIAN_POINT ( 'NONE', ( 19.70863784699480448, 149.1560517737245561, 182.9541186021026817 ) ) ; +#24427 = EDGE_CURVE ( 'NONE', #34118, #21532, #5411, .T. ) ; +#24428 = EDGE_CURVE ( 'NONE', #10727, #18757, #24454, .T. ) ; +#24429 = ORIENTED_EDGE ( 'NONE', *, *, #27848, .F. ) ; +#24430 = EDGE_CURVE ( 'NONE', #33123, #40304, #14420, .T. ) ; +#24431 = ADVANCED_FACE ( 'NONE', ( #36491 ), #8499, .F. ) ; +#24432 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748613964, 179.1800746285507842, 103.5747911657901170 ) ) ; +#24433 = CARTESIAN_POINT ( 'NONE', ( -20.23142761837597803, 127.1194786501865508, 91.85271049129865162 ) ) ; +#24434 = ORIENTED_EDGE ( 'NONE', *, *, #39588, .F. ) ; +#24435 = EDGE_CURVE ( 'NONE', #32839, #9483, #40350, .T. ) ; +#24436 = CARTESIAN_POINT ( 'NONE', ( 37.96380763661293400, 191.4135383555317844, 104.3344495138068595 ) ) ; +#24437 = ORIENTED_EDGE ( 'NONE', *, *, #2582, .F. ) ; +#24438 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24439 = EDGE_LOOP ( 'NONE', ( #18953, #30581, #30631, #24645 ) ) ; +#24440 = ADVANCED_FACE ( 'NONE', ( #31371 ), #22379, .F. ) ; +#24441 = EDGE_LOOP ( 'NONE', ( #7571, #36920, #31155, #20700 ) ) ; +#24442 = AXIS2_PLACEMENT_3D ( 'NONE', #23755, #26831, #20680 ) ; +#24443 = ORIENTED_EDGE ( 'NONE', *, *, #11535, .T. ) ; +#24444 = CARTESIAN_POINT ( 'NONE', ( 2.618453597419999834, 209.4619370535999963, 75.68410014526000396 ) ) ; +#24445 = CARTESIAN_POINT ( 'NONE', ( -25.66662714986091132, 118.1127751917333200, 89.94994881093153083 ) ) ; +#24446 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24447 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#24449 = ORIENTED_EDGE ( 'NONE', *, *, #4639, .T. ) ; +#24448 = VECTOR ( 'NONE', #11669, 1000.000000000000000 ) ; +#24450 = ORIENTED_EDGE ( 'NONE', *, *, #9688, .F. ) ; +#24451 = FACE_OUTER_BOUND ( 'NONE', #30351, .T. ) ; +#24452 = EDGE_LOOP ( 'NONE', ( #37270, #34645, #16622, #11337 ) ) ; +#24453 = VERTEX_POINT ( 'NONE', #24656 ) ; +#24454 = LINE ( 'NONE', #30165, #17168 ) ; +#24455 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#24456 = AXIS2_PLACEMENT_3D ( 'NONE', #34714, #18772, #28025 ) ; +#24457 = CARTESIAN_POINT ( 'NONE', ( 22.95436083522999837, 118.1131156702000169, 13.53038997162000001 ) ) ; +#24458 = CYLINDRICAL_SURFACE ( 'NONE', #18676, 6.000000000000008882 ) ; +#24459 = CARTESIAN_POINT ( 'NONE', ( 22.25482580366933405, 135.3257585116184032, 90.88189302714953044 ) ) ; +#24460 = ORIENTED_EDGE ( 'NONE', *, *, #13788, .F. ) ; +#24461 = EDGE_LOOP ( 'NONE', ( #9420, #9076, #3725, #30825 ) ) ; +#24462 = DIRECTION ( 'NONE', ( 0.0005884949961247620560, -0.2249510543439075527, 0.9743698870671261281 ) ) ; +#24463 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7833, #8252, #26872, #4969, #20718, #33171, #19889, #2127, #14596, #5164, #29326, #29517 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999992246202, 0.3749999999988369304, 0.4374999999986430854, 0.4687499999985523247, 0.4843749999985315080, 0.4999999999985107468, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24464 = CARTESIAN_POINT ( 'NONE', ( -36.34981164026000044, 191.9154030711000019, 104.5556768045999974 ) ) ; +#24465 = ORIENTED_EDGE ( 'NONE', *, *, #5577, .T. ) ; +#24466 = CARTESIAN_POINT ( 'NONE', ( 15.38986074322405706, 183.3318898957821546, 101.9691300310993682 ) ) ; +#24467 = ORIENTED_EDGE ( 'NONE', *, *, #2107, .T. ) ; +#24468 = CARTESIAN_POINT ( 'NONE', ( -3.168142195203446754, 126.1261981506732468, 91.85226338672082136 ) ) ; +#24469 = FACE_OUTER_BOUND ( 'NONE', #509, .T. ) ; +#24470 = ORIENTED_EDGE ( 'NONE', *, *, #21291, .F. ) ; +#24471 = CARTESIAN_POINT ( 'NONE', ( 3.858347067253080187, 174.7549553854443332, 102.7438146759574522 ) ) ; +#24472 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31515, #3481, #828, #4494 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24473 = CARTESIAN_POINT ( 'NONE', ( 12.31735976862525561, 136.6810573082978806, 94.28285972987136176 ) ) ; +#24474 = AXIS2_PLACEMENT_3D ( 'NONE', #4218, #1162, #26131 ) ; +#24475 = CARTESIAN_POINT ( 'NONE', ( -46.29694876502865952, 80.51358819988081450, 287.6592691764436154 ) ) ; +#24476 = CARTESIAN_POINT ( 'NONE', ( 41.73867405848197620, 189.2432962648855721, 106.9167062554396068 ) ) ; +#24477 = AXIS2_PLACEMENT_3D ( 'NONE', #35521, #14298, #32699 ) ; +#24478 = VECTOR ( 'NONE', #33083, 1000.000000000000227 ) ; +#24479 = CARTESIAN_POINT ( 'NONE', ( -45.17721186414367907, 180.6407286098181544, 103.9501681112560192 ) ) ; +#24480 = ORIENTED_EDGE ( 'NONE', *, *, #27918, .T. ) ; +#24481 = CARTESIAN_POINT ( 'NONE', ( -15.49852918059724693, 160.1761146120170736, 99.20761365264185372 ) ) ; +#24482 = ADVANCED_FACE ( 'NONE', ( #12551 ), #9101, .T. ) ; +#24483 = AXIS2_PLACEMENT_3D ( 'NONE', #23717, #35955, #8389 ) ; +#24484 = FACE_OUTER_BOUND ( 'NONE', #8412, .T. ) ; +#24485 = EDGE_CURVE ( 'NONE', #22, #13543, #1503, .T. ) ; +#24486 = CARTESIAN_POINT ( 'NONE', ( -38.05885084466000023, 119.4654426599000203, 87.18889340133002008 ) ) ; +#24487 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #17961, #21263, #24748, #14922 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.712388980384485393, 6.509724810461453792 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7484352496336041938, 0.7484352496336041938, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#24488 = PLANE ( 'NONE', #28789 ) ; +#24489 = CARTESIAN_POINT ( 'NONE', ( -25.49994355703909932, 120.2054709989172778, 89.98570258340846806 ) ) ; +#24490 = ORIENTED_EDGE ( 'NONE', *, *, #6085, .T. ) ; +#24491 = CARTESIAN_POINT ( 'NONE', ( -45.56069752896866731, 133.9656849080258496, 337.3347232553839490 ) ) ; +#24492 = VERTEX_POINT ( 'NONE', #22182 ) ; +#24493 = CARTESIAN_POINT ( 'NONE', ( 32.45263285945821252, 152.9980946676346889, 291.5389433581793242 ) ) ; +#24494 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24495 = DIRECTION ( 'NONE', ( -0.0005884949961226037347, 0.2249510543439047494, -0.9743698870671267942 ) ) ; +#24496 = CARTESIAN_POINT ( 'NONE', ( -36.03785673918448396, 115.6782689564399931, 90.28955080164526237 ) ) ; +#24497 = ORIENTED_EDGE ( 'NONE', *, *, #1257, .F. ) ; +#24498 = CONICAL_SURFACE ( 'NONE', #19226, 2.503061127006177777, 0.7853981634091529163 ) ; +#24499 = AXIS2_PLACEMENT_3D ( 'NONE', #32793, #23805, #20514 ) ; +#24500 = EDGE_LOOP ( 'NONE', ( #30610, #22449, #11658, #5752 ) ) ; +#24501 = CARTESIAN_POINT ( 'NONE', ( 8.046776639317595681, 161.2737771581006996, 96.88104755365348808 ) ) ; +#24502 = ADVANCED_FACE ( 'NONE', ( #25658 ), #26251, .F. ) ; +#24503 = AXIS2_PLACEMENT_3D ( 'NONE', #34483, #6685, #25324 ) ; +#24504 = CARTESIAN_POINT ( 'NONE', ( 37.34715196620786060, 164.6396645750260745, 198.2231758344085506 ) ) ; +#24505 = AXIS2_PLACEMENT_3D ( 'NONE', #18298, #30997, #18896 ) ; +#24506 = ORIENTED_EDGE ( 'NONE', *, *, #12936, .T. ) ; +#24507 = CARTESIAN_POINT ( 'NONE', ( -23.36259834854143591, 135.1300385911131627, 91.15744102916718816 ) ) ; +#24508 = AXIS2_PLACEMENT_3D ( 'NONE', #38724, #14006, #36063 ) ; +#24509 = FACE_OUTER_BOUND ( 'NONE', #15924, .T. ) ; +#24510 = ORIENTED_EDGE ( 'NONE', *, *, #30297, .T. ) ; +#24511 = CARTESIAN_POINT ( 'NONE', ( -38.18399642279999995, 119.1291464787000081, 87.44400818926999364 ) ) ; +#24512 = CARTESIAN_POINT ( 'NONE', ( 37.96521291183479008, 190.3639829187772250, 106.6578906949923464 ) ) ; +#24513 = ORIENTED_EDGE ( 'NONE', *, *, #16417, .T. ) ; +#24514 = DIRECTION ( 'NONE', ( 0.0005884949961240085355, -0.2249510543439064425, 0.9743698870671262391 ) ) ; +#24515 = CARTESIAN_POINT ( 'NONE', ( 19.46059643144436535, 126.3442427331793141, 175.5385488862945635 ) ) ; +#24516 = CARTESIAN_POINT ( 'NONE', ( 16.81893173097259009, 122.1576077111467669, 174.6474910666977394 ) ) ; +#24517 = CARTESIAN_POINT ( 'NONE', ( -23.18986705890396394, 115.1130375555242011, 90.28179093782202358 ) ) ; +#24518 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319351123402 ) ) ; +#24519 = ORIENTED_EDGE ( 'NONE', *, *, #9599, .F. ) ; +#24520 = CARTESIAN_POINT ( 'NONE', ( 38.62156013492000284, 119.5280236665000047, 87.38525354376000109 ) ) ; +#24521 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#24522 = CARTESIAN_POINT ( 'NONE', ( 36.53325801408829676, 191.7380623391987058, 104.3522437978620303 ) ) ; +#24523 = PLANE ( 'NONE', #22978 ) ; +#24524 = ADVANCED_FACE ( 'NONE', ( #22976 ), #1290, .F. ) ; +#24525 = ORIENTED_EDGE ( 'NONE', *, *, #19909, .T. ) ; +#24526 = FACE_OUTER_BOUND ( 'NONE', #23411, .T. ) ; +#24527 = EDGE_CURVE ( 'NONE', #6854, #17839, #37300, .T. ) ; +#24528 = CARTESIAN_POINT ( 'NONE', ( 16.14434960479181669, 123.6872145152307922, 173.7816462226733449 ) ) ; +#24529 = CARTESIAN_POINT ( 'NONE', ( 24.96542012578290226, 213.3574743203983530, 73.04342559421955627 ) ) ; +#24530 = AXIS2_PLACEMENT_3D ( 'NONE', #10059, #25209, #3702 ) ; +#24531 = CONICAL_SURFACE ( 'NONE', #25839, 2.503000005691713437, 0.7853981633624692593 ) ; +#24532 = CARTESIAN_POINT ( 'NONE', ( 5.668109638569122311, 127.9115383981770435, 92.25911597461721669 ) ) ; +#24533 = VECTOR ( 'NONE', #36567, 1000.000000000000000 ) ; +#24534 = EDGE_CURVE ( 'NONE', #29659, #20818, #229, .T. ) ; +#24535 = CARTESIAN_POINT ( 'NONE', ( -30.82037056355595084, 183.2973804097868822, 101.9890727088156979 ) ) ; +#24536 = CIRCLE ( 'NONE', #2962, 2.000000000000011546 ) ; +#24537 = CARTESIAN_POINT ( 'NONE', ( -25.84889468334661800, 209.7109668267897007, 73.23528207987367011 ) ) ; +#24538 = CARTESIAN_POINT ( 'NONE', ( 6.040442610973922655, 177.0788152924815506, 103.5573834436911369 ) ) ; +#24539 = SHAPE_DEFINITION_REPRESENTATION ( #10456, #23616 ) ; +#24540 = LINE ( 'NONE', #18756, #20678 ) ; +#24541 = CARTESIAN_POINT ( 'NONE', ( -2.437379602309801996, 196.1181861109790532, 103.6812116298660129 ) ) ; +#24542 = CARTESIAN_POINT ( 'NONE', ( 13.76428958104859746, 149.7303430849865720, 179.8030703197069897 ) ) ; +#24543 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#24544 = CARTESIAN_POINT ( 'NONE', ( 37.18342958457959924, 191.4796220198800256, 104.3003503982839959 ) ) ; +#24545 = CARTESIAN_POINT ( 'NONE', ( 36.51380830376000830, 190.9776620762999926, 106.6665925439999967 ) ) ; +#24546 = ORIENTED_EDGE ( 'NONE', *, *, #27459, .F. ) ; +#24547 = ORIENTED_EDGE ( 'NONE', *, *, #32881, .F. ) ; +#24548 = DIRECTION ( 'NONE', ( 3.092411411307044243E-16, -0.9743043966640313469, -0.2252353050503803911 ) ) ; +#24549 = EDGE_CURVE ( 'NONE', #16868, #34038, #21931, .T. ) ; +#24550 = FACE_OUTER_BOUND ( 'NONE', #6755, .T. ) ; +#24551 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #38981, #10988 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24552 = CYLINDRICAL_SURFACE ( 'NONE', #15408, 59.40509898897002472 ) ; +#24553 = CONICAL_SURFACE ( 'NONE', #19289, 5.003058809538631024, 0.7854316141403709928 ) ; +#24554 = CARTESIAN_POINT ( 'NONE', ( 16.16915973785429372, 151.9784250564231343, 184.4864535658479383 ) ) ; +#24555 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; +#24556 = AXIS2_PLACEMENT_3D ( 'NONE', #34746, #18613, #12304 ) ; +#24557 = ORIENTED_EDGE ( 'NONE', *, *, #24163, .F. ) ; +#24558 = CIRCLE ( 'NONE', #14775, 1.999999999727680722 ) ; +#24559 = CARTESIAN_POINT ( 'NONE', ( 15.50068700820734335, 127.4824608105999744, 90.27255908592694311 ) ) ; +#24560 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971562072 ) ) ; +#24561 = VECTOR ( 'NONE', #13148, 1000.000000000000000 ) ; +#24562 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#24563 = ORIENTED_EDGE ( 'NONE', *, *, #39640, .T. ) ; +#24564 = AXIS2_PLACEMENT_3D ( 'NONE', #20397, #4854, #32480 ) ; +#24565 = CARTESIAN_POINT ( 'NONE', ( -53.48535521792690872, 68.11573456465821153, 284.1968697250433706 ) ) ; +#24566 = EDGE_CURVE ( 'NONE', #16069, #40361, #13403, .T. ) ; +#24567 = CARTESIAN_POINT ( 'NONE', ( 20.25158342518999888, 118.4641756243000117, 90.00571388583000498 ) ) ; +#24568 = VECTOR ( 'NONE', #37919, 1000.000000000000114 ) ; +#24569 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559296 ) ) ; +#24570 = CARTESIAN_POINT ( 'NONE', ( -5.662686464640452222, 188.3429660633563287, 103.1387990589197869 ) ) ; +#24571 = CARTESIAN_POINT ( 'NONE', ( -22.23345940463643444, 214.0123076496562078, 76.07197583563208809 ) ) ; +#24572 = ORIENTED_EDGE ( 'NONE', *, *, #21201, .T. ) ; +#24573 = ADVANCED_FACE ( 'NONE', ( #35710 ), #10021, .F. ) ; +#24574 = LINE ( 'NONE', #37029, #25257 ) ; +#24575 = CARTESIAN_POINT ( 'NONE', ( 2.894932050292999826, 190.8748715014000084, 103.8886708489000057 ) ) ; +#24576 = CARTESIAN_POINT ( 'NONE', ( -33.70586835455132046, 218.5902260770999987, 73.07886158226766327 ) ) ; +#24577 = EDGE_CURVE ( 'NONE', #20818, #5436, #32851, .T. ) ; +#24578 = VERTEX_POINT ( 'NONE', #33066 ) ; +#24579 = CYLINDRICAL_SURFACE ( 'NONE', #31607, 2.000000000000000000 ) ; +#24580 = EDGE_LOOP ( 'NONE', ( #8655, #3491, #39748, #36859 ) ) ; +#24581 = EDGE_CURVE ( 'NONE', #21600, #38636, #34389, .T. ) ; +#24582 = EDGE_CURVE ( 'NONE', #18145, #629, #17797, .T. ) ; +#24583 = EDGE_CURVE ( 'NONE', #12315, #30815, #34142, .T. ) ; +#24584 = AXIS2_PLACEMENT_3D ( 'NONE', #29770, #17061, #39758 ) ; +#24585 = CARTESIAN_POINT ( 'NONE', ( -39.61054748937312553, 129.5177821288435780, 336.3042500576304974 ) ) ; +#24586 = VECTOR ( 'NONE', #778, 999.9999999999998863 ) ; +#24587 = LINE ( 'NONE', #12294, #29002 ) ; +#24588 = CARTESIAN_POINT ( 'NONE', ( -8.607980242643897384, 290.0045490278850480, 216.9380081958158826 ) ) ; +#24589 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; +#24590 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #503, #22206, #3968, #12996 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24591 = CARTESIAN_POINT ( 'NONE', ( 28.45310815370287472, 181.6925917411357148, 101.5827842051393617 ) ) ; +#24592 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; +#24593 = CARTESIAN_POINT ( 'NONE', ( -36.65000432357000193, 191.5328112857000065, 106.2711270500000040 ) ) ; +#24594 = ORIENTED_EDGE ( 'NONE', *, *, #32302, .F. ) ; +#24595 = AXIS2_PLACEMENT_3D ( 'NONE', #37299, #27314, #3141 ) ; +#24596 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; +#24597 = CYLINDRICAL_SURFACE ( 'NONE', #13670, 2.000000000000014655 ) ; +#24598 = DIRECTION ( 'NONE', ( 0.0005884949961236470625, -0.2249510543439058041, 0.9743698870671265722 ) ) ; +#24600 = CARTESIAN_POINT ( 'NONE', ( 16.21976467472907757, 122.6436220881636814, 172.0961230653717564 ) ) ; +#24599 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394468885165, 153.0051697192222093, 297.5584364845166760 ) ) ; +#24601 = ORIENTED_EDGE ( 'NONE', *, *, #16411, .T. ) ; +#24602 = EDGE_CURVE ( 'NONE', #17839, #28078, #25038, .T. ) ; +#24603 = EDGE_LOOP ( 'NONE', ( #15978, #36351, #26837, #7320 ) ) ; +#24604 = ORIENTED_EDGE ( 'NONE', *, *, #5547, .F. ) ; +#24605 = CARTESIAN_POINT ( 'NONE', ( -35.45414161168002920, 207.8686442570738677, 77.29845581748402594 ) ) ; +#24606 = CARTESIAN_POINT ( 'NONE', ( 13.35510997216094609, 181.7652417701797276, 101.6086696847208657 ) ) ; +#24607 = CARTESIAN_POINT ( 'NONE', ( -20.16727645646760436, 196.4248145870187443, 103.8226647487338283 ) ) ; +#24608 = CARTESIAN_POINT ( 'NONE', ( 39.70674893776387648, 114.9516458920610660, 150.7368254606779772 ) ) ; +#24609 = CARTESIAN_POINT ( 'NONE', ( 12.64144988264126646, 130.9981868284926918, 89.91003945015222598 ) ) ; +#24610 = DIRECTION ( 'NONE', ( 0.1305262373691799260, 0.9659798014921964215, 0.2232620085624539286 ) ) ; +#24611 = ORIENTED_EDGE ( 'NONE', *, *, #17597, .T. ) ; +#24612 = EDGE_CURVE ( 'NONE', #20537, #19373, #8032, .T. ) ; +#24613 = EDGE_LOOP ( 'NONE', ( #7521, #30511, #34022, #34290 ) ) ; +#24614 = CIRCLE ( 'NONE', #36346, 4.999999999999990230 ) ; +#24615 = CARTESIAN_POINT ( 'NONE', ( -5.668235839012205624, 187.2935674832718007, 105.4622348357629136 ) ) ; +#24616 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33394, #36266, #2335, #30142, #38712, #10729 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24617 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971583443 ) ) ; +#24618 = ORIENTED_EDGE ( 'NONE', *, *, #858, .T. ) ; +#24619 = EDGE_CURVE ( 'NONE', #15583, #35994, #13906, .T. ) ; +#24620 = CARTESIAN_POINT ( 'NONE', ( -36.19285314463999725, 191.4786645193000254, 106.5770535557000045 ) ) ; +#24621 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, -1.298960938811000068E-14 ) ) ; +#24622 = CIRCLE ( 'NONE', #33074, 2.500000000054189098 ) ; +#24623 = EDGE_CURVE ( 'NONE', #9539, #2007, #35310, .T. ) ; +#24624 = AXIS2_PLACEMENT_3D ( 'NONE', #19790, #7332, #13882 ) ; +#24625 = CARTESIAN_POINT ( 'NONE', ( 1.190304246311000069, 188.4394388974999970, 106.2357951811000021 ) ) ; +#24626 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32401, #26272, #32983, #1506 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.003686124984095357545, 0.004393344450578582673 ), + .UNSPECIFIED. ) ; +#24627 = VERTEX_POINT ( 'NONE', #24306 ) ; +#24628 = LINE ( 'NONE', #30948, #3977 ) ; +#24629 = EDGE_CURVE ( 'NONE', #328, #26074, #6577, .T. ) ; +#24630 = CARTESIAN_POINT ( 'NONE', ( 13.49774948664089536, 124.4632236369325113, 88.50938697307681480 ) ) ; +#24631 = CARTESIAN_POINT ( 'NONE', ( 24.86285456769096669, 182.2983400162870851, 101.7247947455283992 ) ) ; +#24632 = CARTESIAN_POINT ( 'NONE', ( 4.644859472722845162, 147.7869572978819406, 93.76942395331053604 ) ) ; +#24633 = ORIENTED_EDGE ( 'NONE', *, *, #15360, .T. ) ; +#24634 = CARTESIAN_POINT ( 'NONE', ( 25.99116264712915125, 206.1770306668426258, 74.47098211211711316 ) ) ; +#24635 = FACE_OUTER_BOUND ( 'NONE', #15959, .T. ) ; +#24636 = CARTESIAN_POINT ( 'NONE', ( -20.49852830656245928, 127.1805961887959029, 91.59301651814030265 ) ) ; +#24637 = ORIENTED_EDGE ( 'NONE', *, *, #39821, .T. ) ; +#24638 = AXIS2_PLACEMENT_3D ( 'NONE', #6617, #9714, #21786 ) ; +#24639 = CARTESIAN_POINT ( 'NONE', ( 16.48384946166832421, 121.5382711781017520, 177.2995345887800624 ) ) ; +#24640 = ORIENTED_EDGE ( 'NONE', *, *, #3475, .T. ) ; +#24641 = AXIS2_PLACEMENT_3D ( 'NONE', #23816, #2343, #39534 ) ; +#24643 = CARTESIAN_POINT ( 'NONE', ( -16.89042424569320389, 121.5869331581628785, 176.9809332940324111 ) ) ; +#24642 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24644 = ORIENTED_EDGE ( 'NONE', *, *, #34586, .F. ) ; +#24645 = ORIENTED_EDGE ( 'NONE', *, *, #27831, .F. ) ; +#24646 = ORIENTED_EDGE ( 'NONE', *, *, #7485, .F. ) ; +#24647 = CARTESIAN_POINT ( 'NONE', ( 2.358838354253999903, 209.4281692024999870, 75.42491224581000608 ) ) ; +#24648 = DIRECTION ( 'NONE', ( -2.486577296501327517E-19, -1.000000000000000000, 1.222202472776332422E-14 ) ) ; +#24649 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #6663, #34464 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24650 = CARTESIAN_POINT ( 'NONE', ( 44.93984957629947274, 145.3877245808612031, 285.0133094889154677 ) ) ; +#24651 = LINE ( 'NONE', #19278, #26031 ) ; +#24652 = EDGE_LOOP ( 'NONE', ( #17565, #21066, #30739, #8076 ) ) ; +#24653 = ORIENTED_EDGE ( 'NONE', *, *, #11383, .T. ) ; +#24654 = ORIENTED_EDGE ( 'NONE', *, *, #40460, .F. ) ; +#24655 = ORIENTED_EDGE ( 'NONE', *, *, #40376, .T. ) ; +#24656 = CARTESIAN_POINT ( 'NONE', ( 41.04644941598475327, 220.4002260660249988, 75.53371351150769897 ) ) ; +#24657 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178582662422E-05, 0.0002331579774919529443 ) ) ; +#24658 = CYLINDRICAL_SURFACE ( 'NONE', #33753, 17.00000000000406430 ) ; +#24659 = CARTESIAN_POINT ( 'NONE', ( 35.89873956569999791, 192.3079086021000137, 104.2139990170999937 ) ) ; +#24660 = ADVANCED_FACE ( 'NONE', ( #34077 ), #33267, .F. ) ; +#24661 = ORIENTED_EDGE ( 'NONE', *, *, #32532, .F. ) ; +#24662 = ADVANCED_FACE ( 'NONE', ( #2421 ), #24401, .F. ) ; +#24663 = ORIENTED_EDGE ( 'NONE', *, *, #13597, .F. ) ; +#24664 = CARTESIAN_POINT ( 'NONE', ( -35.44810745642832472, 111.2706431035999941, 87.28919406043203821 ) ) ; +#24665 = ADVANCED_FACE ( 'NONE', ( #15485 ), #36775, .T. ) ; +#24666 = PLANE ( 'NONE', #24638 ) ; +#24667 = EDGE_CURVE ( 'NONE', #10753, #14963, #2623, .T. ) ; +#24668 = CARTESIAN_POINT ( 'NONE', ( 15.99983399408007934, 184.6056815932580832, 102.2628396612452661 ) ) ; +#24669 = ORIENTED_EDGE ( 'NONE', *, *, #19643, .T. ) ; +#24670 = PLANE ( 'NONE', #26499 ) ; +#24671 = FACE_OUTER_BOUND ( 'NONE', #39702, .T. ) ; +#24672 = CARTESIAN_POINT ( 'NONE', ( 40.85748915988408925, 189.7900928382927361, 106.8264131337932525 ) ) ; +#24673 = ORIENTED_EDGE ( 'NONE', *, *, #37448, .T. ) ; +#24674 = ADVANCED_FACE ( 'NONE', ( #24509 ), #21439, .T. ) ; +#24675 = VECTOR ( 'NONE', #1914, 1000.000000000000227 ) ; +#24676 = CARTESIAN_POINT ( 'NONE', ( -28.25689436368393714, 186.9042180597057836, 103.3333805992548093 ) ) ; +#24677 = CARTESIAN_POINT ( 'NONE', ( -3.789621669352976951, 167.8773217199183136, 101.2314878384422627 ) ) ; +#24678 = CONICAL_SURFACE ( 'NONE', #9018, 4.999996804348348256, 0.7853981633997131340 ) ; +#24679 = ADVANCED_FACE ( 'NONE', ( #35064 ), #6754, .T. ) ; +#24680 = CARTESIAN_POINT ( 'NONE', ( -19.31979924309097996, 124.8061162773214079, 177.8324071844828893 ) ) ; +#24681 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24682 = ORIENTED_EDGE ( 'NONE', *, *, #811, .T. ) ; +#24683 = CARTESIAN_POINT ( 'NONE', ( -25.50888515336086471, 210.1678456467333262, 75.57414870955754793 ) ) ; +#24684 = ORIENTED_EDGE ( 'NONE', *, *, #14361, .F. ) ; +#24685 = DIRECTION ( 'NONE', ( 0.0005884949961242131244, -0.2249510543439063315, 0.9743698870671262391 ) ) ; +#24686 = CARTESIAN_POINT ( 'NONE', ( -38.41865702959000117, 119.0471156571999956, 87.62986678990000655 ) ) ; +#24687 = DIRECTION ( 'NONE', ( -0.9999998176078294110, -4.624125832697041071E-09, 0.0006039737643754598991 ) ) ; +#24688 = EDGE_CURVE ( 'NONE', #22702, #16794, #29479, .T. ) ; +#24689 = ORIENTED_EDGE ( 'NONE', *, *, #8450, .F. ) ; +#24690 = LINE ( 'NONE', #9736, #22618 ) ; +#24691 = ORIENTED_EDGE ( 'NONE', *, *, #5514, .T. ) ; +#24692 = CARTESIAN_POINT ( 'NONE', ( -25.49272541574507756, 191.9759150222000130, 101.9368443076606781 ) ) ; +#24693 = CARTESIAN_POINT ( 'NONE', ( -27.47868548835393554, 187.3896051497354165, 103.4449709403760664 ) ) ; +#24694 = CARTESIAN_POINT ( 'NONE', ( 15.99999293039724257, 151.9655111556795362, 94.72726368743165892 ) ) ; +#24695 = EDGE_LOOP ( 'NONE', ( #24021, #27320, #36769, #32689 ) ) ; +#24696 = CARTESIAN_POINT ( 'NONE', ( 20.00178331300101320, 191.9758063960465790, 106.9093738487591736 ) ) ; +#24697 = AXIS2_PLACEMENT_3D ( 'NONE', #4714, #20874, #24158 ) ; +#24698 = FACE_OUTER_BOUND ( 'NONE', #19796, .T. ) ; +#24699 = LINE ( 'NONE', #40200, #9153 ) ; +#24700 = CARTESIAN_POINT ( 'NONE', ( -35.69752021810370479, 164.7755956597675890, 192.0310054951918062 ) ) ; +#24701 = PLANE ( 'NONE', #3787 ) ; +#24702 = CYLINDRICAL_SURFACE ( 'NONE', #25649, 2.000000000000011546 ) ; +#24703 = CARTESIAN_POINT ( 'NONE', ( -37.30738829746174900, 117.9206417508360119, 90.29031756689468580 ) ) ; +#24704 = AXIS2_PLACEMENT_3D ( 'NONE', #18714, #34849, #31213 ) ; +#24705 = ORIENTED_EDGE ( 'NONE', *, *, #5493, .T. ) ; +#24706 = ORIENTED_EDGE ( 'NONE', *, *, #6492, .T. ) ; +#24707 = CARTESIAN_POINT ( 'NONE', ( 14.29931438863112092, 182.1696114513096632, 104.4382672223416222 ) ) ; +#24708 = CARTESIAN_POINT ( 'NONE', ( 0.5638618802117814077, 189.0000000030334490, 105.7369977366696219 ) ) ; +#24709 = CARTESIAN_POINT ( 'NONE', ( 26.00076108762728211, 119.7153706401760758, 90.35460073770548206 ) ) ; +#24710 = ORIENTED_EDGE ( 'NONE', *, *, #13157, .T. ) ; +#24711 = CARTESIAN_POINT ( 'NONE', ( 30.06995708078038376, 134.8478347390543490, 93.33259620325232220 ) ) ; +#24712 = EDGE_CURVE ( 'NONE', #43, #22159, #1531, .T. ) ; +#24713 = EDGE_CURVE ( 'NONE', #5306, #16662, #338, .T. ) ; +#24714 = ORIENTED_EDGE ( 'NONE', *, *, #3432, .F. ) ; +#24715 = FACE_OUTER_BOUND ( 'NONE', #18977, .T. ) ; +#24716 = CARTESIAN_POINT ( 'NONE', ( -29.30068297576036329, 112.1827979207552204, 175.8248936460288689 ) ) ; +#24717 = CARTESIAN_POINT ( 'NONE', ( -3.773828854691173795, 143.5900193873110595, 95.64051042385062829 ) ) ; +#24718 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#24719 = EDGE_LOOP ( 'NONE', ( #19498, #1087, #4184, #20503 ) ) ; +#24720 = CARTESIAN_POINT ( 'NONE', ( 35.58419356007505030, 192.4129442132274903, 106.8842446272596760 ) ) ; +#24721 = CARTESIAN_POINT ( 'NONE', ( -44.17354594865898321, 122.7351850097861217, 88.13690480915462899 ) ) ; +#24722 = CARTESIAN_POINT ( 'NONE', ( -25.90186315104000059, 190.6817704679999963, 106.6412877755000181 ) ) ; +#24723 = CARTESIAN_POINT ( 'NONE', ( -25.46031050648948835, 116.3743324429477752, 90.28316222877178632 ) ) ; +#24724 = CARTESIAN_POINT ( 'NONE', ( -37.94542170312856655, 145.9448510932590466, 287.7682489638611401 ) ) ; +#24725 = ORIENTED_EDGE ( 'NONE', *, *, #13200, .T. ) ; +#24726 = DIRECTION ( 'NONE', ( 0.7933530821293327540, 0.5932640870757643903, 0.1364866662427079991 ) ) ; +#24727 = LINE ( 'NONE', #24930, #10793 ) ; +#24728 = CARTESIAN_POINT ( 'NONE', ( 37.44995078656224763, 191.4485665340594096, 104.3357062982521200 ) ) ; +#24729 = VECTOR ( 'NONE', #1249, 1000.000000000000114 ) ; +#24730 = CARTESIAN_POINT ( 'NONE', ( -46.04337971101557514, 125.2490563996582722, 91.73451529294362672 ) ) ; +#24731 = ORIENTED_EDGE ( 'NONE', *, *, #22582, .F. ) ; +#24732 = CARTESIAN_POINT ( 'NONE', ( 38.65471576631835404, 119.1564763279458816, 90.25899222980254422 ) ) ; +#24733 = FACE_OUTER_BOUND ( 'NONE', #15571, .T. ) ; +#24734 = CARTESIAN_POINT ( 'NONE', ( 24.72869410855758687, 213.5506750203912816, 73.04356857080210830 ) ) ; +#24735 = CARTESIAN_POINT ( 'NONE', ( 19.98316611204134929, 210.6265419835666819, 73.04643475079905102 ) ) ; +#24736 = EDGE_CURVE ( 'NONE', #35055, #22424, #2861, .T. ) ; +#24737 = CARTESIAN_POINT ( 'NONE', ( -17.94609826159735633, 149.1879437480716035, 179.6906816993563041 ) ) ; +#24738 = CARTESIAN_POINT ( 'NONE', ( -25.50804370222000372, 190.9259865639999987, 106.3128279799000069 ) ) ; +#24739 = CARTESIAN_POINT ( 'NONE', ( -30.80024147420870051, 183.2447159666111816, 101.9769020043998751 ) ) ; +#24740 = CARTESIAN_POINT ( 'NONE', ( 10.31965884734673722, 131.0228646151953456, 89.89575833596944676 ) ) ; +#24741 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455649311516, -31.54510897440487938, 136.4474729010643159 ) ) ; +#24742 = FACE_OUTER_BOUND ( 'NONE', #3606, .T. ) ; +#24743 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35467, #17485, #20773, #19946, #38754, #20562, #1556, #38560, #16873, #33033, #29382, #4813, #5024, #23047, #7891, #4618 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.0003877968441633214782, 0.0007755936883266429565, 0.001163390532489964272, 0.001551187376653285913, 0.001938984220816607337, 0.002326781064979928544, 0.003102374753306582668 ), + .UNSPECIFIED. ) ; +#24744 = CARTESIAN_POINT ( 'NONE', ( 23.35435660873492125, 181.0170614477807476, 104.5088077577469221 ) ) ; +#24745 = VERTEX_POINT ( 'NONE', #6269 ) ; +#24746 = DIRECTION ( 'NONE', ( 2.489096615839555607E-14, -0.9743700558016280544, -0.2249510932561391563 ) ) ; +#24747 = CARTESIAN_POINT ( 'NONE', ( -20.15558927018948765, 184.3214773799085435, 105.1365765294155921 ) ) ; +#24748 = CARTESIAN_POINT ( 'NONE', ( -21.48817384324611979, 118.0722736972649898, 177.1883150436515280 ) ) ; +#24749 = CARTESIAN_POINT ( 'NONE', ( 36.36654068213999835, 191.7219889394999939, 106.3953969253999929 ) ) ; +#24750 = CARTESIAN_POINT ( 'NONE', ( 36.36211810150999924, 190.7161817749000079, 106.8880682140000005 ) ) ; +#24751 = ORIENTED_EDGE ( 'NONE', *, *, #1360, .F. ) ; +#24752 = ORIENTED_EDGE ( 'NONE', *, *, #29239, .F. ) ; +#24754 = AXIS2_PLACEMENT_3D ( 'NONE', #192, #21493, #39865 ) ; +#24753 = DIRECTION ( 'NONE', ( 0.1943643238945209628, -0.07321898756438961764, 0.9781929714821464561 ) ) ; +#24755 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319114355331 ) ) ; +#24756 = VECTOR ( 'NONE', #5748, 999.9999999999998863 ) ; +#24757 = CARTESIAN_POINT ( 'NONE', ( 25.83391288418735598, 118.1142945796899255, 90.08549593924796284 ) ) ; +#24758 = VECTOR ( 'NONE', #1314, 1000.000000000000114 ) ; +#24759 = EDGE_CURVE ( 'NONE', #4954, #19471, #18723, .T. ) ; +#24760 = EDGE_CURVE ( 'NONE', #18814, #25255, #24649, .T. ) ; +#24761 = ORIENTED_EDGE ( 'NONE', *, *, #12820, .T. ) ; +#24762 = CARTESIAN_POINT ( 'NONE', ( -38.90251905809999755, 119.2803178473000116, 90.18438403657999913 ) ) ; +#24763 = DIRECTION ( 'NONE', ( 0.0005884949961279498272, -0.2249510543439066645, 0.9743698870671262391 ) ) ; +#24764 = DIRECTION ( 'NONE', ( 3.469446951933831529E-16, -1.000000000000000000, -2.775557561547065224E-15 ) ) ; +#24765 = ORIENTED_EDGE ( 'NONE', *, *, #9688, .T. ) ; +#24766 = DIRECTION ( 'NONE', ( -0.7066795775160008564, -0.000000000000000000, 0.7075337269147008445 ) ) ; +#24767 = LINE ( 'NONE', #37614, #32878 ) ; +#24768 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971567068 ) ) ; +#24769 = DIRECTION ( 'NONE', ( -0.0005884949961246437695, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#24770 = CARTESIAN_POINT ( 'NONE', ( 24.86462005268900910, 181.6234868533236693, 104.6479044067249333 ) ) ; +#24771 = CARTESIAN_POINT ( 'NONE', ( -20.01839443158612397, 211.4829603436011780, 76.07060235661742809 ) ) ; +#24772 = ORIENTED_EDGE ( 'NONE', *, *, #6316, .F. ) ; +#24773 = CARTESIAN_POINT ( 'NONE', ( -28.12454816702999949, 187.5040379097000027, 103.0833663594000029 ) ) ; +#24774 = CARTESIAN_POINT ( 'NONE', ( 2.029765967374830282, 189.6354671328150232, 103.8765996616880045 ) ) ; +#24775 = FACE_OUTER_BOUND ( 'NONE', #29658, .T. ) ; +#24776 = EDGE_LOOP ( 'NONE', ( #14589, #34947, #2302, #31467 ) ) ; +#24777 = ORIENTED_EDGE ( 'NONE', *, *, #23358, .F. ) ; +#24778 = CARTESIAN_POINT ( 'NONE', ( 3.534206243108678702, 168.5015396740323581, 98.55243403413919623 ) ) ; +#24779 = VERTEX_POINT ( 'NONE', #18935 ) ; +#24780 = AXIS2_PLACEMENT_3D ( 'NONE', #31694, #38408, #13673 ) ; +#24781 = EDGE_CURVE ( 'NONE', #34802, #23158, #32230, .T. ) ; +#24782 = CIRCLE ( 'NONE', #5818, 22.00000000001092815 ) ; +#24783 = CONICAL_SURFACE ( 'NONE', #11051, 5.000000000100801145, 0.7853981634448925497 ) ; +#24784 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825598724, 151.4111237538535022, 97.16110465179032474 ) ) ; +#24785 = CARTESIAN_POINT ( 'NONE', ( -35.95747480195999657, 192.2464068831000077, 105.0133062726000190 ) ) ; +#24786 = VECTOR ( 'NONE', #2446, 1000.000000000000000 ) ; +#24787 = FACE_OUTER_BOUND ( 'NONE', #25939, .T. ) ; +#24788 = DIRECTION ( 'NONE', ( -0.6087614115774877543, 0.7730004600455410158, 0.1785492440296698458 ) ) ; +#24789 = CARTESIAN_POINT ( 'NONE', ( 36.06517739910999865, 192.1776130000999956, 106.5431043960000039 ) ) ; +#24790 = CARTESIAN_POINT ( 'NONE', ( -25.50127375672713725, 118.8155664721400058, 87.78318651355773738 ) ) ; +#24791 = CARTESIAN_POINT ( 'NONE', ( -36.63236904341999889, 191.1666167420000022, 106.4755554933000070 ) ) ; +#24792 = ORIENTED_EDGE ( 'NONE', *, *, #15755, .T. ) ; +#24793 = EDGE_CURVE ( 'NONE', #27115, #13672, #39239, .T. ) ; +#24794 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7503, #16499, #22469, #16304 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.003194535362460158325, 0.003705816747171950844 ), + .UNSPECIFIED. ) ; +#24795 = CARTESIAN_POINT ( 'NONE', ( -30.04055490880000079, 163.2729245447999915, 152.4718672074000381 ) ) ; +#24796 = DIRECTION ( 'NONE', ( -0.9999998176071864808, 0.000000000000000000, 0.0006039748286988863828 ) ) ; +#24798 = CARTESIAN_POINT ( 'NONE', ( -15.94475171933955693, 152.3708470875648686, 183.5791127486476171 ) ) ; +#24797 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24799 = VERTEX_POINT ( 'NONE', #3595 ) ; +#24800 = ORIENTED_EDGE ( 'NONE', *, *, #11877, .T. ) ; +#24801 = ADVANCED_FACE ( 'NONE', ( #28762 ), #38164, .F. ) ; +#24802 = ORIENTED_EDGE ( 'NONE', *, *, #34057, .F. ) ; +#24803 = EDGE_CURVE ( 'NONE', #16205, #1321, #447, .T. ) ; +#24804 = ORIENTED_EDGE ( 'NONE', *, *, #3305, .F. ) ; +#24805 = CARTESIAN_POINT ( 'NONE', ( 39.66605737025999900, 119.4471712140000079, 89.89566567319000967 ) ) ; +#24806 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -2.074124140377000483E-15, -0.0006039748319395083463 ) ) ; +#24807 = AXIS2_PLACEMENT_3D ( 'NONE', #24368, #36815, #8201 ) ; +#24808 = EDGE_CURVE ( 'NONE', #37651, #3915, #35869, .T. ) ; +#24809 = PLANE ( 'NONE', #31267 ) ; +#24810 = CARTESIAN_POINT ( 'NONE', ( -20.25903087670999980, 201.9933824238000000, 90.49061847330999342 ) ) ; +#24811 = CARTESIAN_POINT ( 'NONE', ( -12.64073606257721494, 135.0070896801547633, 90.95226204523241620 ) ) ; +#24812 = VERTEX_POINT ( 'NONE', #4607 ) ; +#24813 = VECTOR ( 'NONE', #10758, 1000.000000000000227 ) ; +#24814 = ORIENTED_EDGE ( 'NONE', *, *, #30184, .F. ) ; +#24815 = AXIS2_PLACEMENT_3D ( 'NONE', #22676, #973, #35911 ) ; +#24816 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22849, #953, #17077, #32247 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 3.918369104575206286E-11, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24817 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#24818 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901852, 132.2978364233190689, 93.26432363104480316 ) ) ; +#24819 = CIRCLE ( 'NONE', #1256, 6.000000000000007994 ) ; +#24820 = CARTESIAN_POINT ( 'NONE', ( 13.49999896020854528, 126.8049029696502430, 88.91681356176201234 ) ) ; +#24821 = LINE ( 'NONE', #40318, #11894 ) ; +#24822 = ORIENTED_EDGE ( 'NONE', *, *, #32262, .F. ) ; +#24823 = DIRECTION ( 'NONE', ( -0.7066795775298632121, -2.488830132209913689E-16, 0.7075337269008552532 ) ) ; +#24824 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11578, #20980, #15638, #17881, #30991, #2957, #18685, #39976, #11986, #37121, #15251, #30591, #6228, #6034, #9116, #39567, #27939, #21399 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.0009489744502343151061, 0.001423461675351503017, 0.001897948900468690928, 0.002372436125585878838, 0.002609679738144433762, 0.002846923350702988253, 0.003321410575820165322, 0.003795897800937342390 ), + .UNSPECIFIED. ) ; +#24825 = CARTESIAN_POINT ( 'NONE', ( 2.685831556720999824, 190.9742776067000136, 106.4315507416000059 ) ) ; +#24826 = VERTEX_POINT ( 'NONE', #10757 ) ; +#24827 = CARTESIAN_POINT ( 'NONE', ( 1.802356818792059556, 188.6677323499311569, 106.3017207989387884 ) ) ; +#24828 = VERTEX_POINT ( 'NONE', #38358 ) ; +#24829 = EDGE_CURVE ( 'NONE', #27587, #11205, #12009, .T. ) ; +#24830 = CARTESIAN_POINT ( 'NONE', ( -0.01811060958565999940, 181.5011387225000021, 104.6346866557999959 ) ) ; +#24831 = CARTESIAN_POINT ( 'NONE', ( 2.814369781637076962, 190.9457800965926708, 106.5567121617033166 ) ) ; +#24832 = LINE ( 'NONE', #11738, #28077 ) ; +#24833 = VERTEX_POINT ( 'NONE', #11162 ) ; +#24834 = CARTESIAN_POINT ( 'NONE', ( 25.99899579567804864, 120.3902236066977025, 87.43149108636995948 ) ) ; +#24835 = CARTESIAN_POINT ( 'NONE', ( -33.70405643004532692, 218.5902260770999987, 76.07886103513565956 ) ) ; +#24836 = CARTESIAN_POINT ( 'NONE', ( 0.5456353355600667143, 208.9999999999988916, 75.55817498829235035 ) ) ; +#24837 = AXIS2_PLACEMENT_3D ( 'NONE', #32055, #347, #29183 ) ; +#24838 = AXIS2_PLACEMENT_3D ( 'NONE', #21538, #27883, #12503 ) ; +#24839 = ORIENTED_EDGE ( 'NONE', *, *, #2816, .T. ) ; +#24840 = ADVANCED_FACE ( 'NONE', ( #23633 ), #17836, .T. ) ; +#24841 = AXIS2_PLACEMENT_3D ( 'NONE', #37349, #12592, #31419 ) ; +#24842 = VECTOR ( 'NONE', #36574, 1000.000000000000114 ) ; +#24843 = CARTESIAN_POINT ( 'NONE', ( -23.36150835703034190, 130.4188133218702319, 90.28973853220963974 ) ) ; +#24844 = ORIENTED_EDGE ( 'NONE', *, *, #30615, .T. ) ; +#24846 = CARTESIAN_POINT ( 'NONE', ( -3.169906973602109712, 126.7999172216492099, 88.92891361563410157 ) ) ; +#24845 = CARTESIAN_POINT ( 'NONE', ( -13.50718409113456886, 124.3648481134796242, 88.37302201493642428 ) ) ; +#24847 = ORIENTED_EDGE ( 'NONE', *, *, #2634, .T. ) ; +#24849 = ORIENTED_EDGE ( 'NONE', *, *, #23162, .F. ) ; +#24848 = ADVANCED_FACE ( 'NONE', ( #36082 ), #17062, .T. ) ; +#24850 = ORIENTED_EDGE ( 'NONE', *, *, #29730, .F. ) ; +#24851 = CARTESIAN_POINT ( 'NONE', ( 2.600535225549999829, 209.5323685392000073, 75.67987893369000574 ) ) ; +#24852 = EDGE_CURVE ( 'NONE', #20460, #25549, #35457, .T. ) ; +#24853 = CARTESIAN_POINT ( 'NONE', ( 3.166355817006013318, 184.7209557258482562, 102.2972154149039170 ) ) ; +#24854 = EDGE_LOOP ( 'NONE', ( #28283, #31662, #14494, #20563, #33967, #37842 ) ) ; +#24855 = ORIENTED_EDGE ( 'NONE', *, *, #25799, .T. ) ; +#24856 = ADVANCED_FACE ( 'NONE', ( #8084 ), #27696, .F. ) ; +#24857 = ORIENTED_EDGE ( 'NONE', *, *, #3716, .F. ) ; +#24858 = CARTESIAN_POINT ( 'NONE', ( -30.69720236079256992, 110.6131156702000027, 88.78632490663589749 ) ) ; +#24859 = DIRECTION ( 'NONE', ( 0.7933533411653264089, -0.5930537057989665461, -0.1373964268091649732 ) ) ; +#24860 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; +#24861 = ORIENTED_EDGE ( 'NONE', *, *, #17228, .T. ) ; +#24862 = ORIENTED_EDGE ( 'NONE', *, *, #35972, .T. ) ; +#24863 = ORIENTED_EDGE ( 'NONE', *, *, #24941, .F. ) ; +#24864 = CARTESIAN_POINT ( 'NONE', ( -5.670012814440080540, 124.0935331432966535, 91.03995203424359772 ) ) ; +#24865 = CARTESIAN_POINT ( 'NONE', ( 20.94615154526903567, 129.3425601203839221, 89.50137061379278691 ) ) ; +#24866 = CARTESIAN_POINT ( 'NONE', ( -25.73111875745999910, 121.5455867069999982, 88.07164025260999551 ) ) ; +#24867 = AXIS2_PLACEMENT_3D ( 'NONE', #3761, #16630, #31394 ) ; +#24868 = VERTEX_POINT ( 'NONE', #24041 ) ; +#24869 = CARTESIAN_POINT ( 'NONE', ( -14.46467930928257495, 149.8570382443049596, 184.5378989473168758 ) ) ; +#24870 = LINE ( 'NONE', #11784, #3868 ) ; +#24871 = AXIS2_PLACEMENT_3D ( 'NONE', #5975, #18027, #34174 ) ; +#24872 = EDGE_LOOP ( 'NONE', ( #25601, #26115, #1067, #32914 ) ) ; +#24873 = CIRCLE ( 'NONE', #33330, 2.000000000000000000 ) ; +#24874 = CIRCLE ( 'NONE', #18321, 2.499999999953833374 ) ; +#24875 = CARTESIAN_POINT ( 'NONE', ( 3.691301857067404324, 174.7169919634399662, 102.9066912158349254 ) ) ; +#24876 = CARTESIAN_POINT ( 'NONE', ( 14.29793062126701386, 176.6394715875823920, 100.7668241702324963 ) ) ; +#24877 = FACE_OUTER_BOUND ( 'NONE', #15458, .T. ) ; +#24878 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250611660, 132.8554482850399836, 90.84904174544993793 ) ) ; +#24879 = DIRECTION ( 'NONE', ( -0.5989082241854613020, 0.8008175873178837723, 0.0003617255600150170764 ) ) ; +#24880 = EDGE_LOOP ( 'NONE', ( #27409, #14972 ) ) ; +#24881 = LINE ( 'NONE', #5437, #3400 ) ; +#24882 = CARTESIAN_POINT ( 'NONE', ( 37.50072579531459382, 80.67056815341622666, 284.7731742817271652 ) ) ; +#24883 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#24884 = CARTESIAN_POINT ( 'NONE', ( 37.71625730213000338, 118.5106538418999946, 90.40116625531000238 ) ) ; +#24885 = CARTESIAN_POINT ( 'NONE', ( 45.20175636960371435, 116.0874664461612014, 126.6159648105440709 ) ) ; +#24886 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5761, #30717, #2710, #25 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 2.257925450127345695E-06, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24887 = EDGE_LOOP ( 'NONE', ( #2035, #5762, #25459, #36060 ) ) ; +#24888 = CARTESIAN_POINT ( 'NONE', ( 20.79492132475692401, 105.5805168949505486, 90.25522522787177593 ) ) ; +#24889 = ADVANCED_FACE ( 'NONE', ( #11773 ), #15243, .F. ) ; +#24890 = ORIENTED_EDGE ( 'NONE', *, *, #7353, .T. ) ; +#24891 = FACE_OUTER_BOUND ( 'NONE', #34408, .T. ) ; +#24892 = EDGE_CURVE ( 'NONE', #25997, #28271, #11569, .T. ) ; +#24893 = ADVANCED_FACE ( 'NONE', ( #21173 ), #225, .F. ) ; +#24894 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21428, #27765, #27168, #30209 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24895 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24896 = AXIS2_PLACEMENT_3D ( 'NONE', #26516, #7479, #1347 ) ; +#24897 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14746, #21076, #33523, #32730, #1647, #31481 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24898 = VERTEX_POINT ( 'NONE', #5628 ) ; +#24899 = FACE_OUTER_BOUND ( 'NONE', #31433, .T. ) ; +#24900 = EDGE_CURVE ( 'NONE', #35520, #23170, #21393, .T. ) ; +#24901 = AXIS2_PLACEMENT_3D ( 'NONE', #27975, #12602, #15087 ) ; +#24902 = CARTESIAN_POINT ( 'NONE', ( -39.72145289206626018, 121.0205764120224785, 124.6541090863944561 ) ) ; +#24903 = DIRECTION ( 'NONE', ( 0.1632030863883311977, -0.3417424275059330885, 0.9255143790539803739 ) ) ; +#24904 = CARTESIAN_POINT ( 'NONE', ( -35.36713754167588064, 164.6438278936635129, 191.4737616427881051 ) ) ; +#24905 = CARTESIAN_POINT ( 'NONE', ( 23.36311786012575453, 177.3181033220963911, 100.9835260450758767 ) ) ; +#24906 = CARTESIAN_POINT ( 'NONE', ( -35.64357260033455077, 114.3379716377514228, 90.28931266390532073 ) ) ; +#24907 = ORIENTED_EDGE ( 'NONE', *, *, #11018, .F. ) ; +#24908 = VERTEX_POINT ( 'NONE', #11350 ) ; +#24909 = EDGE_CURVE ( 'NONE', #28309, #21459, #33522, .T. ) ; +#24910 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 3.781471998463680422E-12, 291.5876487235622108 ) ) ; +#24911 = DIRECTION ( 'NONE', ( 0.7072735235945206700, 0.6508952239914190807, 0.2758615054830080293 ) ) ; +#24912 = EDGE_LOOP ( 'NONE', ( #9805, #30311, #37671, #3527 ) ) ; +#24913 = PLANE ( 'NONE', #33750 ) ; +#24914 = ORIENTED_EDGE ( 'NONE', *, *, #7688, .T. ) ; +#24915 = CARTESIAN_POINT ( 'NONE', ( -20.50418741012917678, 191.9757880780653068, 101.9338467359436322 ) ) ; +#24916 = ADVANCED_FACE ( 'NONE', ( #40364 ), #9918, .F. ) ; +#24917 = CARTESIAN_POINT ( 'NONE', ( -5.667172181233267381, 130.8762171797660869, 89.99523841397406443 ) ) ; +#24918 = FACE_OUTER_BOUND ( 'NONE', #28938, .T. ) ; +#24919 = ORIENTED_EDGE ( 'NONE', *, *, #38018, .F. ) ; +#24920 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#24921 = CARTESIAN_POINT ( 'NONE', ( -43.57128771414367918, 121.9172130293124212, 88.19101713714755419 ) ) ; +#24922 = FACE_OUTER_BOUND ( 'NONE', #32527, .T. ) ; +#24923 = AXIS2_PLACEMENT_3D ( 'NONE', #21641, #21030, #2630 ) ; +#24924 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597321 ) ) ; +#24925 = CARTESIAN_POINT ( 'NONE', ( 3.333016505657594220, 125.9281135555316240, 88.72370363824984452 ) ) ; +#24926 = VERTEX_POINT ( 'NONE', #25258 ) ; +#24927 = AXIS2_PLACEMENT_3D ( 'NONE', #7033, #3363, #18689 ) ; +#24928 = CARTESIAN_POINT ( 'NONE', ( -14.55306118018871508, 176.9194272080598296, 100.5067835523781667 ) ) ; +#24929 = VECTOR ( 'NONE', #12479, 1000.000000000000114 ) ; +#24930 = CARTESIAN_POINT ( 'NONE', ( 15.46162228069872313, 153.1807904976651571, 28.07870763888208998 ) ) ; +#24931 = FACE_OUTER_BOUND ( 'NONE', #27767, .T. ) ; +#24932 = CARTESIAN_POINT ( 'NONE', ( -46.02961742942664358, 125.2286349362630204, 91.74328517761594526 ) ) ; +#24933 = ORIENTED_EDGE ( 'NONE', *, *, #8961, .T. ) ; +#24934 = ORIENTED_EDGE ( 'NONE', *, *, #11487, .F. ) ; +#24935 = PLANE ( 'NONE', #27094 ) ; +#24936 = DIRECTION ( 'NONE', ( -0.0005884949961219227473, 0.2249510543439028620, -0.9743698870671272383 ) ) ; +#24937 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#24938 = CARTESIAN_POINT ( 'NONE', ( -25.54227450396999899, 190.4807502401999955, 106.2100577384999980 ) ) ; +#24939 = EDGE_CURVE ( 'NONE', #30873, #22764, #9713, .T. ) ; +#24940 = EDGE_CURVE ( 'NONE', #7275, #35342, #16789, .T. ) ; +#24941 = EDGE_CURVE ( 'NONE', #27328, #8100, #11445, .T. ) ; +#24942 = CARTESIAN_POINT ( 'NONE', ( -12.63887418211175095, 181.8702697237338839, 101.8994121222765159 ) ) ; +#24943 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971581778 ) ) ; +#24944 = CARTESIAN_POINT ( 'NONE', ( -2.604006908027095779, 196.2716038095343265, 103.7464336095590340 ) ) ; +#24945 = CARTESIAN_POINT ( 'NONE', ( -37.52245665281768794, 145.6118553205347439, 282.0399067415914374 ) ) ; +#24946 = EDGE_CURVE ( 'NONE', #3689, #7666, #18732, .T. ) ; +#24947 = CARTESIAN_POINT ( 'NONE', ( -19.99825438583805237, 190.8509747501094580, 106.8052823956111013 ) ) ; +#24948 = CARTESIAN_POINT ( 'NONE', ( 36.19014522556999935, 192.0260854207000136, 105.7241431756999930 ) ) ; +#24949 = AXIS2_PLACEMENT_3D ( 'NONE', #27891, #21548, #6180 ) ; +#24950 = CARTESIAN_POINT ( 'NONE', ( 36.41168230344000278, 191.0646043602000077, 106.6848967381999955 ) ) ; +#24951 = ORIENTED_EDGE ( 'NONE', *, *, #20370, .F. ) ; +#24952 = ORIENTED_EDGE ( 'NONE', *, *, #6810, .F. ) ; +#24953 = ORIENTED_EDGE ( 'NONE', *, *, #39523, .T. ) ; +#24954 = VECTOR ( 'NONE', #20159, 999.9999999999998863 ) ; +#24955 = ADVANCED_FACE ( 'NONE', ( #13577 ), #31591, .F. ) ; +#24956 = CARTESIAN_POINT ( 'NONE', ( -5.255239607819333969, 135.0401204062967508, 90.83256365259357779 ) ) ; +#24957 = AXIS2_PLACEMENT_3D ( 'NONE', #36834, #8839, #21307 ) ; +#24958 = CARTESIAN_POINT ( 'NONE', ( 32.43759465430078137, 141.7182063835813324, 280.9329271823174281 ) ) ; +#24959 = CARTESIAN_POINT ( 'NONE', ( -30.07215349727681541, 177.7873460224360542, 100.7165300549321643 ) ) ; +#24960 = ORIENTED_EDGE ( 'NONE', *, *, #5041, .T. ) ; +#24961 = CARTESIAN_POINT ( 'NONE', ( 36.50162370931000311, 191.8959790318999978, 104.5103187171999934 ) ) ; +#24962 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971545418 ) ) ; +#24963 = CARTESIAN_POINT ( 'NONE', ( -15.10714331244187214, 129.6097141051087362, 89.58480571958619976 ) ) ; +#24964 = CYLINDRICAL_SURFACE ( 'NONE', #3975, 9.000000000000001776 ) ; +#24965 = ORIENTED_EDGE ( 'NONE', *, *, #33014, .T. ) ; +#24966 = CARTESIAN_POINT ( 'NONE', ( -21.57450327001340540, 130.0068484170668341, 89.85144842513163610 ) ) ; +#24967 = PLANE ( 'NONE', #28958 ) ; +#24968 = CARTESIAN_POINT ( 'NONE', ( 41.39749877257511201, 121.2433985891848067, 87.61916177723681187 ) ) ; +#24969 = CARTESIAN_POINT ( 'NONE', ( 37.02554508276092804, 117.3704043342096952, 90.24542233776027444 ) ) ; +#24970 = CARTESIAN_POINT ( 'NONE', ( -13.49823346095841714, 185.2306144803302459, 105.5070429579131144 ) ) ; +#24971 = ORIENTED_EDGE ( 'NONE', *, *, #8062, .T. ) ; +#24972 = CARTESIAN_POINT ( 'NONE', ( 13.43345251867550516, 169.1002433633066744, 29.42954392776661976 ) ) ; +#24973 = CARTESIAN_POINT ( 'NONE', ( 2.508104382811000121, 190.4796221226000057, 104.1196928475000050 ) ) ; +#24974 = CARTESIAN_POINT ( 'NONE', ( -28.46737701140902033, 184.1209660424817400, 102.1777913196515755 ) ) ; +#24975 = ORIENTED_EDGE ( 'NONE', *, *, #19721, .T. ) ; +#24976 = CARTESIAN_POINT ( 'NONE', ( 31.79629795468130027, 77.14301703112144537, 291.5393397680163616 ) ) ; +#24977 = ORIENTED_EDGE ( 'NONE', *, *, #19274, .F. ) ; +#24978 = CONICAL_SURFACE ( 'NONE', #6668, 2.499999999971520115, 0.7853981634347277918 ) ; +#24979 = AXIS2_PLACEMENT_3D ( 'NONE', #9346, #34259, #28166 ) ; +#24980 = CARTESIAN_POINT ( 'NONE', ( -16.56460900707709882, 121.8134807487768398, 177.5599358238133618 ) ) ; +#24981 = DIRECTION ( 'NONE', ( -0.7075229215369458480, -9.360719862668606239E-05, -0.7066903895890456200 ) ) ; +#24982 = CARTESIAN_POINT ( 'NONE', ( 13.49999901409649361, 138.5114860101464558, 91.61958570690872250 ) ) ; +#24983 = EDGE_CURVE ( 'NONE', #32940, #20118, #39709, .T. ) ; +#24984 = EDGE_CURVE ( 'NONE', #28078, #10631, #9493, .T. ) ; +#24985 = DIRECTION ( 'NONE', ( 0.7730662169443226484, 0.5272861007345267526, 0.3526159273084130130 ) ) ; +#24986 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#24987 = LINE ( 'NONE', #21911, #34059 ) ; +#24988 = CARTESIAN_POINT ( 'NONE', ( -13.46442671968396709, 158.3027909046028583, 96.20813345690331175 ) ) ; +#24989 = CARTESIAN_POINT ( 'NONE', ( -36.48805020081999828, 191.2769265263999898, 106.4956810465999979 ) ) ; +#24990 = ORIENTED_EDGE ( 'NONE', *, *, #16815, .T. ) ; +#24991 = DIRECTION ( 'NONE', ( 0.0005884949961183550717, -0.2249510543439067201, 0.9743698870671262391 ) ) ; +#24992 = CARTESIAN_POINT ( 'NONE', ( 19.71670726246199123, 125.1288345936551423, 175.0446023669997260 ) ) ; +#24993 = FACE_OUTER_BOUND ( 'NONE', #12497, .T. ) ; +#24995 = DIRECTION ( 'NONE', ( 0.0004161288024472093046, 0.5299192578742120130, 0.8480479980348188951 ) ) ; +#24994 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2255194953558363191, 0.9742386449830560124 ) ) ; +#24996 = ORIENTED_EDGE ( 'NONE', *, *, #39996, .T. ) ; +#24997 = VERTEX_POINT ( 'NONE', #2122 ) ; +#24998 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19647, #30989, #7181, #7376, #32141, #13932, #20450, #27029, #17375, #36412, #8416 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998875899, 0.3749999999998465672, 0.4374999999998260836, 0.4687499999998270828, 0.4999999999998280265, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#24999 = DIRECTION ( 'NONE', ( -0.5987319967475925875, -0.8009494341533932582, 0.000000000000000000 ) ) ; +#25000 = CONICAL_SURFACE ( 'NONE', #8683, 2.503023047069385942, 0.7853981633776393467 ) ; +#25001 = VERTEX_POINT ( 'NONE', #27493 ) ; +#25002 = CARTESIAN_POINT ( 'NONE', ( 39.81878037047000163, 119.5363919051000039, 89.91683048606999762 ) ) ; +#25004 = AXIS2_PLACEMENT_3D ( 'NONE', #26007, #15974, #28463 ) ; +#25003 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#25005 = EDGE_CURVE ( 'NONE', #33342, #38719, #33376, .T. ) ; +#25006 = VECTOR ( 'NONE', #37883, 1000.000000000000114 ) ; +#25007 = DIRECTION ( 'NONE', ( -0.6087614115774880874, 0.7730004600455407937, 0.1785492440296698458 ) ) ; +#25008 = CARTESIAN_POINT ( 'NONE', ( -3.168110071453226873, 118.9426017752647766, 90.19381027778267423 ) ) ; +#25009 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; +#25010 = ORIENTED_EDGE ( 'NONE', *, *, #3219, .F. ) ; +#25011 = CARTESIAN_POINT ( 'NONE', ( 15.95593686717950277, 122.0690666329238638, 173.7395398366195991 ) ) ; +#25012 = ORIENTED_EDGE ( 'NONE', *, *, #25640, .F. ) ; +#25013 = CARTESIAN_POINT ( 'NONE', ( -20.01758686034237655, 208.0209483956256804, 76.93031517792222473 ) ) ; +#25014 = CARTESIAN_POINT ( 'NONE', ( 19.98271301993268523, 207.8686081833218111, 77.26500776042075813 ) ) ; +#25015 = DIRECTION ( 'NONE', ( 0.0005884949961189402156, -0.2249510543439089960, 0.9743698870671257950 ) ) ; +#25016 = ORIENTED_EDGE ( 'NONE', *, *, #37474, .T. ) ; +#25017 = ORIENTED_EDGE ( 'NONE', *, *, #27359, .F. ) ; +#25018 = CARTESIAN_POINT ( 'NONE', ( 20.48231950984458649, 205.5677633305384120, 76.28703242847967658 ) ) ; +#25019 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8812, #27236, #15149, #27834, #33930, #5735 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.003244958643172611134, 0.5016224793215863231, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25020 = CARTESIAN_POINT ( 'NONE', ( 0.7856033910142913301, 188.6233245537923437, 103.1995748073575498 ) ) ; +#25021 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.298960938811000068E-14, 1.000000000000000000 ) ) ; +#25022 = ADVANCED_FACE ( 'NONE', ( #24209 ), #27020, .F. ) ; +#25023 = ORIENTED_EDGE ( 'NONE', *, *, #13782, .F. ) ; +#25024 = ORIENTED_EDGE ( 'NONE', *, *, #28305, .F. ) ; +#25025 = CARTESIAN_POINT ( 'NONE', ( -43.55091174308670787, 114.1088787615119600, 121.9228278241811125 ) ) ; +#25026 = LINE ( 'NONE', #14808, #32981 ) ; +#25027 = CARTESIAN_POINT ( 'NONE', ( 36.42022666025140865, 191.3502071219474772, 103.8076029485790883 ) ) ; +#25028 = CARTESIAN_POINT ( 'NONE', ( 41.55515210090072742, 120.2182341932538776, 89.94814927363270840 ) ) ; +#25029 = CIRCLE ( 'NONE', #12588, 48.00000000000002132 ) ; +#25030 = ORIENTED_EDGE ( 'NONE', *, *, #9053, .F. ) ; +#25031 = EDGE_CURVE ( 'NONE', #36967, #31566, #14602, .T. ) ; +#25032 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#25033 = AXIS2_PLACEMENT_3D ( 'NONE', #11764, #37104, #6022 ) ; +#25034 = EDGE_CURVE ( 'NONE', #6177, #1951, #9868, .T. ) ; +#25035 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#25036 = CARTESIAN_POINT ( 'NONE', ( 47.96253192634829077, 87.27946979429619034, 302.5295777741103507 ) ) ; +#25037 = EDGE_CURVE ( 'NONE', #33368, #2967, #2619, .T. ) ; +#25038 = CIRCLE ( 'NONE', #33498, 9.999999999999667821 ) ; +#25039 = ORIENTED_EDGE ( 'NONE', *, *, #7150, .T. ) ; +#25040 = EDGE_CURVE ( 'NONE', #27937, #7297, #27559, .T. ) ; +#25041 = CARTESIAN_POINT ( 'NONE', ( -28.46561152641095660, 183.4461128795074956, 105.1009009807951884 ) ) ; +#25042 = PLANE ( 'NONE', #12657 ) ; +#25043 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #10352, #7252 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 0.9999992929077466952 ), + .UNSPECIFIED. ) ; +#25045 = LINE ( 'NONE', #31363, #10277 ) ; +#25044 = DIRECTION ( 'NONE', ( 5.828670879282083197E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#25046 = VERTEX_POINT ( 'NONE', #13326 ) ; +#25047 = ORIENTED_EDGE ( 'NONE', *, *, #4530, .T. ) ; +#25048 = CARTESIAN_POINT ( 'NONE', ( 30.02141571457803337, 185.4797026207797899, 105.5350675521475381 ) ) ; +#25049 = LINE ( 'NONE', #35401, #31245 ) ; +#25050 = EDGE_LOOP ( 'NONE', ( #22087, #20153, #39897, #33454 ) ) ; +#25051 = EDGE_LOOP ( 'NONE', ( #38504, #24914, #15822, #7481 ) ) ; +#25052 = DIRECTION ( 'NONE', ( -3.006854025019484316E-14, -0.9743700557921584071, -0.2249510932971569566 ) ) ; +#25053 = FACE_OUTER_BOUND ( 'NONE', #40418, .T. ) ; +#25054 = CARTESIAN_POINT ( 'NONE', ( 8.329377690075951080, 151.1912382591438870, 94.89524035922103451 ) ) ; +#25055 = PLANE ( 'NONE', #39802 ) ; +#25056 = VECTOR ( 'NONE', #17409, 1000.000000000000000 ) ; +#25057 = ORIENTED_EDGE ( 'NONE', *, *, #35229, .T. ) ; +#25058 = ORIENTED_EDGE ( 'NONE', *, *, #15423, .T. ) ; +#25059 = CARTESIAN_POINT ( 'NONE', ( -5.669680444114638007, 123.9805980431854948, 91.11052156128529589 ) ) ; +#25060 = CARTESIAN_POINT ( 'NONE', ( 20.20873812859954555, 128.4129448192833820, 89.28717972900743405 ) ) ; +#25061 = AXIS2_PLACEMENT_3D ( 'NONE', #31935, #22732, #16372 ) ; +#25062 = CARTESIAN_POINT ( 'NONE', ( -41.95974523811950263, 77.14301703112136011, 284.1899085454229521 ) ) ; +#25063 = ORIENTED_EDGE ( 'NONE', *, *, #10349, .F. ) ; +#25064 = AXIS2_PLACEMENT_3D ( 'NONE', #28715, #37505, #15443 ) ; +#25065 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749095712, 132.4103119505919892, 92.77713868751720838 ) ) ; +#25066 = LINE ( 'NONE', #20252, #5178 ) ; +#25067 = ORIENTED_EDGE ( 'NONE', *, *, #13617, .T. ) ; +#25068 = EDGE_CURVE ( 'NONE', #33719, #7971, #28323, .T. ) ; +#25069 = FACE_OUTER_BOUND ( 'NONE', #16225, .T. ) ; +#25070 = CARTESIAN_POINT ( 'NONE', ( -21.44517133422852240, 176.2436636369649534, 103.4338440792942890 ) ) ; +#25071 = EDGE_CURVE ( 'NONE', #7877, #31651, #23103, .T. ) ; +#25072 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971577060 ) ) ; +#25073 = LINE ( 'NONE', #28331, #3204 ) ; +#25074 = VERTEX_POINT ( 'NONE', #26410 ) ; +#25075 = CARTESIAN_POINT ( 'NONE', ( -27.18627669408000003, 103.8631156702000027, 90.03420462350000264 ) ) ; +#25076 = ORIENTED_EDGE ( 'NONE', *, *, #14137, .F. ) ; +#25077 = VERTEX_POINT ( 'NONE', #35166 ) ; +#25079 = EDGE_CURVE ( 'NONE', #10320, #4933, #30426, .T. ) ; +#25078 = CARTESIAN_POINT ( 'NONE', ( 40.75388439505659477, 77.63890577630509426, 286.8133149076603559 ) ) ; +#25080 = EDGE_CURVE ( 'NONE', #38370, #16282, #36271, .T. ) ; +#25081 = CARTESIAN_POINT ( 'NONE', ( 19.73921667059327234, 149.8473492619755802, 180.1939462582248836 ) ) ; +#25082 = CYLINDRICAL_SURFACE ( 'NONE', #24227, 51.40509898897000340 ) ; +#25083 = EDGE_CURVE ( 'NONE', #16053, #22424, #33737, .T. ) ; +#25084 = EDGE_CURVE ( 'NONE', #34146, #37846, #37449, .T. ) ; +#25085 = CARTESIAN_POINT ( 'NONE', ( 15.99998378901094576, 184.9656665294078266, 102.3459542884652365 ) ) ; +#25086 = ORIENTED_EDGE ( 'NONE', *, *, #5668, .T. ) ; +#25087 = AXIS2_PLACEMENT_3D ( 'NONE', #21092, #11686, #27850 ) ; +#25088 = VECTOR ( 'NONE', #26794, 1000.000000000000000 ) ; +#25089 = CYLINDRICAL_SURFACE ( 'NONE', #6280, 6.000000000000008882 ) ; +#25090 = EDGE_LOOP ( 'NONE', ( #22930, #21354, #28732, #30160 ) ) ; +#25091 = VECTOR ( 'NONE', #10646, 1000.000000000000114 ) ; +#25092 = CARTESIAN_POINT ( 'NONE', ( -26.81810550607417554, 188.0528084918596221, 103.5976845505095554 ) ) ; +#25093 = VECTOR ( 'NONE', #10266, 1000.000000000000114 ) ; +#25094 = ORIENTED_EDGE ( 'NONE', *, *, #27299, .F. ) ; +#25095 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971565125 ) ) ; +#25096 = LINE ( 'NONE', #9542, #25199 ) ; +#25097 = CARTESIAN_POINT ( 'NONE', ( -49.98529739233697455, 137.2549075708836313, 297.5887348966869013 ) ) ; +#25098 = CARTESIAN_POINT ( 'NONE', ( -22.10847448091438139, 158.3221973905858704, 96.21783456353770703 ) ) ; +#25099 = CARTESIAN_POINT ( 'NONE', ( -35.50523995327358051, 113.6628431183386709, 90.28922911445282296 ) ) ; +#25100 = VERTEX_POINT ( 'NONE', #27447 ) ; +#25101 = EDGE_LOOP ( 'NONE', ( #839, #20769, #4655, #13545 ) ) ; +#25102 = CARTESIAN_POINT ( 'NONE', ( -38.95487693986197542, 209.7096538831000316, 76.08203239919926375 ) ) ; +#25103 = EDGE_CURVE ( 'NONE', #10007, #38150, #17778, .T. ) ; +#25104 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250907130, 179.1753088544017487, 103.5954339977648857 ) ) ; +#25105 = EDGE_LOOP ( 'NONE', ( #22490, #22230, #21400, #25671 ) ) ; +#25106 = CARTESIAN_POINT ( 'NONE', ( 30.06907600959092264, 134.5278394841953684, 93.53255188149118737 ) ) ; +#25107 = ORIENTED_EDGE ( 'NONE', *, *, #34005, .T. ) ; +#25108 = CARTESIAN_POINT ( 'NONE', ( -46.39481885264477512, 125.2269168869080431, 89.10500611615424305 ) ) ; +#25109 = CARTESIAN_POINT ( 'NONE', ( -3.761126252317481100, 143.5871800388951840, 95.65287630653199358 ) ) ; +#25110 = CARTESIAN_POINT ( 'NONE', ( -30.07186420872989530, 134.5903996172291102, 93.52297053483064815 ) ) ; +#25111 = ORIENTED_EDGE ( 'NONE', *, *, #7931, .F. ) ; +#25112 = CARTESIAN_POINT ( 'NONE', ( 28.34935775597000074, 125.4855392668000036, 88.94861811456999590 ) ) ; +#25113 = AXIS2_PLACEMENT_3D ( 'NONE', #18546, #14713, #9177 ) ; +#25114 = AXIS2_PLACEMENT_3D ( 'NONE', #37758, #345, #945 ) ; +#25115 = EDGE_CURVE ( 'NONE', #72, #34749, #17987, .T. ) ; +#25116 = FACE_OUTER_BOUND ( 'NONE', #22820, .T. ) ; +#25117 = LINE ( 'NONE', #19354, #35756 ) ; +#25118 = AXIS2_PLACEMENT_3D ( 'NONE', #8177, #8592, #23319 ) ; +#25119 = CARTESIAN_POINT ( 'NONE', ( -24.05908733069920302, 115.3062187369053788, 90.28231592508538483 ) ) ; +#25120 = CARTESIAN_POINT ( 'NONE', ( 20.06217115067450152, 160.1130821803652111, 96.60582295762662852 ) ) ; +#25121 = ORIENTED_EDGE ( 'NONE', *, *, #35352, .F. ) ; +#25122 = DIRECTION ( 'NONE', ( -0.0006039748319379876444, -1.544770086762009064E-14, -0.9999998176071845934 ) ) ; +#25123 = ADVANCED_FACE ( 'NONE', ( #33933 ), #24967, .F. ) ; +#25124 = CARTESIAN_POINT ( 'NONE', ( 42.44241944724925730, 182.6774603752619441, 137.7418560869625708 ) ) ; +#25125 = CARTESIAN_POINT ( 'NONE', ( 42.85442617173308832, 113.6598254356972149, 123.5406245648973993 ) ) ; +#25126 = EDGE_CURVE ( 'NONE', #29325, #31175, #5934, .T. ) ; +#25127 = DIRECTION ( 'NONE', ( 0.7933533411653097556, -0.5930537057989896388, -0.1373964268091597829 ) ) ; +#25128 = VERTEX_POINT ( 'NONE', #30891 ) ; +#25129 = CARTESIAN_POINT ( 'NONE', ( 38.47871008559464201, 119.0226701210926024, 90.24978937670915968 ) ) ; +#25130 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17692, #1771, #13835, #23243, #4819, #32644, #33038, #17285, #35679, #19950 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25131 = FACE_OUTER_BOUND ( 'NONE', #22187, .T. ) ; +#25132 = DIRECTION ( 'NONE', ( 0.0005884949961239157278, -0.2249510543439051935, 0.9743698870671265722 ) ) ; +#25133 = EDGE_CURVE ( 'NONE', #39586, #27000, #24767, .T. ) ; +#25134 = CARTESIAN_POINT ( 'NONE', ( -25.67278038845593713, 190.9183653190244172, 106.4822186747260275 ) ) ; +#25135 = ORIENTED_EDGE ( 'NONE', *, *, #11859, .T. ) ; +#25136 = CARTESIAN_POINT ( 'NONE', ( 37.96340687623389698, 191.0388351520254560, 103.7347888148996446 ) ) ; +#25137 = CARTESIAN_POINT ( 'NONE', ( 5.666787590609001946, 130.4226561650734766, 90.27309335910574362 ) ) ; +#25138 = AXIS2_PLACEMENT_3D ( 'NONE', #652, #9268, #3114 ) ; +#25139 = ORIENTED_EDGE ( 'NONE', *, *, #14354, .T. ) ; +#25140 = CYLINDRICAL_SURFACE ( 'NONE', #34186, 2.250000000000011102 ) ; +#25141 = LINE ( 'NONE', #28597, #37494 ) ; +#25142 = CARTESIAN_POINT ( 'NONE', ( -75.39652672445234316, 196.3653591838614147, 189.1162797731339822 ) ) ; +#25143 = CARTESIAN_POINT ( 'NONE', ( 37.68864880440000320, 190.9636362356999939, 106.2833514884000010 ) ) ; +#25144 = VECTOR ( 'NONE', #37348, 1000.000000000000114 ) ; +#25146 = ORIENTED_EDGE ( 'NONE', *, *, #4314, .T. ) ; +#25145 = CARTESIAN_POINT ( 'NONE', ( 36.20133086596000282, 190.8593587157999991, 106.9219863341999996 ) ) ; +#25147 = ORIENTED_EDGE ( 'NONE', *, *, #25950, .T. ) ; +#25148 = VERTEX_POINT ( 'NONE', #12669 ) ; +#25149 = CARTESIAN_POINT ( 'NONE', ( -3.893460978919630389, 148.9599728421477494, 129.9645419189286883 ) ) ; +#25150 = CARTESIAN_POINT ( 'NONE', ( 20.48673967653602901, 211.0896571907997554, 75.54495990469186495 ) ) ; +#25151 = CARTESIAN_POINT ( 'NONE', ( -28.94720267997999841, 110.6131156702000027, 88.78526795067999444 ) ) ; +#25152 = EDGE_LOOP ( 'NONE', ( #31593, #15265, #15399, #23638, #31825 ) ) ; +#25153 = CARTESIAN_POINT ( 'NONE', ( 36.28650120326999939, 114.3988653761000052, 87.86647717035999960 ) ) ; +#25154 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25155 = CARTESIAN_POINT ( 'NONE', ( 31.79542160255000027, 226.4002260771029285, 75.53930090045706436 ) ) ; +#25156 = DIRECTION ( 'NONE', ( 0.7066795775160008564, -1.024537656994001489E-14, -0.7075337269147008445 ) ) ; +#25157 = ADVANCED_FACE ( 'NONE', ( #6520 ), #3448, .T. ) ; +#25158 = VERTEX_POINT ( 'NONE', #16136 ) ; +#25159 = DIRECTION ( 'NONE', ( 5.677692444543882716E-15, 0.9743700557921585181, 0.2249510932971561239 ) ) ; +#25160 = EDGE_CURVE ( 'NONE', #23757, #20371, #10421, .T. ) ; +#25161 = EDGE_CURVE ( 'NONE', #13070, #24276, #6003, .T. ) ; +#25162 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#25163 = EDGE_CURVE ( 'NONE', #650, #33804, #4797, .T. ) ; +#25164 = CARTESIAN_POINT ( 'NONE', ( -6.831231556254691917, 155.4618032185357492, 100.6797548176731993 ) ) ; +#25165 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971552357 ) ) ; +#25166 = DIRECTION ( 'NONE', ( -0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; +#25167 = AXIS2_PLACEMENT_3D ( 'NONE', #21413, #6051, #15650 ) ; +#25168 = VERTEX_POINT ( 'NONE', #26363 ) ; +#25169 = FACE_OUTER_BOUND ( 'NONE', #32918, .T. ) ; +#25170 = CARTESIAN_POINT ( 'NONE', ( 1.551058168003000004, 189.2638696655000103, 103.7676963477999976 ) ) ; +#25171 = VECTOR ( 'NONE', #5320, 1000.000000000000114 ) ; +#25172 = CIRCLE ( 'NONE', #12745, 2.000000000000011546 ) ; +#25173 = CARTESIAN_POINT ( 'NONE', ( -42.84346822158022405, 121.2532099058262531, 90.73602644257893246 ) ) ; +#25174 = ADVANCED_FACE ( 'NONE', ( #25564 ), #7395, .F. ) ; +#25175 = ORIENTED_EDGE ( 'NONE', *, *, #11288, .F. ) ; +#25176 = VECTOR ( 'NONE', #26045, 1000.000000000000000 ) ; +#25177 = VERTEX_POINT ( 'NONE', #12374 ) ; +#25178 = CARTESIAN_POINT ( 'NONE', ( 13.51165246697000022, 180.7017300104000128, 28.07991271570000080 ) ) ; +#25179 = EDGE_LOOP ( 'NONE', ( #16194, #1943, #10258, #10644 ) ) ; +#25180 = ADVANCED_FACE ( 'NONE', ( #21601 ), #2960, .T. ) ; +#25181 = CARTESIAN_POINT ( 'NONE', ( -17.26178683907535927, 121.7484489831825130, 175.4673707433541949 ) ) ; +#25182 = CARTESIAN_POINT ( 'NONE', ( -20.51984876312966222, 210.1697757641009900, 73.57088085165091229 ) ) ; +#25183 = CARTESIAN_POINT ( 'NONE', ( 24.52812286584232382, 213.0894194010092519, 75.54387266846563875 ) ) ; +#25184 = CARTESIAN_POINT ( 'NONE', ( -12.63559448522873652, 176.9615553361401510, 103.3843939381521864 ) ) ; +#25185 = LINE ( 'NONE', #3465, #12868 ) ; +#25186 = ORIENTED_EDGE ( 'NONE', *, *, #28006, .T. ) ; +#25187 = PLANE ( 'NONE', #7533 ) ; +#25188 = DIRECTION ( 'NONE', ( -4.086237521180584978E-14, -0.9743700557921587402, -0.2249510932971558463 ) ) ; +#25189 = ORIENTED_EDGE ( 'NONE', *, *, #38131, .F. ) ; +#25190 = FACE_OUTER_BOUND ( 'NONE', #600, .T. ) ; +#25191 = DIRECTION ( 'NONE', ( -3.469446951953620894E-15, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#25192 = CARTESIAN_POINT ( 'NONE', ( -0.02805196447938418727, 127.1761617620222893, 297.5585619722723436 ) ) ; +#25193 = CARTESIAN_POINT ( 'NONE', ( 15.10764778216198323, 128.9370057249701063, 92.49016256005407399 ) ) ; +#25194 = VERTEX_POINT ( 'NONE', #20611 ) ; +#25195 = ORIENTED_EDGE ( 'NONE', *, *, #18512, .T. ) ; +#25196 = AXIS2_PLACEMENT_3D ( 'NONE', #9844, #32114, #31720 ) ; +#25197 = AXIS2_PLACEMENT_3D ( 'NONE', #21752, #21138, #36875 ) ; +#25198 = ORIENTED_EDGE ( 'NONE', *, *, #12537, .F. ) ; +#25199 = VECTOR ( 'NONE', #37149, 1000.000000000000114 ) ; +#25200 = CARTESIAN_POINT ( 'NONE', ( -20.16654258404202693, 118.8155352270249381, 87.44669327667693892 ) ) ; +#25201 = CIRCLE ( 'NONE', #14102, 7.999999999999992895 ) ; +#25202 = ORIENTED_EDGE ( 'NONE', *, *, #6307, .F. ) ; +#25203 = CARTESIAN_POINT ( 'NONE', ( 37.34003727481168511, 163.4882490151146328, 203.2693681478919245 ) ) ; +#25204 = LINE ( 'NONE', #634, #15890 ) ; +#25205 = CARTESIAN_POINT ( 'NONE', ( 23.68142001710316791, 134.4472197773023368, 93.58606303061318954 ) ) ; +#25206 = CARTESIAN_POINT ( 'NONE', ( 28.78718856440784180, 131.0245789305321011, 89.88494191302055469 ) ) ; +#25207 = CARTESIAN_POINT ( 'NONE', ( 13.50000077932746834, 154.4078840096753424, 95.29263748429374914 ) ) ; +#25208 = VERTEX_POINT ( 'NONE', #17731 ) ; +#25209 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25210 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17653, #39324, #39134, #8480 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25211 = ORIENTED_EDGE ( 'NONE', *, *, #17871, .T. ) ; +#25212 = ADVANCED_FACE ( 'NONE', ( #4861 ), #1602, .F. ) ; +#25213 = CARTESIAN_POINT ( 'NONE', ( 15.53487489549969247, 138.6412351325426755, 152.4706544089839326 ) ) ; +#25214 = EDGE_CURVE ( 'NONE', #24997, #9552, #23601, .T. ) ; +#25215 = DIRECTION ( 'NONE', ( -0.0005884949961221202890, 0.2249510543439054433, -0.9743698870671265722 ) ) ; +#25216 = ORIENTED_EDGE ( 'NONE', *, *, #9879, .T. ) ; +#25217 = CARTESIAN_POINT ( 'NONE', ( -19.99824965358324036, 191.4178399844840612, 106.9362295233956814 ) ) ; +#25218 = CARTESIAN_POINT ( 'NONE', ( 0.8185733436017654796, 188.6262843215965290, 103.2002382106960710 ) ) ; +#25219 = CARTESIAN_POINT ( 'NONE', ( -20.24985248663000093, 188.1876851508999948, 103.3682804701000038 ) ) ; +#25220 = APPROVAL ( #27814, '未' ) ; +#25221 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #377, #2896, #570, #25545, #22475, #21113, #33771, #39905, #27268, #31681, #5356 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000604516, 0.3750000000000907052, 0.4375000000000858202, 0.4687500000000547895, 0.5000000000000237588, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25222 = AXIS2_PLACEMENT_3D ( 'NONE', #39560, #11568, #27329 ) ; +#25223 = VERTEX_POINT ( 'NONE', #4562 ) ; +#25224 = CARTESIAN_POINT ( 'NONE', ( 5.667815391070724296, 126.2407929722768074, 91.36024196040290235 ) ) ; +#25225 = CARTESIAN_POINT ( 'NONE', ( -25.50087116340131743, 118.1131725775237413, 88.44976037191148066 ) ) ; +#25226 = ORIENTED_EDGE ( 'NONE', *, *, #39490, .T. ) ; +#25227 = CARTESIAN_POINT ( 'NONE', ( 20.56554265872798837, 117.4584777523052423, 89.75564615045188077 ) ) ; +#25228 = CARTESIAN_POINT ( 'NONE', ( 36.16093536340260783, 191.4947098609792988, 103.8411206460829277 ) ) ; +#25229 = CARTESIAN_POINT ( 'NONE', ( -25.81413844371000010, 122.5880832094999988, 90.39702476309000190 ) ) ; +#25230 = ORIENTED_EDGE ( 'NONE', *, *, #27895, .T. ) ; +#25231 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37785, #23064, #7507, #26145 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 1.217094566236478452E-11, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25232 = AXIS2_PLACEMENT_3D ( 'NONE', #37710, #494, #13381 ) ; +#25233 = CARTESIAN_POINT ( 'NONE', ( 0.8930066394032586397, 188.4030556334941195, 106.2275697269554655 ) ) ; +#25234 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; +#25235 = CARTESIAN_POINT ( 'NONE', ( 39.17918664236205473, 77.03152903297159071, 290.9156096052041676 ) ) ; +#25236 = EDGE_CURVE ( 'NONE', #8100, #26238, #26513, .T. ) ; +#25237 = VERTEX_POINT ( 'NONE', #19696 ) ; +#25238 = DIRECTION ( 'NONE', ( 0.0005884949961241158715, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25239 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23451, #19753, #7697, #7901 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25240 = CYLINDRICAL_SURFACE ( 'NONE', #13304, 2.000000000000014655 ) ; +#25242 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25241 = CARTESIAN_POINT ( 'NONE', ( 36.06891294252045554, 192.2247015031095714, 104.3873542762104449 ) ) ; +#25243 = ORIENTED_EDGE ( 'NONE', *, *, #28102, .T. ) ; +#25244 = VERTEX_POINT ( 'NONE', #27287 ) ; +#25245 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; +#25246 = AXIS2_PLACEMENT_3D ( 'NONE', #9917, #22590, #35012 ) ; +#25247 = DIRECTION ( 'NONE', ( -0.7066905299392122197, -0.1591580245907027458, 0.6893890179736117396 ) ) ; +#25248 = VERTEX_POINT ( 'NONE', #5166 ) ; +#25249 = ORIENTED_EDGE ( 'NONE', *, *, #35785, .T. ) ; +#25250 = CARTESIAN_POINT ( 'NONE', ( 2.783189324004925247, 209.6623415042751617, 75.89015708242718006 ) ) ; +#25251 = CARTESIAN_POINT ( 'NONE', ( 2.547144908305676747, 209.7096538831000032, 78.05696658266772658 ) ) ; +#25252 = CARTESIAN_POINT ( 'NONE', ( -2.557186615398999940, 190.9521776356999965, 106.4289101426000030 ) ) ; +#25253 = AXIS2_PLACEMENT_3D ( 'NONE', #5151, #33975, #5567 ) ; +#25254 = ORIENTED_EDGE ( 'NONE', *, *, #35485, .F. ) ; +#25255 = VERTEX_POINT ( 'NONE', #11730 ) ; +#25256 = CARTESIAN_POINT ( 'NONE', ( -6.032834300266884497, 177.0616227066033730, 103.5393503116357579 ) ) ; +#25257 = VECTOR ( 'NONE', #27845, 1000.000000000000114 ) ; +#25259 = EDGE_CURVE ( 'NONE', #6456, #33719, #8997, .T. ) ; +#25258 = CARTESIAN_POINT ( 'NONE', ( -5.658908186421000686, 187.6682623620686172, 106.0618792668577015 ) ) ; +#25260 = PLANE ( 'NONE', #5019 ) ; +#25261 = EDGE_CURVE ( 'NONE', #1494, #27517, #1570, .T. ) ; +#25262 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#25263 = ORIENTED_EDGE ( 'NONE', *, *, #12101, .T. ) ; +#25264 = CARTESIAN_POINT ( 'NONE', ( -29.42789445533455961, 116.9990604785378423, 176.9382643005241107 ) ) ; +#25265 = CARTESIAN_POINT ( 'NONE', ( 37.18882002358459715, 126.0768346319694189, 91.81650343837480932 ) ) ; +#25266 = ORIENTED_EDGE ( 'NONE', *, *, #536, .F. ) ; +#25267 = EDGE_CURVE ( 'NONE', #9107, #7260, #20927, .T. ) ; +#25268 = CARTESIAN_POINT ( 'NONE', ( 14.55306318046054592, 176.9232825744718411, 100.4900915860747403 ) ) ; +#25269 = ORIENTED_EDGE ( 'NONE', *, *, #15515, .T. ) ; +#25270 = CARTESIAN_POINT ( 'NONE', ( -39.71326994697852086, 161.5379849440253395, 197.5000934441027880 ) ) ; +#25271 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#25272 = LINE ( 'NONE', #31805, #1250 ) ; +#25273 = CIRCLE ( 'NONE', #7616, 2.500000000036972203 ) ; +#25274 = ORIENTED_EDGE ( 'NONE', *, *, #37884, .F. ) ; +#25275 = DIRECTION ( 'NONE', ( 0.9999998268366975251, 0.0001323826338100946118, -0.0005734120799280602960 ) ) ; +#25276 = ORIENTED_EDGE ( 'NONE', *, *, #18103, .T. ) ; +#25277 = CYLINDRICAL_SURFACE ( 'NONE', #23808, 2.000000000000000000 ) ; +#25278 = AXIS2_PLACEMENT_3D ( 'NONE', #1744, #26698, #33004 ) ; +#25279 = DIRECTION ( 'NONE', ( -0.7691761624280200049, -0.6302414090841089722, 0.1056588729268925636 ) ) ; +#25280 = CONICAL_SURFACE ( 'NONE', #38969, 40.50000000000950706, 0.7853981633972851872 ) ; +#25281 = CARTESIAN_POINT ( 'NONE', ( 13.49436806345008399, 123.6932719124138345, 91.28058047958029420 ) ) ; +#25282 = ADVANCED_FACE ( 'NONE', ( #15202 ), #27051, .T. ) ; +#25283 = DIRECTION ( 'NONE', ( 0.0002083763306416868528, -0.2252353001604435467, 0.9743043755115440296 ) ) ; +#25284 = ORIENTED_EDGE ( 'NONE', *, *, #39213, .F. ) ; +#25285 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25286 = VERTEX_POINT ( 'NONE', #23795 ) ; +#25287 = VECTOR ( 'NONE', #37499, 1000.000000000000114 ) ; +#25288 = CARTESIAN_POINT ( 'NONE', ( -37.83635444431042316, 190.3639788717852923, 106.7036751988638912 ) ) ; +#25289 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; +#25290 = ORIENTED_EDGE ( 'NONE', *, *, #90, .F. ) ; +#25291 = ORIENTED_EDGE ( 'NONE', *, *, #21047, .F. ) ; +#25292 = CARTESIAN_POINT ( 'NONE', ( -37.70435768791065101, 218.5902260770999987, 75.58127702559525574 ) ) ; +#25293 = ADVANCED_FACE ( 'NONE', ( #36249 ), #57, .T. ) ; +#25294 = CARTESIAN_POINT ( 'NONE', ( -26.30564657185992417, 122.5409679533868257, 87.95962032719154422 ) ) ; +#25295 = CARTESIAN_POINT ( 'NONE', ( -20.21161457727598076, 159.7565362432869165, 96.54783218446964099 ) ) ; +#25296 = ORIENTED_EDGE ( 'NONE', *, *, #8017, .T. ) ; +#25297 = CARTESIAN_POINT ( 'NONE', ( -15.49970617362840919, 138.0805224087925751, 92.05383544148693886 ) ) ; +#25298 = EDGE_LOOP ( 'NONE', ( #7100, #4874, #29065, #25249 ) ) ; +#25299 = VERTEX_POINT ( 'NONE', #6778 ) ; +#25300 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606776115838874, 137.3532831589803322, 178.0585834212922123 ) ) ; +#25301 = EDGE_CURVE ( 'NONE', #7897, #23733, #21746, .T. ) ; +#25302 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; +#25303 = CONICAL_SURFACE ( 'NONE', #10936, 5.000000517016990109, 0.7853981634346335339 ) ; +#25304 = ORIENTED_EDGE ( 'NONE', *, *, #34449, .T. ) ; +#25305 = CARTESIAN_POINT ( 'NONE', ( 5.957091369052168517, 163.5651307542015900, 97.41131042763848313 ) ) ; +#25306 = EDGE_CURVE ( 'NONE', #21532, #24320, #20633, .T. ) ; +#25307 = EDGE_CURVE ( 'NONE', #22348, #10007, #21673, .T. ) ; +#25308 = VERTEX_POINT ( 'NONE', #232 ) ; +#25309 = FACE_OUTER_BOUND ( 'NONE', #15977, .T. ) ; +#25310 = VECTOR ( 'NONE', #37689, 1000.000000000000000 ) ; +#25311 = EDGE_CURVE ( 'NONE', #2629, #26268, #22129, .T. ) ; +#25312 = ADVANCED_FACE ( 'NONE', ( #9452 ), #34558, .F. ) ; +#25313 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971564292 ) ) ; +#25314 = VERTEX_POINT ( 'NONE', #18820 ) ; +#25315 = CARTESIAN_POINT ( 'NONE', ( 27.72966693972999863, 125.2145490558000063, 89.05755400422999912 ) ) ; +#25316 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425102109, 184.2879064305327574, 105.2862044504857266 ) ) ; +#25317 = FACE_OUTER_BOUND ( 'NONE', #5358, .T. ) ; +#25318 = DIRECTION ( 'NONE', ( -0.0006039748319391919761, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#25319 = CARTESIAN_POINT ( 'NONE', ( 4.700715882528976763, 124.5561775271440581, 88.40614113511351491 ) ) ; +#25320 = ORIENTED_EDGE ( 'NONE', *, *, #2771, .F. ) ; +#25321 = CARTESIAN_POINT ( 'NONE', ( 20.00174647213199108, 119.1180879114202611, 90.25575134532356003 ) ) ; +#25322 = CARTESIAN_POINT ( 'NONE', ( 0.5911775542440182996, 189.0001913861286766, 103.6867748575926242 ) ) ; +#25323 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363196006660E-14, -0.9999998176071844824 ) ) ; +#25324 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; +#25325 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8029, #26862, #17627, #39301 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25326 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25327 = CARTESIAN_POINT ( 'NONE', ( 24.53469179845209780, 109.6131156702000027, 89.75296640909391499 ) ) ; +#25328 = CARTESIAN_POINT ( 'NONE', ( 12.63943526405010154, 181.6152899300451509, 104.1402435546899170 ) ) ; +#25329 = CARTESIAN_POINT ( 'NONE', ( 14.29788517226990585, 182.6944325685452952, 102.1647223417331816 ) ) ; +#25330 = ORIENTED_EDGE ( 'NONE', *, *, #22674, .T. ) ; +#25331 = CARTESIAN_POINT ( 'NONE', ( -25.67144920672187425, 190.9356798558488322, 106.4862152470520584 ) ) ; +#25332 = ORIENTED_EDGE ( 'NONE', *, *, #2076, .T. ) ; +#25333 = VECTOR ( 'NONE', #13279, 1000.000000000000227 ) ; +#25334 = VECTOR ( 'NONE', #6159, 1000.000000000000000 ) ; +#25335 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971570121 ) ) ; +#25336 = CARTESIAN_POINT ( 'NONE', ( -75.98858757284095589, 155.6702750673102287, 98.71704506522313238 ) ) ; +#25337 = ORIENTED_EDGE ( 'NONE', *, *, #26866, .F. ) ; +#25338 = DIRECTION ( 'NONE', ( 0.0006039748319341030564, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#25339 = DIRECTION ( 'NONE', ( -0.0004161288024615436500, 0.8480480897848248212, -0.5299191110434963159 ) ) ; +#25340 = EDGE_CURVE ( 'NONE', #37514, #19656, #39677, .T. ) ; +#25341 = CARTESIAN_POINT ( 'NONE', ( -22.78187663633837801, 153.7285825244628086, 98.23663543168041201 ) ) ; +#25342 = CARTESIAN_POINT ( 'NONE', ( -20.01841854128525711, 211.0875725380936103, 76.07063535483980843 ) ) ; +#25343 = CARTESIAN_POINT ( 'NONE', ( 36.82399100351999977, 191.4977938263000397, 106.2215044991999946 ) ) ; +#25344 = ORIENTED_EDGE ( 'NONE', *, *, #28798, .F. ) ; +#25345 = CARTESIAN_POINT ( 'NONE', ( -3.732613411896025912, 136.4113666306057269, 91.14822121766043495 ) ) ; +#25346 = ADVANCED_FACE ( 'NONE', ( #35360 ), #19824, .T. ) ; +#25347 = CARTESIAN_POINT ( 'NONE', ( -20.41894654420494959, 184.8665439626683735, 102.7752807765683798 ) ) ; +#25348 = EDGE_CURVE ( 'NONE', #6048, #12157, #21147, .T. ) ; +#25349 = CARTESIAN_POINT ( 'NONE', ( -32.37225756500890839, 173.7258698620904340, 102.8591651650622936 ) ) ; +#25350 = CARTESIAN_POINT ( 'NONE', ( 20.66773077360686983, 151.6559761831365734, 197.7415732814573630 ) ) ; +#25351 = ORIENTED_EDGE ( 'NONE', *, *, #6460, .T. ) ; +#25352 = CARTESIAN_POINT ( 'NONE', ( 13.50718655633492382, 188.3455032986072979, 103.1278069412195748 ) ) ; +#25353 = VERTEX_POINT ( 'NONE', #11878 ) ; +#25354 = EDGE_CURVE ( 'NONE', #5203, #20872, #21492, .T. ) ; +#25355 = CARTESIAN_POINT ( 'NONE', ( -3.330163502441660928, 129.4435835497653784, 89.53933837856635591 ) ) ; +#25356 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971553190 ) ) ; +#25357 = ORIENTED_EDGE ( 'NONE', *, *, #21700, .T. ) ; +#25358 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319379466615 ) ) ; +#25359 = AXIS2_PLACEMENT_3D ( 'NONE', #33989, #28091, #28473 ) ; +#25360 = CARTESIAN_POINT ( 'NONE', ( -15.83167302941029853, 126.1635038823812351, 91.69749185279336245 ) ) ; +#25361 = CARTESIAN_POINT ( 'NONE', ( -32.71652505805614197, 141.8894161721785849, 281.5012411679362003 ) ) ; +#25362 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052565999616 ) ) ; +#25363 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540971401, 126.6879451654999116, 89.42365126072036219 ) ) ; +#25364 = VERTEX_POINT ( 'NONE', #6125 ) ; +#25365 = ORIENTED_EDGE ( 'NONE', *, *, #12879, .T. ) ; +#25366 = CARTESIAN_POINT ( 'NONE', ( 21.72426698684031976, 130.1004708904147265, 89.67586055015539159 ) ) ; +#25367 = CARTESIAN_POINT ( 'NONE', ( -10.03773492422904035, 144.2121259786891585, 92.95297688159946858 ) ) ; +#25368 = DIRECTION ( 'NONE', ( -0.0001408393175929667886, 0.2255194967740913881, -0.9742386446549157197 ) ) ; +#25369 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11981, #24466, #36915, #98, #24668, #9112 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25370 = CARTESIAN_POINT ( 'NONE', ( -36.16377129200999718, 191.5154754321000041, 103.9966361450999983 ) ) ; +#25371 = EDGE_LOOP ( 'NONE', ( #28257, #25057, #22346, #19660 ) ) ; +#25372 = DIRECTION ( 'NONE', ( 0.0005464070472052447603, -0.2249510597163257852, 0.9743699103378761217 ) ) ; +#25373 = ORIENTED_EDGE ( 'NONE', *, *, #33244, .F. ) ; +#25374 = CARTESIAN_POINT ( 'NONE', ( -3.669581222327467973, 184.0117732734406104, 102.6507570783573300 ) ) ; +#25375 = CARTESIAN_POINT ( 'NONE', ( -14.03390129455813273, 182.0709040599587922, 101.6957796740224609 ) ) ; +#25376 = CARTESIAN_POINT ( 'NONE', ( -12.63563447629612035, 176.9474841518645860, 103.3618753611535936 ) ) ; +#25377 = CARTESIAN_POINT ( 'NONE', ( 26.87813338839999844, 134.5475818962999881, 93.52178121608000083 ) ) ; +#25378 = AXIS2_PLACEMENT_3D ( 'NONE', #22334, #29056, #34759 ) ; +#25379 = CARTESIAN_POINT ( 'NONE', ( -2.321500140915000010, 209.0507070170999953, 73.74245843209999407 ) ) ; +#25380 = CARTESIAN_POINT ( 'NONE', ( -0.4361371085228029076, 189.0000000148081654, 105.7376017109280184 ) ) ; +#25381 = ORIENTED_EDGE ( 'NONE', *, *, #35152, .F. ) ; +#25382 = ADVANCED_FACE ( 'NONE', ( #36402 ), #20867, .F. ) ; +#25383 = CARTESIAN_POINT ( 'NONE', ( -12.64562993050861550, 181.6872450680611450, 101.6064063805796280 ) ) ; +#25384 = EDGE_CURVE ( 'NONE', #31175, #978, #33729, .T. ) ; +#25385 = CIRCLE ( 'NONE', #22145, 7.999999999973976372 ) ; +#25386 = FACE_OUTER_BOUND ( 'NONE', #21993, .T. ) ; +#25387 = DIRECTION ( 'NONE', ( -0.5988683521957608447, 0.8008474865655346164, 0.000000000000000000 ) ) ; +#25388 = AXIS2_PLACEMENT_3D ( 'NONE', #19416, #19207, #16349 ) ; +#25389 = ADVANCED_FACE ( 'NONE', ( #27233 ), #30684, .T. ) ; +#25390 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18487, #33839, #5840, #8721 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25392 = ADVANCED_FACE ( 'NONE', ( #16129 ), #19178, .F. ) ; +#25391 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1732, #14214, #8273, #26684, #39137, #39325, #36058, #20735, #33186, #20526 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25393 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#25394 = ORIENTED_EDGE ( 'NONE', *, *, #33393, .T. ) ; +#25395 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15292, #3200, #11830, #27780, #150, #40212, #27388, #34081, #6078, #30634, #33474, #15491, #25109, #24717, #24312, #27982, #2627 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000001012246, 0.1875000000001414979, 0.2187500000001616485, 0.2343750000001933453, 0.2421875000002091938, 0.2500000000002250422, 0.3750000000001751932, 0.4375000000001502687, 0.5000000000001253442, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25396 = VERTEX_POINT ( 'NONE', #3053 ) ; +#25397 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#25398 = ADVANCED_FACE ( 'NONE', ( #37806 ), #28612, .T. ) ; +#25399 = DIRECTION ( 'NONE', ( -0.5276053854356862471, 0.5676772811992385481, -0.6319612817803805793 ) ) ; +#25400 = FACE_BOUND ( 'NONE', #22238, .T. ) ; +#25401 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1333, #28560, #13813, #528, #17866, #26497, #20541, #14842, #5004, #11768 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.0004318883629631480991, 0.0008637767259262961982, 0.001295665088889418710, 0.001727553451852541005 ), + .UNSPECIFIED. ) ; +#25402 = ORIENTED_EDGE ( 'NONE', *, *, #617, .T. ) ; +#25403 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#25404 = EDGE_CURVE ( 'NONE', #29199, #37303, #31275, .T. ) ; +#25405 = CARTESIAN_POINT ( 'NONE', ( -31.84898476996059813, 157.9423125112969331, 186.4027463543498584 ) ) ; +#25406 = DIRECTION ( 'NONE', ( 0.6771712326825870543, -0.7358254695422995484, 0.000000000000000000 ) ) ; +#25407 = CARTESIAN_POINT ( 'NONE', ( -38.24845629298000205, 118.9502302476000040, 87.58082788912000183 ) ) ; +#25408 = DIRECTION ( 'NONE', ( 2.081668263520925717E-15, 0.9743700557921588512, 0.2249510932971553467 ) ) ; +#25409 = ORIENTED_EDGE ( 'NONE', *, *, #37696, .F. ) ; +#25410 = CARTESIAN_POINT ( 'NONE', ( 16.57412657401275524, 123.0642243256057640, 172.1930205136684719 ) ) ; +#25411 = ORIENTED_EDGE ( 'NONE', *, *, #36729, .F. ) ; +#25412 = LINE ( 'NONE', #7375, #29233 ) ; +#25413 = CARTESIAN_POINT ( 'NONE', ( 41.50318924951093891, 120.3350044911163366, 90.14619003234494699 ) ) ; +#25414 = EDGE_CURVE ( 'NONE', #20649, #5506, #37606, .T. ) ; +#25415 = ORIENTED_EDGE ( 'NONE', *, *, #36870, .T. ) ; +#25416 = AXIS2_PLACEMENT_3D ( 'NONE', #18728, #18530, #9561 ) ; +#25417 = CARTESIAN_POINT ( 'NONE', ( 35.04645050414097085, 226.4002260770962778, 75.53733736050621417 ) ) ; +#25418 = CARTESIAN_POINT ( 'NONE', ( 1.939042107997019926, 189.0253960982757633, 103.2917037063839132 ) ) ; +#25419 = CARTESIAN_POINT ( 'NONE', ( 25.49999482590744293, 118.1133917706950598, 89.08575900863124275 ) ) ; +#25420 = AXIS2_PLACEMENT_3D ( 'NONE', #16339, #25975, #9828 ) ; +#25421 = CONICAL_SURFACE ( 'NONE', #35146, 48.00000000000691358, 0.7853981633972819676 ) ; +#25422 = ORIENTED_EDGE ( 'NONE', *, *, #7407, .F. ) ; +#25423 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25424 = CARTESIAN_POINT ( 'NONE', ( -39.66922356035500741, 107.0867199669675358, 184.9165548509024006 ) ) ; +#25425 = VERTEX_POINT ( 'NONE', #19179 ) ; +#25426 = DIRECTION ( 'NONE', ( -0.0004161288024563961291, -0.5299192578740949955, -0.8480479980348919478 ) ) ; +#25427 = CARTESIAN_POINT ( 'NONE', ( -25.49213558285381254, 194.2771767961476996, 102.9136721320308538 ) ) ; +#25428 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748607925, 179.1800746285725552, 103.5747911656959133 ) ) ; +#25429 = ORIENTED_EDGE ( 'NONE', *, *, #22616, .T. ) ; +#25430 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19588, #13270, #579, #25756 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25431 = CARTESIAN_POINT ( 'NONE', ( 2.929713194329027992, 190.0626957488375979, 106.6094977884659585 ) ) ; +#25432 = DIRECTION ( 'NONE', ( 0.0005884949961256158652, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25433 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, -0.000000000000000000, 0.9999998176071844824 ) ) ; +#25434 = VERTEX_POINT ( 'NONE', #587 ) ; +#25435 = ADVANCED_FACE ( 'NONE', ( #25558 ), #5480, .F. ) ; +#25436 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501097082, 181.7423509807036908, 104.7012344479479395 ) ) ; +#25437 = CARTESIAN_POINT ( 'NONE', ( 40.02829803166415701, 120.8820227754755905, 90.61547142951589251 ) ) ; +#25438 = ADVANCED_FACE ( 'NONE', ( #19985 ), #14081, .F. ) ; +#25439 = EDGE_CURVE ( 'NONE', #6111, #10930, #40093, .T. ) ; +#25441 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#25440 = CARTESIAN_POINT ( 'NONE', ( 37.28562273015844397, 178.8217641854361091, 136.8524436601264540 ) ) ; +#25442 = ORIENTED_EDGE ( 'NONE', *, *, #1697, .T. ) ; +#25443 = VECTOR ( 'NONE', #39459, 1000.000000000000000 ) ; +#25444 = CARTESIAN_POINT ( 'NONE', ( -19.44534333246823721, 148.3822623830060365, 180.6034369735336895 ) ) ; +#25445 = ORIENTED_EDGE ( 'NONE', *, *, #3138, .F. ) ; +#25446 = CARTESIAN_POINT ( 'NONE', ( 3.666638747408697441, 128.4736512688499488, 89.82433808099703754 ) ) ; +#25447 = EDGE_CURVE ( 'NONE', #21126, #11864, #29221, .T. ) ; +#25448 = CONICAL_SURFACE ( 'NONE', #29986, 5.999999999882503765, 0.7853981634237914289 ) ; +#25449 = CONICAL_SURFACE ( 'NONE', #29344, 2.999999999897231984, 0.7853981633957719533 ) ; +#25450 = CARTESIAN_POINT ( 'NONE', ( -36.55035161422085110, 265.0550681697489495, 206.0315697972555427 ) ) ; +#25451 = ORIENTED_EDGE ( 'NONE', *, *, #4707, .T. ) ; +#25452 = VECTOR ( 'NONE', #25433, 1000.000000000000114 ) ; +#25453 = ORIENTED_EDGE ( 'NONE', *, *, #27211, .F. ) ; +#25454 = CARTESIAN_POINT ( 'NONE', ( 15.83499441773212091, 126.1668223937077187, 91.67911834837939011 ) ) ; +#25455 = ADVANCED_FACE ( 'NONE', ( #13868 ), #10814, .T. ) ; +#25456 = CARTESIAN_POINT ( 'NONE', ( 28.46433317245000438, 130.4256741636303047, 90.26002097362676579 ) ) ; +#25457 = CARTESIAN_POINT ( 'NONE', ( 36.06386299210247870, 192.3813622508035905, 104.3665697773190715 ) ) ; +#25458 = CARTESIAN_POINT ( 'NONE', ( 36.35265157396000291, 191.8665494351999996, 104.3770947058000047 ) ) ; +#25459 = ORIENTED_EDGE ( 'NONE', *, *, #23721, .T. ) ; +#25460 = ORIENTED_EDGE ( 'NONE', *, *, #32747, .F. ) ; +#25461 = ORIENTED_EDGE ( 'NONE', *, *, #1574, .T. ) ; +#25462 = CARTESIAN_POINT ( 'NONE', ( -6.034877889022303599, 176.8731890827487803, 103.2377949967901003 ) ) ; +#25463 = LINE ( 'NONE', #9110, #33746 ) ; +#25464 = CARTESIAN_POINT ( 'NONE', ( 39.35924215062428289, 182.9779358206116342, 104.9518492583050886 ) ) ; +#25465 = EDGE_CURVE ( 'NONE', #6175, #7200, #35712, .T. ) ; +#25466 = ORIENTED_EDGE ( 'NONE', *, *, #22733, .T. ) ; +#25467 = LINE ( 'NONE', #3758, #24568 ) ; +#25468 = ORIENTED_EDGE ( 'NONE', *, *, #13157, .F. ) ; +#25469 = DIRECTION ( 'NONE', ( 0.0005884949961191475150, -0.2249510543439081633, 0.9743698870671259060 ) ) ; +#25470 = ORIENTED_EDGE ( 'NONE', *, *, #32675, .F. ) ; +#25471 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; +#25472 = AXIS2_PLACEMENT_3D ( 'NONE', #11220, #2228, #8564 ) ; +#25473 = CARTESIAN_POINT ( 'NONE', ( -2.298658047590000031, 191.0926590853000278, 106.2034744358000040 ) ) ; +#25474 = CARTESIAN_POINT ( 'NONE', ( -2.435788377003461846, 191.0000002182038941, 106.3158216037667358 ) ) ; +#25475 = AXIS2_PLACEMENT_3D ( 'NONE', #4771, #17439, #26881 ) ; +#25476 = ORIENTED_EDGE ( 'NONE', *, *, #35820, .T. ) ; +#25477 = CARTESIAN_POINT ( 'NONE', ( 2.941278393888057341, 209.7096877029368613, 73.05672770647804271 ) ) ; +#25478 = ORIENTED_EDGE ( 'NONE', *, *, #6162, .F. ) ; +#25479 = CIRCLE ( 'NONE', #7818, 5.500000000083335117 ) ; +#25480 = ORIENTED_EDGE ( 'NONE', *, *, #28982, .F. ) ; +#25481 = CARTESIAN_POINT ( 'NONE', ( -20.49973909911777881, 191.9757886370473443, 104.4339460251406706 ) ) ; +#25482 = DIRECTION ( 'NONE', ( 0.1305262373691799260, 0.9659798014921964215, 0.2232620085624539286 ) ) ; +#25483 = AXIS2_PLACEMENT_3D ( 'NONE', #20216, #1214, #38234 ) ; +#25484 = CARTESIAN_POINT ( 'NONE', ( 13.49990341355065837, 123.9200986791754246, 91.13891943753979774 ) ) ; +#25485 = CARTESIAN_POINT ( 'NONE', ( 20.50147081074398869, 137.9496117188596429, 94.05447709496644393 ) ) ; +#25486 = EDGE_LOOP ( 'NONE', ( #18765, #22552, #6600, #432 ) ) ; +#25487 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2393, #31202, #14867, #21200 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999992929045369294 ), + .UNSPECIFIED. ) ; +#25488 = LINE ( 'NONE', #12804, #26694 ) ; +#25489 = EDGE_CURVE ( 'NONE', #38998, #16388, #33881, .T. ) ; +#25490 = ADVANCED_FACE ( 'NONE', ( #8967 ), #18333, .F. ) ; +#25491 = FACE_OUTER_BOUND ( 'NONE', #15701, .T. ) ; +#25492 = VERTEX_POINT ( 'NONE', #20602 ) ; +#25493 = ORIENTED_EDGE ( 'NONE', *, *, #17309, .T. ) ; +#25494 = FACE_OUTER_BOUND ( 'NONE', #19465, .T. ) ; +#25495 = DIRECTION ( 'NONE', ( 0.0001338301624287874996, 0.9743705222004039879, 0.2249490332417534988 ) ) ; +#25496 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178539432571E-05, -0.0002331579774923554001 ) ) ; +#25497 = CARTESIAN_POINT ( 'NONE', ( 20.00028792540915035, 151.9820690596619102, 94.72877128701482263 ) ) ; +#25498 = CARTESIAN_POINT ( 'NONE', ( -0.4555724343627732265, 211.0000000000011653, 73.55877932795836216 ) ) ; +#25499 = ORIENTED_EDGE ( 'NONE', *, *, #16975, .F. ) ; +#25500 = ORIENTED_EDGE ( 'NONE', *, *, #23301, .T. ) ; +#25501 = CARTESIAN_POINT ( 'NONE', ( 37.35925905962992033, 145.4105082909675275, 281.9992692111848100 ) ) ; +#25502 = AXIS2_PLACEMENT_3D ( 'NONE', #4197, #34864, #6874 ) ; +#25503 = CARTESIAN_POINT ( 'NONE', ( -20.49853923645481757, 186.5872419690744550, 105.3081126573685822 ) ) ; +#25504 = VECTOR ( 'NONE', #7510, 1000.000000000000000 ) ; +#25505 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34753, #10046, #19224, #31731 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25506 = ORIENTED_EDGE ( 'NONE', *, *, #3572, .F. ) ; +#25507 = CARTESIAN_POINT ( 'NONE', ( -38.93790737325827678, 191.2886348490596902, 104.1810045873903050 ) ) ; +#25508 = CIRCLE ( 'NONE', #19579, 5.500000000080834894 ) ; +#25509 = VERTEX_POINT ( 'NONE', #36753 ) ; +#25510 = LINE ( 'NONE', #8965, #8537 ) ; +#25511 = EDGE_CURVE ( 'NONE', #26891, #27880, #39165, .T. ) ; +#25512 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#25513 = CARTESIAN_POINT ( 'NONE', ( -41.54213446450223302, 190.5842469323372086, 103.6778548217435372 ) ) ; +#25514 = VERTEX_POINT ( 'NONE', #40021 ) ; +#25515 = CARTESIAN_POINT ( 'NONE', ( 28.25941677355000081, 125.5847679582000040, 89.14271750808001116 ) ) ; +#25516 = DIRECTION ( 'NONE', ( 0.7933533411653073131, 0.5931840316265227786, 0.1368326740407717623 ) ) ; +#25517 = CARTESIAN_POINT ( 'NONE', ( -20.45366101552173532, 211.0901972962080322, 75.63591788811629613 ) ) ; +#25518 = PLANE ( 'NONE', #22233 ) ; +#25519 = CARTESIAN_POINT ( 'NONE', ( -77.81044467944656162, 193.2853083808247163, 188.4036545891195544 ) ) ; +#25520 = ORIENTED_EDGE ( 'NONE', *, *, #27056, .T. ) ; +#25521 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921578520, 0.2249510932971586774 ) ) ; +#25522 = CARTESIAN_POINT ( 'NONE', ( 1.209138936786560592, 189.1031875914025306, 103.7138824602396596 ) ) ; +#25523 = CARTESIAN_POINT ( 'NONE', ( -2.316587851187592140, 189.2328037104950624, 106.4210707141687493 ) ) ; +#25524 = EDGE_CURVE ( 'NONE', #25874, #17201, #39366, .T. ) ; +#25525 = CARTESIAN_POINT ( 'NONE', ( 39.69446386203616584, 161.8153251821185563, 196.1471770628630793 ) ) ; +#25526 = DIRECTION ( 'NONE', ( -0.6087613488993157684, 0.7729391301027055405, 0.1788147679649486899 ) ) ; +#25527 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#25528 = FACE_OUTER_BOUND ( 'NONE', #37020, .T. ) ; +#25529 = AXIS2_PLACEMENT_3D ( 'NONE', #37123, #30993, #2380 ) ; +#25530 = ADVANCED_FACE ( 'NONE', ( #36353 ), #18938, .T. ) ; +#25531 = VECTOR ( 'NONE', #12182, 1000.000000000000000 ) ; +#25532 = VERTEX_POINT ( 'NONE', #3004 ) ; +#25533 = CONICAL_SURFACE ( 'NONE', #36613, 2.503101642511124325, 0.7853981633721776046 ) ; +#25534 = AXIS2_PLACEMENT_3D ( 'NONE', #13398, #3371, #3775 ) ; +#25535 = EDGE_CURVE ( 'NONE', #7238, #20110, #3602, .T. ) ; +#25536 = EDGE_CURVE ( 'NONE', #17579, #6068, #3801, .T. ) ; +#25537 = EDGE_CURVE ( 'NONE', #25759, #32563, #9161, .T. ) ; +#25538 = CARTESIAN_POINT ( 'NONE', ( 6.036802112625085925, 176.8031174218945409, 103.1161773563228081 ) ) ; +#25539 = CARTESIAN_POINT ( 'NONE', ( 19.99905349769186458, 193.8169544161346494, 102.6908434160864800 ) ) ; +#25540 = ORIENTED_EDGE ( 'NONE', *, *, #211, .T. ) ; +#25541 = CARTESIAN_POINT ( 'NONE', ( 22.67196836059710918, 115.6131113076032477, 87.75389050448781347 ) ) ; +#25542 = CARTESIAN_POINT ( 'NONE', ( -25.99151685856759997, 191.8641472349464436, 103.9340191741391521 ) ) ; +#25543 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25544 = FACE_OUTER_BOUND ( 'NONE', #26799, .T. ) ; +#25545 = CARTESIAN_POINT ( 'NONE', ( 3.857291306865842095, 143.6128663871600111, 95.55518041699281184 ) ) ; +#25546 = CARTESIAN_POINT ( 'NONE', ( -20.99990893075895571, 136.4130174721703668, 91.33008588846020359 ) ) ; +#25547 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #15813, #31571, #28505, #25654 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.3157706852075154447, 1.746568277883796982 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8365544822326855812, 0.8365544822326855812, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#25548 = ORIENTED_EDGE ( 'NONE', *, *, #22733, .F. ) ; +#25549 = VERTEX_POINT ( 'NONE', #21831 ) ; +#25550 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25551 = CARTESIAN_POINT ( 'NONE', ( 20.50146814542411278, 184.4050074329408915, 104.7795556516932436 ) ) ; +#25552 = DIRECTION ( 'NONE', ( -0.6087614810001780175, 0.7729390313185915407, 0.1788147452386051883 ) ) ; +#25553 = ORIENTED_EDGE ( 'NONE', *, *, #14079, .T. ) ; +#25554 = FACE_OUTER_BOUND ( 'NONE', #1594, .T. ) ; +#25555 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34509, #15724, #22833, #29172 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25556 = EDGE_LOOP ( 'NONE', ( #35420, #28169, #13710, #7194 ) ) ; +#25557 = VECTOR ( 'NONE', #16549, 1000.000000000000114 ) ; +#25558 = FACE_OUTER_BOUND ( 'NONE', #36983, .T. ) ; +#25559 = CARTESIAN_POINT ( 'NONE', ( -4.217709453195823244, 130.5806486384503842, 89.80238664217760913 ) ) ; +#25560 = CARTESIAN_POINT ( 'NONE', ( -3.669188902168228683, 128.3225182885998947, 90.47807979629892827 ) ) ; +#25561 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099476, 179.7424522643767375, 101.1388664481733173 ) ) ; +#25562 = AXIS2_PLACEMENT_3D ( 'NONE', #33061, #30214, #11821 ) ; +#25563 = VECTOR ( 'NONE', #22085, 1000.000000000000227 ) ; +#25564 = FACE_OUTER_BOUND ( 'NONE', #16379, .T. ) ; +#25565 = CARTESIAN_POINT ( 'NONE', ( -45.96073629545556827, 185.2536905089892514, 105.5287798515274176 ) ) ; +#25566 = DIRECTION ( 'NONE', ( 0.0005884949961178157895, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25567 = CARTESIAN_POINT ( 'NONE', ( 14.17154132021859780, 182.3114712258959571, 104.3000443475247749 ) ) ; +#25568 = VERTEX_POINT ( 'NONE', #149 ) ; +#25569 = VERTEX_POINT ( 'NONE', #34275 ) ; +#25570 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#25571 = CARTESIAN_POINT ( 'NONE', ( -30.06407784565124430, 177.7873364699197793, 100.7165267053679969 ) ) ; +#25572 = CARTESIAN_POINT ( 'NONE', ( -22.64184747305000300, 158.4882854875999953, 96.51307724670000709 ) ) ; +#25573 = ADVANCED_FACE ( 'NONE', ( #6272 ), #18727, .F. ) ; +#25574 = ORIENTED_EDGE ( 'NONE', *, *, #25634, .T. ) ; +#25575 = CARTESIAN_POINT ( 'NONE', ( -20.51767729163077547, 205.5669979433283743, 76.31342074382325791 ) ) ; +#25576 = ORIENTED_EDGE ( 'NONE', *, *, #12318, .T. ) ; +#25577 = CARTESIAN_POINT ( 'NONE', ( 5.666638401077995546, 182.0642691150685550, 102.1955013911927352 ) ) ; +#25578 = VERTEX_POINT ( 'NONE', #20143 ) ; +#25579 = ADVANCED_FACE ( 'NONE', ( #26112 ), #16675, .T. ) ; +#25580 = DIRECTION ( 'NONE', ( -0.1305262051638224619, -0.9660383185115548610, -0.2230086925052462976 ) ) ; +#25581 = FACE_OUTER_BOUND ( 'NONE', #28954, .T. ) ; +#25582 = VECTOR ( 'NONE', #9464, 1000.000000000000114 ) ; +#25583 = EDGE_CURVE ( 'NONE', #7856, #27296, #35876, .T. ) ; +#25584 = CARTESIAN_POINT ( 'NONE', ( -12.62895464393706924, 177.1149013944556145, 103.6296996846185152 ) ) ; +#25585 = EDGE_CURVE ( 'NONE', #39006, #26460, #4410, .T. ) ; +#25586 = CONICAL_SURFACE ( 'NONE', #19012, 8.500000000023945290, 0.7853981633972964005 ) ; +#25587 = LINE ( 'NONE', #34538, #27252 ) ; +#25588 = EDGE_CURVE ( 'NONE', #6068, #982, #10165, .T. ) ; +#25589 = AXIS2_PLACEMENT_3D ( 'NONE', #31113, #15560, #23 ) ; +#25590 = CARTESIAN_POINT ( 'NONE', ( -2.469696937619000110, 209.6697490365999954, 73.43898226951000652 ) ) ; +#25591 = CARTESIAN_POINT ( 'NONE', ( 38.49272623736000298, 118.5587213001000038, 89.80777509628001098 ) ) ; +#25592 = EDGE_LOOP ( 'NONE', ( #15478, #20146, #40230, #21895, #13336, #513, #17672, #29894, #33555, #21437, #36388, #6752, #34748, #14146, #8320, #7418, #27143, #27464, #23938, #10649, #39703, #34306, #35998, #37206 ) ) ; +#25593 = CARTESIAN_POINT ( 'NONE', ( -39.42639396830977461, 119.7153704062085353, 90.39411697856569106 ) ) ; +#25594 = CARTESIAN_POINT ( 'NONE', ( -22.78222448785094656, 147.3951731907068563, 96.77445160504784383 ) ) ; +#25595 = DIRECTION ( 'NONE', ( 0.6087614115774879764, -0.7730004600455407937, -0.1785492440296699013 ) ) ; +#25597 = EDGE_LOOP ( 'NONE', ( #29523, #1134, #30477, #5484 ) ) ; +#25596 = CARTESIAN_POINT ( 'NONE', ( -13.49052885539015278, 188.3420772061585353, 103.1432726234667427 ) ) ; +#25598 = ORIENTED_EDGE ( 'NONE', *, *, #24485, .T. ) ; +#25599 = VERTEX_POINT ( 'NONE', #16474 ) ; +#25600 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9981, #552, #28381, #38183 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.0008906419405732026156 ), + .UNSPECIFIED. ) ; +#25601 = ORIENTED_EDGE ( 'NONE', *, *, #23916, .F. ) ; +#25602 = LINE ( 'NONE', #8899, #1334 ) ; +#25603 = DIRECTION ( 'NONE', ( -0.1305262373691799260, -0.9659798014921964215, -0.2232620085624539286 ) ) ; +#25604 = ORIENTED_EDGE ( 'NONE', *, *, #13373, .T. ) ; +#25605 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25606 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052565999616 ) ) ; +#25607 = CARTESIAN_POINT ( 'NONE', ( -38.26352553902000153, 118.9655503529000100, 87.58139881257000070 ) ) ; +#25608 = CARTESIAN_POINT ( 'NONE', ( -22.99976245438101330, 118.1131156702000169, 90.28469153849982831 ) ) ; +#25609 = ORIENTED_EDGE ( 'NONE', *, *, #32117, .F. ) ; +#25610 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25611 = ORIENTED_EDGE ( 'NONE', *, *, #27589, .T. ) ; +#25612 = CARTESIAN_POINT ( 'NONE', ( -25.18449714766744307, 116.8540101816006427, 89.78296773362393424 ) ) ; +#25613 = VECTOR ( 'NONE', #34725, 1000.000000000000227 ) ; +#25614 = CARTESIAN_POINT ( 'NONE', ( -2.454714023685454993, 208.9999998232322014, 74.98064760642650128 ) ) ; +#25615 = ORIENTED_EDGE ( 'NONE', *, *, #20094, .F. ) ; +#25616 = CIRCLE ( 'NONE', #17076, 10.00000000000000533 ) ; +#25617 = ORIENTED_EDGE ( 'NONE', *, *, #4873, .T. ) ; +#25618 = DIRECTION ( 'NONE', ( 0.7933532411131101192, 0.5932638852154232811, 0.1364866195435442964 ) ) ; +#25619 = AXIS2_PLACEMENT_3D ( 'NONE', #35302, #13659, #1375 ) ; +#25620 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.261220487827980678E-14, 0.9999998176071847045 ) ) ; +#25621 = ADVANCED_FACE ( 'NONE', ( #38362 ), #21923, .T. ) ; +#25622 = FACE_OUTER_BOUND ( 'NONE', #38903, .T. ) ; +#25623 = EDGE_CURVE ( 'NONE', #34118, #37905, #14238, .T. ) ; +#25624 = EDGE_CURVE ( 'NONE', #662, #38536, #39974, .T. ) ; +#25625 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #28336, #6633, #37722 ), + ( #12384, #37132, #9128 ), + ( #15649, #21610, #37530 ), + ( #25078, #113, #15460 ), + ( #18496, #40381, #12575 ), + ( #34441, #31004, #9327 ), + ( #24882, #6840, #12998 ), + ( #21805, #15842, #2970 ), + ( #9731, #306, #6434 ), + ( #22409, #34639, #34243 ) ), + .UNSPECIFIED., .F., .F., .T. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 2, 2, 2, 4 ), + ( 3, 3 ), + ( 0.05538191844473741576, 0.1462505983937870679, 0.2371192783428366924, 0.3279879582918863168, 0.4188566382409359967 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.9441684504446133941, 1.000000000000000000), + ( 1.000000000000000000, 0.9410511299423663933, 1.000000000000000000), + ( 1.000000000000000000, 0.9350843932276490245, 1.000000000000000000), + ( 1.000000000000000000, 0.9167142712460382148, 1.000000000000000000), + ( 1.000000000000000000, 0.9042814830954841732, 1.000000000000000000), + ( 1.000000000000000000, 0.8733377745246642121, 1.000000000000000000), + ( 1.000000000000000000, 0.8548373006127086837, 1.000000000000000000), + ( 1.000000000000000000, 0.8135092030853890988, 1.000000000000000000), + ( 1.000000000000000000, 0.7907138362263389508, 1.000000000000000000), + ( 1.000000000000000000, 0.7669877085542754491, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#25626 = EDGE_LOOP ( 'NONE', ( #19250, #32641, #29047, #31049 ) ) ; +#25627 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#25628 = CARTESIAN_POINT ( 'NONE', ( 22.50071804764001371, 153.6597986086584910, 96.31184697053201660 ) ) ; +#25629 = ORIENTED_EDGE ( 'NONE', *, *, #3726, .T. ) ; +#25630 = ADVANCED_FACE ( 'NONE', ( #24049 ), #6899, .T. ) ; +#25631 = LINE ( 'NONE', #6785, #8881 ) ; +#25632 = DIRECTION ( 'NONE', ( -5.204170427930391307E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#25633 = CARTESIAN_POINT ( 'NONE', ( -28.81763517994743751, 225.0820812896716632, 76.07590975914473574 ) ) ; +#25634 = EDGE_CURVE ( 'NONE', #20950, #4106, #27131, .T. ) ; +#25635 = ORIENTED_EDGE ( 'NONE', *, *, #22510, .T. ) ; +#25636 = LINE ( 'NONE', #7802, #38051 ) ; +#25637 = CARTESIAN_POINT ( 'NONE', ( 1.214526914179933081, 188.4681291261784111, 106.2423989390525207 ) ) ; +#25638 = CARTESIAN_POINT ( 'NONE', ( -37.92154252050418961, 118.5963699847487192, 87.57341342349630509 ) ) ; +#25639 = LINE ( 'NONE', #12956, #25452 ) ; +#25640 = EDGE_CURVE ( 'NONE', #27113, #8395, #4260, .T. ) ; +#25641 = ORIENTED_EDGE ( 'NONE', *, *, #23630, .F. ) ; +#25642 = CARTESIAN_POINT ( 'NONE', ( 26.00730275886190057, 120.2355259078189818, 90.47935005272459819 ) ) ; +#25643 = DIRECTION ( 'NONE', ( -0.0005884949961232365835, 0.2249510543439025012, -0.9743698870671272383 ) ) ; +#25644 = CARTESIAN_POINT ( 'NONE', ( -20.33181978585839289, 137.5888522171624686, 94.16684457232651084 ) ) ; +#25645 = CIRCLE ( 'NONE', #2137, 22.00000000001089973 ) ; +#25647 = CARTESIAN_POINT ( 'NONE', ( -11.75635721658684574, 154.1573362836760737, 95.25004801869390292 ) ) ; +#25646 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25648 = EDGE_CURVE ( 'NONE', #4584, #27521, #11782, .T. ) ; +#25649 = AXIS2_PLACEMENT_3D ( 'NONE', #31422, #5867, #34069 ) ; +#25650 = CARTESIAN_POINT ( 'NONE', ( 20.00104065772422146, 118.8155603627228203, 94.25570476258155850 ) ) ; +#25651 = ORIENTED_EDGE ( 'NONE', *, *, #36361, .F. ) ; +#25652 = CARTESIAN_POINT ( 'NONE', ( 15.67905408082599727, 145.8568665348935554, 183.6205611131604485 ) ) ; +#25653 = CARTESIAN_POINT ( 'NONE', ( -35.93776700278350233, 192.3813625493561119, 104.4100568030667660 ) ) ; +#25654 = CARTESIAN_POINT ( 'NONE', ( 31.82998378949513452, 157.8941376960632397, 186.4072502462622367 ) ) ; +#25655 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#25656 = ORIENTED_EDGE ( 'NONE', *, *, #2466, .F. ) ; +#25657 = ORIENTED_EDGE ( 'NONE', *, *, #10960, .F. ) ; +#25658 = FACE_OUTER_BOUND ( 'NONE', #3335, .T. ) ; +#25659 = CARTESIAN_POINT ( 'NONE', ( 22.78191781013921968, 158.2317512751428126, 98.73560149028561739 ) ) ; +#25660 = CARTESIAN_POINT ( 'NONE', ( -46.20100370308558269, 125.7463382206120173, 91.79056768027822955 ) ) ; +#25661 = CARTESIAN_POINT ( 'NONE', ( 3.168077512235829563, 183.4518822370066289, 105.0831384053979036 ) ) ; +#25662 = ORIENTED_EDGE ( 'NONE', *, *, #5662, .F. ) ; +#25663 = VERTEX_POINT ( 'NONE', #23844 ) ; +#25664 = DIRECTION ( 'NONE', ( -0.0005884949961166157945, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#25665 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825842615387340, 0.0005734119041737265748 ) ) ; +#25666 = CARTESIAN_POINT ( 'NONE', ( -25.53470936712000139, 185.3002260771000067, 32.42391899273999911 ) ) ; +#25667 = ORIENTED_EDGE ( 'NONE', *, *, #24055, .F. ) ; +#25668 = FACE_OUTER_BOUND ( 'NONE', #5959, .T. ) ; +#25669 = VERTEX_POINT ( 'NONE', #37709 ) ; +#25670 = CARTESIAN_POINT ( 'NONE', ( 20.50029382287623037, 174.4060969903238458, 100.4185135684600993 ) ) ; +#25671 = ORIENTED_EDGE ( 'NONE', *, *, #16682, .F. ) ; +#25672 = AXIS2_PLACEMENT_3D ( 'NONE', #19719, #34454, #25496 ) ; +#25673 = EDGE_CURVE ( 'NONE', #12970, #29757, #34310, .T. ) ; +#25674 = EDGE_CURVE ( 'NONE', #26075, #28651, #4946, .T. ) ; +#25675 = EDGE_CURVE ( 'NONE', #15031, #27146, #12776, .T. ) ; +#25676 = AXIS2_PLACEMENT_3D ( 'NONE', #23626, #10959, #5200 ) ; +#25677 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364818587623, 136.5649596138779884, 181.4686487119677167 ) ) ; +#25678 = ADVANCED_FACE ( 'NONE', ( #10475 ), #24670, .T. ) ; +#25679 = DIRECTION ( 'NONE', ( 0.0005884949961216892102, -0.2249510543439063592, 0.9743698870671262391 ) ) ; +#25680 = ORIENTED_EDGE ( 'NONE', *, *, #15906, .T. ) ; +#25681 = LINE ( 'NONE', #31395, #15749 ) ; +#25682 = VECTOR ( 'NONE', #22959, 1000.000000000000000 ) ; +#25683 = CARTESIAN_POINT ( 'NONE', ( -2.502144820012000004, 190.3949449552999909, 106.2773598966000037 ) ) ; +#25684 = CARTESIAN_POINT ( 'NONE', ( -12.63633101993597130, 136.6777708571482606, 94.29709491087972140 ) ) ; +#25685 = EDGE_CURVE ( 'NONE', #1228, #10977, #24998, .T. ) ; +#25686 = ORIENTED_EDGE ( 'NONE', *, *, #2312, .F. ) ; +#25687 = PLANE ( 'NONE', #17752 ) ; +#25688 = CARTESIAN_POINT ( 'NONE', ( -20.49970532888763941, 191.4139234226054498, 104.3698659823340478 ) ) ; +#25689 = CARTESIAN_POINT ( 'NONE', ( 20.29385838999352742, 212.4069381654295796, 73.04624710044845415 ) ) ; +#25690 = LINE ( 'NONE', #6843, #36614 ) ; +#25691 = EDGE_CURVE ( 'NONE', #19108, #33611, #12147, .T. ) ; +#25692 = CARTESIAN_POINT ( 'NONE', ( -42.56963625464027245, 120.8513313564750575, 90.65827283841386475 ) ) ; +#25693 = VERTEX_POINT ( 'NONE', #29675 ) ; +#25694 = CARTESIAN_POINT ( 'NONE', ( 22.20643291937885877, 214.0123450240148202, 76.04556629009920243 ) ) ; +#25695 = CARTESIAN_POINT ( 'NONE', ( 25.43540111634469270, 117.4590002937401181, 89.75256112228039740 ) ) ; +#25696 = CARTESIAN_POINT ( 'NONE', ( -37.34320747774000182, 117.7695368308999946, 90.15184626625000419 ) ) ; +#25697 = ORIENTED_EDGE ( 'NONE', *, *, #12326, .F. ) ; +#25698 = AXIS2_PLACEMENT_3D ( 'NONE', #15420, #37485, #9690 ) ; +#25699 = CARTESIAN_POINT ( 'NONE', ( 31.79421363390603261, 220.4002260770989778, 73.53930126518000066 ) ) ; +#25700 = ORIENTED_EDGE ( 'NONE', *, *, #12641, .F. ) ; +#25701 = CARTESIAN_POINT ( 'NONE', ( -28.46358003787008784, 130.0931529937463438, 92.44131419057775645 ) ) ; +#25702 = CARTESIAN_POINT ( 'NONE', ( -3.953839019659958431, 174.7728703276109741, 102.6551122695953637 ) ) ; +#25703 = VECTOR ( 'NONE', #24201, 1000.000000000000000 ) ; +#25704 = CARTESIAN_POINT ( 'NONE', ( -12.63780404429605042, 128.4714928439248638, 89.83368724503242220 ) ) ; +#25705 = ORIENTED_EDGE ( 'NONE', *, *, #33158, .T. ) ; +#25706 = VERTEX_POINT ( 'NONE', #35770 ) ; +#25707 = ORIENTED_EDGE ( 'NONE', *, *, #20188, .T. ) ; +#25708 = CARTESIAN_POINT ( 'NONE', ( -42.69294731529282672, 103.5236703916287553, 167.6615886432229843 ) ) ; +#25709 = PLANE ( 'NONE', #34654 ) ; +#25710 = DIRECTION ( 'NONE', ( -0.6087614883550946931, 0.7730004026499607273, 0.1785492307423600378 ) ) ; +#25711 = ORIENTED_EDGE ( 'NONE', *, *, #38782, .T. ) ; +#25712 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 171.7660675377210282, 184.4841745997615021 ) ) ; +#25713 = CARTESIAN_POINT ( 'NONE', ( -25.75129388820000287, 120.5227984420999974, 87.74993035635000638 ) ) ; +#25714 = CARTESIAN_POINT ( 'NONE', ( 36.51299379403999978, 191.8889899160000141, 104.5096745278000157 ) ) ; +#25715 = CARTESIAN_POINT ( 'NONE', ( 2.959628761272101283, 209.6631827712477900, 76.05717346085170050 ) ) ; +#25716 = CARTESIAN_POINT ( 'NONE', ( 45.31676687487262711, 123.9859615478322183, 91.32887818729398077 ) ) ; +#25717 = CARTESIAN_POINT ( 'NONE', ( -15.49970618539471268, 185.7934281236995844, 103.0692296848312282 ) ) ; +#25718 = ORIENTED_EDGE ( 'NONE', *, *, #37288, .F. ) ; +#25719 = CARTESIAN_POINT ( 'NONE', ( 28.30074384216000283, 125.2974345084000021, 88.73412754224999333 ) ) ; +#25720 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13898, #4066, #39030, #4889 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25721 = CARTESIAN_POINT ( 'NONE', ( -20.51763439869084849, 207.5364665811183613, 76.82466709321089127 ) ) ; +#25722 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; +#25723 = EDGE_CURVE ( 'NONE', #15729, #27481, #26952, .T. ) ; +#25724 = EDGE_CURVE ( 'NONE', #12087, #30603, #39595, .T. ) ; +#25725 = CARTESIAN_POINT ( 'NONE', ( -25.74931979772765800, 116.9126722973494168, 90.28333678314174904 ) ) ; +#25726 = CARTESIAN_POINT ( 'NONE', ( 21.23524577242590183, 158.6168070940844075, 96.25967206434769707 ) ) ; +#25727 = ORIENTED_EDGE ( 'NONE', *, *, #29362, .T. ) ; +#25728 = CARTESIAN_POINT ( 'NONE', ( -21.21399091018682981, 129.1232532189451376, 89.98933777676734280 ) ) ; +#25729 = CARTESIAN_POINT ( 'NONE', ( -15.56570128697116395, 127.6534963204462514, 175.2992203924931687 ) ) ; +#25730 = VECTOR ( 'NONE', #11990, 999.9999999999998863 ) ; +#25731 = AXIS2_PLACEMENT_3D ( 'NONE', #28297, #12960, #34597 ) ; +#25732 = CARTESIAN_POINT ( 'NONE', ( 36.43823293609931824, 191.7962655817395046, 104.3583410344040772 ) ) ; +#25733 = CARTESIAN_POINT ( 'NONE', ( 20.50153854971994960, 118.8155953598612484, 89.75541792533370256 ) ) ; +#25734 = VECTOR ( 'NONE', #21524, 1000.000000000000227 ) ; +#25735 = CARTESIAN_POINT ( 'NONE', ( 38.47818596117896561, 119.0222560628710369, 90.24976562745140996 ) ) ; +#25736 = CARTESIAN_POINT ( 'NONE', ( 31.79365004200798595, 115.2698610323616890, 176.5535528959301530 ) ) ; +#25737 = PLANE ( 'NONE', #701 ) ; +#25738 = CARTESIAN_POINT ( 'NONE', ( 18.98783187499508074, 148.3993599496172351, 183.8670116001150632 ) ) ; +#25739 = ORIENTED_EDGE ( 'NONE', *, *, #28383, .T. ) ; +#25740 = CARTESIAN_POINT ( 'NONE', ( 6.037208908824005960, 176.8656333337133333, 103.2162234373518004 ) ) ; +#25741 = ADVANCED_FACE ( 'NONE', ( #11884 ), #20875, .T. ) ; +#25742 = CARTESIAN_POINT ( 'NONE', ( -45.38224234400345125, 124.4312361121064896, 88.40754498314288412 ) ) ; +#25743 = CARTESIAN_POINT ( 'NONE', ( -16.53785153513707584, 123.0772470471530085, 172.1883206570706477 ) ) ; +#25744 = ORIENTED_EDGE ( 'NONE', *, *, #20235, .T. ) ; +#25745 = DIRECTION ( 'NONE', ( 0.0006039748499252115509, 0.000000000000000000, 0.9999998176071738243 ) ) ; +#25746 = CARTESIAN_POINT ( 'NONE', ( -25.99159371425722398, 191.8593449687673456, 103.9335660634491063 ) ) ; +#25747 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319403664923 ) ) ; +#25748 = LINE ( 'NONE', #974, #25504 ) ; +#25749 = CARTESIAN_POINT ( 'NONE', ( 22.78079353263602869, 153.8098031058628692, 95.66210622315543333 ) ) ; +#25750 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#25751 = VERTEX_POINT ( 'NONE', #5323 ) ; +#25752 = DIRECTION ( 'NONE', ( 0.7942820423213359238, 0.5918950211223032998, 0.1370267171630252800 ) ) ; +#25753 = AXIS2_PLACEMENT_3D ( 'NONE', #9625, #34733, #6735 ) ; +#25754 = CARTESIAN_POINT ( 'NONE', ( 35.74933844504462854, 114.7932138186078816, 87.24619258741343231 ) ) ; +#25755 = AXIS2_PLACEMENT_3D ( 'NONE', #1576, #2201, #24079 ) ; +#25756 = CARTESIAN_POINT ( 'NONE', ( -23.36150835703034190, 130.4188133218702319, 90.28973853220963974 ) ) ; +#25757 = EDGE_LOOP ( 'NONE', ( #35016, #16511, #9618, #24951 ) ) ; +#25758 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474973922409778, 155.7928101624883936, 98.18628735359267523 ) ) ; +#25759 = VERTEX_POINT ( 'NONE', #30275 ) ; +#25760 = PLANE ( 'NONE', #29983 ) ; +#25761 = CARTESIAN_POINT ( 'NONE', ( -13.59692594909000007, 163.2545600168000135, 28.07991271570000080 ) ) ; +#25762 = DIRECTION ( 'NONE', ( 0.0004161288024514938006, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#25763 = CARTESIAN_POINT ( 'NONE', ( 37.79562854142448458, 218.5902260770999987, 75.53567692577773585 ) ) ; +#25764 = ADVANCED_FACE ( 'NONE', ( #8618 ), #15382, .T. ) ; +#25765 = ADVANCED_FACE ( 'NONE', ( #21082 ), #14751, .T. ) ; +#25766 = CARTESIAN_POINT ( 'NONE', ( 34.29411924272742596, 218.5902260770999987, 73.03779129371591239 ) ) ; +#25767 = CARTESIAN_POINT ( 'NONE', ( 20.50042280545328310, 118.5813761975761764, 87.75531210468815857 ) ) ; +#25768 = EDGE_LOOP ( 'NONE', ( #26793, #38716, #37262, #10337 ) ) ; +#25769 = LINE ( 'NONE', #24972, #6957 ) ; +#25770 = CARTESIAN_POINT ( 'NONE', ( 30.07022246028604329, 177.5684875020558877, 100.8237775184044267 ) ) ; +#25771 = CARTESIAN_POINT ( 'NONE', ( 5.703605760174398576, 177.7921183530763471, 100.6960230178058282 ) ) ; +#25772 = CARTESIAN_POINT ( 'NONE', ( -20.51844305912966249, 206.3036150481032394, 75.12978008876878278 ) ) ; +#25773 = ORIENTED_EDGE ( 'NONE', *, *, #7830, .F. ) ; +#25774 = EDGE_LOOP ( 'NONE', ( #9745, #9548, #35045, #28624 ) ) ; +#25775 = LINE ( 'NONE', #29025, #11368 ) ; +#25776 = ORIENTED_EDGE ( 'NONE', *, *, #32762, .T. ) ; +#25777 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35377, #17180, #35567, #16574 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25778 = LINE ( 'NONE', #3271, #24929 ) ; +#25779 = AXIS2_PLACEMENT_3D ( 'NONE', #603, #409, #16344 ) ; +#25780 = CIRCLE ( 'NONE', #40114, 2.000000000000011546 ) ; +#25781 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#25782 = CIRCLE ( 'NONE', #15323, 5.999999999944575002 ) ; +#25783 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4051, #25565, #22089, #10224, #1197, #22889, #19399, #13676, #22496, #38216, #9818, #31896, #35113, #10422, #19597, #3855 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 4 ), + ( 8.202606158603310806E-15, 0.0003993169203146928721, 0.0007986338406211832127, 0.001197950760927673662, 0.001597267681234163786, 0.001996584601540654126, 0.002395901521847144684, 0.003194535362460158325 ), + .UNSPECIFIED. ) ; +#25784 = CARTESIAN_POINT ( 'NONE', ( -25.99964915362324192, 120.0929955239077032, 90.47318932755659660 ) ) ; +#25785 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8858, #37056, #21325, #27672 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.699745388805494750, 1.699780469277642814 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999998974467008, 0.9999999998974467008, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#25786 = CARTESIAN_POINT ( 'NONE', ( 39.31906229016909293, 129.4589100703372821, 89.51864490113773343 ) ) ; +#25787 = ADVANCED_FACE ( 'NONE', ( #33739 ), #18188, .T. ) ; +#25788 = CARTESIAN_POINT ( 'NONE', ( -2.578765801273999791, 209.0167477900000108, 73.48847337076000485 ) ) ; +#25789 = CARTESIAN_POINT ( 'NONE', ( 38.34695031038000224, 118.7616814038999991, 90.10264553476001481 ) ) ; +#25790 = ORIENTED_EDGE ( 'NONE', *, *, #28799, .T. ) ; +#25791 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825924600143509, 0.0005734119022810348423 ) ) ; +#25792 = CARTESIAN_POINT ( 'NONE', ( 35.55352252806802227, 109.6131156654499961, 87.24631085522547380 ) ) ; +#25793 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; +#25794 = CARTESIAN_POINT ( 'NONE', ( -26.00624846271685442, 190.8511609718977127, 106.8090059743847178 ) ) ; +#25795 = ORIENTED_EDGE ( 'NONE', *, *, #4366, .F. ) ; +#25796 = ORIENTED_EDGE ( 'NONE', *, *, #11825, .F. ) ; +#25797 = ORIENTED_EDGE ( 'NONE', *, *, #22451, .T. ) ; +#25798 = CARTESIAN_POINT ( 'NONE', ( 44.05441677404900958, 112.7011882844216615, 88.72434494931374616 ) ) ; +#25799 = EDGE_CURVE ( 'NONE', #29453, #39083, #3537, .T. ) ; +#25800 = CARTESIAN_POINT ( 'NONE', ( 38.29229177720002042, 119.0091981861925206, 87.46444357072304854 ) ) ; +#25801 = CARTESIAN_POINT ( 'NONE', ( 2.431955026391375618, 158.3626469589818271, 101.3438727543389035 ) ) ; +#25802 = DIRECTION ( 'NONE', ( -0.6087614810001780175, 0.7729390313185915407, 0.1788147452386051883 ) ) ; +#25803 = ORIENTED_EDGE ( 'NONE', *, *, #29306, .F. ) ; +#25804 = AXIS2_PLACEMENT_3D ( 'NONE', #17901, #11594, #17495 ) ; +#25805 = CARTESIAN_POINT ( 'NONE', ( 14.81744580022004243, 163.8812281945125733, 152.8157487480565351 ) ) ; +#25806 = ADVANCED_FACE ( 'NONE', ( #18996 ), #38224, .F. ) ; +#25807 = CARTESIAN_POINT ( 'NONE', ( 20.94615154526903567, 129.3425601203839221, 89.50137061379278691 ) ) ; +#25808 = CARTESIAN_POINT ( 'NONE', ( -12.63633103062601570, 183.4475335476649889, 105.0947473920673190 ) ) ; +#25809 = CARTESIAN_POINT ( 'NONE', ( -40.55546040064906776, 184.3694241705995296, 104.8082140455743883 ) ) ; +#25810 = ORIENTED_EDGE ( 'NONE', *, *, #28293, .T. ) ; +#25811 = CARTESIAN_POINT ( 'NONE', ( 94.27346847287640230, 222.2365666497040024, 195.1387431474686309 ) ) ; +#25812 = ORIENTED_EDGE ( 'NONE', *, *, #25623, .T. ) ; +#25813 = CARTESIAN_POINT ( 'NONE', ( -14.78542059478467330, 183.3574060367851359, 102.5063981592711571 ) ) ; +#25814 = CIRCLE ( 'NONE', #8170, 2.499999999994495514 ) ; +#25815 = ADVANCED_FACE ( 'NONE', ( #28231 ), #31284, .F. ) ; +#25816 = EDGE_CURVE ( 'NONE', #25194, #1872, #4913, .T. ) ; +#25817 = CARTESIAN_POINT ( 'NONE', ( -2.435788377003461846, 191.0000002182038941, 106.3158216037667358 ) ) ; +#25818 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319350685384 ) ) ; +#25819 = ORIENTED_EDGE ( 'NONE', *, *, #23122, .T. ) ; +#25820 = ADVANCED_FACE ( 'NONE', ( #15472 ), #27966, .F. ) ; +#25821 = ORIENTED_EDGE ( 'NONE', *, *, #5337, .T. ) ; +#25822 = CARTESIAN_POINT ( 'NONE', ( -19.99991124754194516, 196.0294354676498472, 104.9180633642943405 ) ) ; +#25823 = EDGE_CURVE ( 'NONE', #24745, #9304, #25096, .T. ) ; +#25824 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391912172 ) ) ; +#25825 = CARTESIAN_POINT ( 'NONE', ( 20.25014673412999855, 188.1903989944999864, 103.3444460256000212 ) ) ; +#25826 = VERTEX_POINT ( 'NONE', #24902 ) ; +#25827 = CARTESIAN_POINT ( 'NONE', ( 20.26084502294995460, 118.1108187821794502, 87.51605973384316428 ) ) ; +#25828 = CARTESIAN_POINT ( 'NONE', ( -12.68284606093999933, 201.2278123622000123, 28.07991271570000080 ) ) ; +#25829 = ORIENTED_EDGE ( 'NONE', *, *, #31340, .T. ) ; +#25830 = CARTESIAN_POINT ( 'NONE', ( 27.07873119645540783, 119.5134203564188198, 171.3751642805570157 ) ) ; +#25831 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29177, #12827, #26113, #4006 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25832 = CARTESIAN_POINT ( 'NONE', ( 36.49264889551449897, 191.3170871187571151, 103.7999128507424871 ) ) ; +#25833 = ORIENTED_EDGE ( 'NONE', *, *, #19030, .T. ) ; +#25834 = CARTESIAN_POINT ( 'NONE', ( 1.373544093530520760, 188.5169685701486344, 106.2535783728023659 ) ) ; +#25835 = CARTESIAN_POINT ( 'NONE', ( -37.67574118798827243, 118.8155645602721222, 87.29053938956874958 ) ) ; +#25836 = CARTESIAN_POINT ( 'NONE', ( -3.233981241130774009, 126.1655476077336573, 88.78248592047526699 ) ) ; +#25837 = EDGE_CURVE ( 'NONE', #19459, #34206, #19099, .T. ) ; +#25838 = AXIS2_PLACEMENT_3D ( 'NONE', #34376, #28861, #840 ) ; +#25839 = AXIS2_PLACEMENT_3D ( 'NONE', #39316, #39517, #17641 ) ; +#25840 = VERTEX_POINT ( 'NONE', #12213 ) ; +#25841 = CARTESIAN_POINT ( 'NONE', ( 26.00471032461299714, 120.1087538276019870, 90.45505707459361133 ) ) ; +#25842 = CARTESIAN_POINT ( 'NONE', ( 37.28972153584570037, 172.2751332797207624, 165.2090122940432195 ) ) ; +#25843 = CIRCLE ( 'NONE', #38858, 2.000000000000011546 ) ; +#25844 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7269, #28963, #4003, #31085 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 5.777484129617390118E-06, 0.0006658699108300950801 ), + .UNSPECIFIED. ) ; +#25846 = CARTESIAN_POINT ( 'NONE', ( -9.003483374562920361, 152.5917386336430468, 94.88693858845569196 ) ) ; +#25845 = CARTESIAN_POINT ( 'NONE', ( -22.49823373369745028, 184.2867141917648723, 105.2913686032300973 ) ) ; +#25847 = ORIENTED_EDGE ( 'NONE', *, *, #36994, .T. ) ; +#25848 = DIRECTION ( 'NONE', ( 0.0006039748319383109534, 1.233022124494217175E-14, 0.9999998176071845934 ) ) ; +#25849 = CARTESIAN_POINT ( 'NONE', ( 15.94054669826102177, 152.1475402096681080, 184.5616883112009816 ) ) ; +#25850 = VERTEX_POINT ( 'NONE', #39792 ) ; +#25851 = CARTESIAN_POINT ( 'NONE', ( 21.30326722320182498, 111.8959539139345623, 163.3359429212474652 ) ) ; +#25852 = ADVANCED_FACE ( 'NONE', ( #24698 ), #11466, .T. ) ; +#25853 = CARTESIAN_POINT ( 'NONE', ( -77.86967201343009037, 193.6973639405334211, 188.4988971914144997 ) ) ; +#25854 = EDGE_LOOP ( 'NONE', ( #5970, #35708, #35550, #38919, #23555, #13161, #37450, #26854, #12290, #31369 ) ) ; +#25855 = VERTEX_POINT ( 'NONE', #6451 ) ; +#25856 = CARTESIAN_POINT ( 'NONE', ( 35.54796091243969869, 209.7096538831000032, 78.03703491673005033 ) ) ; +#25857 = EDGE_CURVE ( 'NONE', #4191, #16108, #16667, .T. ) ; +#25858 = CARTESIAN_POINT ( 'NONE', ( -46.10293086928386685, 125.3510531446604119, 91.69924967890207768 ) ) ; +#25859 = DIRECTION ( 'NONE', ( 0.7066905234128858515, 0.1590644159615968445, -0.6894106292284863935 ) ) ; +#25860 = CARTESIAN_POINT ( 'NONE', ( 35.91400125412999955, 192.1945380241000123, 104.2261858913000054 ) ) ; +#25861 = EDGE_CURVE ( 'NONE', #12419, #21377, #18920, .T. ) ; +#25862 = ORIENTED_EDGE ( 'NONE', *, *, #38505, .F. ) ; +#25863 = ORIENTED_EDGE ( 'NONE', *, *, #15698, .T. ) ; +#25864 = AXIS2_PLACEMENT_3D ( 'NONE', #36399, #2263, #15335 ) ; +#25865 = CARTESIAN_POINT ( 'NONE', ( -15.49852918184222439, 151.4059875814179463, 97.18286991562941068 ) ) ; +#25866 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #20672, #16973, #39672, #38860 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.218337603126023794, 4.671255600858287949 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9829783718293336747, 0.9829783718293336747, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#25867 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, 2.333520449303964377E-14, 0.9999998176071847045 ) ) ; +#25868 = CIRCLE ( 'NONE', #11488, 7.999999999987271515 ) ; +#25869 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -1.540743955509789367E-33, 0.0006039748319385908944 ) ) ; +#25870 = ORIENTED_EDGE ( 'NONE', *, *, #33527, .T. ) ; +#25871 = ADVANCED_FACE ( 'NONE', ( #25900 ), #17984, .T. ) ; +#25872 = EDGE_LOOP ( 'NONE', ( #40105, #14926, #20387, #9804 ) ) ; +#25873 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; +#25874 = VERTEX_POINT ( 'NONE', #37948 ) ; +#25875 = CARTESIAN_POINT ( 'NONE', ( -37.48991906556833698, 117.3311509667802568, 89.72388382565569032 ) ) ; +#25876 = CONICAL_SURFACE ( 'NONE', #39525, 2.503060577177303347, 0.7853981633905392501 ) ; +#25877 = CARTESIAN_POINT ( 'NONE', ( 26.00891783773975874, 196.5784392904109836, 103.8593946022765522 ) ) ; +#25878 = LINE ( 'NONE', #34822, #29429 ) ; +#25879 = ORIENTED_EDGE ( 'NONE', *, *, #33080, .F. ) ; +#25880 = CARTESIAN_POINT ( 'NONE', ( -38.09245941673125202, 165.8295026144894848, 188.3351898487784979 ) ) ; +#25881 = CARTESIAN_POINT ( 'NONE', ( -20.00025820447960001, 138.1823733798348428, 91.56700283718186029 ) ) ; +#25882 = CARTESIAN_POINT ( 'NONE', ( -85.24348513260991922, 108.2328939675489039, 25.03902193712222513 ) ) ; +#25883 = EDGE_LOOP ( 'NONE', ( #12746, #37666, #2897, #10527 ) ) ; +#25884 = CARTESIAN_POINT ( 'NONE', ( -15.49823494792000034, 183.2823103887000116, 105.0552522186000033 ) ) ; +#25885 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#25886 = DIRECTION ( 'NONE', ( 0.9914446600486714889, -0.1270322995874083039, -0.03000468167651988011 ) ) ; +#25887 = FACE_OUTER_BOUND ( 'NONE', #21509, .T. ) ; +#25888 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#25889 = ORIENTED_EDGE ( 'NONE', *, *, #37343, .F. ) ; +#25890 = VECTOR ( 'NONE', #8505, 1000.000000000000000 ) ; +#25891 = CARTESIAN_POINT ( 'NONE', ( 5.672673928745917138, 188.3446234544624360, 103.1322799088097213 ) ) ; +#25892 = VECTOR ( 'NONE', #37535, 1000.000000000000000 ) ; +#25893 = CARTESIAN_POINT ( 'NONE', ( -38.51153276251000079, 118.3243097615000039, 89.55231124261001696 ) ) ; +#25894 = ORIENTED_EDGE ( 'NONE', *, *, #18898, .T. ) ; +#25895 = ORIENTED_EDGE ( 'NONE', *, *, #22906, .T. ) ; +#25896 = EDGE_CURVE ( 'NONE', #26354, #8120, #3625, .T. ) ; +#25898 = VECTOR ( 'NONE', #36655, 1000.000000000000114 ) ; +#25897 = FACE_OUTER_BOUND ( 'NONE', #15424, .T. ) ; +#25899 = EDGE_CURVE ( 'NONE', #18328, #326, #4467, .T. ) ; +#25900 = FACE_OUTER_BOUND ( 'NONE', #11316, .T. ) ; +#25901 = LINE ( 'NONE', #37949, #34594 ) ; +#25902 = EDGE_CURVE ( 'NONE', #31162, #14004, #35853, .T. ) ; +#25903 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37667, #13330, #25822, #6573, #19244, #22548, #451, #55, #25217, #7185 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000013494206, 0.5000000000026988412, 0.7500000000040483172, 1.000000000005397682 ), + .UNSPECIFIED. ) ; +#25904 = CARTESIAN_POINT ( 'NONE', ( 23.36189990591568133, 177.7981167418394648, 100.6835809371482071 ) ) ; +#25905 = FACE_OUTER_BOUND ( 'NONE', #39579, .T. ) ; +#25906 = ORIENTED_EDGE ( 'NONE', *, *, #33397, .F. ) ; +#25907 = ORIENTED_EDGE ( 'NONE', *, *, #6486, .T. ) ; +#25908 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#25909 = LINE ( 'NONE', #16269, #7230 ) ; +#25910 = ADVANCED_FACE ( 'NONE', ( #14008 ), #21317, .F. ) ; +#25911 = EDGE_LOOP ( 'NONE', ( #4169, #25175, #14015, #13528 ) ) ; +#25912 = CARTESIAN_POINT ( 'NONE', ( -25.50869118940049418, 205.9699382466141060, 75.53276979609236719 ) ) ; +#25913 = CARTESIAN_POINT ( 'NONE', ( 35.76259268655000056, 114.4925971151999988, 87.35906496734000370 ) ) ; +#25914 = CARTESIAN_POINT ( 'NONE', ( 20.31802304245822199, 148.9701552444815889, 180.2359233600722064 ) ) ; +#25915 = CARTESIAN_POINT ( 'NONE', ( 2.967323546165053560, 209.6397747443908202, 76.05789313520143935 ) ) ; +#25916 = EDGE_CURVE ( 'NONE', #18594, #36032, #14218, .T. ) ; +#25917 = CARTESIAN_POINT ( 'NONE', ( 37.65057158750833821, 122.6594394773597969, 91.02725657039249541 ) ) ; +#25918 = CARTESIAN_POINT ( 'NONE', ( 21.72804141255551968, 135.8412665901933281, 91.00123227078390187 ) ) ; +#25919 = ORIENTED_EDGE ( 'NONE', *, *, #17142, .T. ) ; +#25920 = CARTESIAN_POINT ( 'NONE', ( 28.43207377478999831, 125.3828625717000023, 88.75274922023000101 ) ) ; +#25921 = AXIS2_PLACEMENT_3D ( 'NONE', #23407, #29746, #9794 ) ; +#25922 = CARTESIAN_POINT ( 'NONE', ( 28.26067382423566698, 125.1347711400599110, 91.09124888412546284 ) ) ; +#25923 = DIRECTION ( 'NONE', ( -6.938893903907188146E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#25924 = DIRECTION ( 'NONE', ( 0.0005884949961234757585, -0.2249510543439061094, 0.9743698870671263501 ) ) ; +#25925 = CARTESIAN_POINT ( 'NONE', ( 4.661269518560463787, 124.5726190011685617, 88.40996077378878226 ) ) ; +#25926 = ORIENTED_EDGE ( 'NONE', *, *, #31623, .F. ) ; +#25927 = EDGE_CURVE ( 'NONE', #23376, #1726, #38938, .T. ) ; +#25928 = CARTESIAN_POINT ( 'NONE', ( 21.26009136220303120, 136.4215387128503494, 93.70123539943294588 ) ) ; +#25929 = CARTESIAN_POINT ( 'NONE', ( 0.5903394205705844167, 189.0001744873707139, 103.6876116629842954 ) ) ; +#25930 = CARTESIAN_POINT ( 'NONE', ( -75.43462682692893395, 196.7891049527112841, 189.2142300545978344 ) ) ; +#25931 = CONICAL_SURFACE ( 'NONE', #6318, 2.503106776662724187, 0.7853981633574818044 ) ; +#25932 = CARTESIAN_POINT ( 'NONE', ( 12.63660632401984607, 130.0048512205758868, 92.26772709118364446 ) ) ; +#25933 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555410 ) ) ; +#25934 = CARTESIAN_POINT ( 'NONE', ( -20.51998460911297784, 211.0905570173818546, 73.57089872868714053 ) ) ; +#25935 = CARTESIAN_POINT ( 'NONE', ( -20.24838124913999948, 187.6253075150000029, 105.8042051877000063 ) ) ; +#25936 = CARTESIAN_POINT ( 'NONE', ( -39.35534632512823805, 183.2999964971099303, 101.9948315917579293 ) ) ; +#25937 = CARTESIAN_POINT ( 'NONE', ( -20.49878101475079006, 193.0431070017871207, 106.3366395002382774 ) ) ; +#25938 = LINE ( 'NONE', #23252, #387 ) ; +#25939 = EDGE_LOOP ( 'NONE', ( #30963, #13284, #33305, #12638 ) ) ; +#25940 = FACE_OUTER_BOUND ( 'NONE', #8955, .T. ) ; +#25941 = FACE_OUTER_BOUND ( 'NONE', #37692, .T. ) ; +#25942 = ORIENTED_EDGE ( 'NONE', *, *, #16099, .F. ) ; +#25943 = CARTESIAN_POINT ( 'NONE', ( -24.30274708465592326, 117.2756935949167314, 170.8452364414067688 ) ) ; +#25944 = CARTESIAN_POINT ( 'NONE', ( -25.99172658142667558, 191.8212920557626830, 103.9312229004612931 ) ) ; +#25945 = CONICAL_SURFACE ( 'NONE', #22002, 2.502999999907702389, 0.7853981633983988520 ) ; +#25946 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#25947 = CARTESIAN_POINT ( 'NONE', ( 36.06506287055499627, 192.7079431075819969, 106.3534797050179890 ) ) ; +#25948 = EDGE_CURVE ( 'NONE', #15910, #27558, #33690, .T. ) ; +#25949 = DIRECTION ( 'NONE', ( 0.0005884949961212082581, -0.2249510543439042498, 0.9743698870671267942 ) ) ; +#25950 = EDGE_CURVE ( 'NONE', #8723, #16362, #14622, .T. ) ; +#25951 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825803063353275, 0.0005734119050868656054 ) ) ; +#25952 = CARTESIAN_POINT ( 'NONE', ( 36.20498506693999730, 192.7754826498999989, 106.1893283618999959 ) ) ; +#25953 = AXIS2_PLACEMENT_3D ( 'NONE', #5186, #2145, #20947 ) ; +#25954 = ORIENTED_EDGE ( 'NONE', *, *, #29997, .F. ) ; +#25955 = CARTESIAN_POINT ( 'NONE', ( -2.749347475841000144, 209.4717962128000295, 75.90003642860000355 ) ) ; +#25956 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6080, #12029, #31038, #3007, #31849, #6470 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 4 ), + ( 0.000000000000000000, 0.3333332908269993622, 0.6666665931978983384, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#25957 = CARTESIAN_POINT ( 'NONE', ( 17.91044079408289846, 122.0699274945536672, 171.9639141926653849 ) ) ; +#25958 = LINE ( 'NONE', #4240, #1715 ) ; +#25959 = CARTESIAN_POINT ( 'NONE', ( -26.71688048469999899, 177.4879621182000164, 100.9019602402999993 ) ) ; +#25960 = ORIENTED_EDGE ( 'NONE', *, *, #38928, .F. ) ; +#25961 = CARTESIAN_POINT ( 'NONE', ( 6.035661899977945666, 177.4419340092994162, 100.9146504478096489 ) ) ; +#25962 = ORIENTED_EDGE ( 'NONE', *, *, #1043, .F. ) ; +#25963 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386880390 ) ) ; +#25964 = CARTESIAN_POINT ( 'NONE', ( 25.99899579567804864, 120.3902236066977025, 87.43149108636995948 ) ) ; +#25965 = ORIENTED_EDGE ( 'NONE', *, *, #3172, .F. ) ; +#25966 = DIRECTION ( 'NONE', ( 0.7855473026356902810, 0.6188014303620729128, -0.0004744508866335531562 ) ) ; +#25967 = CARTESIAN_POINT ( 'NONE', ( -15.49852919137054741, 126.2381079287689403, 91.37240600825562353 ) ) ; +#25968 = CARTESIAN_POINT ( 'NONE', ( -19.34721860474193633, 124.8429025638662750, 177.8375121285605189 ) ) ; +#25969 = CARTESIAN_POINT ( 'NONE', ( -0.4540625018068648600, 211.4999999999330385, 76.05877887195120479 ) ) ; +#25970 = EDGE_LOOP ( 'NONE', ( #33541, #29923, #25739, #31575 ) ) ; +#25971 = ORIENTED_EDGE ( 'NONE', *, *, #31944, .F. ) ; +#25972 = EDGE_CURVE ( 'NONE', #25255, #6456, #11496, .T. ) ; +#25973 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; +#25974 = CARTESIAN_POINT ( 'NONE', ( -13.49052885539015278, 188.3420772061585353, 103.1432726234667427 ) ) ; +#25975 = DIRECTION ( 'NONE', ( 0.0005884949961217588160, -0.2249510543439091625, 0.9743698870671256840 ) ) ; +#25976 = VECTOR ( 'NONE', #33983, 1000.000000000000114 ) ; +#25977 = LINE ( 'NONE', #16927, #12483 ) ; +#25978 = VERTEX_POINT ( 'NONE', #2554 ) ; +#25979 = ORIENTED_EDGE ( 'NONE', *, *, #13931, .F. ) ; +#25980 = CARTESIAN_POINT ( 'NONE', ( -20.40297810709813220, 153.0607523594057966, 190.9281641407467589 ) ) ; +#25981 = CONICAL_SURFACE ( 'NONE', #24013, 6.500001124525312868, 0.7853982240593504471 ) ; +#25982 = CARTESIAN_POINT ( 'NONE', ( 2.538357414086004127, 209.1910662834000050, 73.57953838714999506 ) ) ; +#25983 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.782262518445068689E-15, 0.0006039748319343033085 ) ) ; +#25984 = CARTESIAN_POINT ( 'NONE', ( 26.18206239126000412, 190.7066273046999925, 106.8817066621000009 ) ) ; +#25985 = CARTESIAN_POINT ( 'NONE', ( -2.215708771335000105, 209.6118119513000124, 73.69668462555000588 ) ) ; +#25986 = CARTESIAN_POINT ( 'NONE', ( 38.13603377551000051, 118.9082903320999947, 90.39814881894000109 ) ) ; +#25987 = ORIENTED_EDGE ( 'NONE', *, *, #10455, .T. ) ; +#25988 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999894129, 179.7376864901495992, 101.1595092802908198 ) ) ; +#25989 = CARTESIAN_POINT ( 'NONE', ( 25.99211731546482795, 209.7096512574500480, 76.04280604205342797 ) ) ; +#25990 = CARTESIAN_POINT ( 'NONE', ( -13.83865842395234935, 150.1303200752071803, 181.2121488737601283 ) ) ; +#25991 = EDGE_CURVE ( 'NONE', #38021, #11146, #35237, .T. ) ; +#25992 = ADVANCED_FACE ( 'NONE', ( #21158 ), #14831, .T. ) ; +#25994 = ORIENTED_EDGE ( 'NONE', *, *, #12233, .F. ) ; +#25993 = CARTESIAN_POINT ( 'NONE', ( -26.03762780489454798, 190.4430338229397819, 106.7148013156263175 ) ) ; +#25995 = ORIENTED_EDGE ( 'NONE', *, *, #617, .F. ) ; +#25996 = ORIENTED_EDGE ( 'NONE', *, *, #3666, .T. ) ; +#25997 = VERTEX_POINT ( 'NONE', #18664 ) ; +#25998 = CARTESIAN_POINT ( 'NONE', ( -34.98386828774999913, 220.4002260771000010, 28.07991271570000080 ) ) ; +#25999 = AXIS2_PLACEMENT_3D ( 'NONE', #6277, #3207, #5472 ) ; +#26000 = LINE ( 'NONE', #32518, #7879 ) ; +#26001 = CARTESIAN_POINT ( 'NONE', ( 20.00000190450869653, 184.9707748627797912, 102.3447125600660002 ) ) ; +#26002 = VECTOR ( 'NONE', #40202, 999.9999999999998863 ) ; +#26003 = ORIENTED_EDGE ( 'NONE', *, *, #25071, .T. ) ; +#26004 = FACE_BOUND ( 'NONE', #17876, .T. ) ; +#26005 = FACE_OUTER_BOUND ( 'NONE', #14499, .T. ) ; +#26006 = FACE_OUTER_BOUND ( 'NONE', #880, .T. ) ; +#26007 = CARTESIAN_POINT ( 'NONE', ( -25.02288790548047004, 130.6107454572028246, 89.82190017567243956 ) ) ; +#26008 = ORIENTED_EDGE ( 'NONE', *, *, #22325, .F. ) ; +#26009 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; +#26010 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #18869, #16214 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26011 = VERTEX_POINT ( 'NONE', #30968 ) ; +#26012 = CARTESIAN_POINT ( 'NONE', ( 8.121789135547750504, 134.9201405189939180, 90.79681010353952786 ) ) ; +#26013 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#26014 = FACE_OUTER_BOUND ( 'NONE', #1741, .T. ) ; +#26015 = CARTESIAN_POINT ( 'NONE', ( 25.91449224139000407, 181.3172170175000133, 104.3199862606000039 ) ) ; +#26016 = ORIENTED_EDGE ( 'NONE', *, *, #16779, .T. ) ; +#26017 = EDGE_CURVE ( 'NONE', #2346, #18635, #10862, .T. ) ; +#26018 = CARTESIAN_POINT ( 'NONE', ( -2.389070030422000279, 190.4669482803000164, 104.1095728949999994 ) ) ; +#26019 = CARTESIAN_POINT ( 'NONE', ( 20.50144823217644330, 191.6366434279915438, 106.4097421862435766 ) ) ; +#26020 = CARTESIAN_POINT ( 'NONE', ( 2.942907856069000072, 190.9056063678999919, 106.6791766134000170 ) ) ; +#26021 = ORIENTED_EDGE ( 'NONE', *, *, #24214, .F. ) ; +#26022 = CARTESIAN_POINT ( 'NONE', ( -21.50356562057856991, 213.7091158727889990, 73.07149169719511406 ) ) ; +#26023 = DIRECTION ( 'NONE', ( 0.0006039748319395907457, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#26024 = VERTEX_POINT ( 'NONE', #12351 ) ; +#26025 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; +#26026 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32921, #32526, #16966, #35979 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26027 = EDGE_CURVE ( 'NONE', #19409, #7166, #31764, .T. ) ; +#26028 = VECTOR ( 'NONE', #16190, 1000.000000000000000 ) ; +#26029 = EDGE_LOOP ( 'NONE', ( #9201, #15467, #7831 ) ) ; +#26030 = CARTESIAN_POINT ( 'NONE', ( -3.589080270979503773, 149.3464402625826608, 130.0539584791989967 ) ) ; +#26031 = VECTOR ( 'NONE', #31368, 999.9999999999998863 ) ; +#26032 = CARTESIAN_POINT ( 'NONE', ( 25.49182901039327831, 209.7089661076149127, 75.54314178666862745 ) ) ; +#26033 = EDGE_CURVE ( 'NONE', #9657, #36005, #26010, .T. ) ; +#26034 = ORIENTED_EDGE ( 'NONE', *, *, #37881, .F. ) ; +#26035 = ORIENTED_EDGE ( 'NONE', *, *, #173, .T. ) ; +#26036 = CARTESIAN_POINT ( 'NONE', ( 26.00011972461669174, 120.0901139229121100, 90.43138363690108861 ) ) ; +#26037 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#26038 = ADVANCED_FACE ( 'NONE', ( #3534 ), #29803, .F. ) ; +#26039 = EDGE_CURVE ( 'NONE', #20184, #9884, #9425, .T. ) ; +#26041 = CARTESIAN_POINT ( 'NONE', ( 39.77206948006279674, 161.5605239982007504, 197.5119495795953810 ) ) ; +#26040 = CARTESIAN_POINT ( 'NONE', ( 20.48183248207558549, 208.2252159794623196, 76.03069286372645763 ) ) ; +#26042 = ADVANCED_FACE ( 'NONE', ( #7209 ), #34799, .T. ) ; +#26043 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#26044 = VERTEX_POINT ( 'NONE', #38292 ) ; +#26045 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#26046 = CARTESIAN_POINT ( 'NONE', ( -39.61053789571219852, 75.07173372617528173, 323.7343870505221730 ) ) ; +#26047 = ORIENTED_EDGE ( 'NONE', *, *, #28089, .F. ) ; +#26048 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20167, #25738, #13644, #29592 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 4.799113383051342829, 4.799119433357724063 ), + .UNSPECIFIED. ) ; +#26049 = ORIENTED_EDGE ( 'NONE', *, *, #9235, .F. ) ; +#26050 = FACE_OUTER_BOUND ( 'NONE', #8566, .T. ) ; +#26051 = CIRCLE ( 'NONE', #5787, 5.249999999999986677 ) ; +#26052 = CARTESIAN_POINT ( 'NONE', ( -44.97770985034782854, 124.1127469420047191, 93.47909829974288698 ) ) ; +#26053 = CARTESIAN_POINT ( 'NONE', ( -3.070528409906000178, 190.8178548437000188, 106.9268874777999940 ) ) ; +#26054 = CARTESIAN_POINT ( 'NONE', ( 36.02403025217999755, 191.5672976319999918, 103.8486584797000063 ) ) ; +#26055 = ORIENTED_EDGE ( 'NONE', *, *, #14679, .T. ) ; +#26056 = CIRCLE ( 'NONE', #7727, 4.999999999999990230 ) ; +#26057 = ORIENTED_EDGE ( 'NONE', *, *, #3474, .T. ) ; +#26058 = CARTESIAN_POINT ( 'NONE', ( -6.034883611057908936, 176.9196591974746866, 103.3121627513912841 ) ) ; +#26059 = VECTOR ( 'NONE', #32168, 999.9999999999998863 ) ; +#26060 = CARTESIAN_POINT ( 'NONE', ( 20.50147081996105314, 160.1804844985509817, 99.18687942156120130 ) ) ; +#26061 = CARTESIAN_POINT ( 'NONE', ( -13.54026526282000198, 167.3593566666999948, 28.07991271570000080 ) ) ; +#26062 = VECTOR ( 'NONE', #4064, 1000.000000000000114 ) ; +#26063 = ORIENTED_EDGE ( 'NONE', *, *, #6354, .T. ) ; +#26064 = EDGE_CURVE ( 'NONE', #16908, #10983, #33298, .T. ) ; +#26065 = CARTESIAN_POINT ( 'NONE', ( -13.50000254163585822, 174.5144785022299061, 99.94784507006426111 ) ) ; +#26066 = ORIENTED_EDGE ( 'NONE', *, *, #33527, .F. ) ; +#26067 = CARTESIAN_POINT ( 'NONE', ( -38.15302004047697437, 118.1466911995112667, 89.71266419572562256 ) ) ; +#26068 = CARTESIAN_POINT ( 'NONE', ( 22.50136996952335267, 157.6320572232312998, 99.11047108320519783 ) ) ; +#26069 = ORIENTED_EDGE ( 'NONE', *, *, #5918, .F. ) ; +#26070 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#26071 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#26072 = FACE_OUTER_BOUND ( 'NONE', #9111, .T. ) ; +#26073 = EDGE_CURVE ( 'NONE', #38119, #1188, #14131, .T. ) ; +#26074 = VERTEX_POINT ( 'NONE', #2109 ) ; +#26075 = VERTEX_POINT ( 'NONE', #40306 ) ; +#26076 = CARTESIAN_POINT ( 'NONE', ( 21.21575625058384063, 175.4487304674486552, 102.7114009836462003 ) ) ; +#26077 = FACE_OUTER_BOUND ( 'NONE', #25883, .T. ) ; +#26078 = DIRECTION ( 'NONE', ( -0.6087614810001780175, 0.7729390313185915407, 0.1788147452386051883 ) ) ; +#26079 = AXIS2_PLACEMENT_3D ( 'NONE', #6877, #16080, #16676 ) ; +#26080 = EDGE_CURVE ( 'NONE', #26158, #27515, #24054, .T. ) ; +#26081 = CARTESIAN_POINT ( 'NONE', ( -41.28986358703587456, 120.5685454323574817, 90.59221360106587895 ) ) ; +#26082 = EDGE_LOOP ( 'NONE', ( #2693, #25030, #22215, #28295, #386 ) ) ; +#26083 = EDGE_CURVE ( 'NONE', #20184, #30729, #13119, .T. ) ; +#26084 = AXIS2_PLACEMENT_3D ( 'NONE', #3165, #11992, #110 ) ; +#26085 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366368657916, 137.4659008082770697, 177.5714312369256049 ) ) ; +#26086 = EDGE_CURVE ( 'NONE', #2177, #32373, #21925, .T. ) ; +#26087 = AXIS2_PLACEMENT_3D ( 'NONE', #8224, #20472, #29090 ) ; +#26088 = CARTESIAN_POINT ( 'NONE', ( -37.71441295843000319, 118.5995274305000038, 90.44743091121000589 ) ) ; +#26089 = EDGE_CURVE ( 'NONE', #12175, #15089, #39557, .T. ) ; +#26090 = ORIENTED_EDGE ( 'NONE', *, *, #19633, .F. ) ; +#26091 = EDGE_CURVE ( 'NONE', #929, #9411, #25505, .T. ) ; +#26092 = EDGE_LOOP ( 'NONE', ( #17814, #31735, #16082, #13525, #2760, #30126, #5750, #39939 ) ) ; +#26093 = CARTESIAN_POINT ( 'NONE', ( -28.46145970092849709, 130.2180706372660666, 92.64122260005370890 ) ) ; +#26094 = CARTESIAN_POINT ( 'NONE', ( 35.21203317443208647, 88.41000286829014954, 281.4602140209115646 ) ) ; +#26095 = DIRECTION ( 'NONE', ( -0.0005884949961238380989, 0.2249510543439045829, -0.9743698870671267942 ) ) ; +#26096 = ORIENTED_EDGE ( 'NONE', *, *, #6519, .F. ) ; +#26097 = ORIENTED_EDGE ( 'NONE', *, *, #17488, .F. ) ; +#26098 = DIRECTION ( 'NONE', ( 0.0004161288024528962161, 0.5299192578740949955, 0.8480479980348919478 ) ) ; +#26099 = ORIENTED_EDGE ( 'NONE', *, *, #23963, .T. ) ; +#26100 = ORIENTED_EDGE ( 'NONE', *, *, #38338, .F. ) ; +#26101 = CARTESIAN_POINT ( 'NONE', ( 5.675840488321574284, 188.3446150673902650, 103.1322824216947396 ) ) ; +#26102 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498896523, 181.7471167547632547, 104.6805916157985195 ) ) ; +#26103 = CARTESIAN_POINT ( 'NONE', ( -27.08876248542915377, 119.4912842839333535, 171.3567424277059956 ) ) ; +#26104 = CARTESIAN_POINT ( 'NONE', ( -45.39606049366843621, 123.6566771517818637, 91.23024032489176705 ) ) ; +#26105 = ORIENTED_EDGE ( 'NONE', *, *, #39031, .T. ) ; +#26106 = CARTESIAN_POINT ( 'NONE', ( -25.50911727185309630, 206.5315393778744522, 74.85791579066014378 ) ) ; +#26107 = DIRECTION ( 'NONE', ( -0.0004161288024448787037, 0.8480480898058688766, -0.5299191110098189217 ) ) ; +#26108 = CYLINDRICAL_SURFACE ( 'NONE', #30292, 1.000000000000015099 ) ; +#26109 = CARTESIAN_POINT ( 'NONE', ( 3.038435836854210148, 209.3322921572255950, 76.08940849261169603 ) ) ; +#26110 = AXIS2_PLACEMENT_3D ( 'NONE', #32827, #4807, #17269 ) ; +#26111 = ORIENTED_EDGE ( 'NONE', *, *, #38180, .T. ) ; +#26112 = FACE_OUTER_BOUND ( 'NONE', #29178, .T. ) ; +#26113 = CARTESIAN_POINT ( 'NONE', ( -14.90630211925956417, 176.5437391631601258, 100.4202597877415712 ) ) ; +#26114 = CARTESIAN_POINT ( 'NONE', ( 31.51045601729472878, 191.4722053967427371, 106.4044942135075615 ) ) ; +#26115 = ORIENTED_EDGE ( 'NONE', *, *, #24289, .T. ) ; +#26116 = VECTOR ( 'NONE', #32909, 1000.000000000000114 ) ; +#26117 = CARTESIAN_POINT ( 'NONE', ( -1.458415330480473004, 144.9404864492774720, 129.0359332386186679 ) ) ; +#26118 = AXIS2_PLACEMENT_3D ( 'NONE', #29600, #17302, #29205 ) ; +#26119 = CARTESIAN_POINT ( 'NONE', ( -37.23839612158430157, 105.3143004547666521, 178.4910803265802031 ) ) ; +#26120 = CARTESIAN_POINT ( 'NONE', ( -44.46004285478915108, 188.8078265508242168, 105.8352584314367135 ) ) ; +#26121 = CARTESIAN_POINT ( 'NONE', ( -12.63650000504985549, 176.7400935515184131, 103.0299816119349714 ) ) ; +#26122 = EDGE_LOOP ( 'NONE', ( #23405, #6878, #11274, #26003 ) ) ; +#26123 = CARTESIAN_POINT ( 'NONE', ( 37.33774095389934899, 168.2370055128168644, 182.6413831928035165 ) ) ; +#26124 = CARTESIAN_POINT ( 'NONE', ( 0.7564024116337380033, 189.0098714485679636, 103.6863029074804530 ) ) ; +#26125 = CARTESIAN_POINT ( 'NONE', ( -30.04734455941837368, 126.8158942839318399, 89.11987558063840709 ) ) ; +#26126 = EDGE_CURVE ( 'NONE', #39643, #35545, #22328, .T. ) ; +#26127 = ADVANCED_FACE ( 'NONE', ( #19631 ), #23254, .F. ) ; +#26128 = CARTESIAN_POINT ( 'NONE', ( 12.63710206518894630, 130.0516725572641690, 92.34265652479372477 ) ) ; +#26129 = ADVANCED_FACE ( 'NONE', ( #13515 ), #1432, .T. ) ; +#26130 = CARTESIAN_POINT ( 'NONE', ( -25.87155708262000076, 191.7567966093000109, 104.0465514997000014 ) ) ; +#26131 = DIRECTION ( 'NONE', ( -0.0005734119072323138125, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#26132 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825921615701389, 0.0005734119023492946932 ) ) ; +#26133 = EDGE_CURVE ( 'NONE', #39877, #23218, #4619, .T. ) ; +#26134 = CARTESIAN_POINT ( 'NONE', ( -44.76727314987169137, 188.9782592361786726, 103.7990538156673637 ) ) ; +#26135 = DIRECTION ( 'NONE', ( 0.7855473026356903921, 0.6188014303620726908, -0.0004744508866335689855 ) ) ; +#26136 = VERTEX_POINT ( 'NONE', #35547 ) ; +#26137 = EDGE_CURVE ( 'NONE', #31137, #4945, #32722, .T. ) ; +#26138 = CARTESIAN_POINT ( 'NONE', ( 29.05503365078199707, 110.6131156702000027, 89.75023623571587450 ) ) ; +#26139 = ADVANCED_FACE ( 'NONE', ( #38440 ), #24552, .T. ) ; +#26140 = CONICAL_SURFACE ( 'NONE', #39157, 59.40509898907522768, 0.7853981633972503262 ) ; +#26141 = CARTESIAN_POINT ( 'NONE', ( -12.63649281425979254, 129.9703308616587947, 92.23232912629561042 ) ) ; +#26142 = VECTOR ( 'NONE', #4349, 1000.000000000000000 ) ; +#26143 = ORIENTED_EDGE ( 'NONE', *, *, #12885, .F. ) ; +#26144 = CARTESIAN_POINT ( 'NONE', ( -24.62180453110569545, 117.2407823713247694, 170.8370874554811394 ) ) ; +#26145 = CARTESIAN_POINT ( 'NONE', ( 46.05118615274398763, 124.8743111081185049, 91.53352630994533001 ) ) ; +#26146 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33097, #33502, #30660, #14510, #2453, #23710, #18913, #6445, #39428, #2043, #2659, #24537, #8381, #26995, #15124, #5293, #8787, #30245, #26788, #14916, #3377, #5085, #39637, #39233, #5491, #11236, #21256, #2244 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 1, 2, 2, 1, 1, 1, 2, 2, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999994391153, 0.1874999999991534549, 0.2187499999989995225, 0.2343749999989190869, 0.2421874999988790911, 0.2460937499988591071, 0.2499999999988390953, 0.3749999999987644328, 0.4374999999987063126, 0.4687499999986773913, 0.4843749999986785570, 0.4999999999986797228, 0.6249999999987549959, 0.6874999999987920773, 0.7187499999988170574, 0.7343749999988294919, 0.7421874999988588018, 0.7499999999988880006, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26147 = AXIS2_PLACEMENT_3D ( 'NONE', #14121, #36590, #8594 ) ; +#26148 = LINE ( 'NONE', #23066, #8479 ) ; +#26149 = CARTESIAN_POINT ( 'NONE', ( 20.00140612192502942, 118.1043503129110093, 90.25575274657424529 ) ) ; +#26150 = AXIS2_PLACEMENT_3D ( 'NONE', #33995, #17642, #24007 ) ; +#26151 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319392994206 ) ) ; +#26152 = CYLINDRICAL_SURFACE ( 'NONE', #7595, 2.000000000000011546 ) ; +#26153 = ORIENTED_EDGE ( 'NONE', *, *, #24333, .T. ) ; +#26154 = EDGE_CURVE ( 'NONE', #34987, #19810, #28891, .T. ) ; +#26155 = FACE_OUTER_BOUND ( 'NONE', #29779, .T. ) ; +#26156 = CARTESIAN_POINT ( 'NONE', ( -16.53681909317384324, 122.5194902194745055, 174.6067105814985609 ) ) ; +#26157 = PLANE ( 'NONE', #422 ) ; +#26158 = VERTEX_POINT ( 'NONE', #23729 ) ; +#26159 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971554578 ) ) ; +#26160 = CARTESIAN_POINT ( 'NONE', ( 3.777496618107850868, 136.7362355281202326, 94.04957486231310781 ) ) ; +#26161 = ORIENTED_EDGE ( 'NONE', *, *, #25068, .F. ) ; +#26162 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319388554398 ) ) ; +#26163 = CARTESIAN_POINT ( 'NONE', ( -37.97633501673850986, 143.6343013820186627, 291.5814806899745122 ) ) ; +#26164 = VERTEX_POINT ( 'NONE', #14531 ) ; +#26165 = CARTESIAN_POINT ( 'NONE', ( 24.86432580519088376, 181.7359623805197089, 104.1607194630871049 ) ) ; +#26166 = CARTESIAN_POINT ( 'NONE', ( -15.99825050089035550, 126.1262029676268668, 91.86002998339648684 ) ) ; +#26167 = CARTESIAN_POINT ( 'NONE', ( -30.06929056564133518, 176.9377538507572467, 103.3599937213831481 ) ) ; +#26168 = FACE_OUTER_BOUND ( 'NONE', #18273, .T. ) ; +#26169 = ORIENTED_EDGE ( 'NONE', *, *, #11278, .T. ) ; +#26170 = FACE_OUTER_BOUND ( 'NONE', #19610, .T. ) ; +#26171 = CIRCLE ( 'NONE', #13747, 59.40509898897001051 ) ; +#26172 = CARTESIAN_POINT ( 'NONE', ( -4.584463781762333490, 177.3496358541460722, 100.6000816012465719 ) ) ; +#26173 = LINE ( 'NONE', #4259, #5124 ) ; +#26174 = AXIS2_PLACEMENT_3D ( 'NONE', #27315, #39743, #18066 ) ; +#26176 = EDGE_LOOP ( 'NONE', ( #15216, #29975, #25797, #24705 ) ) ; +#26175 = ADVANCED_FACE ( 'NONE', ( #5509 ), #38248, .F. ) ; +#26177 = CIRCLE ( 'NONE', #2687, 4.999999999999990230 ) ; +#26178 = FACE_OUTER_BOUND ( 'NONE', #3045, .T. ) ; +#26179 = ADVANCED_FACE ( 'NONE', ( #36398 ), #27226, .F. ) ; +#26180 = VERTEX_POINT ( 'NONE', #11873 ) ; +#26181 = FACE_OUTER_BOUND ( 'NONE', #10478, .T. ) ; +#26182 = CARTESIAN_POINT ( 'NONE', ( 33.55689699144527083, 164.0672018394440386, 187.8347355915257424 ) ) ; +#26183 = DIRECTION ( 'NONE', ( 0.0005884949961238529524, -0.2249510543439058596, 0.9743698870671263501 ) ) ; +#26184 = ADVANCED_FACE ( 'NONE', ( #33722, #5727, #6319 ), #40458, .F. ) ; +#26185 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#26186 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#26187 = CARTESIAN_POINT ( 'NONE', ( 28.46780168972100000, 130.8254044408606660, 90.01024004489680408 ) ) ; +#26188 = EDGE_CURVE ( 'NONE', #31921, #1239, #8229, .T. ) ; +#26189 = DIRECTION ( 'NONE', ( 0.6086215548477215131, 0.7730393818215737234, 0.1788572534946829551 ) ) ; +#26190 = CARTESIAN_POINT ( 'NONE', ( 38.68092143719999854, 118.3938811684000143, 89.51262490514000092 ) ) ; +#26191 = VERTEX_POINT ( 'NONE', #12457 ) ; +#26192 = DIRECTION ( 'NONE', ( 0.0005884949961244022093, -0.2249510543439064980, 0.9743698870671262391 ) ) ; +#26193 = CARTESIAN_POINT ( 'NONE', ( 39.31413750895951154, 144.6232979504316063, 291.5347991813059707 ) ) ; +#26194 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -3.519737327345223780E-16, 0.0006039748319385488274 ) ) ; +#26195 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825945353352502, 0.0005734119018001440160 ) ) ; +#26196 = VERTEX_POINT ( 'NONE', #9207 ) ; +#26197 = EDGE_LOOP ( 'NONE', ( #5983, #22876, #38126, #17004 ) ) ; +#26198 = VECTOR ( 'NONE', #8929, 1000.000000000000227 ) ; +#26199 = ADVANCED_FACE ( 'NONE', ( #6119 ), #34976, .T. ) ; +#26200 = EDGE_LOOP ( 'NONE', ( #2825, #35011, #10361, #21567 ) ) ; +#26201 = CARTESIAN_POINT ( 'NONE', ( 30.17789666961413175, 126.0876384020114784, 91.82323258389868670 ) ) ; +#26202 = AXIS2_PLACEMENT_3D ( 'NONE', #18979, #37409, #3437 ) ; +#26203 = CARTESIAN_POINT ( 'NONE', ( -9.583319590155999990, 187.4804039283999941, 105.7643101227000102 ) ) ; +#26204 = CONICAL_SURFACE ( 'NONE', #33361, 2.503090990479985400, 0.7853981633820344976 ) ; +#26205 = CARTESIAN_POINT ( 'NONE', ( -38.70467835487419705, 118.9896782172050536, 90.01319670810939044 ) ) ; +#26206 = ORIENTED_EDGE ( 'NONE', *, *, #6537, .T. ) ; +#26207 = CARTESIAN_POINT ( 'NONE', ( -2.452854177136032376, 209.7096538831000032, 78.05998645682016956 ) ) ; +#26208 = DIRECTION ( 'NONE', ( 0.0005884949961245723206, -0.2249510543439059984, 0.9743698870671263501 ) ) ; +#26209 = CARTESIAN_POINT ( 'NONE', ( -38.80491609783999962, 119.2274846327999995, 87.75209770429999878 ) ) ; +#26210 = CARTESIAN_POINT ( 'NONE', ( 13.50176813047575131, 173.8418126276867213, 102.8614805459236976 ) ) ; +#26211 = VERTEX_POINT ( 'NONE', #6508 ) ; +#26212 = CARTESIAN_POINT ( 'NONE', ( 13.85658554608545678, 124.7833813612844693, 174.0357207340887271 ) ) ; +#26213 = ORIENTED_EDGE ( 'NONE', *, *, #33725, .F. ) ; +#26214 = LINE ( 'NONE', #10671, #37684 ) ; +#26215 = CARTESIAN_POINT ( 'NONE', ( -20.51188059855327950, 203.6447578621130390, 85.96051626286971725 ) ) ; +#26216 = CARTESIAN_POINT ( 'NONE', ( 16.59040448417249891, 121.5622698803751121, 177.2309519810485767 ) ) ; +#26217 = CARTESIAN_POINT ( 'NONE', ( -22.98769208757434157, 131.0176466878757253, 89.91461220895010342 ) ) ; +#26218 = VERTEX_POINT ( 'NONE', #12875 ) ; +#26219 = VERTEX_POINT ( 'NONE', #25349 ) ; +#26220 = CARTESIAN_POINT ( 'NONE', ( -0.6433655274230000165, 188.6108429602000172, 103.1975560712999993 ) ) ; +#26221 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989940797, 0.1373964268091562024 ) ) ; +#26222 = CARTESIAN_POINT ( 'NONE', ( 3.199885833601999963, 190.8329213794999930, 106.9264235504000169 ) ) ; +#26223 = EDGE_CURVE ( 'NONE', #6019, #5116, #9808, .T. ) ; +#26224 = EDGE_LOOP ( 'NONE', ( #6008, #39296, #39851, #28217 ) ) ; +#26225 = CONICAL_SURFACE ( 'NONE', #34676, 51.90509899264980476, 0.7853981633972885179 ) ; +#26226 = DIRECTION ( 'NONE', ( -1.387778772392002640E-15, 0.9743700557921582961, 0.2249510932971574839 ) ) ; +#26227 = CARTESIAN_POINT ( 'NONE', ( -25.50006284340070906, 118.1130153187805689, 89.78316558933853742 ) ) ; +#26228 = EDGE_CURVE ( 'NONE', #4779, #4523, #20105, .T. ) ; +#26229 = VERTEX_POINT ( 'NONE', #29214 ) ; +#26230 = CIRCLE ( 'NONE', #38596, 2.499999999999997335 ) ; +#26231 = AXIS2_PLACEMENT_3D ( 'NONE', #24180, #5344, #18002 ) ; +#26232 = EDGE_LOOP ( 'NONE', ( #26523, #13432, #12718, #6571 ) ) ; +#26233 = CARTESIAN_POINT ( 'NONE', ( 30.05084665326030446, 185.2025551396338585, 102.9053044902910869 ) ) ; +#26234 = ORIENTED_EDGE ( 'NONE', *, *, #11911, .F. ) ; +#26235 = CARTESIAN_POINT ( 'NONE', ( -26.00800983458967508, 191.5260122442129216, 103.8858970416150385 ) ) ; +#26236 = CARTESIAN_POINT ( 'NONE', ( 19.99933118494021755, 196.5785306413737601, 103.8628508136982731 ) ) ; +#26237 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#26238 = VERTEX_POINT ( 'NONE', #13862 ) ; +#26239 = ORIENTED_EDGE ( 'NONE', *, *, #37899, .T. ) ; +#26240 = CARTESIAN_POINT ( 'NONE', ( 26.00569871841100067, 120.1361694506069853, 90.45417752614380902 ) ) ; +#26241 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490428653439, 156.2427122712157086, 96.23754757944941218 ) ) ; +#26243 = CARTESIAN_POINT ( 'NONE', ( -13.49833818120469964, 188.0172640734645597, 103.3462508437664553 ) ) ; +#26242 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490399013737, 151.3708619921459615, 95.11279211292851699 ) ) ; +#26244 = EDGE_CURVE ( 'NONE', #32437, #24067, #25958, .T. ) ; +#26245 = CARTESIAN_POINT ( 'NONE', ( -38.81660742513911089, 106.4213634552623517, 168.3324163836322782 ) ) ; +#26246 = VERTEX_POINT ( 'NONE', #38591 ) ; +#26247 = CARTESIAN_POINT ( 'NONE', ( -2.070178905375853251, 189.2110454056422668, 103.3369857030061638 ) ) ; +#26248 = CARTESIAN_POINT ( 'NONE', ( 21.83140103668416998, 176.0486778938952739, 102.8495379525328985 ) ) ; +#26249 = CARTESIAN_POINT ( 'NONE', ( -8.332516390861295363, 151.1890326084896401, 94.90479451117724352 ) ) ; +#26250 = ORIENTED_EDGE ( 'NONE', *, *, #24781, .F. ) ; +#26251 = CYLINDRICAL_SURFACE ( 'NONE', #40039, 2.000000000000011546 ) ; +#26253 = CIRCLE ( 'NONE', #26892, 6.499999999981660004 ) ; +#26252 = CARTESIAN_POINT ( 'NONE', ( 2.562971096207687260, 190.9999997773000189, 104.2603522706010750 ) ) ; +#26254 = CIRCLE ( 'NONE', #28220, 5.249999999999986677 ) ; +#26255 = CARTESIAN_POINT ( 'NONE', ( 5.671051541955929309, 187.5796154020130757, 105.9111029366380308 ) ) ; +#26256 = LINE ( 'NONE', #32964, #39161 ) ; +#26257 = ORIENTED_EDGE ( 'NONE', *, *, #31288, .T. ) ; +#26258 = ORIENTED_EDGE ( 'NONE', *, *, #11233, .F. ) ; +#26259 = EDGE_CURVE ( 'NONE', #15606, #8964, #7314, .T. ) ; +#26260 = VERTEX_POINT ( 'NONE', #26554 ) ; +#26261 = CARTESIAN_POINT ( 'NONE', ( -23.36699950098072165, 134.2659706838206262, 93.72240624211983118 ) ) ; +#26262 = VERTEX_POINT ( 'NONE', #13666 ) ; +#26263 = CARTESIAN_POINT ( 'NONE', ( -35.60304309402999934, 192.7598035524999887, 106.7122942566000035 ) ) ; +#26264 = EDGE_CURVE ( 'NONE', #10007, #25177, #19977, .T. ) ; +#26265 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#26266 = CARTESIAN_POINT ( 'NONE', ( 2.564266820190244545, 191.0024198337800669, 106.3123278577045738 ) ) ; +#26267 = EDGE_CURVE ( 'NONE', #15841, #36524, #392, .T. ) ; +#26268 = VERTEX_POINT ( 'NONE', #11766 ) ; +#26269 = CARTESIAN_POINT ( 'NONE', ( -20.00006126831510400, 120.3902141372887087, 87.45929000627990035 ) ) ; +#26270 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825907063166864, 0.0005734119026844853358 ) ) ; +#26271 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#26272 = CARTESIAN_POINT ( 'NONE', ( 44.41682338754539217, 189.0408562691112877, 103.4406660154240285 ) ) ; +#26273 = ORIENTED_EDGE ( 'NONE', *, *, #32170, .F. ) ; +#26274 = CARTESIAN_POINT ( 'NONE', ( 23.36366720388904383, 183.4529741750082508, 105.0711814503917765 ) ) ; +#26275 = CONICAL_SURFACE ( 'NONE', #11235, 5.500000000083335117, 0.7853981634365208020 ) ; +#26276 = CARTESIAN_POINT ( 'NONE', ( 20.38505473614282693, 212.5804310127830377, 73.04619202014056611 ) ) ; +#26277 = CARTESIAN_POINT ( 'NONE', ( 21.45549066267129135, 213.0890993161042957, 75.54548350635269571 ) ) ; +#26278 = CONICAL_SURFACE ( 'NONE', #8657, 51.90509899272856842, 0.7853981633972877408 ) ; +#26279 = AXIS2_PLACEMENT_3D ( 'NONE', #19478, #25848, #10095 ) ; +#26280 = DIRECTION ( 'NONE', ( -0.0003759831730439093154, 0.7826081568524194676, -0.6225145230954155506 ) ) ; +#26281 = ORIENTED_EDGE ( 'NONE', *, *, #22487, .F. ) ; +#26282 = CARTESIAN_POINT ( 'NONE', ( -1.762796036252210596, 151.6652447677504369, 130.5904578368505327 ) ) ; +#26283 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #32872, #16919 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26284 = CARTESIAN_POINT ( 'NONE', ( -35.69719521574999987, 115.1371617642000160, 90.43415643094000700 ) ) ; +#26285 = ORIENTED_EDGE ( 'NONE', *, *, #30308, .F. ) ; +#26286 = ORIENTED_EDGE ( 'NONE', *, *, #246, .F. ) ; +#26287 = LINE ( 'NONE', #17246, #17924 ) ; +#26288 = DIRECTION ( 'NONE', ( 0.7855473026356902810, 0.6188014303620729128, -0.0004744508866335532104 ) ) ; +#26289 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#26290 = ORIENTED_EDGE ( 'NONE', *, *, #7127, .T. ) ; +#26291 = VERTEX_POINT ( 'NONE', #34027 ) ; +#26292 = CARTESIAN_POINT ( 'NONE', ( -42.56963625464027245, 120.8513313564750575, 90.65827283841386475 ) ) ; +#26293 = ORIENTED_EDGE ( 'NONE', *, *, #3750, .T. ) ; +#26294 = ORIENTED_EDGE ( 'NONE', *, *, #36984, .F. ) ; +#26295 = CARTESIAN_POINT ( 'NONE', ( 77.74752315181704887, 192.2565373609087089, 194.3622733290381461 ) ) ; +#26296 = CARTESIAN_POINT ( 'NONE', ( -44.76913686494872735, 108.4408363393548882, 169.8241779223887136 ) ) ; +#26297 = CARTESIAN_POINT ( 'NONE', ( -29.94780647241524107, 109.6131156702000027, 87.78587210735845758 ) ) ; +#26298 = VECTOR ( 'NONE', #15226, 1000.000000000000114 ) ; +#26299 = ADVANCED_FACE ( 'NONE', ( #18471 ), #2943, .F. ) ; +#26300 = ORIENTED_EDGE ( 'NONE', *, *, #16259, .F. ) ; +#26301 = LINE ( 'NONE', #23030, #26522 ) ; +#26302 = LINE ( 'NONE', #13622, #1276 ) ; +#26304 = AXIS2_PLACEMENT_3D ( 'NONE', #35514, #1605, #14090 ) ; +#26303 = CARTESIAN_POINT ( 'NONE', ( 36.49546895817999825, 191.9015982269000062, 104.5102558848000029 ) ) ; +#26305 = CARTESIAN_POINT ( 'NONE', ( 3.012748634343953125, 209.4749847006376342, 76.06918713120469988 ) ) ; +#26306 = EDGE_CURVE ( 'NONE', #25514, #6360, #15704, .T. ) ; +#26307 = ORIENTED_EDGE ( 'NONE', *, *, #1147, .T. ) ; +#26308 = AXIS2_PLACEMENT_3D ( 'NONE', #1927, #31554, #28685 ) ; +#26309 = CARTESIAN_POINT ( 'NONE', ( 22.78008436521043123, 158.4318469938418730, 96.38708833722530755 ) ) ; +#26310 = CARTESIAN_POINT ( 'NONE', ( -23.35804788357050654, 177.0119981395035893, 103.4735393260193064 ) ) ; +#26311 = ORIENTED_EDGE ( 'NONE', *, *, #2644, .F. ) ; +#26312 = CARTESIAN_POINT ( 'NONE', ( 0.5932910502135863018, 188.6078699368097205, 103.1961229790743175 ) ) ; +#26313 = CARTESIAN_POINT ( 'NONE', ( 16.16445611541705674, 122.9245094293323888, 174.2137880000448718 ) ) ; +#26314 = ADVANCED_FACE ( 'NONE', ( #25053 ), #30578, .F. ) ; +#26315 = CARTESIAN_POINT ( 'NONE', ( -20.16670854996598550, 160.6934792717234473, 96.93531027717119741 ) ) ; +#26316 = EDGE_CURVE ( 'NONE', #18111, #6578, #33825, .T. ) ; +#26317 = DIRECTION ( 'NONE', ( -0.1305263947813612435, -0.9659212020967549162, -0.2235153050807486830 ) ) ; +#26318 = EDGE_CURVE ( 'NONE', #8044, #17792, #19283, .T. ) ; +#26319 = ORIENTED_EDGE ( 'NONE', *, *, #30375, .F. ) ; +#26320 = CARTESIAN_POINT ( 'NONE', ( -22.69003647934751555, 158.3009287201703046, 96.21327555204996429 ) ) ; +#26321 = ADVANCED_FACE ( 'NONE', ( #29111 ), #22980, .F. ) ; +#26322 = CARTESIAN_POINT ( 'NONE', ( -13.50000254341547468, 185.9068427740967593, 102.5779769526163960 ) ) ; +#26323 = DIRECTION ( 'NONE', ( -0.0005884949961257158286, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#26324 = LINE ( 'NONE', #17492, #24954 ) ; +#26325 = ORIENTED_EDGE ( 'NONE', *, *, #9560, .T. ) ; +#26326 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#26327 = CARTESIAN_POINT ( 'NONE', ( 22.89468650464132793, 120.6933875991700944, 183.2782711976167889 ) ) ; +#26328 = CARTESIAN_POINT ( 'NONE', ( 25.63631768314000325, 192.1800716756999918, 104.2809280454000174 ) ) ; +#26329 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #15338, #12462 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26330 = CARTESIAN_POINT ( 'NONE', ( -20.49933784730817266, 194.4843916009270401, 105.7062759226449771 ) ) ; +#26331 = CIRCLE ( 'NONE', #39379, 6.499999999986447285 ) ; +#26332 = CARTESIAN_POINT ( 'NONE', ( -15.66646951627509488, 138.1199964649966603, 91.89200017561881850 ) ) ; +#26333 = ORIENTED_EDGE ( 'NONE', *, *, #10517, .F. ) ; +#26334 = PLANE ( 'NONE', #20326 ) ; +#26335 = CIRCLE ( 'NONE', #8717, 47.50000000000962075 ) ; +#26336 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16022, #28513, #12975, #25457 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26337 = CARTESIAN_POINT ( 'NONE', ( -30.11526611033000123, 185.0088482550999913, 105.2061072122999974 ) ) ; +#26338 = AXIS2_PLACEMENT_3D ( 'NONE', #24092, #12414, #33471 ) ; +#26339 = CARTESIAN_POINT ( 'NONE', ( -45.34134577087812801, 120.7154725862561406, 105.4905015689576402 ) ) ; +#26340 = CARTESIAN_POINT ( 'NONE', ( -20.49852830327300879, 119.8277974066376999, 89.89548907266683386 ) ) ; +#26341 = CARTESIAN_POINT ( 'NONE', ( 28.46511207851075653, 181.6173849797036439, 104.1311689223658448 ) ) ; +#26342 = DIRECTION ( 'NONE', ( -0.0002393071182782278061, -0.2252352986010052738, 0.9743043687658489160 ) ) ; +#26343 = LINE ( 'NONE', #16709, #30551 ) ; +#26344 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.261220487827980362E-14, 0.9999998176071844824 ) ) ; +#26345 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4706, #5107, #10662, #39254 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26346 = CARTESIAN_POINT ( 'NONE', ( 35.93887322615999835, 192.6195093084999996, 106.4794051886999995 ) ) ; +#26347 = ORIENTED_EDGE ( 'NONE', *, *, #21799, .T. ) ; +#26348 = CARTESIAN_POINT ( 'NONE', ( -2.849818446583026521, 209.7134542144498539, 76.06022768558052860 ) ) ; +#26349 = FACE_OUTER_BOUND ( 'NONE', #36848, .T. ) ; +#26350 = ADVANCED_FACE ( 'NONE', ( #16612 ), #482, .T. ) ; +#26351 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; +#26352 = VERTEX_POINT ( 'NONE', #34805 ) ; +#26353 = CARTESIAN_POINT ( 'NONE', ( 19.98273361849968310, 207.8686263722649983, 77.26501546795368824 ) ) ; +#26354 = VERTEX_POINT ( 'NONE', #13571 ) ; +#26355 = EDGE_CURVE ( 'NONE', #18851, #30696, #13368, .T. ) ; +#26356 = CARTESIAN_POINT ( 'NONE', ( 20.00000522920557700, 138.5176112521621690, 91.62015419223651236 ) ) ; +#26357 = CARTESIAN_POINT ( 'NONE', ( 24.83917560697537397, 115.7109693989694819, 87.25278205238181783 ) ) ; +#26358 = ORIENTED_EDGE ( 'NONE', *, *, #6264, .T. ) ; +#26359 = CARTESIAN_POINT ( 'NONE', ( 36.48374016940825015, 191.5972485995277452, 106.3709165627377473 ) ) ; +#26360 = VECTOR ( 'NONE', #8794, 999.9999999999998863 ) ; +#26361 = EDGE_CURVE ( 'NONE', #31227, #12564, #23028, .T. ) ; +#26362 = DIRECTION ( 'NONE', ( -0.0005884949961230354640, 0.2249510543439063315, -0.9743698870671264611 ) ) ; +#26363 = CARTESIAN_POINT ( 'NONE', ( 36.06296285845981942, 194.2771771405940058, 102.8764942496974442 ) ) ; +#26364 = DIRECTION ( 'NONE', ( -3.854941057724316235E-15, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#26365 = CARTESIAN_POINT ( 'NONE', ( 22.64345175836523794, 177.7183216167047988, 100.6687544531553300 ) ) ; +#26366 = CARTESIAN_POINT ( 'NONE', ( -13.55691060191283093, 147.9587722923776312, 94.33323613806213359 ) ) ; +#26367 = EDGE_CURVE ( 'NONE', #13796, #21433, #10223, .T. ) ; +#26368 = ORIENTED_EDGE ( 'NONE', *, *, #6334, .F. ) ; +#26369 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; +#26370 = CARTESIAN_POINT ( 'NONE', ( 30.06906075427019331, 177.1956492900629598, 101.0567532827656123 ) ) ; +#26371 = CARTESIAN_POINT ( 'NONE', ( 45.12876369734329529, 130.2598771944438170, 92.77743955731769177 ) ) ; +#26372 = CARTESIAN_POINT ( 'NONE', ( 16.34205233782973110, 152.1117390883541418, 181.2100924961355020 ) ) ; +#26373 = EDGE_LOOP ( 'NONE', ( #18484, #28012, #11641, #31722 ) ) ; +#26374 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 3.780719906273090593E-12, 291.5295797804326980 ) ) ; +#26375 = CARTESIAN_POINT ( 'NONE', ( -39.59757934998344098, 114.7797396141357638, 151.0610028020948334 ) ) ; +#26376 = CARTESIAN_POINT ( 'NONE', ( 3.230168859074256993, 129.2213076314029365, 89.48405965364526082 ) ) ; +#26377 = CARTESIAN_POINT ( 'NONE', ( 22.79650250807785028, 156.9263452827057392, 182.1842925253231726 ) ) ; +#26378 = FACE_OUTER_BOUND ( 'NONE', #36566, .T. ) ; +#26379 = CARTESIAN_POINT ( 'NONE', ( 25.42423066774999896, 190.7516350470000077, 106.0994300395999943 ) ) ; +#26380 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; +#26381 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#26382 = CARTESIAN_POINT ( 'NONE', ( -37.91710613048000056, 190.5102213490000054, 106.6127102881000042 ) ) ; +#26383 = CIRCLE ( 'NONE', #4143, 2.500000015113077012 ) ; +#26384 = AXIS2_PLACEMENT_3D ( 'NONE', #22369, #7003, #26386 ) ; +#26385 = ORIENTED_EDGE ( 'NONE', *, *, #34145, .T. ) ; +#26386 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#26387 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; +#26388 = CARTESIAN_POINT ( 'NONE', ( 22.99030223357639002, 211.0902260770999987, 73.03848514436592154 ) ) ; +#26389 = DIRECTION ( 'NONE', ( -0.7933533411653074241, -0.5931840316265225566, -0.1368326740407711517 ) ) ; +#26390 = FACE_OUTER_BOUND ( 'NONE', #38396, .T. ) ; +#26391 = ORIENTED_EDGE ( 'NONE', *, *, #7492, .T. ) ; +#26392 = ORIENTED_EDGE ( 'NONE', *, *, #854, .T. ) ; +#26393 = ORIENTED_EDGE ( 'NONE', *, *, #21442, .F. ) ; +#26394 = CARTESIAN_POINT ( 'NONE', ( -13.50149634685153188, 124.6162873816535352, 88.77554189603409895 ) ) ; +#26395 = ADVANCED_FACE ( 'NONE', ( #10917 ), #35812, .F. ) ; +#26396 = EDGE_CURVE ( 'NONE', #6620, #17466, #17213, .T. ) ; +#26397 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250611660, 132.8554482850408931, 90.84904174544594468 ) ) ; +#26398 = ADVANCED_FACE ( 'NONE', ( #29717 ), #1701, .F. ) ; +#26400 = EDGE_CURVE ( 'NONE', #1388, #5869, #36292, .T. ) ; +#26399 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #511, #24693, #25092, #9537, #3378, #22017 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26401 = ORIENTED_EDGE ( 'NONE', *, *, #12280, .T. ) ; +#26402 = CARTESIAN_POINT ( 'NONE', ( 14.17036433007075757, 182.7613733346053380, 102.3513045738081502 ) ) ; +#26403 = DIRECTION ( 'NONE', ( -0.0005884949961239352434, 0.2249510543439079413, -0.9743698870671259060 ) ) ; +#26404 = CARTESIAN_POINT ( 'NONE', ( -38.16683231563000334, 119.1115699835000044, 87.44296902379001324 ) ) ; +#26405 = CARTESIAN_POINT ( 'NONE', ( -36.58517893228000162, 117.6712416552000207, 87.16057593239999335 ) ) ; +#26406 = ORIENTED_EDGE ( 'NONE', *, *, #18771, .F. ) ; +#26407 = EDGE_CURVE ( 'NONE', #37286, #38119, #6169, .T. ) ; +#26408 = CARTESIAN_POINT ( 'NONE', ( 24.53469179845202675, 109.6131156702000027, 89.75296640898022815 ) ) ; +#26409 = ORIENTED_EDGE ( 'NONE', *, *, #37564, .T. ) ; +#26410 = CARTESIAN_POINT ( 'NONE', ( 16.29171451679812677, 147.1883472421681347, 179.8230240704290566 ) ) ; +#26411 = DIRECTION ( 'NONE', ( 0.0005734119072322988505, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#26412 = CARTESIAN_POINT ( 'NONE', ( 5.670716164162284301, 130.2572556929138443, 92.67712889164683077 ) ) ; +#26413 = LINE ( 'NONE', #35563, #10436 ) ; +#26414 = CARTESIAN_POINT ( 'NONE', ( -12.63763155967610174, 181.4131765941279184, 104.2789412034183130 ) ) ; +#26415 = AXIS2_PLACEMENT_3D ( 'NONE', #11705, #28248, #24185 ) ; +#26416 = EDGE_CURVE ( 'NONE', #13145, #20943, #561, .T. ) ; +#26417 = ORIENTED_EDGE ( 'NONE', *, *, #34101, .F. ) ; +#26418 = CARTESIAN_POINT ( 'NONE', ( -2.206982623110000041, 189.3059093070999950, 103.3589691778000059 ) ) ; +#26419 = CARTESIAN_POINT ( 'NONE', ( 13.50176625667807428, 160.0671410552039333, 99.67807866355113333 ) ) ; +#26420 = AXIS2_PLACEMENT_3D ( 'NONE', #26987, #11642, #17945 ) ; +#26421 = CARTESIAN_POINT ( 'NONE', ( 28.46551015877975033, 129.9757720508976888, 92.20876074269682476 ) ) ; +#26422 = CARTESIAN_POINT ( 'NONE', ( 2.428544953242000037, 191.0028154567999934, 106.1725792724000144 ) ) ; +#26423 = AXIS2_PLACEMENT_3D ( 'NONE', #31676, #19968, #566 ) ; +#26424 = ORIENTED_EDGE ( 'NONE', *, *, #256, .F. ) ; +#26425 = CARTESIAN_POINT ( 'NONE', ( 22.78080448403245839, 154.4094593426142978, 95.28739704982865533 ) ) ; +#26426 = CARTESIAN_POINT ( 'NONE', ( 38.56885418974432866, 118.4610218664272452, 89.66265752007532797 ) ) ; +#26427 = ORIENTED_EDGE ( 'NONE', *, *, #38572, .F. ) ; +#26428 = ORIENTED_EDGE ( 'NONE', *, *, #32131, .F. ) ; +#26429 = ORIENTED_EDGE ( 'NONE', *, *, #12007, .T. ) ; +#26430 = ORIENTED_EDGE ( 'NONE', *, *, #24145, .T. ) ; +#26431 = CARTESIAN_POINT ( 'NONE', ( -28.25392304131139909, 186.4523300311939806, 105.2782402284340009 ) ) ; +#26432 = CARTESIAN_POINT ( 'NONE', ( 37.96459664868978479, 191.1136021723184797, 105.6336056618651327 ) ) ; +#26433 = ORIENTED_EDGE ( 'NONE', *, *, #27154, .F. ) ; +#26434 = CARTESIAN_POINT ( 'NONE', ( -15.56603823848756463, 127.7826210529339761, 174.7414047399441586 ) ) ; +#26435 = ORIENTED_EDGE ( 'NONE', *, *, #20944, .T. ) ; +#26436 = CARTESIAN_POINT ( 'NONE', ( 26.00477353184719931, 120.1786686628320098, 90.46666206596498228 ) ) ; +#26437 = CARTESIAN_POINT ( 'NONE', ( 25.50773672857076235, 191.9759150222000130, 101.9060413065578530 ) ) ; +#26439 = CARTESIAN_POINT ( 'NONE', ( -13.49827548779789765, 187.9541051343499873, 103.3857169024480243 ) ) ; +#26438 = CARTESIAN_POINT ( 'NONE', ( -26.71540924721000110, 176.9255844822999961, 103.3378849579000018 ) ) ; +#26440 = SECURITY_CLASSIFICATION ( '', '', #2841 ) ; +#26441 = AXIS2_PLACEMENT_3D ( 'NONE', #28935, #28540, #35429 ) ; +#26442 = VERTEX_POINT ( 'NONE', #18025 ) ; +#26443 = AXIS2_PLACEMENT_3D ( 'NONE', #13490, #10022, #35329 ) ; +#26444 = ORIENTED_EDGE ( 'NONE', *, *, #36499, .F. ) ; +#26445 = CARTESIAN_POINT ( 'NONE', ( -36.12226215597334544, 191.9555097253573877, 104.4198144025714470 ) ) ; +#26446 = EDGE_CURVE ( 'NONE', #12675, #21782, #36114, .T. ) ; +#26447 = AXIS2_PLACEMENT_3D ( 'NONE', #14620, #19913, #23211 ) ; +#26448 = EDGE_CURVE ( 'NONE', #25158, #5478, #12241, .T. ) ; +#26449 = ORIENTED_EDGE ( 'NONE', *, *, #10086, .F. ) ; +#26450 = CARTESIAN_POINT ( 'NONE', ( -36.02057461644638181, 116.0743563047277860, 87.28953981649921445 ) ) ; +#26451 = CARTESIAN_POINT ( 'NONE', ( -45.66754398715169572, 124.0145021363698987, 91.55527929137910803 ) ) ; +#26452 = LINE ( 'NONE', #38901, #11100 ) ; +#26453 = VERTEX_POINT ( 'NONE', #12945 ) ; +#26454 = ORIENTED_EDGE ( 'NONE', *, *, #2929, .F. ) ; +#26455 = ORIENTED_EDGE ( 'NONE', *, *, #23807, .F. ) ; +#26456 = DIRECTION ( 'NONE', ( -0.0005884949961207905150, 0.2249510543439056653, -0.9743698870671265722 ) ) ; +#26457 = FACE_OUTER_BOUND ( 'NONE', #13454, .T. ) ; +#26458 = ORIENTED_EDGE ( 'NONE', *, *, #13005, .T. ) ; +#26459 = CARTESIAN_POINT ( 'NONE', ( -35.43417201705999986, 192.6082312290999994, 106.9072920318999991 ) ) ; +#26460 = VERTEX_POINT ( 'NONE', #34580 ) ; +#26461 = DIRECTION ( 'NONE', ( -0.0006039748319417796414, 6.167438909946999677E-15, -0.9999998176071844824 ) ) ; +#26462 = CARTESIAN_POINT ( 'NONE', ( 2.730823538927626970, 190.9423656580330544, 106.4698396510861329 ) ) ; +#26463 = EDGE_LOOP ( 'NONE', ( #36701, #27106, #23607, #32316 ) ) ; +#26464 = CARTESIAN_POINT ( 'NONE', ( -30.07299557348812868, 135.2291654960487222, 91.32134674634657756 ) ) ; +#26465 = CIRCLE ( 'NONE', #8851, 2.000000000000000000 ) ; +#26466 = ADVANCED_FACE ( 'NONE', ( #16391 ), #9672, .F. ) ; +#26467 = CARTESIAN_POINT ( 'NONE', ( 15.99998384348811875, 126.8035267017516787, 88.91816380576780432 ) ) ; +#26468 = CIRCLE ( 'NONE', #36258, 5.499999999738594880 ) ; +#26469 = DIRECTION ( 'NONE', ( -4.163336342338438714E-15, 0.9743700557921581851, 0.2249510932971575949 ) ) ; +#26470 = CARTESIAN_POINT ( 'NONE', ( 21.21575639516963463, 182.9122697023876754, 104.4344951008579443 ) ) ; +#26471 = ORIENTED_EDGE ( 'NONE', *, *, #1410, .F. ) ; +#26472 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7450, #17660, #2149, #20740 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26473 = CIRCLE ( 'NONE', #6872, 2.500000000128479449 ) ; +#26474 = CARTESIAN_POINT ( 'NONE', ( -39.56097452997838104, 120.1276920425286363, 87.66704820878976534 ) ) ; +#26475 = LINE ( 'NONE', #1509, #18587 ) ; +#26476 = CARTESIAN_POINT ( 'NONE', ( 22.33741204818806381, 213.5250432875125455, 75.54510607509934061 ) ) ; +#26477 = VERTEX_POINT ( 'NONE', #16582 ) ; +#26478 = CARTESIAN_POINT ( 'NONE', ( -25.02259563561056410, 181.9805275934310487, 102.1947033449129236 ) ) ; +#26480 = CARTESIAN_POINT ( 'NONE', ( -38.33390653700000428, 118.5050223875999933, 89.85075258204000193 ) ) ; +#26479 = FACE_OUTER_BOUND ( 'NONE', #31073, .T. ) ; +#26481 = EDGE_LOOP ( 'NONE', ( #7050, #8602, #17048, #37491 ) ) ; +#26482 = ORIENTED_EDGE ( 'NONE', *, *, #20814, .F. ) ; +#26483 = DIRECTION ( 'NONE', ( 0.0005884949961231158034, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#26484 = LINE ( 'NONE', #29354, #3928 ) ; +#26485 = DIRECTION ( 'NONE', ( 0.0005884949961230071663, -0.2249510543439071641, 0.9743698870671261281 ) ) ; +#26486 = VERTEX_POINT ( 'NONE', #4108 ) ; +#26487 = EDGE_CURVE ( 'NONE', #12603, #11146, #21525, .T. ) ; +#26488 = VECTOR ( 'NONE', #24994, 999.9999999999998863 ) ; +#26489 = ORIENTED_EDGE ( 'NONE', *, *, #35308, .T. ) ; +#26490 = CARTESIAN_POINT ( 'NONE', ( -37.31472541183903502, 185.8277164819467373, 106.5063005560201077 ) ) ; +#26491 = VERTEX_POINT ( 'NONE', #3317 ) ; +#26492 = CONICAL_SURFACE ( 'NONE', #36946, 9.999999999987895904, 0.7853981633973070586 ) ; +#26493 = VERTEX_POINT ( 'NONE', #10286 ) ; +#26494 = CARTESIAN_POINT ( 'NONE', ( 20.00000279695219874, 118.8155797008581374, 87.25566994753728522 ) ) ; +#26495 = CARTESIAN_POINT ( 'NONE', ( -2.438441564891038915, 191.9759150222000130, 101.9229200978912075 ) ) ; +#26496 = CIRCLE ( 'NONE', #8880, 2.000000000091077368 ) ; +#26497 = CARTESIAN_POINT ( 'NONE', ( 19.33143288873693777, 125.0839867570798276, 178.0727432645037140 ) ) ; +#26498 = CIRCLE ( 'NONE', #23873, 2.000000000012064127 ) ; +#26499 = AXIS2_PLACEMENT_3D ( 'NONE', #3358, #9720, #18486 ) ; +#26500 = EDGE_CURVE ( 'NONE', #2594, #23127, #12739, .T. ) ; +#26501 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19385, #22680, #38397, #31879 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26502 = ORIENTED_EDGE ( 'NONE', *, *, #31058, .F. ) ; +#26503 = CARTESIAN_POINT ( 'NONE', ( 14.03369338234965547, 177.4093650441238594, 100.6026262734140886 ) ) ; +#26504 = CIRCLE ( 'NONE', #8886, 17.00000000000405009 ) ; +#26505 = CARTESIAN_POINT ( 'NONE', ( 15.75161875086000052, 126.6561517763000211, 91.70662082261000592 ) ) ; +#26506 = CARTESIAN_POINT ( 'NONE', ( 36.68571676468000220, 115.8645254848999997, 87.83987621432000026 ) ) ; +#26507 = CARTESIAN_POINT ( 'NONE', ( 37.41381076609000189, 191.3544000862000019, 104.1956138584999962 ) ) ; +#26508 = CARTESIAN_POINT ( 'NONE', ( -25.83450491736957488, 120.6757604736500156, 87.67667375659091533 ) ) ; +#26509 = LINE ( 'NONE', #17067, #8232 ) ; +#26510 = CARTESIAN_POINT ( 'NONE', ( -34.95668960138998926, 225.9002260769401857, 73.07961704690882243 ) ) ; +#26511 = ORIENTED_EDGE ( 'NONE', *, *, #29313, .F. ) ; +#26512 = CARTESIAN_POINT ( 'NONE', ( -20.51848083070238360, 208.9757843690321124, 75.68082748707900009 ) ) ; +#26513 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32198, #17020, #18038, #33790 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.003332437842000458231 ), + .UNSPECIFIED. ) ; +#26514 = CARTESIAN_POINT ( 'NONE', ( -28.94720267997999841, 110.6131156702000027, 88.78526795067999444 ) ) ; +#26515 = CARTESIAN_POINT ( 'NONE', ( 20.49952841817542293, 195.9524980432203449, 104.0580825165111918 ) ) ; +#26516 = CARTESIAN_POINT ( 'NONE', ( -48.18209110666130357, 87.27946979429619034, 302.5876467172398065 ) ) ; +#26517 = VERTEX_POINT ( 'NONE', #31757 ) ; +#26518 = CARTESIAN_POINT ( 'NONE', ( -13.46733474056920699, 153.4793893552323709, 97.83137644993696824 ) ) ; +#26519 = EDGE_CURVE ( 'NONE', #18457, #38693, #19457, .T. ) ; +#26520 = CARTESIAN_POINT ( 'NONE', ( 1.765977884755008054, 189.4024649853499795, 103.7998658718349674 ) ) ; +#26521 = CARTESIAN_POINT ( 'NONE', ( -2.851221542150457200, 209.7096659646922774, 76.06022685436926167 ) ) ; +#26522 = VECTOR ( 'NONE', #9961, 1000.000000000000114 ) ; +#26523 = ORIENTED_EDGE ( 'NONE', *, *, #12830, .F. ) ; +#26524 = DIRECTION ( 'NONE', ( -0.0005884949961226875435, 0.2249510543439053323, -0.9743698870671265722 ) ) ; +#26525 = ORIENTED_EDGE ( 'NONE', *, *, #15596, .F. ) ; +#26526 = CARTESIAN_POINT ( 'NONE', ( -25.87094890256999946, 191.7877093630999923, 104.0495366172000047 ) ) ; +#26527 = CIRCLE ( 'NONE', #8902, 2.499999842035334652 ) ; +#26528 = CARTESIAN_POINT ( 'NONE', ( 37.28139794753688108, 124.9423866440358069, 93.60865750304402866 ) ) ; +#26529 = CARTESIAN_POINT ( 'NONE', ( -25.01941299468369806, 212.6267528717874598, 73.57339763463777160 ) ) ; +#26530 = CARTESIAN_POINT ( 'NONE', ( -19.99670393405153490, 118.1131156702000169, 90.28287776640389950 ) ) ; +#26531 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12242, #11846, #36982, #6286 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0001747927338281522725, 0.0002406710670090404878 ), + .UNSPECIFIED. ) ; +#26532 = CARTESIAN_POINT ( 'NONE', ( 16.41758150636829683, 152.5211099512976887, 181.7218298998406283 ) ) ; +#26533 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#26534 = ORIENTED_EDGE ( 'NONE', *, *, #2587, .F. ) ; +#26535 = AXIS2_PLACEMENT_3D ( 'NONE', #8402, #17971, #14933 ) ; +#26536 = EDGE_CURVE ( 'NONE', #8699, #1973, #852, .T. ) ; +#26537 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#26538 = EDGE_CURVE ( 'NONE', #21098, #33439, #24622, .T. ) ; +#26539 = CARTESIAN_POINT ( 'NONE', ( -15.49852919459145184, 184.4001630190128367, 104.8001769099776652 ) ) ; +#26540 = CARTESIAN_POINT ( 'NONE', ( 44.84982446188305261, 177.0778658525795493, 147.7896410935606184 ) ) ; +#26541 = CARTESIAN_POINT ( 'NONE', ( 36.84464589683999947, 190.4136331379999945, 106.8139093804000055 ) ) ; +#26542 = CARTESIAN_POINT ( 'NONE', ( 32.40796694493486285, 176.2190259035834856, 100.3167171782768321 ) ) ; +#26543 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700562689210365, 0.2249510912320714373 ) ) ; +#26544 = EDGE_CURVE ( 'NONE', #9147, #5625, #37148, .T. ) ; +#26545 = ADVANCED_FACE ( 'NONE', ( #10077 ), #34970, .F. ) ; +#26546 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251395983, 181.3676414799208203, 104.1015739576456411 ) ) ; +#26547 = EDGE_LOOP ( 'NONE', ( #1384, #26561, #32013, #2733 ) ) ; +#26548 = EDGE_CURVE ( 'NONE', #13536, #14788, #16193, .T. ) ; +#26549 = ORIENTED_EDGE ( 'NONE', *, *, #35945, .F. ) ; +#26550 = CARTESIAN_POINT ( 'NONE', ( 35.83878747195931425, 167.1160280305729771, 182.3999273569982336 ) ) ; +#26551 = DIRECTION ( 'NONE', ( 0.0005884949961222158072, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#26552 = EDGE_CURVE ( 'NONE', #15606, #72, #249, .T. ) ; +#26553 = CARTESIAN_POINT ( 'NONE', ( -32.44499774467648479, 136.5818299423348492, 91.20491734193556965 ) ) ; +#26554 = CARTESIAN_POINT ( 'NONE', ( 8.048542122852918368, 150.7638762473669658, 97.53355711752999468 ) ) ; +#26555 = EDGE_LOOP ( 'NONE', ( #23819, #14427, #32888, #36436 ) ) ; +#26556 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#26557 = AXIS2_PLACEMENT_3D ( 'NONE', #8904, #34369, #6365 ) ; +#26558 = ORIENTED_EDGE ( 'NONE', *, *, #3431, .T. ) ; +#26559 = VECTOR ( 'NONE', #11650, 999.9999999999998863 ) ; +#26560 = DIRECTION ( 'NONE', ( -0.0005884949961254009763, 0.2249510543439060262, -0.9743698870671263501 ) ) ; +#26561 = ORIENTED_EDGE ( 'NONE', *, *, #11085, .F. ) ; +#26562 = CARTESIAN_POINT ( 'NONE', ( 36.65077066423717866, 191.4293016981708035, 106.3500278736450753 ) ) ; +#26563 = AXIS2_PLACEMENT_3D ( 'NONE', #15786, #15991, #28479 ) ; +#26564 = FACE_OUTER_BOUND ( 'NONE', #26688, .T. ) ; +#26565 = FACE_OUTER_BOUND ( 'NONE', #28703, .T. ) ; +#26566 = AXIS2_PLACEMENT_3D ( 'NONE', #10978, #32058, #32448 ) ; +#26567 = FACE_OUTER_BOUND ( 'NONE', #15084, .T. ) ; +#26568 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #40178, #39776, #33845, #37126 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26569 = CARTESIAN_POINT ( 'NONE', ( -5.669748535203316564, 124.7404542330243800, 88.96810042129679630 ) ) ; +#26570 = ORIENTED_EDGE ( 'NONE', *, *, #25037, .F. ) ; +#26571 = CARTESIAN_POINT ( 'NONE', ( -0.03375341898833555260, -31.76863880746333280, 137.4221703796379188 ) ) ; +#26572 = ADVANCED_FACE ( 'NONE', ( #37473 ), #9471, .T. ) ; +#26573 = CARTESIAN_POINT ( 'NONE', ( 12.63088349563799184, 181.6904995670203391, 101.5918601121804556 ) ) ; +#26574 = CARTESIAN_POINT ( 'NONE', ( 22.49999922077095604, 184.9675253677921773, 102.3424519572064355 ) ) ; +#26575 = ORIENTED_EDGE ( 'NONE', *, *, #10280, .F. ) ; +#26576 = CARTESIAN_POINT ( 'NONE', ( -45.30267887931935178, 123.9248666885585806, 93.18489076007304561 ) ) ; +#26577 = ORIENTED_EDGE ( 'NONE', *, *, #7272, .T. ) ; +#26578 = CARTESIAN_POINT ( 'NONE', ( 19.99994303953296182, 119.3449851748513737, 87.25570516597396420 ) ) ; +#26579 = CARTESIAN_POINT ( 'NONE', ( -38.95517892727801268, 209.7096538831000032, 75.58203249027424420 ) ) ; +#26580 = DIRECTION ( 'NONE', ( -3.469446951887147924E-15, 0.9743700557921581851, 0.2249510932971580390 ) ) ; +#26581 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -3.869599770875634371E-16, -0.0006039748319386379488 ) ) ; +#26582 = CARTESIAN_POINT ( 'NONE', ( 18.08289561727003658, 152.6324032069051384, 184.7487331658680887 ) ) ; +#26583 = CIRCLE ( 'NONE', #27911, 1.650000000000002798 ) ; +#26584 = CARTESIAN_POINT ( 'NONE', ( -13.01298190969827040, 181.6879564457013885, 101.6067526251711826 ) ) ; +#26585 = CIRCLE ( 'NONE', #10275, 6.500000000082327034 ) ; +#26586 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#26587 = VECTOR ( 'NONE', #17241, 1000.000000000000114 ) ; +#26588 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 1.540743955509788340E-33, 0.0006039748319384538513 ) ) ; +#26589 = EDGE_CURVE ( 'NONE', #22348, #38150, #10249, .T. ) ; +#26590 = FACE_OUTER_BOUND ( 'NONE', #6378, .T. ) ; +#26591 = CARTESIAN_POINT ( 'NONE', ( 3.326633047918813535, 183.2667907456296632, 101.9613865925673508 ) ) ; +#26592 = ORIENTED_EDGE ( 'NONE', *, *, #1225, .F. ) ; +#26593 = AXIS2_PLACEMENT_3D ( 'NONE', #25251, #6023, #9704 ) ; +#26594 = EDGE_CURVE ( 'NONE', #29915, #38998, #8835, .T. ) ; +#26595 = DIRECTION ( 'NONE', ( -0.7072262180194089920, -0.6509452856072081017, -0.2758646619118033660 ) ) ; +#26596 = DIRECTION ( 'NONE', ( 0.9999998268368057719, 0.0001323825923583700991, -0.0005734119003960201286 ) ) ; +#26597 = CARTESIAN_POINT ( 'NONE', ( 19.56153773728087941, 148.7179920449207202, 184.4707757878970256 ) ) ; +#26598 = CARTESIAN_POINT ( 'NONE', ( 26.01072490218321676, 191.2306769852524724, 106.8537119624654110 ) ) ; +#26599 = EDGE_CURVE ( 'NONE', #22006, #7652, #1060, .T. ) ; +#26601 = ORIENTED_EDGE ( 'NONE', *, *, #19003, .T. ) ; +#26600 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; +#26602 = ORIENTED_EDGE ( 'NONE', *, *, #21951, .F. ) ; +#26603 = EDGE_LOOP ( 'NONE', ( #37925, #930, #6890, #24142 ) ) ; +#26604 = ADVANCED_FACE ( 'NONE', ( #34779 ), #3682, .F. ) ; +#26605 = EDGE_LOOP ( 'NONE', ( #17054, #34962, #15415, #38270, #21269, #2672, #4291, #31083, #18925, #20477, #19655 ) ) ; +#26606 = FACE_OUTER_BOUND ( 'NONE', #40075, .T. ) ; +#26607 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; +#26608 = ORIENTED_EDGE ( 'NONE', *, *, #28882, .T. ) ; +#26609 = ORIENTED_EDGE ( 'NONE', *, *, #11627, .F. ) ; +#26610 = FACE_BOUND ( 'NONE', #29176, .T. ) ; +#26611 = CARTESIAN_POINT ( 'NONE', ( -30.07831637853678686, 134.9151858147922667, 90.81876078434068233 ) ) ; +#26612 = CARTESIAN_POINT ( 'NONE', ( -37.83922575564000113, 118.0391086144000070, 87.84578005413000312 ) ) ; +#26613 = ORIENTED_EDGE ( 'NONE', *, *, #20670, .T. ) ; +#26614 = CARTESIAN_POINT ( 'NONE', ( 3.334680587944353736, 185.2725092996106184, 105.3322985861469760 ) ) ; +#26615 = AXIS2_PLACEMENT_3D ( 'NONE', #6178, #5784, #40317 ) ; +#26616 = ORIENTED_EDGE ( 'NONE', *, *, #5291, .F. ) ; +#26617 = CARTESIAN_POINT ( 'NONE', ( 4.133310199970877008, 187.8594049812016067, 103.0211881142743238 ) ) ; +#26618 = CARTESIAN_POINT ( 'NONE', ( 35.56910103317023442, 113.0588457072281585, 90.24630199347080861 ) ) ; +#26619 = VECTOR ( 'NONE', #39903, 1000.000000000000000 ) ; +#26620 = DIRECTION ( 'NONE', ( 4.047688110583664430E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; +#26621 = VERTEX_POINT ( 'NONE', #26426 ) ; +#26622 = FACE_OUTER_BOUND ( 'NONE', #3061, .T. ) ; +#26623 = CARTESIAN_POINT ( 'NONE', ( 0.6372482775786000309, 189.0047147329999859, 103.6952764219000045 ) ) ; +#26624 = CARTESIAN_POINT ( 'NONE', ( -40.30153468720526178, 187.7974083947837585, 108.1652340796715492 ) ) ; +#26625 = CARTESIAN_POINT ( 'NONE', ( -37.68439733255148383, 188.7463803737940395, 106.3301322885044016 ) ) ; +#26626 = ORIENTED_EDGE ( 'NONE', *, *, #20294, .F. ) ; +#26627 = ORIENTED_EDGE ( 'NONE', *, *, #583, .T. ) ; +#26628 = CARTESIAN_POINT ( 'NONE', ( 36.09418572946387371, 97.50014116332937419, 154.5721339787388047 ) ) ; +#26629 = CARTESIAN_POINT ( 'NONE', ( -23.01879311717446086, 214.0903458147471383, 76.07243274013872281 ) ) ; +#26630 = ORIENTED_EDGE ( 'NONE', *, *, #39490, .F. ) ; +#26631 = ORIENTED_EDGE ( 'NONE', *, *, #17625, .T. ) ; +#26632 = EDGE_CURVE ( 'NONE', #3089, #3943, #27897, .T. ) ; +#26633 = EDGE_CURVE ( 'NONE', #15772, #38661, #6285, .T. ) ; +#26634 = ORIENTED_EDGE ( 'NONE', *, *, #34996, .F. ) ; +#26635 = EDGE_CURVE ( 'NONE', #11146, #22, #35155, .T. ) ; +#26636 = VERTEX_POINT ( 'NONE', #7387 ) ; +#26637 = EDGE_CURVE ( 'NONE', #31429, #37342, #7599, .T. ) ; +#26638 = DIRECTION ( 'NONE', ( -0.9999998268368966992, -0.0001323825576369143267, 0.0005734117500054078387 ) ) ; +#26639 = CARTESIAN_POINT ( 'NONE', ( -8.472443777046803959, 150.6153475619768187, 96.99609267642283328 ) ) ; +#26640 = VERTEX_POINT ( 'NONE', #20058 ) ; +#26641 = LINE ( 'NONE', #35799, #32361 ) ; +#26642 = ORIENTED_EDGE ( 'NONE', *, *, #3626, .T. ) ; +#26643 = EDGE_CURVE ( 'NONE', #10604, #2295, #31282, .T. ) ; +#26644 = CARTESIAN_POINT ( 'NONE', ( 28.12620697607000508, 124.5905266982999962, 91.30778919159000395 ) ) ; +#26645 = AXIS2_PLACEMENT_3D ( 'NONE', #34720, #31699, #13484 ) ; +#26646 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; +#26647 = AXIS2_PLACEMENT_3D ( 'NONE', #39089, #33153, #23983 ) ; +#26649 = PLANE ( 'NONE', #22061 ) ; +#26648 = FACE_OUTER_BOUND ( 'NONE', #21142, .T. ) ; +#26650 = ORIENTED_EDGE ( 'NONE', *, *, #4355, .F. ) ; +#26651 = EDGE_CURVE ( 'NONE', #9209, #39608, #30479, .T. ) ; +#26652 = ORIENTED_EDGE ( 'NONE', *, *, #16204, .T. ) ; +#26653 = ORIENTED_EDGE ( 'NONE', *, *, #14903, .F. ) ; +#26654 = LINE ( 'NONE', #20081, #16518 ) ; +#26655 = EDGE_CURVE ( 'NONE', #31583, #6212, #22953, .T. ) ; +#26656 = CARTESIAN_POINT ( 'NONE', ( 36.04689830202195822, 205.5673820495391055, 76.27844315541416620 ) ) ; +#26657 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#26658 = ORIENTED_EDGE ( 'NONE', *, *, #19855, .F. ) ; +#26659 = ORIENTED_EDGE ( 'NONE', *, *, #29507, .T. ) ; +#26660 = ORIENTED_EDGE ( 'NONE', *, *, #28431, .F. ) ; +#26661 = CARTESIAN_POINT ( 'NONE', ( 20.14702854017319922, 209.7098729452407326, 73.21335924537376627 ) ) ; +#26662 = CARTESIAN_POINT ( 'NONE', ( -37.21052966546948682, 132.5657015190818697, 337.0064682716691777 ) ) ; +#26663 = CARTESIAN_POINT ( 'NONE', ( 26.07151325143000165, 121.8396282002999982, 87.76599268405001908 ) ) ; +#26664 = ORIENTED_EDGE ( 'NONE', *, *, #13399, .F. ) ; +#26665 = CARTESIAN_POINT ( 'NONE', ( -35.47176629106999712, 192.2367679710000061, 106.9459547420999996 ) ) ; +#26666 = VERTEX_POINT ( 'NONE', #32351 ) ; +#26667 = LINE ( 'NONE', #1294, #16363 ) ; +#26668 = ORIENTED_EDGE ( 'NONE', *, *, #4249, .T. ) ; +#26669 = DIRECTION ( 'NONE', ( 0.0006039748319395906373, 1.291365685536979971E-14, 0.9999998176071844824 ) ) ; +#26670 = CONICAL_SURFACE ( 'NONE', #22730, 10.00000000000456346, 0.7853981633973012855 ) ; +#26671 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178570922545E-05, 0.0002331579774915894113 ) ) ; +#26672 = FACE_OUTER_BOUND ( 'NONE', #34818, .T. ) ; +#26673 = CYLINDRICAL_SURFACE ( 'NONE', #26725, 2.000000000000011546 ) ; +#26674 = EDGE_CURVE ( 'NONE', #35038, #34336, #33736, .T. ) ; +#26675 = ORIENTED_EDGE ( 'NONE', *, *, #624, .F. ) ; +#26676 = EDGE_CURVE ( 'NONE', #2746, #34239, #29285, .T. ) ; +#26677 = ADVANCED_FACE ( 'NONE', ( #22687 ), #40255, .F. ) ; +#26678 = CARTESIAN_POINT ( 'NONE', ( 3.867708199630259358, 137.2814764503893628, 91.68658596503725278 ) ) ; +#26679 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552150381, 77.14301703112145958, 291.5584375788748162 ) ) ; +#26680 = ORIENTED_EDGE ( 'NONE', *, *, #38423, .T. ) ; +#26681 = EDGE_CURVE ( 'NONE', #9823, #38321, #35009, .T. ) ; +#26682 = LINE ( 'NONE', #16841, #33858 ) ; +#26684 = CARTESIAN_POINT ( 'NONE', ( 14.74038206972566023, 158.6023471296159357, 96.26025645282702214 ) ) ; +#26683 = FACE_OUTER_BOUND ( 'NONE', #9959, .T. ) ; +#26685 = EDGE_CURVE ( 'NONE', #11816, #11521, #9062, .T. ) ; +#26686 = AXIS2_PLACEMENT_3D ( 'NONE', #23334, #32920, #8191 ) ; +#26687 = ORIENTED_EDGE ( 'NONE', *, *, #1352, .F. ) ; +#26688 = EDGE_LOOP ( 'NONE', ( #12652, #10580, #15223, #37918 ) ) ; +#26689 = CARTESIAN_POINT ( 'NONE', ( -35.94780306588808116, 112.9281708003797036, 87.78949364045074333 ) ) ; +#26690 = AXIS2_PLACEMENT_3D ( 'NONE', #14498, #39622, #30033 ) ; +#26691 = DIRECTION ( 'NONE', ( 0.0005884949961253973984, -0.2249510543501614945, 0.9743698870656820610 ) ) ; +#26692 = CARTESIAN_POINT ( 'NONE', ( -24.13060896835314395, 149.4040876299065417, 197.0825913028203900 ) ) ; +#26693 = PLANE ( 'NONE', #34751 ) ; +#26694 = VECTOR ( 'NONE', #37939, 1000.000000000000114 ) ; +#26695 = FACE_OUTER_BOUND ( 'NONE', #28142, .T. ) ; +#26696 = ORIENTED_EDGE ( 'NONE', *, *, #19082, .T. ) ; +#26697 = EDGE_LOOP ( 'NONE', ( #14013, #36017, #23895, #27823, #38525, #4181, #35843, #22195, #5056 ) ) ; +#26698 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#26699 = ORIENTED_EDGE ( 'NONE', *, *, #2020, .T. ) ; +#26700 = VERTEX_POINT ( 'NONE', #10411 ) ; +#26701 = CARTESIAN_POINT ( 'NONE', ( 5.667981290316929766, 188.0310117602156197, 103.3282556105816639 ) ) ; +#26702 = FACE_OUTER_BOUND ( 'NONE', #32558, .T. ) ; +#26703 = EDGE_CURVE ( 'NONE', #14375, #28275, #16716, .T. ) ; +#26704 = CARTESIAN_POINT ( 'NONE', ( 39.42035703641028022, 114.3667165859880015, 151.6079144922757109 ) ) ; +#26705 = ORIENTED_EDGE ( 'NONE', *, *, #32564, .T. ) ; +#26706 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749094291, 179.1800746285969410, 103.5747911657857685 ) ) ; +#26707 = CARTESIAN_POINT ( 'NONE', ( 36.03687122555673739, 218.5902260770998282, 61.03673652647002257 ) ) ; +#26708 = CARTESIAN_POINT ( 'NONE', ( -36.15951732602999869, 191.7854204790999972, 104.2892810376000057 ) ) ; +#26709 = CARTESIAN_POINT ( 'NONE', ( 38.07467335044000123, 191.1277935667999941, 103.8765590109999977 ) ) ; +#26710 = CARTESIAN_POINT ( 'NONE', ( -25.50095891563999828, 120.6767459707999990, 88.04209109285001489 ) ) ; +#26711 = DIRECTION ( 'NONE', ( -0.7933535320750288999, 0.5931614265262136199, 0.1369295264925108890 ) ) ; +#26712 = ORIENTED_EDGE ( 'NONE', *, *, #23802, .T. ) ; +#26713 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#26714 = CARTESIAN_POINT ( 'NONE', ( -23.35627702857092913, 177.0509736354910615, 103.5359117850035773 ) ) ; +#26715 = ORIENTED_EDGE ( 'NONE', *, *, #3350, .T. ) ; +#26716 = CARTESIAN_POINT ( 'NONE', ( 0.6204049449089953372, 188.6158442063491520, 103.1979476084812717 ) ) ; +#26717 = CARTESIAN_POINT ( 'NONE', ( -13.50000077922901731, 184.9627595935803868, 102.3630947892575307 ) ) ; +#26718 = DIRECTION ( 'NONE', ( 0.7066903833891088338, 9.361005957145118576E-05, -0.7075229277292088836 ) ) ; +#26719 = CARTESIAN_POINT ( 'NONE', ( -43.16067970895235106, 137.0136042933273472, 338.0369414682852494 ) ) ; +#26720 = ORIENTED_EDGE ( 'NONE', *, *, #18430, .T. ) ; +#26721 = FACE_OUTER_BOUND ( 'NONE', #10180, .T. ) ; +#26722 = VECTOR ( 'NONE', #2818, 1000.000000000000000 ) ; +#26723 = CARTESIAN_POINT ( 'NONE', ( 2.562971096584431230, 190.9999997793927093, 104.2603522665603890 ) ) ; +#26724 = CARTESIAN_POINT ( 'NONE', ( 20.00004282447493864, 191.5259056233101091, 103.8580927373495371 ) ) ; +#26725 = AXIS2_PLACEMENT_3D ( 'NONE', #13785, #23801, #20315 ) ; +#26726 = ORIENTED_EDGE ( 'NONE', *, *, #8276, .F. ) ; +#26727 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971578447 ) ) ; +#26728 = VECTOR ( 'NONE', #29859, 1000.000000000000114 ) ; +#26729 = ADVANCED_FACE ( 'NONE', ( #13667 ), #382, .T. ) ; +#26730 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#26731 = EDGE_CURVE ( 'NONE', #22702, #127, #33210, .T. ) ; +#26732 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971554023 ) ) ; +#26733 = CONICAL_SURFACE ( 'NONE', #18845, 6.000000000012161827, 0.7853981634347138030 ) ; +#26734 = CARTESIAN_POINT ( 'NONE', ( -20.60932504597193926, 129.3771293980497603, 89.53443240656145008 ) ) ; +#26735 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#26736 = DIRECTION ( 'NONE', ( 0.5988683521957647304, -0.8008474865655316188, 0.000000000000000000 ) ) ; +#26737 = ORIENTED_EDGE ( 'NONE', *, *, #2396, .F. ) ; +#26738 = CYLINDRICAL_SURFACE ( 'NONE', #36352, 2.000000000000000000 ) ; +#26739 = CARTESIAN_POINT ( 'NONE', ( 20.39369772661039448, 175.8775066034073404, 100.2451275383852902 ) ) ; +#26740 = CARTESIAN_POINT ( 'NONE', ( 3.667815741540035646, 183.5629855103865964, 104.5953232250576406 ) ) ; +#26741 = CARTESIAN_POINT ( 'NONE', ( 36.95058457225000126, 190.7035229651999941, 106.6077189348000047 ) ) ; +#26742 = LINE ( 'NONE', #36340, #10471 ) ; +#26743 = CARTESIAN_POINT ( 'NONE', ( -1.762796036274244527, 145.3269866793034168, 129.1252078605875795 ) ) ; +#26744 = CARTESIAN_POINT ( 'NONE', ( -5.667825639563665696, 130.0010482692081553, 92.27601498940221347 ) ) ; +#26745 = CARTESIAN_POINT ( 'NONE', ( 23.00089693216080988, 115.1133509736824152, 90.25389292129368357 ) ) ; +#26746 = ORIENTED_EDGE ( 'NONE', *, *, #38445, .T. ) ; +#26748 = VECTOR ( 'NONE', #33334, 1000.000000000000114 ) ; +#26747 = CARTESIAN_POINT ( 'NONE', ( 27.30382602036842954, 110.6131156702000027, 87.75129355648586227 ) ) ; +#26749 = CARTESIAN_POINT ( 'NONE', ( -31.01530004135919327, 135.0949612155151272, 90.86078308433575046 ) ) ; +#26750 = AXIS2_PLACEMENT_3D ( 'NONE', #2239, #39024, #17747 ) ; +#26751 = ORIENTED_EDGE ( 'NONE', *, *, #35733, .F. ) ; +#26752 = FACE_OUTER_BOUND ( 'NONE', #34600, .T. ) ; +#26753 = AXIS2_PLACEMENT_3D ( 'NONE', #16707, #23461, #13656 ) ; +#26754 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9882, #248, #16192, #31756, #22149, #12944, #25827, #10485, #28478, #32156 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000549560, 0.3750000000000826006, 0.4375000000000809353, 0.5000000000000792699, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26755 = CARTESIAN_POINT ( 'NONE', ( 25.50041447495308233, 118.1134306400200416, 89.75249416949174019 ) ) ; +#26756 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26899, #39334, #2353, #2152 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26757 = CONICAL_SURFACE ( 'NONE', #19555, 51.90509898885028406, 0.7853981633972950682 ) ; +#26758 = ORIENTED_EDGE ( 'NONE', *, *, #11037, .F. ) ; +#26759 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971567068 ) ) ; +#26760 = CARTESIAN_POINT ( 'NONE', ( -22.49852798327293613, 137.6294278362846910, 94.00652773583050248 ) ) ; +#26761 = ORIENTED_EDGE ( 'NONE', *, *, #34355, .T. ) ; +#26762 = PLANE ( 'NONE', #21730 ) ; +#26763 = ADVANCED_FACE ( 'NONE', ( #28806 ), #9604, .T. ) ; +#26764 = FACE_OUTER_BOUND ( 'NONE', #25768, .T. ) ; +#26765 = CARTESIAN_POINT ( 'NONE', ( -12.63215091093176135, 130.3073820208400377, 92.77172047309325364 ) ) ; +#26766 = CARTESIAN_POINT ( 'NONE', ( -35.93631444825950183, 190.8511609687279815, 106.8150034675900173 ) ) ; +#26767 = CARTESIAN_POINT ( 'NONE', ( 37.40434350968867250, 145.4460227941551409, 282.5393146728916918 ) ) ; +#26768 = ORIENTED_EDGE ( 'NONE', *, *, #1315, .F. ) ; +#26769 = ORIENTED_EDGE ( 'NONE', *, *, #28889, .T. ) ; +#26770 = DIRECTION ( 'NONE', ( -0.0006039748319378610095, -9.939046677758948188E-15, -0.9999998176071845934 ) ) ; +#26771 = CARTESIAN_POINT ( 'NONE', ( -20.49970524097187763, 120.2776284062741325, 87.94673202274765345 ) ) ; +#26772 = FACE_OUTER_BOUND ( 'NONE', #35371, .T. ) ; +#26773 = CARTESIAN_POINT ( 'NONE', ( -26.77281046845786960, 181.6852968820032004, 101.6144925486012482 ) ) ; +#26774 = EDGE_CURVE ( 'NONE', #36789, #16908, #29004, .T. ) ; +#26775 = ORIENTED_EDGE ( 'NONE', *, *, #6235, .T. ) ; +#26776 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971571786 ) ) ; +#26777 = ADVANCED_FACE ( 'NONE', ( #10004 ), #31884, .F. ) ; +#26778 = CARTESIAN_POINT ( 'NONE', ( -42.64899167230314703, 121.2509807306891503, 91.18371451274786921 ) ) ; +#26780 = EDGE_CURVE ( 'NONE', #11951, #26904, #14162, .T. ) ; +#26779 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; +#26781 = LINE ( 'NONE', #30041, #5848 ) ; +#26782 = CARTESIAN_POINT ( 'NONE', ( 29.40506628721518112, 160.9732782815168832, 187.1184765030605774 ) ) ; +#26783 = AXIS2_PLACEMENT_3D ( 'NONE', #24770, #9221, #21693 ) ; +#26784 = VECTOR ( 'NONE', #30979, 1000.000000000000000 ) ; +#26785 = CARTESIAN_POINT ( 'NONE', ( 20.00016034875645943, 127.4394136103090887, 89.06260552501319694 ) ) ; +#26786 = VECTOR ( 'NONE', #21426, 1000.000000000000000 ) ; +#26787 = CARTESIAN_POINT ( 'NONE', ( -22.78373664920998465, 158.6756214348941967, 96.81298893720612853 ) ) ; +#26788 = CARTESIAN_POINT ( 'NONE', ( -25.70423657749428514, 209.7106478409149020, 73.37976546826619995 ) ) ; +#26789 = CARTESIAN_POINT ( 'NONE', ( 25.37184720669000271, 191.3685744429000124, 106.2318680839000109 ) ) ; +#26790 = CARTESIAN_POINT ( 'NONE', ( 38.47734842322999782, 119.0019185009000040, 87.58017102035999812 ) ) ; +#26791 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319351121233 ) ) ; +#26792 = CARTESIAN_POINT ( 'NONE', ( 26.01908888004416198, 121.3240759725699576, 87.64707579647844682 ) ) ; +#26793 = ORIENTED_EDGE ( 'NONE', *, *, #13984, .F. ) ; +#26794 = DIRECTION ( 'NONE', ( 0.0003761318146485119322, -0.7826081568524122511, 0.6225145230056309265 ) ) ; +#26795 = FACE_OUTER_BOUND ( 'NONE', #3749, .T. ) ; +#26796 = CARTESIAN_POINT ( 'NONE', ( -20.99988231331349198, 183.1828074682273098, 102.1277500980325925 ) ) ; +#26797 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#26798 = DIRECTION ( 'NONE', ( 0.0005884949961208347504, -0.2249510543439081633, 0.9743698870671259060 ) ) ; +#26799 = EDGE_LOOP ( 'NONE', ( #24032, #17353, #31347, #21978 ) ) ; +#26800 = ORIENTED_EDGE ( 'NONE', *, *, #36994, .F. ) ; +#26801 = ORIENTED_EDGE ( 'NONE', *, *, #38114, .T. ) ; +#26802 = CARTESIAN_POINT ( 'NONE', ( -23.35464359634993770, 177.7881151143831744, 100.7126876897662697 ) ) ; +#26803 = CARTESIAN_POINT ( 'NONE', ( 44.67372889100202826, 177.7390009530348891, 153.4812792797092413 ) ) ; +#26804 = CARTESIAN_POINT ( 'NONE', ( 42.84319492119625039, 107.4629127437788441, 150.2239362889277174 ) ) ; +#26805 = ORIENTED_EDGE ( 'NONE', *, *, #13647, .T. ) ; +#26806 = FACE_BOUND ( 'NONE', #8467, .T. ) ; +#26807 = AXIS2_PLACEMENT_3D ( 'NONE', #15451, #33643, #12190 ) ; +#26808 = AXIS2_PLACEMENT_3D ( 'NONE', #37707, #28129, #9715 ) ; +#26809 = CARTESIAN_POINT ( 'NONE', ( -38.08733905160174515, 161.7245877003365706, 191.3073351807457811 ) ) ; +#26810 = PLANE ( 'NONE', #17523 ) ; +#26811 = DIRECTION ( 'NONE', ( 0.0005884949961195158185, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#26812 = CARTESIAN_POINT ( 'NONE', ( -37.26090046766999819, 117.2573710810000165, 87.85948469216999968 ) ) ; +#26813 = ORIENTED_EDGE ( 'NONE', *, *, #29397, .T. ) ; +#26814 = CARTESIAN_POINT ( 'NONE', ( -2.935232621041004020, 190.8511156531020276, 106.7950609103722286 ) ) ; +#26815 = EDGE_CURVE ( 'NONE', #14158, #19947, #9574, .T. ) ; +#26816 = CIRCLE ( 'NONE', #2000, 2.000000000000011546 ) ; +#26817 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20009, #32501, #38814, #4471, #14107, #16533, #32894, #26376, #35738, #29845 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.002118074346442883234, 0.2515885557598321887, 0.5010590371732214221, 0.7505295185866107666, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26818 = AXIS2_PLACEMENT_3D ( 'NONE', #15845, #6636, #911 ) ; +#26819 = CARTESIAN_POINT ( 'NONE', ( 20.49249339799013470, 105.2139170029020079, 152.4743314729049644 ) ) ; +#26820 = CARTESIAN_POINT ( 'NONE', ( 46.51603001997818865, 125.2609579198457368, 89.05674941267899669 ) ) ; +#26821 = EDGE_LOOP ( 'NONE', ( #33841, #28557, #12527, #34978 ) ) ; +#26822 = ORIENTED_EDGE ( 'NONE', *, *, #7124, .T. ) ; +#26823 = EDGE_CURVE ( 'NONE', #36593, #9503, #4324, .T. ) ; +#26824 = CARTESIAN_POINT ( 'NONE', ( -2.210524828757970184, 189.3034206159340158, 103.3540988507229912 ) ) ; +#26825 = CARTESIAN_POINT ( 'NONE', ( 0.8837433930371000335, 188.6289352372000110, 103.1999597849000025 ) ) ; +#26826 = DIRECTION ( 'NONE', ( -0.0005884949961246006183, 0.2249510543439056653, -0.9743698870671265722 ) ) ; +#26827 = CARTESIAN_POINT ( 'NONE', ( 26.28854775478996686, 121.8696897106344892, 90.85179081473795293 ) ) ; +#26828 = ORIENTED_EDGE ( 'NONE', *, *, #23813, .F. ) ; +#26829 = EDGE_CURVE ( 'NONE', #19329, #8486, #25430, .T. ) ; +#26830 = EDGE_LOOP ( 'NONE', ( #20663, #23726, #39280, #38803, #19752, #30217, #11321, #22164, #7249, #1251, #34140 ) ) ; +#26831 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023851578 ) ) ; +#26832 = ORIENTED_EDGE ( 'NONE', *, *, #17835, .T. ) ; +#26833 = EDGE_CURVE ( 'NONE', #38150, #5749, #38277, .T. ) ; +#26834 = ORIENTED_EDGE ( 'NONE', *, *, #27574, .T. ) ; +#26835 = EDGE_CURVE ( 'NONE', #22159, #21490, #3018, .T. ) ; +#26836 = ADVANCED_FACE ( 'NONE', ( #35309 ), #7315, .T. ) ; +#26837 = ORIENTED_EDGE ( 'NONE', *, *, #23204, .F. ) ; +#26838 = ORIENTED_EDGE ( 'NONE', *, *, #25034, .T. ) ; +#26839 = CARTESIAN_POINT ( 'NONE', ( 22.33620396352009152, 213.5250434016230940, 73.54492077792029647 ) ) ; +#26840 = CARTESIAN_POINT ( 'NONE', ( -20.01736593119981222, 207.8686407175673594, 77.28911966098117148 ) ) ; +#26841 = VECTOR ( 'NONE', #6599, 1000.000000000000114 ) ; +#26842 = ORIENTED_EDGE ( 'NONE', *, *, #28633, .T. ) ; +#26843 = DIRECTION ( 'NONE', ( 0.0005884949961212082581, -0.2249510543439042498, 0.9743698870671267942 ) ) ; +#26844 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#26845 = ORIENTED_EDGE ( 'NONE', *, *, #36932, .F. ) ; +#26846 = AXIS2_PLACEMENT_3D ( 'NONE', #11204, #36131, #36345 ) ; +#26847 = CARTESIAN_POINT ( 'NONE', ( 26.66063621298999919, 123.4172645953999989, 90.86668199093000453 ) ) ; +#26848 = VECTOR ( 'NONE', #29874, 1000.000000000000114 ) ; +#26849 = DIRECTION ( 'NONE', ( 0.7933533411653088674, -0.5930537057989926364, -0.1373964268091528718 ) ) ; +#26850 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38545, #7065, #25503, #3587 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26852 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#26851 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#26853 = ORIENTED_EDGE ( 'NONE', *, *, #20486, .T. ) ; +#26854 = ORIENTED_EDGE ( 'NONE', *, *, #30017, .T. ) ; +#26855 = CARTESIAN_POINT ( 'NONE', ( -36.05603307849823835, 192.0347168703188174, 104.4252530631643339 ) ) ; +#26856 = CYLINDRICAL_SURFACE ( 'NONE', #39343, 2.000000000000001332 ) ; +#26857 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38302, #31372, #10316, #3344, #22778, #1486, #14188, #17421, #35810, #11506, #7622, #2113, #14583, #26450, #8026, #27068, #23781, #23379, #1902, #8240, #4550, #16814, #35604, #39297 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 1, 1, 1, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999919231, 0.1874999999999908684, 0.2187499999999934774, 0.2499999999999960587, 0.3749999999999950595, 0.4374999999999977240, 0.4687499999999958922, 0.4843749999999950040, 0.4999999999999941158, 0.6249999999999951150, 0.6874999999999963363, 0.7187499999999970024, 0.7343749999999953371, 0.7499999999999935607, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26858 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #38598, #38214, #4246, #6925 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.570796326794905662, 3.321000581826871301 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7606123116729073264, 0.7606123116729073264, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#26859 = ORIENTED_EDGE ( 'NONE', *, *, #18060, .T. ) ; +#26860 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930881478 ) ) ; +#26861 = CARTESIAN_POINT ( 'NONE', ( -37.20408499830807614, 118.8543451047710278, 123.0175147464529886 ) ) ; +#26862 = CARTESIAN_POINT ( 'NONE', ( -22.78207419572857617, 153.6036766290901596, 98.03674867519744396 ) ) ; +#26863 = VERTEX_POINT ( 'NONE', #31690 ) ; +#26864 = EDGE_CURVE ( 'NONE', #28866, #29827, #3640, .T. ) ; +#26865 = VERTEX_POINT ( 'NONE', #23076 ) ; +#26866 = EDGE_CURVE ( 'NONE', #30574, #24578, #16907, .T. ) ; +#26867 = FACE_OUTER_BOUND ( 'NONE', #10035, .T. ) ; +#26868 = CARTESIAN_POINT ( 'NONE', ( 15.99999439207489615, 185.9093013714976053, 102.5638074086867846 ) ) ; +#26869 = CIRCLE ( 'NONE', #30125, 5.249999999999986677 ) ; +#26870 = EDGE_LOOP ( 'NONE', ( #36400, #7785 ) ) ; +#26871 = ADVANCED_FACE ( 'NONE', ( #15034 ), #30778, .T. ) ; +#26872 = CARTESIAN_POINT ( 'NONE', ( 30.06805065029857005, 135.2198668957702807, 91.25923900005884093 ) ) ; +#26873 = VECTOR ( 'NONE', #10038, 1000.000000000000000 ) ; +#26874 = ADVANCED_FACE ( 'NONE', ( #32475 ), #39554, .F. ) ; +#26875 = CARTESIAN_POINT ( 'NONE', ( -22.49829783392772953, 153.4788092355344702, 97.83669617681565001 ) ) ; +#26876 = VERTEX_POINT ( 'NONE', #27324 ) ; +#26877 = CARTESIAN_POINT ( 'NONE', ( 6.666633792382095969, 120.3902219392796411, 87.44316696365504527 ) ) ; +#26878 = ADVANCED_FACE ( 'NONE', ( #23271 ), #24458, .F. ) ; +#26879 = CARTESIAN_POINT ( 'NONE', ( -46.23974599993426438, 125.3236958879561058, 88.95620493717709110 ) ) ; +#26880 = CYLINDRICAL_SURFACE ( 'NONE', #40449, 2.000000000000014655 ) ; +#26881 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825920995632343, 0.0005734119023635456634 ) ) ; +#26882 = EDGE_LOOP ( 'NONE', ( #18569, #34062, #9448, #5916 ) ) ; +#26883 = PLANE ( 'NONE', #8161 ) ; +#26884 = DIRECTION ( 'NONE', ( 0.0002393071182786170076, 0.2252352986010032476, -0.9743043687658492491 ) ) ; +#26885 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38802, #2229, #20197, #4867 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26886 = ORIENTED_EDGE ( 'NONE', *, *, #10336, .F. ) ; +#26887 = CARTESIAN_POINT ( 'NONE', ( 37.28741399843698900, 124.9789241431960392, 93.24647550195996359 ) ) ; +#26888 = AXIS2_PLACEMENT_3D ( 'NONE', #5372, #10372, #35272 ) ; +#26890 = CARTESIAN_POINT ( 'NONE', ( 5.666638401078098575, 182.0642691150555663, 102.1955013913653545 ) ) ; +#26889 = CARTESIAN_POINT ( 'NONE', ( 13.61340840401525654, 135.2710827206831823, 90.87448932346926256 ) ) ; +#26891 = VERTEX_POINT ( 'NONE', #7517 ) ; +#26892 = AXIS2_PLACEMENT_3D ( 'NONE', #26983, #27194, #33284 ) ; +#26893 = ORIENTED_EDGE ( 'NONE', *, *, #32627, .F. ) ; +#26894 = CARTESIAN_POINT ( 'NONE', ( 25.02024140749000125, 130.2799456493999912, 91.25476132727000333 ) ) ; +#26895 = CARTESIAN_POINT ( 'NONE', ( 38.63435032335372910, 118.5239118084539172, 89.66224185811006464 ) ) ; +#26896 = ORIENTED_EDGE ( 'NONE', *, *, #40232, .F. ) ; +#26897 = CARTESIAN_POINT ( 'NONE', ( 2.580582809155000046, 209.5994064289000107, 75.67760466619000681 ) ) ; +#26898 = CARTESIAN_POINT ( 'NONE', ( 37.30457061651406292, 191.0696620593575688, 106.2962842821977176 ) ) ; +#26899 = CARTESIAN_POINT ( 'NONE', ( 14.74167426920670465, 136.8705781667366068, 91.75623271434285755 ) ) ; +#26900 = ORIENTED_EDGE ( 'NONE', *, *, #3256, .T. ) ; +#26901 = ORIENTED_EDGE ( 'NONE', *, *, #32667, .F. ) ; +#26902 = CARTESIAN_POINT ( 'NONE', ( -5.674480817841737412, 181.6879534348617824, 101.6022789869470131 ) ) ; +#26903 = VERTEX_POINT ( 'NONE', #11971 ) ; +#26904 = VERTEX_POINT ( 'NONE', #27536 ) ; +#26905 = CARTESIAN_POINT ( 'NONE', ( 3.882702609227124846, 148.9606115484772602, 129.9617790688552077 ) ) ; +#26906 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #25305, #21826 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26907 = CARTESIAN_POINT ( 'NONE', ( 47.95588724831284111, 89.52656283054035669, 291.5279987808671081 ) ) ; +#26908 = ORIENTED_EDGE ( 'NONE', *, *, #4825, .F. ) ; +#26909 = EDGE_CURVE ( 'NONE', #12627, #21765, #16627, .T. ) ; +#26910 = ORIENTED_EDGE ( 'NONE', *, *, #21824, .F. ) ; +#26911 = EDGE_CURVE ( 'NONE', #24195, #31968, #8847, .T. ) ; +#26912 = ORIENTED_EDGE ( 'NONE', *, *, #39528, .T. ) ; +#26913 = DIRECTION ( 'NONE', ( -0.6772239534962611884, 0.7357769477300126759, 0.000000000000000000 ) ) ; +#26914 = EDGE_CURVE ( 'NONE', #22883, #2849, #22681, .T. ) ; +#26915 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#26916 = CARTESIAN_POINT ( 'NONE', ( -36.17829791151999785, 192.0984349645000009, 104.5680916760999963 ) ) ; +#26917 = CARTESIAN_POINT ( 'NONE', ( 36.26754167136000007, 191.5402796886000090, 103.9582622207999947 ) ) ; +#26919 = EDGE_CURVE ( 'NONE', #27687, #20220, #12844, .T. ) ; +#26918 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23105, #32899, #38426, #17341 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26920 = CARTESIAN_POINT ( 'NONE', ( -25.52832686761000147, 121.2413356678000014, 88.17240013551000288 ) ) ; +#26921 = PLANE ( 'NONE', #1471 ) ; +#26922 = DIRECTION ( 'NONE', ( 0.5988683521957514078, -0.8008474865655416108, 6.245004513516477772E-14 ) ) ; +#26923 = CARTESIAN_POINT ( 'NONE', ( 3.666638747417580557, 185.7959654145790864, 103.0582394725906568 ) ) ; +#26924 = CARTESIAN_POINT ( 'NONE', ( -25.05644770639884200, 131.0181980617547026, 89.91603302966900912 ) ) ; +#26925 = ORIENTED_EDGE ( 'NONE', *, *, #8352, .T. ) ; +#26926 = EDGE_CURVE ( 'NONE', #22589, #36851, #2364, .T. ) ; +#26927 = CARTESIAN_POINT ( 'NONE', ( -16.15249828763665363, 151.1189587783885884, 184.8292094970151425 ) ) ; +#26928 = LINE ( 'NONE', #36094, #8401 ) ; +#26929 = VECTOR ( 'NONE', #594, 1000.000000000000114 ) ; +#26930 = PLANE ( 'NONE', #16989 ) ; +#26931 = DIRECTION ( 'NONE', ( -0.0001408404346091657539, 0.2255194953558361803, -0.9742386449830560124 ) ) ; +#26932 = ORIENTED_EDGE ( 'NONE', *, *, #21557, .F. ) ; +#26934 = ADVANCED_FACE ( 'NONE', ( #18278 ), #26157, .T. ) ; +#26933 = CARTESIAN_POINT ( 'NONE', ( -20.89282324149344561, 183.0959377177359215, 101.9365769416837253 ) ) ; +#26935 = AXIS2_PLACEMENT_3D ( 'NONE', #13558, #31778, #268 ) ; +#26936 = CARTESIAN_POINT ( 'NONE', ( 13.88399914228467757, 136.0347715473272672, 91.56378953181273062 ) ) ; +#26937 = CARTESIAN_POINT ( 'NONE', ( -8.573576785595708571, 209.7096749608995196, 76.06368285521188000 ) ) ; +#26938 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7981, #20242, #20445, #36189 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999992929598529035 ), + .UNSPECIFIED. ) ; +#26939 = ORIENTED_EDGE ( 'NONE', *, *, #13099, .F. ) ; +#26940 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7154541036601359538, -0.6986597351757660723 ) ) ; +#26941 = VERTEX_POINT ( 'NONE', #35707 ) ; +#26942 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #30194, #17084, #35681, #11372 ), + .UNSPECIFIED., .F., .F. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.0003551482881305434674, 1.571423989884809469 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8046736173937256709, 0.8046736173937256709, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#26943 = CARTESIAN_POINT ( 'NONE', ( -1.458415328224369478, 144.9404864464127058, 129.0359332379569253 ) ) ; +#26944 = CARTESIAN_POINT ( 'NONE', ( 16.57214424012681064, 121.8478803258931720, 177.5755000349597026 ) ) ; +#26945 = CARTESIAN_POINT ( 'NONE', ( 26.14938448941000004, 192.1174886745999970, 103.7633825134000034 ) ) ; +#26946 = CARTESIAN_POINT ( 'NONE', ( 6.032339368669187962, 135.0240263800323817, 90.96470306000986739 ) ) ; +#26947 = ORIENTED_EDGE ( 'NONE', *, *, #32073, .T. ) ; +#26948 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#26949 = CARTESIAN_POINT ( 'NONE', ( 3.062737380639022344, 196.5784460000043055, 103.8732377138169483 ) ) ; +#26950 = LINE ( 'NONE', #14875, #30319 ) ; +#26951 = CARTESIAN_POINT ( 'NONE', ( 22.50046737220517201, 154.0096474681598124, 95.53736714637915384 ) ) ; +#26952 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1863, #23742, #26215, #7581 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26953 = CARTESIAN_POINT ( 'NONE', ( 19.01970210477341894, 125.1712956467094529, 177.2425045390261573 ) ) ; +#26954 = PLANE ( 'NONE', #18931 ) ; +#26955 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#26956 = AXIS2_PLACEMENT_3D ( 'NONE', #21434, #18326, #3194 ) ; +#26957 = CARTESIAN_POINT ( 'NONE', ( -20.49852829818812694, 127.1805961891525385, 91.59301651659605170 ) ) ; +#26958 = CARTESIAN_POINT ( 'NONE', ( -38.41439781631743955, 118.8735558289109235, 87.72267610939334759 ) ) ; +#26959 = EDGE_LOOP ( 'NONE', ( #36023, #4822, #14099, #1813 ) ) ; +#26960 = CONICAL_SURFACE ( 'NONE', #9319, 2.502999999946897702, 0.7853981633984010724 ) ; +#26961 = CARTESIAN_POINT ( 'NONE', ( 3.697220241243522221, 144.1788877089946652, 93.10421244235104155 ) ) ; +#26962 = AXIS2_PLACEMENT_3D ( 'NONE', #37196, #39842, #18560 ) ; +#26963 = CARTESIAN_POINT ( 'NONE', ( -32.41149745080540612, 136.4913485010586101, 91.18400781810954925 ) ) ; +#26964 = ORIENTED_EDGE ( 'NONE', *, *, #22278, .F. ) ; +#26965 = CARTESIAN_POINT ( 'NONE', ( 2.564209066518882807, 190.9903029846934430, 106.3100561862119378 ) ) ; +#26966 = ADVANCED_FACE ( 'NONE', ( #11767 ), #38592, .F. ) ; +#26967 = EDGE_CURVE ( 'NONE', #8977, #3835, #36641, .T. ) ; +#26968 = ORIENTED_EDGE ( 'NONE', *, *, #12007, .F. ) ; +#26969 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28814, #989, #7122, #13482 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26970 = CARTESIAN_POINT ( 'NONE', ( -17.09842820193908963, 152.0927262417674797, 183.8356208079428882 ) ) ; +#26971 = ORIENTED_EDGE ( 'NONE', *, *, #11406, .F. ) ; +#26972 = CARTESIAN_POINT ( 'NONE', ( 36.35311034930725071, 191.7638335428474647, 106.3857863246174134 ) ) ; +#26973 = DIRECTION ( 'NONE', ( 0.0006039748319385908944, 1.293414132305980107E-14, 0.9999998176071845934 ) ) ; +#26974 = LINE ( 'NONE', #36143, #19433 ) ; +#26975 = CARTESIAN_POINT ( 'NONE', ( -12.63707001172994104, 130.8324915394589709, 90.02598128956542212 ) ) ; +#26976 = DIRECTION ( 'NONE', ( 0.6087611427401034003, 0.7731004639645453480, 0.1781166575802726748 ) ) ; +#26977 = ORIENTED_EDGE ( 'NONE', *, *, #10789, .F. ) ; +#26978 = CARTESIAN_POINT ( 'NONE', ( 39.59524713850000666, 119.9028460329000154, 87.70178263936999485 ) ) ; +#26979 = DIRECTION ( 'NONE', ( -1.040834085586078261E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#26980 = AXIS2_PLACEMENT_3D ( 'NONE', #1790, #38994, #14471 ) ; +#26981 = CARTESIAN_POINT ( 'NONE', ( -20.27003028652000083, 210.4001054583000041, 73.32073907762999454 ) ) ; +#26982 = ORIENTED_EDGE ( 'NONE', *, *, #33500, .T. ) ; +#26983 = CARTESIAN_POINT ( 'NONE', ( -13.55543936442094122, 163.9606856050033343, 100.5933294418133102 ) ) ; +#26984 = ORIENTED_EDGE ( 'NONE', *, *, #6662, .T. ) ; +#26985 = ORIENTED_EDGE ( 'NONE', *, *, #36551, .T. ) ; +#26986 = CIRCLE ( 'NONE', #17165, 58.90509898899682639 ) ; +#26987 = CARTESIAN_POINT ( 'NONE', ( -38.94544030404210844, 127.6228067830301711, 91.70624984242061828 ) ) ; +#26988 = CARTESIAN_POINT ( 'NONE', ( -42.36692568814963522, 121.1167509210004170, 92.72420472768362742 ) ) ; +#26989 = CARTESIAN_POINT ( 'NONE', ( 14.89442708580793528, 182.7495487637143015, 104.5717966455644898 ) ) ; +#26990 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#26991 = EDGE_CURVE ( 'NONE', #14963, #35463, #32676, .T. ) ; +#26992 = VECTOR ( 'NONE', #30576, 1000.000000000000000 ) ; +#26993 = CARTESIAN_POINT ( 'NONE', ( -24.86074681069491632, 213.4929432232339082, 73.07351935051005398 ) ) ; +#26994 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38189, #22664, #7099, #16697, #10393, #35088 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#26995 = CARTESIAN_POINT ( 'NONE', ( -25.78537060397050595, 209.7107784368876651, 73.29872942540529834 ) ) ; +#26996 = DIRECTION ( 'NONE', ( -0.7075337269008449281, -1.092317403744933227E-14, -0.7066795775298735371 ) ) ; +#26997 = CARTESIAN_POINT ( 'NONE', ( 37.93651756058999780, 118.4146852817000024, 87.57225098144000697 ) ) ; +#26998 = CARTESIAN_POINT ( 'NONE', ( 39.06502905710053142, 190.9636352783319069, 106.2825191316666888 ) ) ; +#26999 = CARTESIAN_POINT ( 'NONE', ( 28.52919418227002879, 125.2871234584923883, 88.56050369811191558 ) ) ; +#27000 = VERTEX_POINT ( 'NONE', #2567 ) ; +#27001 = CARTESIAN_POINT ( 'NONE', ( 39.81119971704559646, 75.02554102933939362, 323.6757538848392528 ) ) ; +#27002 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250898248, 132.4055461763671246, 92.79778151964485744 ) ) ; +#27003 = CARTESIAN_POINT ( 'NONE', ( -28.47344760044883216, 181.6851202344923308, 101.6154648382260035 ) ) ; +#27004 = FACE_OUTER_BOUND ( 'NONE', #11006, .T. ) ; +#27006 = ORIENTED_EDGE ( 'NONE', *, *, #18337, .T. ) ; +#27005 = FACE_OUTER_BOUND ( 'NONE', #16383, .T. ) ; +#27007 = ORIENTED_EDGE ( 'NONE', *, *, #27909, .F. ) ; +#27008 = ORIENTED_EDGE ( 'NONE', *, *, #39113, .F. ) ; +#27009 = CARTESIAN_POINT ( 'NONE', ( 43.53526136507346678, 121.9496774062499043, 88.05073105187337035 ) ) ; +#27010 = VERTEX_POINT ( 'NONE', #29609 ) ; +#27011 = CARTESIAN_POINT ( 'NONE', ( -23.35885086855935810, 177.6508992509094185, 100.7984980571552143 ) ) ; +#27012 = VECTOR ( 'NONE', #1271, 1000.000000000000114 ) ; +#27013 = DIRECTION ( 'NONE', ( 0.0005884949961231208991, -0.2249510543439063315, 0.9743698870671262391 ) ) ; +#27014 = FACE_OUTER_BOUND ( 'NONE', #7999, .T. ) ; +#27015 = EDGE_CURVE ( 'NONE', #24627, #39281, #34655, .T. ) ; +#27016 = AXIS2_PLACEMENT_3D ( 'NONE', #9052, #2722, #36853 ) ; +#27017 = EDGE_CURVE ( 'NONE', #14571, #20733, #6856, .T. ) ; +#27018 = EDGE_LOOP ( 'NONE', ( #16784, #14762, #9756, #38101 ) ) ; +#27019 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#27020 = CONICAL_SURFACE ( 'NONE', #23735, 6.500000000009604761, 0.7853981634430725611 ) ; +#27021 = CARTESIAN_POINT ( 'NONE', ( -13.49295016813580439, 187.6291709519775850, 106.0054573042264110 ) ) ; +#27022 = CARTESIAN_POINT ( 'NONE', ( -37.61513335043999717, 118.9651505575999977, 87.16503455104999887 ) ) ; +#27023 = ORIENTED_EDGE ( 'NONE', *, *, #3115, .F. ) ; +#27024 = LINE ( 'NONE', #17986, #8788 ) ; +#27025 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13111, #10648, #4078, #13510 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27026 = ORIENTED_EDGE ( 'NONE', *, *, #37957, .T. ) ; +#27027 = CARTESIAN_POINT ( 'NONE', ( -5.668235839012000454, 187.2935674866481293, 105.4622348367114881 ) ) ; +#27028 = DIRECTION ( 'NONE', ( 0.7933530821293306445, 0.5932640870757670548, 0.1364866662427089150 ) ) ; +#27029 = CARTESIAN_POINT ( 'NONE', ( 20.24598356238904273, 184.3484679134213593, 105.0290154610982682 ) ) ; +#27030 = FACE_BOUND ( 'NONE', #3769, .T. ) ; +#27031 = CARTESIAN_POINT ( 'NONE', ( 3.168077837919118345, 126.1295738578562009, 91.84923819592059147 ) ) ; +#27032 = CARTESIAN_POINT ( 'NONE', ( -12.63742615055529228, 181.2452767761304813, 104.3838565639638460 ) ) ; +#27033 = ORIENTED_EDGE ( 'NONE', *, *, #34527, .F. ) ; +#27034 = CARTESIAN_POINT ( 'NONE', ( 76.10601358361097368, 156.3575724116847425, 95.70494597593847175 ) ) ; +#27035 = CARTESIAN_POINT ( 'NONE', ( 38.11757776978107159, 119.1971814748143146, 87.25517274288121428 ) ) ; +#27036 = CARTESIAN_POINT ( 'NONE', ( -3.668109984895000508, 181.5006555260000027, 104.6367796092000049 ) ) ; +#27037 = CARTESIAN_POINT ( 'NONE', ( -35.74942256790419037, 191.5232899416273824, 106.9256828509688120 ) ) ; +#27038 = VERTEX_POINT ( 'NONE', #92 ) ; +#27039 = LINE ( 'NONE', #7795, #37466 ) ; +#27040 = VERTEX_POINT ( 'NONE', #27726 ) ; +#27041 = ADVANCED_FACE ( 'NONE', ( #37701 ), #12360, .F. ) ; +#27042 = AXIS2_PLACEMENT_3D ( 'NONE', #24129, #15519, #25338 ) ; +#27043 = ORIENTED_EDGE ( 'NONE', *, *, #28034, .F. ) ; +#27044 = CARTESIAN_POINT ( 'NONE', ( -26.71605068641907010, 124.3153334168429325, 88.88266128990301240 ) ) ; +#27045 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6351, #39896, #21521, #18803, #11905, #36841, #33958, #2885, #21714, #12297, #37438, #8844, #31309, #3276 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000517364, 0.3750000000000776046, 0.5000000000001034728, 0.6250000000001293410, 0.6875000000001078027, 0.7500000000000863754, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27046 = ORIENTED_EDGE ( 'NONE', *, *, #23620, .F. ) ; +#27047 = CONICAL_SURFACE ( 'NONE', #887, 8.500000000041723069, 0.7853981633973075027 ) ; +#27048 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474981082756854, 150.9209598835162467, 97.06153188701080126 ) ) ; +#27049 = PLANE ( 'NONE', #4458 ) ; +#27050 = CARTESIAN_POINT ( 'NONE', ( -40.30153468720526178, 187.7974083947837585, 108.1652340796715492 ) ) ; +#27051 = CONICAL_SURFACE ( 'NONE', #8774, 5.999999999841580056, 0.7853981633778843729 ) ; +#27052 = ORIENTED_EDGE ( 'NONE', *, *, #4323, .T. ) ; +#27053 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2440, #18144, #6093, #3217 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27054 = DIRECTION ( 'NONE', ( 0.0005884949961199716171, -0.2249510543439088850, 0.9743698870671256840 ) ) ; +#27055 = EDGE_LOOP ( 'NONE', ( #6310, #15804, #33482, #19296, #14455, #20300, #5603, #26449, #22588, #34608, #24060, #29152, #9810, #10591, #33375, #4693, #19070, #25819, #17656, #11276, #26720, #38197 ) ) ; +#27056 = EDGE_CURVE ( 'NONE', #12430, #9057, #12173, .T. ) ; +#27057 = CARTESIAN_POINT ( 'NONE', ( 26.49281508937000140, 122.3671901727000062, 90.96660212795001144 ) ) ; +#27058 = LINE ( 'NONE', #23161, #3206 ) ; +#27060 = CARTESIAN_POINT ( 'NONE', ( -28.46611168752988874, 181.6098482732715240, 104.1638139686604063 ) ) ; +#27059 = CARTESIAN_POINT ( 'NONE', ( 1.752039179668189783, 151.6655327357930219, 130.5892088565730091 ) ) ; +#27061 = ORIENTED_EDGE ( 'NONE', *, *, #20396, .T. ) ; +#27062 = ADVANCED_FACE ( 'NONE', ( #34028 ), #24658, .F. ) ; +#27063 = ORIENTED_EDGE ( 'NONE', *, *, #16853, .T. ) ; +#27064 = EDGE_CURVE ( 'NONE', #11505, #33548, #37572, .T. ) ; +#27065 = ADVANCED_FACE ( 'NONE', ( #12764 ), #27253, .T. ) ; +#27066 = EDGE_LOOP ( 'NONE', ( #27734, #17044, #37385, #38878, #30911 ) ) ; +#27067 = EDGE_CURVE ( 'NONE', #5068, #29516, #4351, .T. ) ; +#27068 = CARTESIAN_POINT ( 'NONE', ( -36.29655452800435000, 116.7398215997537250, 87.28970650145031129 ) ) ; +#27069 = EDGE_CURVE ( 'NONE', #19402, #22354, #455, .T. ) ; +#27070 = CARTESIAN_POINT ( 'NONE', ( 45.36150865113177844, 124.3281719932639078, 88.32935533049811738 ) ) ; +#27071 = CARTESIAN_POINT ( 'NONE', ( -32.80403412233768279, 153.0051697192221525, 292.8436197697606076 ) ) ; +#27072 = ORIENTED_EDGE ( 'NONE', *, *, #38885, .F. ) ; +#27073 = AXIS2_PLACEMENT_3D ( 'NONE', #4267, #20414, #10636 ) ; +#27074 = CIRCLE ( 'NONE', #12031, 4.499999999969424458 ) ; +#27075 = ORIENTED_EDGE ( 'NONE', *, *, #20420, .T. ) ; +#27076 = ORIENTED_EDGE ( 'NONE', *, *, #2587, .T. ) ; +#27077 = CARTESIAN_POINT ( 'NONE', ( -28.94810864222802849, 110.6131156702000027, 87.28526822420690223 ) ) ; +#27078 = CIRCLE ( 'NONE', #12067, 2.499999998777807875 ) ; +#27079 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #664, #25638, #37886, #25835 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27080 = CARTESIAN_POINT ( 'NONE', ( 26.02916777764000500, 122.7390752681000095, 88.31594180099000369 ) ) ; +#27081 = ORIENTED_EDGE ( 'NONE', *, *, #27909, .T. ) ; +#27082 = FACE_OUTER_BOUND ( 'NONE', #39141, .T. ) ; +#27083 = CARTESIAN_POINT ( 'NONE', ( 3.075509731022991744, 190.8879536221248543, 106.8135930214097016 ) ) ; +#27084 = EDGE_LOOP ( 'NONE', ( #19136, #7884, #32017, #2165 ) ) ; +#27085 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421484904, 126.1293544849782222, 91.84293499097150004 ) ) ; +#27086 = CARTESIAN_POINT ( 'NONE', ( -6.037299711039155525, 177.1908694358191099, 101.0774571033729785 ) ) ; +#27087 = CARTESIAN_POINT ( 'NONE', ( 3.667815737396929343, 128.0237491602000262, 91.77307785488999059 ) ) ; +#27088 = CARTESIAN_POINT ( 'NONE', ( 3.751221408336166352, 145.8377404464781932, 93.31995143763465705 ) ) ; +#27089 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6108, #34113, #3429, #28598, #6910, #9799, #9590, #15711, #31464, #3633, #37787 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999659717, 0.1874999999999533429, 0.2499999999999407141, 0.4999999999999737987, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27090 = VERTEX_POINT ( 'NONE', #34611 ) ; +#27091 = CARTESIAN_POINT ( 'NONE', ( 5.958856854324413810, 148.4719693777741725, 97.00569074539359349 ) ) ; +#27092 = PLANE ( 'NONE', #18207 ) ; +#27093 = AXIS2_PLACEMENT_3D ( 'NONE', #555, #31864, #7698 ) ; +#27094 = AXIS2_PLACEMENT_3D ( 'NONE', #37771, #3614, #22258 ) ; +#27095 = CONICAL_SURFACE ( 'NONE', #30999, 48.00000000000466116, 0.7853981633973027288 ) ; +#27096 = ORIENTED_EDGE ( 'NONE', *, *, #18611, .F. ) ; +#27097 = EDGE_CURVE ( 'NONE', #3459, #3422, #31580, .T. ) ; +#27098 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049120382, 153.7268358530341743, 98.24418217438510226 ) ) ; +#27099 = AXIS2_PLACEMENT_3D ( 'NONE', #15660, #9540, #33458 ) ; +#27100 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8694, #39943, #11139, #17847 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.1794079282370794892, 1.009264216782575829 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9434301930918600476, 0.9434301930918600476, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#27101 = CARTESIAN_POINT ( 'NONE', ( 15.50029467954679596, 184.8540555714758966, 102.8336351796044426 ) ) ; +#27102 = VERTEX_POINT ( 'NONE', #37107 ) ; +#27104 = EDGE_LOOP ( 'NONE', ( #20833, #32736, #11033, #17493 ) ) ; +#27103 = EDGE_CURVE ( 'NONE', #13591, #3287, #11731, .T. ) ; +#27105 = DIRECTION ( 'NONE', ( 0.0006039760799765779781, 0.000000000000000000, 0.9999998176064307520 ) ) ; +#27106 = ORIENTED_EDGE ( 'NONE', *, *, #22890, .F. ) ; +#27107 = DIRECTION ( 'NONE', ( -0.7933535320750288999, 0.5931614265262136199, 0.1369295264925108890 ) ) ; +#27108 = EDGE_CURVE ( 'NONE', #5671, #5625, #21980, .T. ) ; +#27109 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#27110 = LINE ( 'NONE', #8281, #15702 ) ; +#27111 = CARTESIAN_POINT ( 'NONE', ( 12.64218737472634402, 177.6868538132959827, 100.7583657957452630 ) ) ; +#27112 = ORIENTED_EDGE ( 'NONE', *, *, #21723, .T. ) ; +#27113 = VERTEX_POINT ( 'NONE', #37910 ) ; +#27114 = CARTESIAN_POINT ( 'NONE', ( -37.46813412068708260, 187.1458312067469762, 105.9604857125427060 ) ) ; +#27115 = VERTEX_POINT ( 'NONE', #34418 ) ; +#27116 = VERTEX_POINT ( 'NONE', #27930 ) ; +#27117 = EDGE_CURVE ( 'NONE', #34711, #25492, #6356, .T. ) ; +#27118 = LINE ( 'NONE', #29363, #15212 ) ; +#27119 = CARTESIAN_POINT ( 'NONE', ( -16.85990575226742649, 148.9750591898919652, 176.9023370295861355 ) ) ; +#27120 = CARTESIAN_POINT ( 'NONE', ( 3.036536040797000346, 209.1865194081000254, 73.08174489113000050 ) ) ; +#27121 = ORIENTED_EDGE ( 'NONE', *, *, #19586, .F. ) ; +#27122 = ORIENTED_EDGE ( 'NONE', *, *, #26318, .F. ) ; +#27123 = EDGE_LOOP ( 'NONE', ( #36812, #33633, #8109, #36489 ) ) ; +#27124 = CARTESIAN_POINT ( 'NONE', ( -35.93638238082320413, 190.3639747180721713, 106.7025276796284317 ) ) ; +#27125 = CARTESIAN_POINT ( 'NONE', ( -36.02452622425000328, 191.9021276050999916, 104.3034201498000186 ) ) ; +#27126 = CARTESIAN_POINT ( 'NONE', ( 36.40864326631000125, 191.7024945688000059, 104.2333916175000041 ) ) ; +#27127 = ORIENTED_EDGE ( 'NONE', *, *, #1588, .F. ) ; +#27128 = CARTESIAN_POINT ( 'NONE', ( -25.83460698300319081, 120.7121441152833512, 87.70047778154363982 ) ) ; +#27129 = VECTOR ( 'NONE', #8053, 1000.000000000000114 ) ; +#27130 = ORIENTED_EDGE ( 'NONE', *, *, #6117, .F. ) ; +#27131 = LINE ( 'NONE', #30377, #8196 ) ; +#27132 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; +#27133 = CARTESIAN_POINT ( 'NONE', ( -23.35927170582755252, 176.8628753195245338, 103.2348938219602417 ) ) ; +#27134 = ORIENTED_EDGE ( 'NONE', *, *, #20094, .T. ) ; +#27135 = CIRCLE ( 'NONE', #34921, 5.999999999985974775 ) ; +#27136 = CARTESIAN_POINT ( 'NONE', ( -20.51847108333184977, 208.9445514787146010, 75.69061570010751439 ) ) ; +#27137 = CYLINDRICAL_SURFACE ( 'NONE', #3925, 2.000000000000014655 ) ; +#27138 = CARTESIAN_POINT ( 'NONE', ( -20.00100377755662961, 193.8169056301028945, 102.7149817412491473 ) ) ; +#27139 = ORIENTED_EDGE ( 'NONE', *, *, #19773, .F. ) ; +#27140 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971541810 ) ) ; +#27141 = CARTESIAN_POINT ( 'NONE', ( -35.45366962857106330, 209.7096538831000032, 78.07991812242501339 ) ) ; +#27142 = CARTESIAN_POINT ( 'NONE', ( -28.46737701145232791, 131.0177980776269067, 89.91795667690330163 ) ) ; +#27143 = ORIENTED_EDGE ( 'NONE', *, *, #15969, .T. ) ; +#27144 = CARTESIAN_POINT ( 'NONE', ( 30.03671969012000176, 185.1161778121999930, 105.1945559053000068 ) ) ; +#27145 = ORIENTED_EDGE ( 'NONE', *, *, #8299, .F. ) ; +#27146 = VERTEX_POINT ( 'NONE', #15820 ) ; +#27147 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#27148 = FACE_OUTER_BOUND ( 'NONE', #22519, .T. ) ; +#27149 = CARTESIAN_POINT ( 'NONE', ( -20.89285664280696864, 129.6089482465050366, 89.58812326051432251 ) ) ; +#27150 = CARTESIAN_POINT ( 'NONE', ( 77.77061555252048208, 193.1292924429064328, 190.4585453522111322 ) ) ; +#27151 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -2.074124140377000483E-15, -0.0006039748319395083463 ) ) ; +#27152 = ADVANCED_FACE ( 'NONE', ( #31178 ), #9601, .F. ) ; +#27153 = EDGE_LOOP ( 'NONE', ( #32177, #5061, #39918, #31755 ) ) ; +#27154 = EDGE_CURVE ( 'NONE', #20460, #16454, #4552, .T. ) ; +#27155 = EDGE_CURVE ( 'NONE', #12177, #39651, #8330, .T. ) ; +#27156 = EDGE_CURVE ( 'NONE', #12519, #21533, #38105, .T. ) ; +#27157 = AXIS2_PLACEMENT_3D ( 'NONE', #15413, #70, #36672 ) ; +#27158 = CARTESIAN_POINT ( 'NONE', ( -13.46986788395000012, 176.3366685932843154, 152.9217693939943388 ) ) ; +#27159 = CONICAL_SURFACE ( 'NONE', #17980, 4.999999999985747401, 0.7853981633878592827 ) ; +#27160 = VECTOR ( 'NONE', #9073, 1000.000000000000114 ) ; +#27161 = CARTESIAN_POINT ( 'NONE', ( -15.83167356403315473, 184.3257607663358044, 105.1253098898049387 ) ) ; +#27163 = AXIS2_PLACEMENT_3D ( 'NONE', #33529, #5524, #30491 ) ; +#27162 = CARTESIAN_POINT ( 'NONE', ( -2.853038766185818087, 209.7096500570610544, 73.06022702708840200 ) ) ; +#27164 = EDGE_CURVE ( 'NONE', #16454, #14577, #878, .T. ) ; +#27165 = CARTESIAN_POINT ( 'NONE', ( 20.33352780025000683, 184.8935324260419009, 102.6687779362811028 ) ) ; +#27166 = CARTESIAN_POINT ( 'NONE', ( 30.39240633519054668, 177.7944416303146511, 100.6816479718193165 ) ) ; +#27167 = AXIS2_PLACEMENT_3D ( 'NONE', #9816, #22289, #6721 ) ; +#27168 = CARTESIAN_POINT ( 'NONE', ( -14.42530067724887211, 135.8540152427108865, 91.19705531837325907 ) ) ; +#27169 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12240, #27405, #11843, #15108, #24728, #8776, #21240, #34094, #33689, #37372, #5696, #9373, #33896, #21847, #18739, #40033, #3216, #15692, #8980, #18142, #18348, #27603, #30647, #2643, #12040, #24522, #36980, #28978, #3609, #4213, #9776, #25732, #15887, #38182, #19562, #16689, #7088 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 1, 1, 2, 2, 2, 1, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000004381218, 0.1875000000006571965, 0.2500000000008762435, 0.3750000000013145041, 0.4375000000015357715, 0.4687500000016565083, 0.4843750000017174595, 0.4921875000018005597, 0.4960937500018024471, 0.5000000000018044455, 0.6250000000013739010, 0.6875000000011586287, 0.7187500000010510481, 0.7500000000009433565, 0.8125000000007281953, 0.8750000000005129230, 0.9375000000002976508, 0.9687500000001487699, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27170 = CARTESIAN_POINT ( 'NONE', ( 20.00140612192502942, 118.1043503129110093, 90.25575274657424529 ) ) ; +#27171 = ORIENTED_EDGE ( 'NONE', *, *, #32975, .F. ) ; +#27172 = ADVANCED_FACE ( 'NONE', ( #13369 ), #21362, .F. ) ; +#27173 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#27174 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#27175 = ORIENTED_EDGE ( 'NONE', *, *, #7047, .T. ) ; +#27176 = CARTESIAN_POINT ( 'NONE', ( 2.564136881974701687, 190.9806058647903910, 106.3073107177100383 ) ) ; +#27177 = CARTESIAN_POINT ( 'NONE', ( 15.99994032177352921, 147.4776376511197782, 93.69121532839281485 ) ) ; +#27178 = EDGE_LOOP ( 'NONE', ( #546, #37528, #40116, #19962 ) ) ; +#27179 = ADVANCED_FACE ( 'NONE', ( #29314 ), #25931, .F. ) ; +#27180 = DIRECTION ( 'NONE', ( -0.0005884949961217841863, 0.2249510543439048882, -0.9743698870671267942 ) ) ; +#27181 = ORIENTED_EDGE ( 'NONE', *, *, #27155, .F. ) ; +#27182 = CARTESIAN_POINT ( 'NONE', ( 35.75412536925829698, 191.7929377062473861, 106.8971639774647144 ) ) ; +#27183 = CARTESIAN_POINT ( 'NONE', ( -35.45668950273073250, 209.7096538831000032, 73.07991903442916737 ) ) ; +#27184 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; +#27185 = CIRCLE ( 'NONE', #7559, 2.000000000024883651 ) ; +#27186 = CARTESIAN_POINT ( 'NONE', ( -12.63088703835403237, 131.0198726340251199, 89.90887950976862442 ) ) ; +#27187 = CARTESIAN_POINT ( 'NONE', ( -22.49962777877401265, 154.4034663070004285, 95.31336199324331915 ) ) ; +#27188 = CIRCLE ( 'NONE', #32384, 9.500000000010519585 ) ; +#27189 = ORIENTED_EDGE ( 'NONE', *, *, #12639, .T. ) ; +#27190 = CARTESIAN_POINT ( 'NONE', ( 39.30609899383000538, 120.4425404122000174, 87.28662907337999854 ) ) ; +#27191 = CARTESIAN_POINT ( 'NONE', ( 24.12242862685433664, 148.1961789144971817, 202.2538657011056102 ) ) ; +#27192 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -6.964038142101568045E-16, -0.0006039748319386693907 ) ) ; +#27193 = VECTOR ( 'NONE', #32474, 1000.000000000000114 ) ; +#27194 = DIRECTION ( 'NONE', ( 0.0005884949961235587000, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#27195 = ORIENTED_EDGE ( 'NONE', *, *, #32541, .T. ) ; +#27196 = CARTESIAN_POINT ( 'NONE', ( -42.81549985150758886, 107.4643023349349136, 150.2765521728149736 ) ) ; +#27197 = CARTESIAN_POINT ( 'NONE', ( -42.51147045056379170, 121.3536403223778990, 91.20814212496861728 ) ) ; +#27198 = CARTESIAN_POINT ( 'NONE', ( 20.50176505208000322, 122.6615237520999955, 91.03809521265999649 ) ) ; +#27199 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#27200 = CARTESIAN_POINT ( 'NONE', ( -8.473620765651141085, 161.4179317431856475, 97.43745832156695030 ) ) ; +#27201 = EDGE_CURVE ( 'NONE', #38073, #36559, #16419, .T. ) ; +#27202 = ADVANCED_FACE ( 'NONE', ( #10513 ), #7625, .F. ) ; +#27203 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971541255 ) ) ; +#27204 = CARTESIAN_POINT ( 'NONE', ( 33.97154681763998951, 93.67127063227000860, 291.5380259722100504 ) ) ; +#27205 = CARTESIAN_POINT ( 'NONE', ( -38.87088589341672673, 169.4517328299331780, 182.9034801424807029 ) ) ; +#27206 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; +#27207 = CARTESIAN_POINT ( 'NONE', ( 25.99865086485452537, 120.9964097819282642, 87.57144042600342004 ) ) ; +#27208 = CARTESIAN_POINT ( 'NONE', ( 15.99998384348811875, 126.8035267017516787, 88.91816380576780432 ) ) ; +#27209 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563182 ) ) ; +#27210 = CARTESIAN_POINT ( 'NONE', ( 3.784352160272999921, 140.7284765685000139, 92.39694077657001969 ) ) ; +#27211 = EDGE_CURVE ( 'NONE', #33804, #17164, #14190, .T. ) ; +#27212 = VECTOR ( 'NONE', #12061, 1000.000000000000114 ) ; +#27213 = CARTESIAN_POINT ( 'NONE', ( 38.93356763724558078, 170.2781293624805699, 164.4932373185801850 ) ) ; +#27214 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -4.437389905419016117E-16, 0.0006039748319385540316 ) ) ; +#27215 = CONICAL_SURFACE ( 'NONE', #15430, 2.503093623396721146, 0.7853981633639495197 ) ; +#27216 = EDGE_LOOP ( 'NONE', ( #28960, #8493, #39954, #39043 ) ) ; +#27218 = VERTEX_POINT ( 'NONE', #23782 ) ; +#27217 = CARTESIAN_POINT ( 'NONE', ( 42.93478411035056297, 121.9318606513537020, 87.77717731540884927 ) ) ; +#27219 = ORIENTED_EDGE ( 'NONE', *, *, #5331, .T. ) ; +#27220 = ORIENTED_EDGE ( 'NONE', *, *, #34487, .F. ) ; +#27221 = EDGE_CURVE ( 'NONE', #4804, #11374, #38307, .T. ) ; +#27222 = CARTESIAN_POINT ( 'NONE', ( -1.525667636861250287, 188.8616647511590543, 103.2559959374175236 ) ) ; +#27223 = ORIENTED_EDGE ( 'NONE', *, *, #26703, .F. ) ; +#27224 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 136.7477301991403920, 291.5295797804309359 ) ) ; +#27225 = VECTOR ( 'NONE', #11563, 1000.000000000000114 ) ; +#27226 = PLANE ( 'NONE', #26535 ) ; +#27227 = CARTESIAN_POINT ( 'NONE', ( 17.25783335673383689, 152.2632692426403196, 183.6728012514050477 ) ) ; +#27228 = DIRECTION ( 'NONE', ( -0.7857167650892391553, 0.6185862428610305885, 0.0004745532376930882020 ) ) ; +#27229 = AXIS2_PLACEMENT_3D ( 'NONE', #26571, #32877, #32294 ) ; +#27230 = ORIENTED_EDGE ( 'NONE', *, *, #5435, .T. ) ; +#27231 = DIRECTION ( 'NONE', ( -0.7075337269147008445, -1.091623643673001211E-14, -0.7066795775160008564 ) ) ; +#27232 = EDGE_CURVE ( 'NONE', #13439, #275, #5152, .T. ) ; +#27233 = FACE_OUTER_BOUND ( 'NONE', #39971, .T. ) ; +#27234 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; +#27235 = CARTESIAN_POINT ( 'NONE', ( -21.10558883492248583, 128.7602791373870730, 92.12913287932676099 ) ) ; +#27236 = CARTESIAN_POINT ( 'NONE', ( -13.00716834305086955, 131.0198804054314223, 89.90909991712500471 ) ) ; +#27237 = VERTEX_POINT ( 'NONE', #8028 ) ; +#27238 = CARTESIAN_POINT ( 'NONE', ( -23.01874678158921839, 213.5902083388722303, 75.57231541044464507 ) ) ; +#27239 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048966905, 181.0091974213203230, 104.5428127881150999 ) ) ; +#27240 = CARTESIAN_POINT ( 'NONE', ( -13.50000077923909636, 138.1929969156116726, 91.56544231091193353 ) ) ; +#27241 = CARTESIAN_POINT ( 'NONE', ( -20.49852807266789867, 190.9630690214611946, 106.3183227610936541 ) ) ; +#27242 = VERTEX_POINT ( 'NONE', #23992 ) ; +#27243 = CARTESIAN_POINT ( 'NONE', ( -26.33557301288999852, 190.3678653649000125, 103.4797773831000001 ) ) ; +#27244 = CARTESIAN_POINT ( 'NONE', ( 0.8401941610674000804, 188.8905993856999999, 103.5322243624000009 ) ) ; +#27245 = CARTESIAN_POINT ( 'NONE', ( 27.17743447187414318, 123.4215292580052221, 91.20952440399904049 ) ) ; +#27246 = AXIS2_PLACEMENT_3D ( 'NONE', #9919, #38499, #29514 ) ; +#27247 = ORIENTED_EDGE ( 'NONE', *, *, #19761, .T. ) ; +#27248 = ORIENTED_EDGE ( 'NONE', *, *, #35275, .F. ) ; +#27249 = LINE ( 'NONE', #21302, #40083 ) ; +#27250 = AXIS2_PLACEMENT_3D ( 'NONE', #3693, #19027, #25603 ) ; +#27251 = ORIENTED_EDGE ( 'NONE', *, *, #35017, .F. ) ; +#27252 = VECTOR ( 'NONE', #31915, 1000.000000000000114 ) ; +#27253 = CONICAL_SURFACE ( 'NONE', #36358, 5.999999999818071750, 0.7853981634251957500 ) ; +#27254 = VERTEX_POINT ( 'NONE', #14378 ) ; +#27255 = ORIENTED_EDGE ( 'NONE', *, *, #7499, .T. ) ; +#27256 = EDGE_CURVE ( 'NONE', #31088, #8695, #32775, .T. ) ; +#27257 = ADVANCED_FACE ( 'NONE', ( #4752 ), #20487, .T. ) ; +#27258 = CARTESIAN_POINT ( 'NONE', ( 23.36440065337908223, 177.7945738895225247, 100.6859232455937416 ) ) ; +#27259 = LINE ( 'NONE', #24182, #27364 ) ; +#27260 = CARTESIAN_POINT ( 'NONE', ( 39.00196056141868439, 77.94040643632342835, 289.0507669139796008 ) ) ; +#27261 = EDGE_LOOP ( 'NONE', ( #14735, #2976, #10611, #27922, #13481 ) ) ; +#27262 = DIRECTION ( 'NONE', ( -0.9914446601362026934, 0.1270323331361944419, 0.03000453674670350637 ) ) ; +#27263 = CARTESIAN_POINT ( 'NONE', ( 27.65309753470299725, 123.9773721635429951, 91.33935050507260200 ) ) ; +#27264 = CARTESIAN_POINT ( 'NONE', ( -21.57450310159030238, 182.6228315559495741, 101.9988072502208212 ) ) ; +#27266 = DIRECTION ( 'NONE', ( -0.0005884949961210389057, 0.2249510543439053878, -0.9743698870671265722 ) ) ; +#27265 = CARTESIAN_POINT ( 'NONE', ( 30.80382538193063269, 110.6131156702000027, 87.74917964457411301 ) ) ; +#27267 = ORIENTED_EDGE ( 'NONE', *, *, #36545, .F. ) ; +#27268 = CARTESIAN_POINT ( 'NONE', ( 3.683263386174287390, 143.5730025742587941, 95.72479304125442923 ) ) ; +#27269 = VERTEX_POINT ( 'NONE', #14792 ) ; +#27270 = AXIS2_PLACEMENT_3D ( 'NONE', #27077, #4963, #23996 ) ; +#27271 = CONICAL_SURFACE ( 'NONE', #20047, 6.500000265539895850, 0.7853981634182136684 ) ; +#27272 = ORIENTED_EDGE ( 'NONE', *, *, #28303, .F. ) ; +#27273 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#27274 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22391, #26261, #31795, #35221, #35612, #13772, #31990, #29122, #20090, #10519, #17014, #1493, #32581, #16230, #19691, #10115, #4356 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999995810573, 0.1874999999994061417, 0.2187499999993340605, 0.2343749999993136601, 0.2499999999992932320, 0.3749999999992274513, 0.4374999999992445487, 0.4687499999992961186, 0.4999999999993476330, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27275 = CARTESIAN_POINT ( 'NONE', ( 0.05451946023377000211, 104.1131156707999992, 90.26775191081999594 ) ) ; +#27276 = LINE ( 'NONE', #25008, #7168 ) ; +#27277 = CARTESIAN_POINT ( 'NONE', ( 12.63590952075130680, 130.8251385450179498, 90.01817474871077707 ) ) ; +#27278 = ORIENTED_EDGE ( 'NONE', *, *, #10016, .T. ) ; +#27279 = ORIENTED_EDGE ( 'NONE', *, *, #14827, .T. ) ; +#27280 = ORIENTED_EDGE ( 'NONE', *, *, #15367, .T. ) ; +#27281 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25366, #37816, #13088, #34727 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27282 = DIRECTION ( 'NONE', ( -0.6075493383219883192, 0.7739051213223903103, 0.1787586772592882622 ) ) ; +#27283 = DIRECTION ( 'NONE', ( 0.6087614810001779064, -0.7729390313185916517, -0.1788147452386051328 ) ) ; +#27284 = CARTESIAN_POINT ( 'NONE', ( 27.64719006305000093, 124.9731607461000209, 88.83074499660999379 ) ) ; +#27285 = ORIENTED_EDGE ( 'NONE', *, *, #23671, .T. ) ; +#27286 = CARTESIAN_POINT ( 'NONE', ( 2.563067459505968149, 191.9759150222000130, 104.4198997672286708 ) ) ; +#27287 = CARTESIAN_POINT ( 'NONE', ( 16.00175042068614317, 126.1291850884666559, 91.84138073825745607 ) ) ; +#27288 = EDGE_CURVE ( 'NONE', #19255, #32274, #17819, .T. ) ; +#27289 = CARTESIAN_POINT ( 'NONE', ( 0.7279486067032001628, 188.9986663015000090, 105.7364963328000158 ) ) ; +#27290 = CARTESIAN_POINT ( 'NONE', ( -20.51978786315646630, 209.7094320854081104, 73.57086927696296641 ) ) ; +#27291 = EDGE_CURVE ( 'NONE', #30592, #21265, #17626, .T. ) ; +#27292 = CARTESIAN_POINT ( 'NONE', ( 13.49904929520333496, 124.5822511035611200, 88.69986977077229540 ) ) ; +#27293 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#27294 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394469186868, 3.303562273565746580E-12, 297.5584364845187224 ) ) ; +#27295 = CIRCLE ( 'NONE', #22703, 6.499999999995704769 ) ; +#27296 = VERTEX_POINT ( 'NONE', #14985 ) ; +#27297 = CARTESIAN_POINT ( 'NONE', ( -20.50092100153493746, 194.2771564787859120, 102.9104786413515740 ) ) ; +#27298 = EDGE_CURVE ( 'NONE', #10469, #32129, #36854, .T. ) ; +#27299 = EDGE_CURVE ( 'NONE', #28855, #7552, #24419, .T. ) ; +#27300 = CARTESIAN_POINT ( 'NONE', ( 25.12855288015667909, 121.2316270687496882, 173.3448655832455927 ) ) ; +#27301 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24358, #11459, #15337, #23947 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27302 = AXIS2_PLACEMENT_3D ( 'NONE', #11293, #30112, #20903 ) ; +#27303 = CARTESIAN_POINT ( 'NONE', ( -20.23987729197799723, 127.1213856368363935, 91.84448901990914749 ) ) ; +#27304 = EDGE_CURVE ( 'NONE', #27296, #9728, #20707, .T. ) ; +#27305 = ORIENTED_EDGE ( 'NONE', *, *, #37287, .F. ) ; +#27306 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825843381894153, 0.0005734119041516987309 ) ) ; +#27307 = VERTEX_POINT ( 'NONE', #26861 ) ; +#27309 = FACE_OUTER_BOUND ( 'NONE', #5744, .T. ) ; +#27308 = CARTESIAN_POINT ( 'NONE', ( -13.49852954174943775, 184.4003819578410628, 104.7990195063615886 ) ) ; +#27310 = ORIENTED_EDGE ( 'NONE', *, *, #37797, .F. ) ; +#27311 = ORIENTED_EDGE ( 'NONE', *, *, #5138, .T. ) ; +#27312 = EDGE_LOOP ( 'NONE', ( #25919, #17193 ) ) ; +#27313 = CARTESIAN_POINT ( 'NONE', ( 2.858838700789999798, 209.5740437366000322, 75.93782419666000294 ) ) ; +#27314 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#27315 = CARTESIAN_POINT ( 'NONE', ( -15.91639284609066429, 147.2972547718010503, 179.5564254920589633 ) ) ; +#27316 = LINE ( 'NONE', #37493, #29292 ) ; +#27317 = VERTEX_POINT ( 'NONE', #26656 ) ; +#27318 = ORIENTED_EDGE ( 'NONE', *, *, #36781, .T. ) ; +#27319 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501099925, 179.0628333272265138, 104.0826189413126741 ) ) ; +#27320 = ORIENTED_EDGE ( 'NONE', *, *, #34798, .F. ) ; +#27321 = ORIENTED_EDGE ( 'NONE', *, *, #5103, .F. ) ; +#27322 = DIRECTION ( 'NONE', ( 0.0005884949961243941862, -0.2249510543439062205, 0.9743698870671264611 ) ) ; +#27323 = FACE_OUTER_BOUND ( 'NONE', #16621, .T. ) ; +#27324 = CARTESIAN_POINT ( 'NONE', ( -30.05378917699556141, 127.2828694753868319, 89.56979070794703546 ) ) ; +#27325 = CARTESIAN_POINT ( 'NONE', ( 5.666342391617226859, 126.8038441147938897, 88.92139996541325786 ) ) ; +#27326 = ORIENTED_EDGE ( 'NONE', *, *, #11539, .F. ) ; +#27327 = VECTOR ( 'NONE', #25162, 1000.000000000000000 ) ; +#27328 = VERTEX_POINT ( 'NONE', #29918 ) ; +#27329 = DIRECTION ( 'NONE', ( -8.673617379883985182E-16, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#27330 = CARTESIAN_POINT ( 'NONE', ( -35.83302225680999697, 192.4812670013000400, 104.2666808249000070 ) ) ; +#27331 = ORIENTED_EDGE ( 'NONE', *, *, #3306, .T. ) ; +#27332 = CARTESIAN_POINT ( 'NONE', ( -25.50236185757985652, 120.6126476325595149, 88.02435165278710372 ) ) ; +#27333 = AXIS2_PLACEMENT_3D ( 'NONE', #13609, #29550, #10552 ) ; +#27334 = EDGE_LOOP ( 'NONE', ( #11600, #8318, #31195, #23994 ) ) ; +#27335 = DIRECTION ( 'NONE', ( 0.7933530821293333091, 0.5932640870757639462, 0.1364866662427067501 ) ) ; +#27336 = LINE ( 'NONE', #11783, #2334 ) ; +#27337 = CARTESIAN_POINT ( 'NONE', ( 40.92065053834265598, 188.7133225016582401, 107.4565697015391237 ) ) ; +#27338 = ORIENTED_EDGE ( 'NONE', *, *, #14679, .F. ) ; +#27339 = EDGE_CURVE ( 'NONE', #30846, #11409, #29718, .T. ) ; +#27340 = CARTESIAN_POINT ( 'NONE', ( 2.617027381767905947, 189.6880601662373067, 103.4442823028655312 ) ) ; +#27341 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364886960122, 136.5649596138813706, 181.4686487119530511 ) ) ; +#27342 = CARTESIAN_POINT ( 'NONE', ( -18.71851310314255556, 125.9964326179262883, 174.7342168340691444 ) ) ; +#27343 = ORIENTED_EDGE ( 'NONE', *, *, #15186, .T. ) ; +#27344 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319390009397 ) ) ; +#27345 = EDGE_CURVE ( 'NONE', #29247, #36212, #3715, .T. ) ; +#27346 = CARTESIAN_POINT ( 'NONE', ( -45.17838929977841644, 181.0906312430929574, 102.0014284585363669 ) ) ; +#27347 = CARTESIAN_POINT ( 'NONE', ( -2.464592264399565469, 152.1442425547639630, 99.91119810786710786 ) ) ; +#27348 = EDGE_CURVE ( 'NONE', #33558, #17622, #24406, .T. ) ; +#27349 = ORIENTED_EDGE ( 'NONE', *, *, #37295, .T. ) ; +#27350 = CARTESIAN_POINT ( 'NONE', ( 23.39899582248410326, 115.1133771340589078, 90.25365243206073274 ) ) ; +#27351 = ORIENTED_EDGE ( 'NONE', *, *, #35445, .F. ) ; +#27352 = FACE_OUTER_BOUND ( 'NONE', #20030, .T. ) ; +#27353 = ADVANCED_FACE ( 'NONE', ( #11715 ), #21372, .F. ) ; +#27354 = DIRECTION ( 'NONE', ( 0.0005884949961234757585, -0.2249510543439061094, 0.9743698870671263501 ) ) ; +#27355 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #12251, #14724, #18360, #30460 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.7409400382494353288, 1.570796326794934972 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9434301930918597145, 0.9434301930918597145, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#27356 = CARTESIAN_POINT ( 'NONE', ( 35.93444066825000505, 112.3658808786999970, 89.86862849967999978 ) ) ; +#27357 = EDGE_CURVE ( 'NONE', #3915, #34342, #10921, .T. ) ; +#27358 = CIRCLE ( 'NONE', #20815, 22.50000000000000000 ) ; +#27359 = EDGE_CURVE ( 'NONE', #9444, #19947, #34577, .T. ) ; +#27360 = CARTESIAN_POINT ( 'NONE', ( 16.16793458963470442, 152.6396212324820283, 181.6320889425181520 ) ) ; +#27361 = CARTESIAN_POINT ( 'NONE', ( 39.06349078196001301, 191.0388279120988670, 103.7341189576915355 ) ) ; +#27362 = ORIENTED_EDGE ( 'NONE', *, *, #7322, .T. ) ; +#27363 = AXIS2_PLACEMENT_3D ( 'NONE', #25219, #12727, #34575 ) ; +#27364 = VECTOR ( 'NONE', #36631, 1000.000000000000114 ) ; +#27365 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7787, #32738, #17179, #14149 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.1624460549302637891 ), + .UNSPECIFIED. ) ; +#27366 = AXIS2_PLACEMENT_3D ( 'NONE', #17006, #13968, #25655 ) ; +#27367 = CARTESIAN_POINT ( 'NONE', ( -22.78369572533183884, 164.5218417749696584, 98.16269547346880131 ) ) ; +#27368 = PLANE ( 'NONE', #9967 ) ; +#27369 = CARTESIAN_POINT ( 'NONE', ( 25.99899579568001329, 120.3902236066962388, 87.43149108637626910 ) ) ; +#27370 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567623 ) ) ; +#27371 = CARTESIAN_POINT ( 'NONE', ( 20.50029254611199292, 184.8549113859068029, 102.8308091169877798 ) ) ; +#27372 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#27373 = CARTESIAN_POINT ( 'NONE', ( 30.07478355117409308, 177.7951688118731681, 100.6820556990014950 ) ) ; +#27374 = CARTESIAN_POINT ( 'NONE', ( -13.55691060191180064, 164.5230632409279110, 98.15740472410433881 ) ) ; +#27375 = CARTESIAN_POINT ( 'NONE', ( 13.55396812693302522, 147.9623613014291266, 94.31769043477856940 ) ) ; +#27376 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15869, #9152, #333, #34074 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27377 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799573900, 177.7873482353427619, 100.7165294113391383 ) ) ; +#27378 = ORIENTED_EDGE ( 'NONE', *, *, #20289, .T. ) ; +#27379 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250095450, 179.6252109630099767, 101.6466942237843796 ) ) ; +#27380 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394468896823, 3.782579493148625290E-12, 297.5584364845186087 ) ) ; +#27381 = ORIENTED_EDGE ( 'NONE', *, *, #2449, .F. ) ; +#27382 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; +#27383 = CARTESIAN_POINT ( 'NONE', ( -19.99964517258172947, 117.7157836421189216, 90.27986412374295355 ) ) ; +#27384 = ORIENTED_EDGE ( 'NONE', *, *, #34626, .T. ) ; +#27385 = CARTESIAN_POINT ( 'NONE', ( -38.12611163673999926, 119.3162191407000137, 87.30866421832999436 ) ) ; +#27386 = CIRCLE ( 'NONE', #12324, 4.999999999999994671 ) ; +#27387 = DIRECTION ( 'NONE', ( 0.7856007465114022148, 0.6187337610642621444, 0.000000000000000000 ) ) ; +#27388 = CARTESIAN_POINT ( 'NONE', ( -3.651672906231635540, 143.5611994651619909, 95.75907850071710925 ) ) ; +#27389 = ORIENTED_EDGE ( 'NONE', *, *, #11677, .T. ) ; +#27390 = LINE ( 'NONE', #15494, #7247 ) ; +#27391 = EDGE_CURVE ( 'NONE', #8395, #15910, #1906, .T. ) ; +#27392 = ADVANCED_FACE ( 'NONE', ( #8242 ), #40311, .T. ) ; +#27393 = AXIS2_PLACEMENT_3D ( 'NONE', #21039, #39417, #20203 ) ; +#27394 = CARTESIAN_POINT ( 'NONE', ( -45.08998768082118858, 123.9203394008390546, 88.31264828985601412 ) ) ; +#27395 = CIRCLE ( 'NONE', #7758, 51.40509898896370089 ) ; +#27396 = EDGE_CURVE ( 'NONE', #30695, #14229, #28461, .T. ) ; +#27397 = CARTESIAN_POINT ( 'NONE', ( -38.39983396593000720, 119.0472737981999956, 90.29717073674000005 ) ) ; +#27398 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091565633 ) ) ; +#27399 = CIRCLE ( 'NONE', #32582, 2.000000000000000000 ) ; +#27400 = CARTESIAN_POINT ( 'NONE', ( -5.672125672682539310, 124.4606923108509733, 88.52038950313867360 ) ) ; +#27401 = ORIENTED_EDGE ( 'NONE', *, *, #7399, .F. ) ; +#27402 = CARTESIAN_POINT ( 'NONE', ( 38.12805139583999647, 119.0312398597000083, 87.35084105904999774 ) ) ; +#27403 = EDGE_CURVE ( 'NONE', #7664, #20184, #22455, .T. ) ; +#27404 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 1.222278445071001364E-14, 0.7075337269147008445 ) ) ; +#27405 = CARTESIAN_POINT ( 'NONE', ( 37.84581718655127958, 191.4135594927475097, 104.3344286323177954 ) ) ; +#27406 = ORIENTED_EDGE ( 'NONE', *, *, #24939, .F. ) ; +#27407 = LINE ( 'NONE', #22050, #31469 ) ; +#27408 = ORIENTED_EDGE ( 'NONE', *, *, #35730, .T. ) ; +#27409 = ORIENTED_EDGE ( 'NONE', *, *, #6799, .F. ) ; +#27410 = CARTESIAN_POINT ( 'NONE', ( 25.01935866475762182, 130.6173723549316605, 89.79320596012071576 ) ) ; +#27411 = FACE_OUTER_BOUND ( 'NONE', #10043, .T. ) ; +#27412 = DIRECTION ( 'NONE', ( -0.7933535320750290110, 0.5931614265262136199, 0.1369295264925107503 ) ) ; +#27413 = DIRECTION ( 'NONE', ( 0.0005884933334881037141, -0.2249510526608013983, 0.9743698874567060519 ) ) ; +#27414 = EDGE_CURVE ( 'NONE', #39678, #5998, #35138, .T. ) ; +#27415 = DIRECTION ( 'NONE', ( 0.7933535325932937754, -0.5931614258681804364, -0.1369295263402622864 ) ) ; +#27416 = CARTESIAN_POINT ( 'NONE', ( 47.89610325056636952, 151.2242448213897319, 192.5437635430896819 ) ) ; +#27417 = CARTESIAN_POINT ( 'NONE', ( 12.31559066567325367, 137.3572934308675713, 91.35375981364765607 ) ) ; +#27418 = DIRECTION ( 'NONE', ( -0.7933532411131102302, -0.5932638852154232811, -0.1364866195435443241 ) ) ; +#27419 = EDGE_CURVE ( 'NONE', #29667, #16580, #27386, .T. ) ; +#27420 = CONICAL_SURFACE ( 'NONE', #574, 4.999999999982097876, 0.7853981633697728615 ) ; +#27421 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35370, #16381, #34961, #16186, #26217, #12935 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27422 = MECHANICAL_CONTEXT ( 'NONE', #17458, 'mechanical' ) ; +#27423 = PLANE ( 'NONE', #33063 ) ; +#27424 = CYLINDRICAL_SURFACE ( 'NONE', #26962, 2.000000000000014655 ) ; +#27425 = DIRECTION ( 'NONE', ( -0.7066905416103477222, -0.1590642632756053831, 0.6894106458034008345 ) ) ; +#27426 = CARTESIAN_POINT ( 'NONE', ( -35.45366962862317450, 209.7096538831000032, 78.07991812243204777 ) ) ; +#27427 = CIRCLE ( 'NONE', #14989, 2.499999999576044907 ) ; +#27428 = CARTESIAN_POINT ( 'NONE', ( -13.55573361191907900, 164.0731611322038077, 100.1061444981561408 ) ) ; +#27429 = CARTESIAN_POINT ( 'NONE', ( -20.00111603559079398, 118.1131148921541438, 87.27965578728156970 ) ) ; +#27430 = VECTOR ( 'NONE', #10450, 1000.000000000000114 ) ; +#27431 = CIRCLE ( 'NONE', #21546, 5.499999999739705991 ) ; +#27433 = ORIENTED_EDGE ( 'NONE', *, *, #28345, .T. ) ; +#27432 = FACE_OUTER_BOUND ( 'NONE', #23361, .T. ) ; +#27434 = ORIENTED_EDGE ( 'NONE', *, *, #20292, .F. ) ; +#27435 = ORIENTED_EDGE ( 'NONE', *, *, #10517, .T. ) ; +#27436 = DIRECTION ( 'NONE', ( 0.0005884949961247527318, -0.2249510186043635618, 0.9743698953182508005 ) ) ; +#27437 = ORIENTED_EDGE ( 'NONE', *, *, #18306, .F. ) ; +#27438 = CARTESIAN_POINT ( 'NONE', ( -12.64562993050861550, 181.6872450680611450, 101.6064063805796280 ) ) ; +#27439 = CARTESIAN_POINT ( 'NONE', ( 15.94054669826102177, 152.1475402096681080, 184.5616883112009816 ) ) ; +#27440 = CARTESIAN_POINT ( 'NONE', ( -20.33171350620593998, 151.3650611303846745, 97.34744253172874551 ) ) ; +#27441 = ORIENTED_EDGE ( 'NONE', *, *, #14118, .T. ) ; +#27442 = CARTESIAN_POINT ( 'NONE', ( 17.00047812746359810, 137.4649845012766889, 177.5753949225429551 ) ) ; +#27443 = CARTESIAN_POINT ( 'NONE', ( -15.92170901910063030, 128.4476379086294742, 89.31701114597424862 ) ) ; +#27444 = FACE_OUTER_BOUND ( 'NONE', #28459, .T. ) ; +#27445 = ORIENTED_EDGE ( 'NONE', *, *, #21427, .T. ) ; +#27446 = DIRECTION ( 'NONE', ( -3.172065784687725564E-14, -1.000000000000000000, 1.586032892343862782E-14 ) ) ; +#27448 = ADVANCED_FACE ( 'NONE', ( #434 ), #27882, .F. ) ; +#27447 = CARTESIAN_POINT ( 'NONE', ( 23.00089693216080988, 115.1133509736824152, 90.25389292129368357 ) ) ; +#27449 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923097663, 174.5173791610835394, 99.93528093894383346 ) ) ; +#27450 = EDGE_CURVE ( 'NONE', #25001, #24833, #5123, .T. ) ; +#27451 = CARTESIAN_POINT ( 'NONE', ( 36.04593084803799741, 218.5902260770999987, 76.03673379060180082 ) ) ; +#27452 = LINE ( 'NONE', #9419, #11919 ) ; +#27453 = ORIENTED_EDGE ( 'NONE', *, *, #31380, .F. ) ; +#27454 = AXIS2_PLACEMENT_3D ( 'NONE', #2776, #27739, #15449 ) ; +#27455 = CARTESIAN_POINT ( 'NONE', ( -27.05502880751999939, 187.5923345152000081, 103.6304557127999999 ) ) ; +#27456 = VECTOR ( 'NONE', #36907, 1000.000000000000000 ) ; +#27457 = CARTESIAN_POINT ( 'NONE', ( 1.112502188512960233, 189.0830338811350089, 103.7168849198249916 ) ) ; +#27458 = CARTESIAN_POINT ( 'NONE', ( 19.98271301993268523, 207.8686081833218111, 77.26500776042075813 ) ) ; +#27459 = EDGE_CURVE ( 'NONE', #8778, #2569, #28017, .T. ) ; +#27460 = AXIS2_PLACEMENT_3D ( 'NONE', #39647, #17962, #1629 ) ; +#27461 = VECTOR ( 'NONE', #35836, 1000.000000000000114 ) ; +#27462 = ORIENTED_EDGE ( 'NONE', *, *, #28253, .F. ) ; +#27463 = CARTESIAN_POINT ( 'NONE', ( -38.92541764308131036, 120.0374990424048463, 87.39585669205436602 ) ) ; +#27464 = ORIENTED_EDGE ( 'NONE', *, *, #8872, .T. ) ; +#27465 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9951, #10154, #35440, #19123 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27466 = ADVANCED_FACE ( 'NONE', ( #18228 ), #15584, .F. ) ; +#27467 = ORIENTED_EDGE ( 'NONE', *, *, #26829, .F. ) ; +#27468 = ORIENTED_EDGE ( 'NONE', *, *, #33734, .F. ) ; +#27469 = CARTESIAN_POINT ( 'NONE', ( -36.54932486753000376, 191.3500546173000032, 106.5983459909000004 ) ) ; +#27470 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048998880, 130.3419545076689872, 92.84535593378656415 ) ) ; +#27471 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#27472 = ORIENTED_EDGE ( 'NONE', *, *, #32392, .T. ) ; +#27473 = CARTESIAN_POINT ( 'NONE', ( 44.89367770789063883, 186.3539630622880452, 107.7797755496722232 ) ) ; +#27474 = CARTESIAN_POINT ( 'NONE', ( -5.674480817841737412, 181.6879534348617824, 101.6022789869470131 ) ) ; +#27475 = ORIENTED_EDGE ( 'NONE', *, *, #6724, .T. ) ; +#27476 = CARTESIAN_POINT ( 'NONE', ( 26.93890014261980070, 123.1557182139219861, 91.15008746119400485 ) ) ; +#27477 = CARTESIAN_POINT ( 'NONE', ( -35.98374720110734870, 191.5283369128620166, 103.8926017044265677 ) ) ; +#27479 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825963545604135, 0.0005734119013806925416 ) ) ; +#27478 = CARTESIAN_POINT ( 'NONE', ( 44.64491191134371917, 188.7542347311224376, 105.7690686227471559 ) ) ; +#27480 = ORIENTED_EDGE ( 'NONE', *, *, #27525, .F. ) ; +#27481 = VERTEX_POINT ( 'NONE', #34559 ) ; +#27482 = CIRCLE ( 'NONE', #32658, 2.500000000019892532 ) ; +#27483 = ORIENTED_EDGE ( 'NONE', *, *, #17090, .T. ) ; +#27484 = CIRCLE ( 'NONE', #32661, 4.999999999999990230 ) ; +#27485 = ORIENTED_EDGE ( 'NONE', *, *, #28386, .T. ) ; +#27486 = CARTESIAN_POINT ( 'NONE', ( -13.46889156257816289, 158.5525648645036938, 96.60790243539881317 ) ) ; +#27487 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557966386011, 0.2249510932777509520 ) ) ; +#27488 = CARTESIAN_POINT ( 'NONE', ( 31.91158941450065356, 174.0369345777030787, 102.3790021461855133 ) ) ; +#27489 = CARTESIAN_POINT ( 'NONE', ( 12.63561476618584045, 130.7779140762933139, 90.04768401957028345 ) ) ; +#27490 = CARTESIAN_POINT ( 'NONE', ( 20.50029382287623037, 174.4060969903238458, 100.4185135684600993 ) ) ; +#27491 = ORIENTED_EDGE ( 'NONE', *, *, #33032, .F. ) ; +#27492 = VERTEX_POINT ( 'NONE', #9256 ) ; +#27494 = EDGE_CURVE ( 'NONE', #15729, #27991, #33656, .T. ) ; +#27493 = CARTESIAN_POINT ( 'NONE', ( -30.44899449634186439, 126.4238598052008484, 91.93747207210981287 ) ) ; +#27495 = ADVANCED_FACE ( 'NONE', ( #37061 ), #12710, .F. ) ; +#27496 = LINE ( 'NONE', #37265, #30806 ) ; +#27497 = ORIENTED_EDGE ( 'NONE', *, *, #20235, .F. ) ; +#27498 = CARTESIAN_POINT ( 'NONE', ( -15.49970617126520445, 160.6260167168586293, 97.25887387978653464 ) ) ; +#27499 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33575, #39917, #8664, #2518, #3104, #5570, #24811, #11928, #15576, #15193, #31328, #24409, #37261, #27679, #9258, #6174, #3300 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999996597722, 0.1874999999995457522, 0.2187499999995137223, 0.2343749999995289324, 0.2499999999995441424, 0.3749999999996101452, 0.4374999999996431188, 0.4687499999996596611, 0.4999999999996761479, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27500 = CARTESIAN_POINT ( 'NONE', ( 28.64682496188636307, 225.5077044860236981, 75.54120257392457916 ) ) ; +#27501 = EDGE_CURVE ( 'NONE', #17427, #34518, #9734, .T. ) ; +#27502 = CARTESIAN_POINT ( 'NONE', ( 1.714626986300999967, 188.8646296950000192, 106.1286134521000122 ) ) ; +#27503 = CARTESIAN_POINT ( 'NONE', ( -18.59008601221150414, 148.0291187291159076, 184.1143154653856868 ) ) ; +#27504 = VECTOR ( 'NONE', #17687, 1000.000000000000000 ) ; +#27505 = CIRCLE ( 'NONE', #11841, 6.000000000000007994 ) ; +#27506 = CARTESIAN_POINT ( 'NONE', ( -37.63979538605995145, 190.3649484233513363, 106.7037812967066230 ) ) ; +#27507 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#27508 = DIRECTION ( 'NONE', ( 0.7947985590179719173, -0.5913221741348984040, -0.1365039814779490934 ) ) ; +#27509 = VECTOR ( 'NONE', #2150, 999.9999999999998863 ) ; +#27510 = ORIENTED_EDGE ( 'NONE', *, *, #22389, .T. ) ; +#27511 = CONICAL_SURFACE ( 'NONE', #29435, 4.500000144651047584, 0.7853905226630654157 ) ; +#27512 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; +#27513 = LINE ( 'NONE', #18651, #7760 ) ; +#27514 = ADVANCED_FACE ( 'NONE', ( #33976 ), #24809, .T. ) ; +#27515 = VERTEX_POINT ( 'NONE', #27677 ) ; +#27516 = CARTESIAN_POINT ( 'NONE', ( -5.668273565523921143, 188.0786322607826548, 103.3040616047431399 ) ) ; +#27517 = VERTEX_POINT ( 'NONE', #5974 ) ; +#27518 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30001, #21816, #39790, #24696 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 7.107475445351315358E-12, 0.1624485751913120335 ), + .UNSPECIFIED. ) ; +#27520 = CARTESIAN_POINT ( 'NONE', ( -12.63793912156000765, 182.0618459069391122, 102.2059974568395120 ) ) ; +#27519 = CARTESIAN_POINT ( 'NONE', ( 15.66685956167340343, 184.8912588079487591, 102.6710766810445392 ) ) ; +#27521 = VERTEX_POINT ( 'NONE', #2902 ) ; +#27522 = ORIENTED_EDGE ( 'NONE', *, *, #6897, .T. ) ; +#27523 = VERTEX_POINT ( 'NONE', #37258 ) ; +#27524 = CARTESIAN_POINT ( 'NONE', ( 2.340793176021000122, 209.5025667088000318, 75.42211677110000778 ) ) ; +#27525 = EDGE_CURVE ( 'NONE', #32129, #32940, #17571, .T. ) ; +#27526 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554023 ) ) ; +#27527 = LINE ( 'NONE', #39950, #31392 ) ; +#27528 = PLANE ( 'NONE', #4436 ) ; +#27529 = ORIENTED_EDGE ( 'NONE', *, *, #3526, .F. ) ; +#27530 = ORIENTED_EDGE ( 'NONE', *, *, #4029, .F. ) ; +#27531 = PLANE ( 'NONE', #15461 ) ; +#27532 = ORIENTED_EDGE ( 'NONE', *, *, #38510, .F. ) ; +#27533 = ORIENTED_EDGE ( 'NONE', *, *, #11955, .T. ) ; +#27535 = CIRCLE ( 'NONE', #23553, 1.650000000000002798 ) ; +#27534 = CARTESIAN_POINT ( 'NONE', ( 35.55533445255997549, 0.000000000000000000, 90.24631030814052224 ) ) ; +#27536 = CARTESIAN_POINT ( 'NONE', ( 20.50147082588080139, 126.8719997938822530, 91.49700837604584081 ) ) ; +#27537 = CARTESIAN_POINT ( 'NONE', ( -0.04020359587071615365, 82.61272530282539606, 339.3741737412128145 ) ) ; +#27538 = CARTESIAN_POINT ( 'NONE', ( 35.90057853183999725, 192.3630497469999909, 104.2039593241999995 ) ) ; +#27539 = ORIENTED_EDGE ( 'NONE', *, *, #38295, .T. ) ; +#27540 = CIRCLE ( 'NONE', #67, 6.000000000084652285 ) ; +#27541 = EDGE_LOOP ( 'NONE', ( #27408, #9678, #6332, #1280 ) ) ; +#27542 = CARTESIAN_POINT ( 'NONE', ( -5.669717579209783587, 123.9552506004847885, 91.12636042124255198 ) ) ; +#27543 = CIRCLE ( 'NONE', #30109, 2.749999999949217511 ) ; +#27544 = ADVANCED_FACE ( 'NONE', ( #9453 ), #3886, .F. ) ; +#27545 = CARTESIAN_POINT ( 'NONE', ( -35.80474254444001048, 191.4979743564000216, 103.7561588177000118 ) ) ; +#27546 = EDGE_CURVE ( 'NONE', #19190, #16912, #32221, .T. ) ; +#27547 = ORIENTED_EDGE ( 'NONE', *, *, #11086, .F. ) ; +#27548 = CARTESIAN_POINT ( 'NONE', ( -20.49921872406353529, 118.1134456025284152, 89.78002774633898753 ) ) ; +#27549 = ORIENTED_EDGE ( 'NONE', *, *, #8158, .T. ) ; +#27550 = CARTESIAN_POINT ( 'NONE', ( -21.21281391978411435, 175.4431137808699930, 102.7357300634946000 ) ) ; +#27551 = CARTESIAN_POINT ( 'NONE', ( 40.76229226433929398, 189.9128859572081751, 106.7721059889926494 ) ) ; +#27552 = EDGE_LOOP ( 'NONE', ( #5167, #21357, #39062, #33733 ) ) ; +#27553 = CARTESIAN_POINT ( 'NONE', ( 3.535984824131890747, 174.6891947503640949, 103.0598728709964576 ) ) ; +#27554 = CARTESIAN_POINT ( 'NONE', ( 39.01174084412672016, 119.4050079532688073, 90.28720122941795978 ) ) ; +#27555 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#27556 = CARTESIAN_POINT ( 'NONE', ( 23.64619383740999936, 151.9652147202999970, 28.07991271570000080 ) ) ; +#27557 = CARTESIAN_POINT ( 'NONE', ( -45.04873142129282115, 180.7068112024259108, 104.1363975995551243 ) ) ; +#27558 = VERTEX_POINT ( 'NONE', #16964 ) ; +#27559 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21739, #18631, #31139, #3108, #37461, #3906, #20250, #10670, #7777, #35560, #29671 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999635292, 0.3749999999999452660, 0.4374999999999819034, 0.4687500000000114908, 0.5000000000000410783, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27560 = CARTESIAN_POINT ( 'NONE', ( 16.00202263909956457, 151.2883905618018048, 97.64994197610543836 ) ) ; +#27561 = VERTEX_POINT ( 'NONE', #35361 ) ; +#27562 = DIRECTION ( 'NONE', ( -0.6087616187692346248, 0.7730003051580285334, 0.1785492081725818525 ) ) ; +#27563 = AXIS2_PLACEMENT_3D ( 'NONE', #28468, #29071, #25818 ) ; +#27564 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#27565 = CARTESIAN_POINT ( 'NONE', ( 3.578322037500690556, 147.6465767615097491, 129.6583090332095196 ) ) ; +#27566 = VECTOR ( 'NONE', #29524, 1000.000000000000114 ) ; +#27567 = EDGE_CURVE ( 'NONE', #31820, #20475, #4091, .T. ) ; +#27568 = LINE ( 'NONE', #19470, #38082 ) ; +#27569 = CARTESIAN_POINT ( 'NONE', ( 6.034364035348885658, 135.2945551070078238, 91.39763805326617785 ) ) ; +#27570 = ORIENTED_EDGE ( 'NONE', *, *, #35262, .T. ) ; +#27571 = CARTESIAN_POINT ( 'NONE', ( 18.08127464052524758, 152.6344612320365286, 184.7492086203702115 ) ) ; +#27572 = ORIENTED_EDGE ( 'NONE', *, *, #13824, .T. ) ; +#27573 = CARTESIAN_POINT ( 'NONE', ( -21.21281391978411435, 175.4431137808699930, 102.7357300634946000 ) ) ; +#27574 = EDGE_CURVE ( 'NONE', #34116, #16205, #27358, .T. ) ; +#27575 = CARTESIAN_POINT ( 'NONE', ( 21.84292934196066938, 154.3261023328925035, 95.26871761115269521 ) ) ; +#27576 = FACE_OUTER_BOUND ( 'NONE', #7458, .T. ) ; +#27577 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825873969720803, 0.0005734119034471432848 ) ) ; +#27578 = CYLINDRICAL_SURFACE ( 'NONE', #28481, 6.000000000000001776 ) ; +#27579 = VERTEX_POINT ( 'NONE', #25807 ) ; +#27580 = LINE ( 'NONE', #21218, #4060 ) ; +#27581 = EDGE_CURVE ( 'NONE', #31116, #16448, #9703, .T. ) ; +#27582 = CARTESIAN_POINT ( 'NONE', ( -37.62184588523724926, 212.3970731564136543, 75.58122719057897143 ) ) ; +#27583 = ORIENTED_EDGE ( 'NONE', *, *, #33140, .T. ) ; +#27584 = CARTESIAN_POINT ( 'NONE', ( 22.78079777786205540, 154.2095749712152326, 95.41230100879079146 ) ) ; +#27585 = EDGE_CURVE ( 'NONE', #31021, #11953, #7801, .T. ) ; +#27586 = EDGE_CURVE ( 'NONE', #33981, #38443, #37765, .T. ) ; +#27587 = VERTEX_POINT ( 'NONE', #16374 ) ; +#27588 = FACE_OUTER_BOUND ( 'NONE', #13312, .T. ) ; +#27589 = EDGE_CURVE ( 'NONE', #18436, #8550, #20114, .T. ) ; +#27590 = AXIS2_PLACEMENT_3D ( 'NONE', #29585, #38978, #1774 ) ; +#27591 = EDGE_CURVE ( 'NONE', #1138, #18169, #37135, .T. ) ; +#27592 = CIRCLE ( 'NONE', #14484, 4.500000113611068997 ) ; +#27593 = CARTESIAN_POINT ( 'NONE', ( 19.99976926757112849, 160.7481248081381295, 96.75239270071580222 ) ) ; +#27594 = ORIENTED_EDGE ( 'NONE', *, *, #2308, .T. ) ; +#27595 = CARTESIAN_POINT ( 'NONE', ( 29.05442967595000070, 103.6131156702000027, 88.75023641814000541 ) ) ; +#27596 = CARTESIAN_POINT ( 'NONE', ( 25.82478768046470208, 211.0921739042685772, 73.20852435745831599 ) ) ; +#27597 = FACE_OUTER_BOUND ( 'NONE', #6442, .T. ) ; +#27598 = CARTESIAN_POINT ( 'NONE', ( -3.537740281288561217, 141.9213324163776520, 92.42018393066655335 ) ) ; +#27599 = CARTESIAN_POINT ( 'NONE', ( -5.670700517399569485, 124.5227858738960549, 88.61975888496604625 ) ) ; +#27600 = EDGE_LOOP ( 'NONE', ( #20327, #40117, #27349, #34697 ) ) ; +#27601 = LINE ( 'NONE', #2027, #21253 ) ; +#27602 = DIRECTION ( 'NONE', ( 0.0001408404346092376365, -0.2249510911124609214, 0.9743700461176365568 ) ) ; +#27603 = CARTESIAN_POINT ( 'NONE', ( 36.60852988986350454, 191.6979107518085641, 104.3488059467087226 ) ) ; +#27604 = CARTESIAN_POINT ( 'NONE', ( -15.94501487834972053, 152.5969443588147669, 182.5988326182429375 ) ) ; +#27605 = EDGE_LOOP ( 'NONE', ( #25862, #39208, #4079, #34427 ) ) ; +#27606 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#27607 = CARTESIAN_POINT ( 'NONE', ( -28.46611168752988874, 181.6098482732715240, 104.1638139686604063 ) ) ; +#27608 = LINE ( 'NONE', #14910, #5218 ) ; +#27609 = CARTESIAN_POINT ( 'NONE', ( -20.50041084545262748, 195.9128271245631367, 104.1754392423040940 ) ) ; +#27610 = DIRECTION ( 'NONE', ( 0.0005884949961259270312, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#27611 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#27612 = CONICAL_SURFACE ( 'NONE', #14511, 2.249999999870928136, 0.7853981634347139140 ) ; +#27613 = CYLINDRICAL_SURFACE ( 'NONE', #18056, 1.999999999999996891 ) ; +#27614 = VECTOR ( 'NONE', #36732, 1000.000000000000114 ) ; +#27615 = CARTESIAN_POINT ( 'NONE', ( 4.722758528658833832, 181.8696323351509534, 101.6379838739853909 ) ) ; +#27616 = FACE_OUTER_BOUND ( 'NONE', #34425, .T. ) ; +#27617 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#27618 = DIRECTION ( 'NONE', ( -0.6087613186456907188, 0.7729176985478710682, 0.1789074850089337476 ) ) ; +#27619 = ADVANCED_FACE ( 'NONE', ( #13522 ), #6764, .F. ) ; +#27620 = CARTESIAN_POINT ( 'NONE', ( -25.50804057823069471, 190.9260211217805363, 106.3128357153982648 ) ) ; +#27621 = CARTESIAN_POINT ( 'NONE', ( 36.67804389992350167, 191.3728214856969885, 106.3843505564480267 ) ) ; +#27622 = ORIENTED_EDGE ( 'NONE', *, *, #6680, .F. ) ; +#27623 = CARTESIAN_POINT ( 'NONE', ( 36.01453331615999787, 191.5443466055999977, 106.7568071878999945 ) ) ; +#27624 = ORIENTED_EDGE ( 'NONE', *, *, #33953, .T. ) ; +#27625 = ORIENTED_EDGE ( 'NONE', *, *, #3255, .F. ) ; +#27626 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; +#27627 = ADVANCED_FACE ( 'NONE', ( #26005 ), #36475, .F. ) ; +#27628 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#27629 = EDGE_CURVE ( 'NONE', #34827, #12043, #29267, .T. ) ; +#27630 = DIRECTION ( 'NONE', ( -0.0006039748319481906373, -1.291365685536980129E-14, -0.9999998176071845934 ) ) ; +#27631 = VERTEX_POINT ( 'NONE', #29873 ) ; +#27632 = CARTESIAN_POINT ( 'NONE', ( 2.563994175896955774, 190.9709097722040099, 106.3045652864306874 ) ) ; +#27633 = EDGE_CURVE ( 'NONE', #20831, #3941, #3881, .T. ) ; +#27634 = LINE ( 'NONE', #34327, #40385 ) ; +#27635 = PLANE ( 'NONE', #7910 ) ; +#27636 = CARTESIAN_POINT ( 'NONE', ( -20.33313848355735587, 151.8903170490826255, 95.07394865144232199 ) ) ; +#27637 = AXIS2_PLACEMENT_3D ( 'NONE', #2556, #14833, #37301 ) ; +#27638 = VERTEX_POINT ( 'NONE', #24152 ) ; +#27639 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -1.240298884185379714E-30, 0.0006039748319385905692 ) ) ; +#27640 = CARTESIAN_POINT ( 'NONE', ( 23.36350214670024172, 176.7448593257297773, 103.0093387781554384 ) ) ; +#27641 = CARTESIAN_POINT ( 'NONE', ( -3.537745534793053981, 170.7699642429265907, 99.08042198971619996 ) ) ; +#27642 = CARTESIAN_POINT ( 'NONE', ( -4.664801184097494335, 188.1377569219451402, 103.0907645738648739 ) ) ; +#27643 = DIRECTION ( 'NONE', ( 0.0005884949961228996135, -0.2249510543439057764, 0.9743698870671265722 ) ) ; +#27644 = ORIENTED_EDGE ( 'NONE', *, *, #10166, .T. ) ; +#27645 = CARTESIAN_POINT ( 'NONE', ( 44.87323697063200001, 186.3386389082236860, 107.7764265916358113 ) ) ; +#27646 = CARTESIAN_POINT ( 'NONE', ( 1.550213941691470199, 189.2649696120780050, 103.7693551905349949 ) ) ; +#27647 = LINE ( 'NONE', #24576, #2553 ) ; +#27648 = ORIENTED_EDGE ( 'NONE', *, *, #33543, .T. ) ; +#27649 = CARTESIAN_POINT ( 'NONE', ( -3.862039046939059528, 136.7519072660630854, 93.97138356709339746 ) ) ; +#27650 = EDGE_LOOP ( 'NONE', ( #24262, #32885, #38438, #10122 ) ) ; +#27651 = CARTESIAN_POINT ( 'NONE', ( -15.94429875659460905, 121.8910548932331182, 174.4616802850389661 ) ) ; +#27652 = LINE ( 'NONE', #21908, #8688 ) ; +#27653 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989908600, 0.1373964268091705798 ) ) ; +#27654 = FACE_OUTER_BOUND ( 'NONE', #13935, .T. ) ; +#27655 = CARTESIAN_POINT ( 'NONE', ( -37.45185207060172417, 190.9974902301310919, 106.3324920097530821 ) ) ; +#27656 = FACE_OUTER_BOUND ( 'NONE', #29551, .T. ) ; +#27657 = CARTESIAN_POINT ( 'NONE', ( 25.82374571092184112, 209.7098874176531638, 73.20956759009925463 ) ) ; +#27658 = CIRCLE ( 'NONE', #25698, 58.90509898146415679 ) ; +#27659 = ORIENTED_EDGE ( 'NONE', *, *, #533, .F. ) ; +#27660 = EDGE_CURVE ( 'NONE', #5402, #5612, #6438, .T. ) ; +#27661 = FACE_OUTER_BOUND ( 'NONE', #11974, .T. ) ; +#27662 = EDGE_CURVE ( 'NONE', #11781, #36191, #11690, .T. ) ; +#27663 = CARTESIAN_POINT ( 'NONE', ( 20.00175897098971589, 118.8155681873422651, 90.25573236258343002 ) ) ; +#27664 = AXIS2_PLACEMENT_3D ( 'NONE', #3146, #30976, #37498 ) ; +#27665 = ADVANCED_FACE ( 'NONE', ( #2474 ), #35787, .T. ) ; +#27667 = DIRECTION ( 'NONE', ( -0.9999998268367413790, -0.0001323826169910145747, 0.0005734120070777408776 ) ) ; +#27666 = CARTESIAN_POINT ( 'NONE', ( -45.14842465761670809, 169.6367057394601829, 151.6138213944554707 ) ) ; +#27668 = VECTOR ( 'NONE', #9450, 1000.000000000000227 ) ; +#27669 = ORIENTED_EDGE ( 'NONE', *, *, #38025, .F. ) ; +#27670 = ADVANCED_FACE ( 'NONE', ( #36188 ), #11670, .F. ) ; +#27671 = CARTESIAN_POINT ( 'NONE', ( 20.36617596090313853, 116.6171548778993525, 87.25548363208405078 ) ) ; +#27672 = CARTESIAN_POINT ( 'NONE', ( 15.94070757266567995, 152.8237909711254190, 181.6389010276846818 ) ) ; +#27673 = ORIENTED_EDGE ( 'NONE', *, *, #14354, .F. ) ; +#27674 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000092726, 179.7424522644023739, 101.1388664480621884 ) ) ; +#27675 = EDGE_CURVE ( 'NONE', #8695, #30770, #18174, .T. ) ; +#27676 = CARTESIAN_POINT ( 'NONE', ( -14.61177127432338629, 128.1281455356962908, 179.5008378358747620 ) ) ; +#27677 = CARTESIAN_POINT ( 'NONE', ( 22.99909745638999681, 115.1133511170128969, 87.25389341346352978 ) ) ; +#27678 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; +#27679 = CARTESIAN_POINT ( 'NONE', ( -12.63882556139555113, 135.1005122211433047, 91.10176790521497026 ) ) ; +#27680 = ORIENTED_EDGE ( 'NONE', *, *, #12311, .F. ) ; +#27681 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32503, #11040, #35135, #38622 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 7.571344363706689254E-07, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27682 = ORIENTED_EDGE ( 'NONE', *, *, #33393, .F. ) ; +#27683 = CARTESIAN_POINT ( 'NONE', ( 6.272186690383747099, 163.3822237695354147, 99.93465344309498732 ) ) ; +#27684 = CARTESIAN_POINT ( 'NONE', ( 22.78193024034098357, 164.0779716071806718, 100.0853080456561202 ) ) ; +#27685 = CARTESIAN_POINT ( 'NONE', ( 22.50176469968679527, 151.2986505458790703, 97.64827954977749869 ) ) ; +#27686 = ADVANCED_FACE ( 'NONE', ( #11062 ), #26810, .F. ) ; +#27687 = VERTEX_POINT ( 'NONE', #17368 ) ; +#27688 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971521271 ) ) ; +#27689 = AXIS2_PLACEMENT_3D ( 'NONE', #18161, #26595, #36389 ) ; +#27690 = CARTESIAN_POINT ( 'NONE', ( 35.04524256069789345, 217.7719116313999734, 73.53733772509932010 ) ) ; +#27691 = CARTESIAN_POINT ( 'NONE', ( 2.942908037749000449, 190.9186745520999864, 106.6822150708999999 ) ) ; +#27692 = CIRCLE ( 'NONE', #28950, 4.499999999983483434 ) ; +#27693 = CARTESIAN_POINT ( 'NONE', ( 32.45263285945821252, 152.9980946676346889, 291.5389433581793242 ) ) ; +#27694 = CARTESIAN_POINT ( 'NONE', ( -12.15421709199686617, 125.0604765512531884, 178.7580882214065525 ) ) ; +#27695 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22843, #13238, #25721, #38174, #22647, #35073, #32053, #38964, #35464, #23642, #14651, #36306, #32829, #27136, #26512, #11170, #10771, #4810 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999709677, 0.1874999999999551470, 0.2187499999999615585, 0.2499999999999680256, 0.5000000000000517364, 0.6250000000000819345, 0.6875000000000873746, 0.7187500000000924816, 0.7500000000000976996, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27696 = CONICAL_SURFACE ( 'NONE', #36118, 2.500000004064246717, 0.7853981633778827076 ) ; +#27697 = FACE_BOUND ( 'NONE', #11681, .T. ) ; +#27698 = LINE ( 'NONE', #39723, #11789 ) ; +#27699 = LINE ( 'NONE', #17838, #30011 ) ; +#27700 = EDGE_LOOP ( 'NONE', ( #33142, #3771, #37913, #32883 ) ) ; +#27701 = CARTESIAN_POINT ( 'NONE', ( -19.99878781686340901, 118.5855806922666744, 90.27986360592157666 ) ) ; +#27702 = CARTESIAN_POINT ( 'NONE', ( -19.99806018810932429, 127.0618145191346713, 92.07850957579123019 ) ) ; +#27703 = ORIENTED_EDGE ( 'NONE', *, *, #30313, .F. ) ; +#27704 = CARTESIAN_POINT ( 'NONE', ( -5.664667741263813561, 188.2818546945390494, 103.1770723517569905 ) ) ; +#27705 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28873, #35184, #7190, #4107, #16581, #39068 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27706 = EDGE_LOOP ( 'NONE', ( #36619, #18669, #35311, #27075 ) ) ; +#27707 = EDGE_CURVE ( 'NONE', #34340, #32409, #5342, .T. ) ; +#27708 = EDGE_CURVE ( 'NONE', #15252, #14369, #19487, .T. ) ; +#27710 = CARTESIAN_POINT ( 'NONE', ( -17.18000789323316724, 121.5355521580427904, 176.6660631287034846 ) ) ; +#27709 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; +#27711 = ORIENTED_EDGE ( 'NONE', *, *, #27918, .F. ) ; +#27712 = ORIENTED_EDGE ( 'NONE', *, *, #32312, .T. ) ; +#27713 = CIRCLE ( 'NONE', #36828, 9.499999999981838528 ) ; +#27714 = EDGE_LOOP ( 'NONE', ( #21175, #26435, #4155, #15823 ) ) ; +#27715 = CARTESIAN_POINT ( 'NONE', ( 2.849529448806000342, 209.6052812332999906, 75.93649384533000557 ) ) ; +#27716 = CARTESIAN_POINT ( 'NONE', ( 39.01510409419797298, 183.0181244353566967, 104.9791813424711364 ) ) ; +#27717 = CARTESIAN_POINT ( 'NONE', ( 40.77511261360605488, 183.2838136414375185, 107.0263220726274227 ) ) ; +#27718 = CARTESIAN_POINT ( 'NONE', ( 5.666344154416935730, 188.3446284886178717, 103.1322861692058268 ) ) ; +#27720 = ORIENTED_EDGE ( 'NONE', *, *, #3259, .T. ) ; +#27719 = CONICAL_SURFACE ( 'NONE', #8139, 2.502986730286343775, 0.7853981633516999850 ) ; +#27721 = ORIENTED_EDGE ( 'NONE', *, *, #17415, .T. ) ; +#27722 = ORIENTED_EDGE ( 'NONE', *, *, #22444, .T. ) ; +#27723 = VERTEX_POINT ( 'NONE', #2064 ) ; +#27724 = DIRECTION ( 'NONE', ( -0.1945914028283885489, 0.07350731974101876176, -0.9781261983454748732 ) ) ; +#27725 = AXIS2_PLACEMENT_3D ( 'NONE', #7323, #1391, #26162 ) ; +#27726 = CARTESIAN_POINT ( 'NONE', ( 26.00820924362151487, 193.8169252988725475, 102.6872016750469072 ) ) ; +#27727 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394468896823, 3.782579493148625290E-12, 297.5584364845186087 ) ) ; +#27728 = DIRECTION ( 'NONE', ( -0.7933535325932956628, 0.5931614258681777718, 0.1369295263402618701 ) ) ; +#27729 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33457, #27161, #33052, #26539 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27730 = ORIENTED_EDGE ( 'NONE', *, *, #5054, .T. ) ; +#27731 = ORIENTED_EDGE ( 'NONE', *, *, #6616, .F. ) ; +#27732 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; +#27733 = DIRECTION ( 'NONE', ( 0.0005884949961245230978, -0.2249510543439041388, 0.9743698870671267942 ) ) ; +#27734 = ORIENTED_EDGE ( 'NONE', *, *, #9642, .F. ) ; +#27735 = DIRECTION ( 'NONE', ( -0.7933533411653073131, 0.5930537057989939687, 0.1373964268091565077 ) ) ; +#27736 = EDGE_CURVE ( 'NONE', #27950, #479, #23948, .T. ) ; +#27737 = VERTEX_POINT ( 'NONE', #33326 ) ; +#27738 = CARTESIAN_POINT ( 'NONE', ( 30.44722912950143012, 185.6116624768459360, 102.4863628262051947 ) ) ; +#27739 = DIRECTION ( 'NONE', ( 0.0002393071182784984501, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#27740 = ORIENTED_EDGE ( 'NONE', *, *, #21577, .T. ) ; +#27741 = CYLINDRICAL_SURFACE ( 'NONE', #8535, 7.999999999999993783 ) ; +#27742 = CARTESIAN_POINT ( 'NONE', ( -15.87307211637148008, 126.0321397929661487, 88.75931998815980251 ) ) ; +#27743 = CYLINDRICAL_SURFACE ( 'NONE', #27771, 9.999999999999996447 ) ; +#27744 = AXIS2_PLACEMENT_3D ( 'NONE', #22507, #19198, #207 ) ; +#27745 = CIRCLE ( 'NONE', #21221, 6.000000000000007994 ) ; +#27746 = FACE_OUTER_BOUND ( 'NONE', #38655, .T. ) ; +#27747 = VERTEX_POINT ( 'NONE', #7771 ) ; +#27748 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#27749 = AXIS2_PLACEMENT_3D ( 'NONE', #27210, #39238, #17759 ) ; +#27750 = DIRECTION ( 'NONE', ( 0.0005884949961228995051, -0.2249510543439057486, 0.9743698870671265722 ) ) ; +#27751 = CARTESIAN_POINT ( 'NONE', ( -38.55305068042999750, 118.7961394416000047, 87.84745821114999842 ) ) ; +#27752 = LINE ( 'NONE', #17902, #20938 ) ; +#27753 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#27754 = EDGE_LOOP ( 'NONE', ( #21177, #21042, #30350, #35448 ) ) ; +#27755 = CARTESIAN_POINT ( 'NONE', ( -29.78153554572921635, 185.0889519713750815, 104.9678231777716633 ) ) ; +#27756 = EDGE_LOOP ( 'NONE', ( #21543, #21196, #36270, #19222 ) ) ; +#27757 = CARTESIAN_POINT ( 'NONE', ( -37.35285048055809654, 145.6614909859866884, 280.9747434382983329 ) ) ; +#27758 = EDGE_CURVE ( 'NONE', #19097, #12909, #29665, .T. ) ; +#27759 = EDGE_CURVE ( 'NONE', #18878, #38902, #24897, .T. ) ; +#27760 = FACE_OUTER_BOUND ( 'NONE', #12187, .T. ) ; +#27761 = CARTESIAN_POINT ( 'NONE', ( -19.99827944177191341, 118.8155627782461181, 90.27982142893266371 ) ) ; +#27762 = ORIENTED_EDGE ( 'NONE', *, *, #27899, .F. ) ; +#27763 = CARTESIAN_POINT ( 'NONE', ( -6.957132718426895401, 133.0026170453613190, 282.5627442275269914 ) ) ; +#27764 = DIRECTION ( 'NONE', ( 0.0005884949961244997875, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#27765 = CARTESIAN_POINT ( 'NONE', ( -14.29753826611796619, 135.9209370902451042, 91.38347899765265936 ) ) ; +#27766 = CARTESIAN_POINT ( 'NONE', ( -36.27425416885741782, 116.2195830436171775, 90.28969357976914978 ) ) ; +#27767 = EDGE_LOOP ( 'NONE', ( #7638, #9376, #24557 ) ) ; +#27768 = CONICAL_SURFACE ( 'NONE', #38812, 3.000000000033070879, 0.7853981634068039064 ) ; +#27769 = CARTESIAN_POINT ( 'NONE', ( 9.584790827646999745, 123.9927411031000020, 91.09544851567000023 ) ) ; +#27770 = CARTESIAN_POINT ( 'NONE', ( 13.46889286300669930, 154.2077898831500136, 95.41751144764988624 ) ) ; +#27771 = AXIS2_PLACEMENT_3D ( 'NONE', #109, #21406, #18092 ) ; +#27772 = ORIENTED_EDGE ( 'NONE', *, *, #14814, .T. ) ; +#27773 = CARTESIAN_POINT ( 'NONE', ( -23.36257451788618411, 135.1062575246979520, 91.11938333801428769 ) ) ; +#27774 = CIRCLE ( 'NONE', #19876, 47.99999999995232969 ) ; +#27775 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319379635751 ) ) ; +#27776 = ORIENTED_EDGE ( 'NONE', *, *, #25414, .T. ) ; +#27777 = CARTESIAN_POINT ( 'NONE', ( 20.50411903179696793, 118.8156364820424358, 94.25541735824513978 ) ) ; +#27778 = EDGE_CURVE ( 'NONE', #24370, #29127, #26051, .T. ) ; +#27779 = CARTESIAN_POINT ( 'NONE', ( -31.75344637200684517, 110.2231456982468814, 198.5388746951010432 ) ) ; +#27780 = CARTESIAN_POINT ( 'NONE', ( -3.608144113922426843, 143.5503432561750117, 95.80119337602084784 ) ) ; +#27781 = VERTEX_POINT ( 'NONE', #28026 ) ; +#27782 = CARTESIAN_POINT ( 'NONE', ( 36.01401218609490940, 191.3156446998485762, 106.8565349524990040 ) ) ; +#27783 = CARTESIAN_POINT ( 'NONE', ( -16.99952089899032615, 137.4668171152774221, 177.5674675513082263 ) ) ; +#27784 = CARTESIAN_POINT ( 'NONE', ( 15.95616423589712340, 121.8747789553152785, 174.5819126748912709 ) ) ; +#27785 = CARTESIAN_POINT ( 'NONE', ( -25.26699933410839805, 116.1375375319907306, 90.28304547366768418 ) ) ; +#27786 = CARTESIAN_POINT ( 'NONE', ( -5.670809738135598188, 124.5658457816913938, 88.68866924740245850 ) ) ; +#27787 = ORIENTED_EDGE ( 'NONE', *, *, #40057, .T. ) ; +#27788 = ORIENTED_EDGE ( 'NONE', *, *, #7348, .F. ) ; +#27789 = CARTESIAN_POINT ( 'NONE', ( 30.05382551891246834, 103.6131156702177094, 87.74963262556697430 ) ) ; +#27790 = FACE_OUTER_BOUND ( 'NONE', #13668, .T. ) ; +#27791 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #1342, #33221 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27792 = LINE ( 'NONE', #40429, #1880 ) ; +#27793 = EDGE_CURVE ( 'NONE', #16151, #16282, #12705, .T. ) ; +#27794 = CARTESIAN_POINT ( 'NONE', ( 21.99952075582769950, 136.5637738048187089, 181.4737781874725044 ) ) ; +#27795 = EDGE_LOOP ( 'NONE', ( #22326, #13136, #33119, #17775 ) ) ; +#27796 = CARTESIAN_POINT ( 'NONE', ( 3.501248248212571301, 127.9869503391333438, 91.93573239970081090 ) ) ; +#27797 = FACE_OUTER_BOUND ( 'NONE', #8094, .T. ) ; +#27798 = AXIS2_PLACEMENT_3D ( 'NONE', #25234, #9680, #34982 ) ; +#27799 = CARTESIAN_POINT ( 'NONE', ( 23.36327396620029262, 181.6167095797193838, 104.1340943760966411 ) ) ; +#27800 = DIRECTION ( 'NONE', ( -0.0001358670886401176173, -0.9743700647852195917, -0.2249510133130793177 ) ) ; +#27801 = EDGE_CURVE ( 'NONE', #35660, #26941, #30885, .T. ) ; +#27802 = CARTESIAN_POINT ( 'NONE', ( -20.50069624036807880, 196.1175417876341385, 103.6936179443737842 ) ) ; +#27803 = AXIS2_PLACEMENT_3D ( 'NONE', #5111, #30080, #8616 ) ; +#27804 = CARTESIAN_POINT ( 'NONE', ( -26.43704716554000100, 188.3998508720999894, 105.9012352929000116 ) ) ; +#27805 = AXIS2_PLACEMENT_3D ( 'NONE', #13626, #23040, #33838 ) ; +#27806 = CARTESIAN_POINT ( 'NONE', ( 21.21741576901515458, 116.0712868709253200, 186.7718674688779288 ) ) ; +#27807 = AXIS2_PLACEMENT_3D ( 'NONE', #10099, #19675, #19276 ) ; +#27808 = EDGE_CURVE ( 'NONE', #38190, #10767, #9408, .T. ) ; +#27809 = EDGE_CURVE ( 'NONE', #36719, #12211, #28638, .T. ) ; +#27810 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14982, #37059, #3100, #12310, #11921, #30929, #37257, #33571 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 4 ), + ( 6.352770773062192013E-11, 0.001095641011820102685, 0.002191300338002477761, 0.003286959664184305099, 0.004382618990366680609, 0.005478278251420251425 ), + .UNSPECIFIED. ) ; +#27811 = EDGE_CURVE ( 'NONE', #17411, #31921, #16056, .T. ) ; +#27812 = LINE ( 'NONE', #36584, #38930 ) ; +#27813 = EDGE_CURVE ( 'NONE', #8681, #28855, #12210, .T. ) ; +#27814 = APPROVAL_STATUS ( 'not_yet_approved' ) ; +#27815 = CARTESIAN_POINT ( 'NONE', ( -25.49213558285381254, 194.2771767961476996, 102.9136721320308538 ) ) ; +#27816 = ORIENTED_EDGE ( 'NONE', *, *, #39576, .F. ) ; +#27817 = CARTESIAN_POINT ( 'NONE', ( -35.45414161172500656, 207.8686442644066403, 77.29845580048690579 ) ) ; +#27818 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927789245053, 0.0005734119022072690875 ) ) ; +#27819 = CARTESIAN_POINT ( 'NONE', ( 39.72066838923261400, 121.2692008855572539, 123.5482992136137597 ) ) ; +#27820 = CARTESIAN_POINT ( 'NONE', ( 37.96378718164481114, 191.4246119842719622, 104.2864744074900045 ) ) ; +#27821 = CARTESIAN_POINT ( 'NONE', ( 36.34654930669000095, 190.7274350762999973, 106.8916613049999995 ) ) ; +#27822 = ORIENTED_EDGE ( 'NONE', *, *, #30793, .F. ) ; +#27823 = ORIENTED_EDGE ( 'NONE', *, *, #33534, .T. ) ; +#27824 = CARTESIAN_POINT ( 'NONE', ( -3.749561473961237290, 136.3728858009279179, 91.13934745270415760 ) ) ; +#27825 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#27826 = AXIS2_PLACEMENT_3D ( 'NONE', #24091, #26556, #36348 ) ; +#27827 = CARTESIAN_POINT ( 'NONE', ( -37.60586764323186060, 218.5902260770999987, 73.08121708413270312 ) ) ; +#27828 = AXIS2_PLACEMENT_3D ( 'NONE', #21110, #33363, #21321 ) ; +#27829 = ORIENTED_EDGE ( 'NONE', *, *, #1517, .F. ) ; +#27830 = CARTESIAN_POINT ( 'NONE', ( -39.84439478701000326, 119.3836004598999949, 89.66600107623999349 ) ) ; +#27831 = EDGE_CURVE ( 'NONE', #29835, #29701, #39071, .T. ) ; +#27832 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#27833 = CONICAL_SURFACE ( 'NONE', #24474, 5.003062882472611328, 0.7854392545927519897 ) ; +#27834 = CARTESIAN_POINT ( 'NONE', ( -14.02911757408319637, 130.6396467055756148, 89.82193326635079700 ) ) ; +#27835 = VERTEX_POINT ( 'NONE', #37018 ) ; +#27836 = AXIS2_PLACEMENT_3D ( 'NONE', #19914, #23614, #29753 ) ; +#27837 = DIRECTION ( 'NONE', ( 0.0005884949961259158639, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#27838 = CARTESIAN_POINT ( 'NONE', ( 23.36476570799907293, 176.9958500756095248, 103.4110070592336115 ) ) ; +#27839 = AXIS2_PLACEMENT_3D ( 'NONE', #5213, #39358, #39566 ) ; +#27840 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#27841 = DIRECTION ( 'NONE', ( -0.7933533416835739649, 0.5930537051408141247, 0.1373964266575323501 ) ) ; +#27842 = LINE ( 'NONE', #5938, #17103 ) ; +#27843 = ORIENTED_EDGE ( 'NONE', *, *, #1177, .F. ) ; +#27844 = ORIENTED_EDGE ( 'NONE', *, *, #35442, .T. ) ; +#27845 = DIRECTION ( 'NONE', ( 0.0004161288024481686067, -0.8480480898038740278, 0.5299191110130112570 ) ) ; +#27846 = CARTESIAN_POINT ( 'NONE', ( 2.031020583090000109, 189.6346843048000039, 103.8749406049000044 ) ) ; +#27847 = LINE ( 'NONE', #21900, #3817 ) ; +#27848 = EDGE_CURVE ( 'NONE', #28666, #34570, #26329, .T. ) ; +#27849 = ORIENTED_EDGE ( 'NONE', *, *, #6849, .F. ) ; +#27850 = DIRECTION ( 'NONE', ( 0.0006039748319384690301, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#27851 = EDGE_LOOP ( 'NONE', ( #20766, #3905, #24673, #21502, #14358 ) ) ; +#27852 = EDGE_CURVE ( 'NONE', #23346, #40336, #8429, .T. ) ; +#27853 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178587041921E-05, 0.0002331579774917524482 ) ) ; +#27854 = EDGE_CURVE ( 'NONE', #19817, #40341, #7085, .T. ) ; +#27855 = FACE_OUTER_BOUND ( 'NONE', #963, .T. ) ; +#27856 = CARTESIAN_POINT ( 'NONE', ( 22.99181599359000217, 213.5902260771004819, 75.54481431629028521 ) ) ; +#27857 = VECTOR ( 'NONE', #32469, 1000.000000000000114 ) ; +#27858 = CARTESIAN_POINT ( 'NONE', ( -37.93529217406000242, 191.1032702454000116, 105.7304225791999954 ) ) ; +#27859 = EDGE_CURVE ( 'NONE', #2177, #34329, #27634, .T. ) ; +#27860 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -1.540743955509788340E-33, -0.0006039748319384538513 ) ) ; +#27861 = ADVANCED_FACE ( 'NONE', ( #33730 ), #21884, .T. ) ; +#27862 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#27863 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12022, #8960, #5876, #27977, #40209, #25106, #12412, #18329, #36961, #12223, #24711 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000003338441, 0.3750000000005007661, 0.4375000000005456191, 0.4687500000004894418, 0.5000000000004332090, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27864 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; +#27865 = CARTESIAN_POINT ( 'NONE', ( -36.46111710323000210, 191.2984778848999952, 106.4996631324000020 ) ) ; +#27866 = VERTEX_POINT ( 'NONE', #5733 ) ; +#27867 = AXIS2_PLACEMENT_3D ( 'NONE', #30767, #34016, #21773 ) ; +#27868 = DIRECTION ( 'NONE', ( 0.7933309737288272157, 0.5932206757314845147, 0.1368034941335623256 ) ) ; +#27869 = CARTESIAN_POINT ( 'NONE', ( -35.43647108214479857, 192.2306391127845586, 103.9283466409799956 ) ) ; +#27870 = LINE ( 'NONE', #33963, #22285 ) ; +#27871 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24216, #40124, #6183, #30330, #12132, #11937, #36663, #14996, #9067, #21550, #5788, #8673 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998647748, 0.3749999999998180344, 0.4374999999997946643, 0.4687499999998108735, 0.4843749999998041567, 0.4999999999997974953, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27872 = AXIS2_PLACEMENT_3D ( 'NONE', #5328, #24165, #15350 ) ; +#27873 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29999, #18108, #36947, #8744, #18314, #30614, #21205, #8948, #1996, #14873 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000001213474, 0.3750000000001508238, 0.4375000000001346145, 0.5000000000001184608, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27875 = CARTESIAN_POINT ( 'NONE', ( 16.22247671335948382, 122.0701589875174164, 174.5870958018068109 ) ) ; +#27874 = DIRECTION ( 'NONE', ( 0.0005884949961280474054, -0.2249510543439049992, 0.9743698870671266832 ) ) ; +#27876 = VERTEX_POINT ( 'NONE', #12665 ) ; +#27877 = ORIENTED_EDGE ( 'NONE', *, *, #4651, .F. ) ; +#27878 = CARTESIAN_POINT ( 'NONE', ( 20.19546531881924167, 117.0454142389978216, 87.25558673703422130 ) ) ; +#27879 = LINE ( 'NONE', #17620, #37416 ) ; +#27880 = VERTEX_POINT ( 'NONE', #37215 ) ; +#27881 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250100069, 132.8554482850266538, 90.84904174538198163 ) ) ; +#27882 = PLANE ( 'NONE', #39736 ) ; +#27883 = DIRECTION ( 'NONE', ( -0.0006039748319389448864, -1.387638830454547823E-14, -0.9999998176071845934 ) ) ; +#27884 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971556798 ) ) ; +#27885 = ORIENTED_EDGE ( 'NONE', *, *, #10397, .T. ) ; +#27886 = ORIENTED_EDGE ( 'NONE', *, *, #8837, .F. ) ; +#27887 = AXIS2_PLACEMENT_3D ( 'NONE', #8994, #37397, #12254 ) ; +#27888 = FACE_OUTER_BOUND ( 'NONE', #27055, .T. ) ; +#27889 = AXIS2_PLACEMENT_3D ( 'NONE', #26397, #2674, #5311 ) ; +#27890 = AXIS2_PLACEMENT_3D ( 'NONE', #9632, #6949, #31719 ) ; +#27891 = CARTESIAN_POINT ( 'NONE', ( 13.53487526333000091, 138.6412561347999883, 152.4718672074000381 ) ) ; +#27892 = VERTEX_POINT ( 'NONE', #25155 ) ; +#27893 = ORIENTED_EDGE ( 'NONE', *, *, #1368, .F. ) ; +#27894 = CARTESIAN_POINT ( 'NONE', ( -36.31334435454239440, 190.8477745772199796, 106.8181128475319923 ) ) ; +#27895 = EDGE_CURVE ( 'NONE', #38686, #38924, #11704, .T. ) ; +#27896 = CARTESIAN_POINT ( 'NONE', ( 2.428755075693000087, 191.0298806613000409, 106.1808864122999978 ) ) ; +#27897 = CIRCLE ( 'NONE', #16098, 2.499999999403085482 ) ; +#27898 = EDGE_CURVE ( 'NONE', #37032, #30211, #22924, .T. ) ; +#27899 = EDGE_CURVE ( 'NONE', #39862, #23240, #18863, .T. ) ; +#27900 = CARTESIAN_POINT ( 'NONE', ( 2.792698159047999784, 190.1826233186000081, 106.4537760261000017 ) ) ; +#27901 = CARTESIAN_POINT ( 'NONE', ( -30.17967539261260868, 185.9478675171641271, 102.6005988726028590 ) ) ; +#27902 = CARTESIAN_POINT ( 'NONE', ( 0.03687779169341001001, 7.827067153267001387E-13, 61.05847962042000887 ) ) ; +#27903 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568178 ) ) ; +#27904 = DIRECTION ( 'NONE', ( 0.0005884949958159830120, -0.2249510543438417998, 0.9743698870671413381 ) ) ; +#27905 = EDGE_CURVE ( 'NONE', #34620, #35660, #35509, .T. ) ; +#27906 = ORIENTED_EDGE ( 'NONE', *, *, #12820, .F. ) ; +#27907 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; +#27908 = CARTESIAN_POINT ( 'NONE', ( -30.05261224253734298, 126.8329673299385405, 91.51853050536497847 ) ) ; +#27909 = EDGE_CURVE ( 'NONE', #23147, #9444, #39096, .T. ) ; +#27910 = EDGE_LOOP ( 'NONE', ( #34364, #786, #27917, #5362 ) ) ; +#27911 = AXIS2_PLACEMENT_3D ( 'NONE', #34037, #6029, #2950 ) ; +#27912 = PLANE ( 'NONE', #5790 ) ; +#27913 = ORIENTED_EDGE ( 'NONE', *, *, #31153, .F. ) ; +#27914 = AXIS2_PLACEMENT_3D ( 'NONE', #2546, #24438, #11546 ) ; +#27916 = CARTESIAN_POINT ( 'NONE', ( 12.63956951859096911, 174.7946995548854829, 102.5655858247352796 ) ) ; +#27915 = CARTESIAN_POINT ( 'NONE', ( -5.675054657474391639, 124.3656264979204167, 88.36836997283377571 ) ) ; +#27917 = ORIENTED_EDGE ( 'NONE', *, *, #4164, .F. ) ; +#27918 = EDGE_CURVE ( 'NONE', #31494, #7275, #19986, .T. ) ; +#27919 = VERTEX_POINT ( 'NONE', #23084 ) ; +#27920 = CARTESIAN_POINT ( 'NONE', ( 25.49139087232281398, 206.5303696782877694, 74.82836958929388516 ) ) ; +#27921 = CARTESIAN_POINT ( 'NONE', ( 36.06505478247691343, 192.7057421170999874, 106.3400883090996132 ) ) ; +#27922 = ORIENTED_EDGE ( 'NONE', *, *, #35945, .T. ) ; +#27923 = CARTESIAN_POINT ( 'NONE', ( 2.588302065746999947, 209.5753207051000118, 75.67882707907000395 ) ) ; +#27924 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#27925 = EDGE_LOOP ( 'NONE', ( #26746, #18861, #17888, #7725 ) ) ; +#27926 = ORIENTED_EDGE ( 'NONE', *, *, #39262, .T. ) ; +#27927 = ORIENTED_EDGE ( 'NONE', *, *, #8780, .T. ) ; +#27928 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#27929 = DIRECTION ( 'NONE', ( 0.0006039748319386520434, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#27930 = CARTESIAN_POINT ( 'NONE', ( 39.82491996314075777, 141.3585264024648609, 285.0163987782322579 ) ) ; +#27931 = CARTESIAN_POINT ( 'NONE', ( -18.71851310314255556, 125.9964326179262883, 174.7342168340691444 ) ) ; +#27932 = ORIENTED_EDGE ( 'NONE', *, *, #20055, .T. ) ; +#27933 = ORIENTED_EDGE ( 'NONE', *, *, #34223, .F. ) ; +#27934 = CARTESIAN_POINT ( 'NONE', ( 21.83140111251249493, 182.3124853075107978, 104.2956521028678054 ) ) ; +#27935 = CARTESIAN_POINT ( 'NONE', ( -20.50069624036807880, 196.1175417876341385, 103.6936179443737842 ) ) ; +#27936 = CARTESIAN_POINT ( 'NONE', ( -20.49852834086299325, 137.6294258426618455, 94.00531932011546132 ) ) ; +#27937 = VERTEX_POINT ( 'NONE', #32481 ) ; +#27938 = DIRECTION ( 'NONE', ( 0.0005884949961279900511, -0.2249510543439064425, 0.9743698870671262391 ) ) ; +#27939 = CARTESIAN_POINT ( 'NONE', ( -39.94461650407871645, 190.2993241498186308, 106.6900227966467156 ) ) ; +#27940 = VERTEX_POINT ( 'NONE', #22286 ) ; +#27941 = VECTOR ( 'NONE', #36245, 1000.000000000000000 ) ; +#27942 = EDGE_CURVE ( 'NONE', #12341, #33655, #28613, .T. ) ; +#27943 = EDGE_CURVE ( 'NONE', #34776, #39273, #26858, .T. ) ; +#27944 = CARTESIAN_POINT ( 'NONE', ( -28.34683059422810558, 187.0784819827278795, 103.2026163153525715 ) ) ; +#27945 = CARTESIAN_POINT ( 'NONE', ( -3.683436850352686864, 167.8539730530844167, 101.3349470994127302 ) ) ; +#27946 = AXIS2_PLACEMENT_3D ( 'NONE', #4646, #4839, #13463 ) ; +#27947 = DIRECTION ( 'NONE', ( -0.0006039748319384734753, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#27948 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 181.5973583084323764, 103.1065612386186103 ) ) ; +#27949 = EDGE_CURVE ( 'NONE', #40156, #29048, #5385, .T. ) ; +#27950 = VERTEX_POINT ( 'NONE', #38004 ) ; +#27951 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.000000000000000000, 1.000000000000000000 ) ) ; +#27952 = ORIENTED_EDGE ( 'NONE', *, *, #27156, .T. ) ; +#27953 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; +#27954 = LINE ( 'NONE', #18304, #17916 ) ; +#27955 = CARTESIAN_POINT ( 'NONE', ( 38.68493554284999902, 118.3875614923999962, 89.50458756611999434 ) ) ; +#27956 = EDGE_CURVE ( 'NONE', #20733, #4624, #10010, .T. ) ; +#27957 = CARTESIAN_POINT ( 'NONE', ( -40.62250926484631464, 78.19640176074449300, 284.1891008884034591 ) ) ; +#27958 = ORIENTED_EDGE ( 'NONE', *, *, #11085, .T. ) ; +#27959 = DIRECTION ( 'NONE', ( -0.6087613508315110611, 0.7729392205173687413, 0.1788143705628724156 ) ) ; +#27960 = EDGE_LOOP ( 'NONE', ( #2108, #4727 ) ) ; +#27961 = CARTESIAN_POINT ( 'NONE', ( 44.93984957629947274, 145.3877245808612031, 285.0133094889154677 ) ) ; +#27962 = EDGE_CURVE ( 'NONE', #28925, #17225, #35811, .T. ) ; +#27963 = ORIENTED_EDGE ( 'NONE', *, *, #34479, .T. ) ; +#27964 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18119, #2804, #31214, #34456 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#27965 = AXIS2_PLACEMENT_3D ( 'NONE', #29831, #17121, #14490 ) ; +#27966 = PLANE ( 'NONE', #9519 ) ; +#27967 = DIRECTION ( 'NONE', ( 0.9999998176071833722, -2.081668157636497989E-12, -0.0006039748339932807545 ) ) ; +#27968 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971542920 ) ) ; +#27969 = CARTESIAN_POINT ( 'NONE', ( -21.71199968648796030, 158.4246146459098838, 96.24123999348603320 ) ) ; +#27970 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218859315, 3.303188515689728130E-12, 297.5295786860755811 ) ) ; +#27971 = VECTOR ( 'NONE', #38942, 1000.000000000000227 ) ; +#27972 = ORIENTED_EDGE ( 'NONE', *, *, #5561, .T. ) ; +#27973 = CARTESIAN_POINT ( 'NONE', ( 5.667347771331193940, 187.7942676616929418, 103.4761900681965869 ) ) ; +#27974 = CYLINDRICAL_SURFACE ( 'NONE', #9316, 2.000000000000014655 ) ; +#27975 = CARTESIAN_POINT ( 'NONE', ( 116.6745667766377892, 205.5703614864765427, 191.2914269756732040 ) ) ; +#27976 = ORIENTED_EDGE ( 'NONE', *, *, #8636, .F. ) ; +#27977 = CARTESIAN_POINT ( 'NONE', ( 30.06884912282138700, 134.4748413268802096, 93.56566892047057138 ) ) ; +#27978 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 130.4381646051676285, 91.31727167258139843 ) ) ; +#27979 = VERTEX_POINT ( 'NONE', #31888 ) ; +#27980 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971545418 ) ) ; +#27981 = CARTESIAN_POINT ( 'NONE', ( -39.76461490650798680, 169.2256028002626635, 164.4823439763816282 ) ) ; +#27982 = CARTESIAN_POINT ( 'NONE', ( -3.952287704705344851, 143.6302336283734178, 95.46685700466385072 ) ) ; +#27983 = ORIENTED_EDGE ( 'NONE', *, *, #1517, .T. ) ; +#27984 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501097438, 132.2930706491154922, 93.28496646309041296 ) ) ; +#27985 = DIRECTION ( 'NONE', ( -0.7075227875440994740, 0.1589708073325998561, -0.6885780910846993619 ) ) ; +#27986 = CARTESIAN_POINT ( 'NONE', ( -26.15087763400000043, 190.7042518446999964, 106.9127768281999948 ) ) ; +#27987 = EDGE_CURVE ( 'NONE', #15231, #929, #3646, .T. ) ; +#27988 = ADVANCED_FACE ( 'NONE', ( #789 ), #25760, .T. ) ; +#27989 = PLANE ( 'NONE', #7813 ) ; +#27990 = CARTESIAN_POINT ( 'NONE', ( -5.670798188510340232, 124.5598963420014513, 88.67914814188733885 ) ) ; +#27991 = VERTEX_POINT ( 'NONE', #35109 ) ; +#27992 = CARTESIAN_POINT ( 'NONE', ( 19.98635445618997863, 211.0854288155255460, 76.04696776081749476 ) ) ; +#27993 = LINE ( 'NONE', #18541, #17272 ) ; +#27994 = CYLINDRICAL_SURFACE ( 'NONE', #29952, 1.750000000000001998 ) ; +#27995 = VECTOR ( 'NONE', #10573, 999.9999999999998863 ) ; +#27996 = FACE_OUTER_BOUND ( 'NONE', #35786, .T. ) ; +#27997 = ORIENTED_EDGE ( 'NONE', *, *, #25674, .F. ) ; +#27998 = CARTESIAN_POINT ( 'NONE', ( 38.42898351650580935, 118.9831930641796447, 90.24774914394696168 ) ) ; +#27999 = CARTESIAN_POINT ( 'NONE', ( 13.45514494945999928, 202.1123865980000289, 28.07991271570000080 ) ) ; +#28000 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501101346, 132.2930706491314936, 93.28496646302122031 ) ) ; +#28001 = CARTESIAN_POINT ( 'NONE', ( -38.11718854129877343, 118.8155790694493561, 90.29079743518840928 ) ) ; +#28002 = CARTESIAN_POINT ( 'NONE', ( -36.36299666547999720, 191.9032661002999873, 104.5546124913999932 ) ) ; +#28003 = CARTESIAN_POINT ( 'NONE', ( -25.83888629021704730, 190.8929348362623557, 106.6474986096369406 ) ) ; +#28004 = DIRECTION ( 'NONE', ( 0.0005884949961243157984, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#28005 = CARTESIAN_POINT ( 'NONE', ( 38.69679614704350001, 191.0388310801824332, 103.7343411210213873 ) ) ; +#28006 = EDGE_CURVE ( 'NONE', #39173, #23378, #35544, .T. ) ; +#28007 = CARTESIAN_POINT ( 'NONE', ( 21.21575639516963463, 182.9122697023876754, 104.4344951008579443 ) ) ; +#28008 = CARTESIAN_POINT ( 'NONE', ( 30.44722912950143012, 185.6116624768459360, 102.4863628262051947 ) ) ; +#28009 = CARTESIAN_POINT ( 'NONE', ( 26.75419196830544166, 181.6923716698377689, 101.5837815084677658 ) ) ; +#28010 = CYLINDRICAL_SURFACE ( 'NONE', #1936, 5.999999999651004501 ) ; +#28011 = CARTESIAN_POINT ( 'NONE', ( 36.18932490265000013, 192.0082684861000075, 104.3659335172000198 ) ) ; +#28012 = ORIENTED_EDGE ( 'NONE', *, *, #33764, .F. ) ; +#28013 = CARTESIAN_POINT ( 'NONE', ( 36.78843971972000304, 191.5252555525999867, 106.2249300401000056 ) ) ; +#28014 = ORIENTED_EDGE ( 'NONE', *, *, #18752, .F. ) ; +#28015 = ORIENTED_EDGE ( 'NONE', *, *, #34274, .F. ) ; +#28017 = CIRCLE ( 'NONE', #9066, 4.999999999999990230 ) ; +#28016 = FACE_OUTER_BOUND ( 'NONE', #14763, .T. ) ; +#28018 = CARTESIAN_POINT ( 'NONE', ( 37.96506445775530381, 190.7637513255541535, 106.4080848624315081 ) ) ; +#28019 = ADVANCED_FACE ( 'NONE', ( #7121 ), #10418, .F. ) ; +#28020 = CYLINDRICAL_SURFACE ( 'NONE', #13444, 8.999999999999994671 ) ; +#28021 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11447, #26598, #8391, #17349 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28022 = AXIS2_PLACEMENT_3D ( 'NONE', #4682, #29439, #13895 ) ; +#28023 = ORIENTED_EDGE ( 'NONE', *, *, #35974, .T. ) ; +#28024 = CARTESIAN_POINT ( 'NONE', ( 36.49193471766000130, 191.9013877111999875, 104.5110495927000045 ) ) ; +#28025 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#28026 = CARTESIAN_POINT ( 'NONE', ( 13.49436806345008399, 123.6932719124138345, 91.28058047958029420 ) ) ; +#28027 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#28028 = DIRECTION ( 'NONE', ( -0.7933533411653073131, 0.5930537057989940797, 0.1373964268091562024 ) ) ; +#28029 = EDGE_LOOP ( 'NONE', ( #27483, #30488, #30092, #23843 ) ) ; +#28030 = DIRECTION ( 'NONE', ( 0.0005884949961241434102, -0.2249510543439057764, 0.9743698870671265722 ) ) ; +#28031 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11645, #11036, #14105, #35943 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28032 = CARTESIAN_POINT ( 'NONE', ( 23.36189990591568133, 175.3591898460452114, 100.1205101937285349 ) ) ; +#28033 = EDGE_CURVE ( 'NONE', #27218, #34462, #37999, .T. ) ; +#28034 = EDGE_CURVE ( 'NONE', #18635, #39966, #14282, .T. ) ; +#28035 = CARTESIAN_POINT ( 'NONE', ( -12.64523939051215073, 134.9174765714697344, 90.80875027841997849 ) ) ; +#28036 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.110223024625155594E-14, -1.000000000000000000 ) ) ; +#28037 = EDGE_CURVE ( 'NONE', #7067, #12730, #33228, .T. ) ; +#28038 = ORIENTED_EDGE ( 'NONE', *, *, #3720, .T. ) ; +#28039 = FACE_OUTER_BOUND ( 'NONE', #26122, .T. ) ; +#28040 = CARTESIAN_POINT ( 'NONE', ( 1.548525489068410366, 189.2671695052339658, 103.7726728760049895 ) ) ; +#28041 = CARTESIAN_POINT ( 'NONE', ( -45.39695617069071432, 130.9021434594297091, 91.44093725908659565 ) ) ; +#28042 = VERTEX_POINT ( 'NONE', #8353 ) ; +#28043 = CARTESIAN_POINT ( 'NONE', ( 18.92701962846999919, 153.5843418025999938, 96.63868624690000786 ) ) ; +#28044 = ORIENTED_EDGE ( 'NONE', *, *, #1928, .T. ) ; +#28045 = CARTESIAN_POINT ( 'NONE', ( -3.169906973560626895, 184.1222312815566795, 102.1628149875517408 ) ) ; +#28046 = VECTOR ( 'NONE', #16281, 1000.000000000000000 ) ; +#28047 = CARTESIAN_POINT ( 'NONE', ( -15.94446165338357702, 121.2066837107214212, 177.4195636231463027 ) ) ; +#28048 = FACE_OUTER_BOUND ( 'NONE', #4791, .T. ) ; +#28049 = CONICAL_SURFACE ( 'NONE', #26084, 51.90509899263580706, 0.7853981633972871856 ) ; +#28050 = CIRCLE ( 'NONE', #5877, 2.999999999919165550 ) ; +#28051 = AXIS2_PLACEMENT_3D ( 'NONE', #29491, #7604, #10897 ) ; +#28052 = PLANE ( 'NONE', #9802 ) ; +#28053 = CARTESIAN_POINT ( 'NONE', ( -3.669581230394507898, 185.7947741359049019, 103.0623953380812168 ) ) ; +#28054 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#28055 = CARTESIAN_POINT ( 'NONE', ( 25.99030105615392827, 209.7097546603872900, 73.04280869622928662 ) ) ; +#28056 = ORIENTED_EDGE ( 'NONE', *, *, #10890, .T. ) ; +#28057 = LINE ( 'NONE', #21915, #25734 ) ; +#28058 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319364164186 ) ) ; +#28059 = LINE ( 'NONE', #30, #16364 ) ; +#28061 = CARTESIAN_POINT ( 'NONE', ( 15.05947164863658116, 123.5176133570900845, 178.5140257238748518 ) ) ; +#28060 = FACE_OUTER_BOUND ( 'NONE', #24199, .T. ) ; +#28062 = ORIENTED_EDGE ( 'NONE', *, *, #12138, .F. ) ; +#28063 = ADVANCED_FACE ( 'NONE', ( #30019 ), #32867, .F. ) ; +#28064 = DIRECTION ( 'NONE', ( 0.0005734119072320155485, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#28065 = ORIENTED_EDGE ( 'NONE', *, *, #18242, .F. ) ; +#28066 = ORIENTED_EDGE ( 'NONE', *, *, #39635, .T. ) ; +#28067 = CARTESIAN_POINT ( 'NONE', ( 39.68494082915999854, 119.6892224767999977, 90.21586879058999386 ) ) ; +#28068 = CARTESIAN_POINT ( 'NONE', ( -13.49083856689536987, 187.6673735495426740, 106.0664666259349644 ) ) ; +#28069 = AXIS2_PLACEMENT_3D ( 'NONE', #4307, #291, #103 ) ; +#28070 = EDGE_CURVE ( 'NONE', #26260, #3107, #22173, .T. ) ; +#28071 = CARTESIAN_POINT ( 'NONE', ( 14.55294048017762698, 182.5605668518259392, 101.7915615195478409 ) ) ; +#28072 = CARTESIAN_POINT ( 'NONE', ( -20.00062605139820704, 196.5784656963837733, 103.8871944330217048 ) ) ; +#28073 = CARTESIAN_POINT ( 'NONE', ( 29.42812340194186049, 130.8370083103818615, 89.84125070675843006 ) ) ; +#28074 = PLANE ( 'NONE', #35372 ) ; +#28075 = VERTEX_POINT ( 'NONE', #20398 ) ; +#28076 = CARTESIAN_POINT ( 'NONE', ( 15.95616231907572313, 121.8746118785549157, 174.5826276267837613 ) ) ; +#28077 = VECTOR ( 'NONE', #27904, 1000.000000000000114 ) ; +#28078 = VERTEX_POINT ( 'NONE', #39005 ) ; +#28079 = VECTOR ( 'NONE', #32074, 1000.000000000000114 ) ; +#28080 = DIRECTION ( 'NONE', ( 0.0005884949961228831336, -0.2249510543439064980, 0.9743698870671262391 ) ) ; +#28081 = EDGE_CURVE ( 'NONE', #4354, #7294, #14119, .T. ) ; +#28082 = ADVANCED_FACE ( 'NONE', ( #21027 ), #27420, .T. ) ; +#28083 = VECTOR ( 'NONE', #24122, 1000.000000000000114 ) ; +#28084 = PLANE ( 'NONE', #24259 ) ; +#28085 = CARTESIAN_POINT ( 'NONE', ( -23.37153626856268218, 181.6857280266875421, 101.6124992246220842 ) ) ; +#28086 = EDGE_CURVE ( 'NONE', #35965, #6128, #34624, .T. ) ; +#28087 = ORIENTED_EDGE ( 'NONE', *, *, #2088, .T. ) ; +#28088 = CARTESIAN_POINT ( 'NONE', ( -36.18404661049999760, 190.9553995324999960, 106.8395213493000000 ) ) ; +#28089 = EDGE_CURVE ( 'NONE', #89, #27242, #6466, .T. ) ; +#28090 = FACE_OUTER_BOUND ( 'NONE', #6612, .T. ) ; +#28091 = DIRECTION ( 'NONE', ( -0.0005884949961227775323, 0.2249510543439063315, -0.9743698870671264611 ) ) ; +#28092 = ORIENTED_EDGE ( 'NONE', *, *, #10347, .T. ) ; +#28093 = ORIENTED_EDGE ( 'NONE', *, *, #7141, .T. ) ; +#28094 = CARTESIAN_POINT ( 'NONE', ( 2.962527580964340324, 190.0861127772304258, 106.6265932751835805 ) ) ; +#28095 = FACE_OUTER_BOUND ( 'NONE', #40405, .T. ) ; +#28096 = CARTESIAN_POINT ( 'NONE', ( 21.27838750203562768, 176.7284879462769425, 100.4410577670730333 ) ) ; +#28097 = CARTESIAN_POINT ( 'NONE', ( -27.20710394601999838, 124.5624848500000041, 90.85369269781000412 ) ) ; +#28098 = CARTESIAN_POINT ( 'NONE', ( -20.01219580461844316, 201.3437115538952469, 84.98297556926431184 ) ) ; +#28099 = CARTESIAN_POINT ( 'NONE', ( 26.73277628323574717, 120.3821797830261033, 171.5759152015846496 ) ) ; +#28100 = CARTESIAN_POINT ( 'NONE', ( 82.77222000466073837, 72.24422888835732692, 166.6196021931943960 ) ) ; +#28101 = VECTOR ( 'NONE', #34473, 1000.000000000000114 ) ; +#28102 = EDGE_CURVE ( 'NONE', #11668, #12094, #32595, .T. ) ; +#28103 = AXIS2_PLACEMENT_3D ( 'NONE', #29963, #36290, #36494 ) ; +#28104 = EDGE_LOOP ( 'NONE', ( #4176, #1671, #18865 ) ) ; +#28105 = AXIS2_PLACEMENT_3D ( 'NONE', #26579, #29639, #5284 ) ; +#28106 = DIRECTION ( 'NONE', ( 0.0005884949961239352434, -0.2249510543439079413, 0.9743698870671259060 ) ) ; +#28107 = EDGE_LOOP ( 'NONE', ( #9708, #22862 ) ) ; +#28109 = CARTESIAN_POINT ( 'NONE', ( 40.29675614866165745, 187.8287955346809213, 108.1243603913822824 ) ) ; +#28108 = CARTESIAN_POINT ( 'NONE', ( 36.14780637420843590, 192.0877688002536843, 104.3837537224991934 ) ) ; +#28110 = ORIENTED_EDGE ( 'NONE', *, *, #33953, .F. ) ; +#28111 = ORIENTED_EDGE ( 'NONE', *, *, #15906, .F. ) ; +#28112 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; +#28113 = EDGE_CURVE ( 'NONE', #36005, #4191, #23477, .T. ) ; +#28114 = CARTESIAN_POINT ( 'NONE', ( 40.91997143381097146, 127.4822456336884358, 89.05980178640240297 ) ) ; +#28115 = CARTESIAN_POINT ( 'NONE', ( -40.69272868350516603, 120.3526484630499880, 90.54200919470581255 ) ) ; +#28116 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#28117 = ORIENTED_EDGE ( 'NONE', *, *, #1257, .T. ) ; +#28118 = VERTEX_POINT ( 'NONE', #2220 ) ; +#28119 = CARTESIAN_POINT ( 'NONE', ( -19.35302328312414488, 125.0106235229416285, 177.9777102502699222 ) ) ; +#28120 = DIRECTION ( 'NONE', ( -0.0006039748319384231684, -2.335630580398557718E-15, -0.9999998176071847045 ) ) ; +#28121 = CARTESIAN_POINT ( 'NONE', ( 2.460508346168839733, 209.5732971666951698, 73.55701931308026076 ) ) ; +#28122 = CARTESIAN_POINT ( 'NONE', ( -43.19348492542150808, 172.3884102536505907, 184.6076772393078897 ) ) ; +#28123 = ADVANCED_FACE ( 'NONE', ( #39612 ), #14311, .F. ) ; +#28124 = EDGE_LOOP ( 'NONE', ( #17777, #39012, #11181 ) ) ; +#28125 = VERTEX_POINT ( 'NONE', #4663 ) ; +#28126 = FACE_OUTER_BOUND ( 'NONE', #15983, .T. ) ; +#28127 = CARTESIAN_POINT ( 'NONE', ( 20.16844586256894800, 173.8874256999797012, 102.6935641049061019 ) ) ; +#28128 = CARTESIAN_POINT ( 'NONE', ( -15.99823486130475736, 118.9409032897876841, 90.20116722531847131 ) ) ; +#28129 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#28130 = EDGE_CURVE ( 'NONE', #626, #25046, #17117, .T. ) ; +#28131 = VERTEX_POINT ( 'NONE', #37557 ) ; +#28132 = CARTESIAN_POINT ( 'NONE', ( 22.50140346553463644, 157.8319422969905759, 98.98556753889189963 ) ) ; +#28133 = CARTESIAN_POINT ( 'NONE', ( 23.39364800404629818, 165.2216646694212727, 152.9217693189764304 ) ) ; +#28134 = DIRECTION ( 'NONE', ( -0.7933533411653075351, -0.5931840316265221125, -0.1368326740407720954 ) ) ; +#28135 = ORIENTED_EDGE ( 'NONE', *, *, #26536, .T. ) ; +#28136 = AXIS2_PLACEMENT_3D ( 'NONE', #24355, #32915, #20858 ) ; +#28137 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; +#28138 = CARTESIAN_POINT ( 'NONE', ( -29.20104124294445214, 148.3921741051831873, 97.00850424916733061 ) ) ; +#28139 = CARTESIAN_POINT ( 'NONE', ( -5.666776224462409139, 187.4258185150888210, 105.6738796381353751 ) ) ; +#28140 = CARTESIAN_POINT ( 'NONE', ( -38.86369644165072401, 118.8228811219059793, 89.72077589445396484 ) ) ; +#28141 = CARTESIAN_POINT ( 'NONE', ( -42.38963504733576571, 73.00513959036860001, 297.5841473069626772 ) ) ; +#28142 = EDGE_LOOP ( 'NONE', ( #12715, #29161, #11759, #39116, #22127, #23337, #37207, #32723 ) ) ; +#28143 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.702666754117757870E-16, 0.0006039748319385827629 ) ) ; +#28144 = ORIENTED_EDGE ( 'NONE', *, *, #25311, .F. ) ; +#28145 = VERTEX_POINT ( 'NONE', #18334 ) ; +#28146 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971551247 ) ) ; +#28147 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; +#28148 = CARTESIAN_POINT ( 'NONE', ( 38.50968654372999822, 118.5704612529000030, 89.80384588171000360 ) ) ; +#28149 = EDGE_LOOP ( 'NONE', ( #39335, #12306, #6469, #18621 ) ) ; +#28150 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; +#28151 = ORIENTED_EDGE ( 'NONE', *, *, #32179, .T. ) ; +#28152 = CARTESIAN_POINT ( 'NONE', ( 6.034640323947002116, 177.1924675530794957, 101.0705349086647828 ) ) ; +#28153 = AXIS2_PLACEMENT_3D ( 'NONE', #23239, #35674, #20152 ) ; +#28154 = CONICAL_SURFACE ( 'NONE', #18316, 2.500000004850577717, 0.7853981634372142473 ) ; +#28155 = ORIENTED_EDGE ( 'NONE', *, *, #5561, .F. ) ; +#28156 = EDGE_CURVE ( 'NONE', #23821, #28951, #37796, .T. ) ; +#28157 = CARTESIAN_POINT ( 'NONE', ( -38.93916630444905280, 183.7310523952955350, 102.0940973430918604 ) ) ; +#28158 = AXIS2_PLACEMENT_3D ( 'NONE', #37998, #10213, #22879 ) ; +#28159 = EDGE_CURVE ( 'NONE', #5720, #14356, #6273, .T. ) ; +#28160 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#28161 = VECTOR ( 'NONE', #7682, 1000.000000000000114 ) ; +#28162 = CARTESIAN_POINT ( 'NONE', ( -37.29474482131207935, 164.7567791378876052, 197.5716176305500085 ) ) ; +#28163 = EDGE_CURVE ( 'NONE', #36719, #38838, #31036, .T. ) ; +#28164 = CARTESIAN_POINT ( 'NONE', ( 23.36232515670958065, 177.1947614343970372, 101.0605990059838462 ) ) ; +#28165 = EDGE_CURVE ( 'NONE', #32551, #23376, #25395, .T. ) ; +#28166 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555133 ) ) ; +#28167 = ORIENTED_EDGE ( 'NONE', *, *, #4497, .T. ) ; +#28168 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#28169 = ORIENTED_EDGE ( 'NONE', *, *, #20209, .F. ) ; +#28170 = VERTEX_POINT ( 'NONE', #27593 ) ; +#28171 = CARTESIAN_POINT ( 'NONE', ( -22.46828090686999957, 162.3883503090999909, 152.4718672074000381 ) ) ; +#28172 = CARTESIAN_POINT ( 'NONE', ( 4.035676230723896474, 174.7936433537998653, 102.5705385170005997 ) ) ; +#28173 = EDGE_CURVE ( 'NONE', #26491, #1098, #12609, .T. ) ; +#28174 = ORIENTED_EDGE ( 'NONE', *, *, #19327, .F. ) ; +#28175 = CARTESIAN_POINT ( 'NONE', ( -23.36173673102033632, 135.2906635749613997, 91.41449413045401684 ) ) ; +#28176 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#28177 = ORIENTED_EDGE ( 'NONE', *, *, #26073, .T. ) ; +#28178 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; +#28179 = ADVANCED_FACE ( 'NONE', ( #12228 ), #37166, .F. ) ; +#28180 = CARTESIAN_POINT ( 'NONE', ( 36.90300980118022522, 190.5697579479422927, 106.7060433226621541 ) ) ; +#28181 = CARTESIAN_POINT ( 'NONE', ( -30.07128175106310408, 134.7905956161418146, 93.39787389195613798 ) ) ; +#28182 = ORIENTED_EDGE ( 'NONE', *, *, #29073, .F. ) ; +#28183 = CARTESIAN_POINT ( 'NONE', ( 27.88838870525999880, 125.3341793757000175, 89.08508767201000467 ) ) ; +#28184 = CARTESIAN_POINT ( 'NONE', ( 3.738724522724006682, 167.8697915648398862, 101.2771627622597634 ) ) ; +#28185 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#28186 = AXIS2_PLACEMENT_3D ( 'NONE', #640, #3899, #13128 ) ; +#28187 = CARTESIAN_POINT ( 'NONE', ( 13.47422552046212019, 158.3810130762119570, 98.09148005191302389 ) ) ; +#28188 = FACE_OUTER_BOUND ( 'NONE', #2276, .T. ) ; +#28189 = ORIENTED_EDGE ( 'NONE', *, *, #17615, .F. ) ; +#28190 = CARTESIAN_POINT ( 'NONE', ( 16.44620207817152036, 122.3647578235614048, 174.6137112058796106 ) ) ; +#28191 = AXIS2_PLACEMENT_3D ( 'NONE', #19414, #4882, #23300 ) ; +#28192 = CARTESIAN_POINT ( 'NONE', ( 35.98188939040999657, 181.5059044966999977, 104.6140438237000012 ) ) ; +#28193 = CARTESIAN_POINT ( 'NONE', ( -45.88101201451510036, 125.0059045045339445, 91.84762798775689419 ) ) ; +#28194 = ORIENTED_EDGE ( 'NONE', *, *, #28880, .F. ) ; +#28195 = ORIENTED_EDGE ( 'NONE', *, *, #37817, .F. ) ; +#28196 = CARTESIAN_POINT ( 'NONE', ( 38.37691917934760966, 118.9413681235701716, 90.24641942494658053 ) ) ; +#28197 = CARTESIAN_POINT ( 'NONE', ( -40.69272868349872851, 120.3526484630613567, 90.54200919472567932 ) ) ; +#28198 = CARTESIAN_POINT ( 'NONE', ( 25.99018610745488900, 211.0908525021142168, 73.04280463953621449 ) ) ; +#28199 = DIRECTION ( 'NONE', ( -0.7069375452530715087, 0.1593035203500499375, -0.6891020936810761111 ) ) ; +#28200 = CARTESIAN_POINT ( 'NONE', ( -25.50169130963128694, 190.9445587163764912, 106.3119803418707789 ) ) ; +#28201 = ORIENTED_EDGE ( 'NONE', *, *, #25535, .T. ) ; +#28202 = CARTESIAN_POINT ( 'NONE', ( -30.96737657860713355, 184.1206350860066152, 102.1792248493828055 ) ) ; +#28203 = FACE_OUTER_BOUND ( 'NONE', #14579, .T. ) ; +#28204 = CARTESIAN_POINT ( 'NONE', ( -22.78329764787637046, 154.4034317766920310, 95.31352365236099899 ) ) ; +#28205 = DIRECTION ( 'NONE', ( -0.6087613505917195411, 0.7729391288371411095, 0.1788147676737769087 ) ) ; +#28206 = ORIENTED_EDGE ( 'NONE', *, *, #7651, .T. ) ; +#28207 = FACE_OUTER_BOUND ( 'NONE', #27084, .T. ) ; +#28208 = DIRECTION ( 'NONE', ( -0.0006039748319369898531, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#28209 = CARTESIAN_POINT ( 'NONE', ( -4.036853220715999946, 137.3587048356999958, 92.90657171102999712 ) ) ; +#28210 = EDGE_CURVE ( 'NONE', #21097, #31137, #39485, .T. ) ; +#28211 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22973, #26249, #4543, #10312 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28212 = AXIS2_PLACEMENT_3D ( 'NONE', #31748, #32537, #3710 ) ; +#28213 = EDGE_CURVE ( 'NONE', #26074, #34665, #38042, .T. ) ; +#28215 = ORIENTED_EDGE ( 'NONE', *, *, #15184, .F. ) ; +#28214 = FACE_OUTER_BOUND ( 'NONE', #34459, .T. ) ; +#28216 = ORIENTED_EDGE ( 'NONE', *, *, #37650, .F. ) ; +#28217 = ORIENTED_EDGE ( 'NONE', *, *, #5766, .T. ) ; +#28218 = CIRCLE ( 'NONE', #8631, 48.00000000000002132 ) ; +#28219 = CARTESIAN_POINT ( 'NONE', ( -3.991797733021813510, 135.9364417893758059, 91.03873269948198299 ) ) ; +#28220 = AXIS2_PLACEMENT_3D ( 'NONE', #35339, #4690, #17148 ) ; +#28221 = CARTESIAN_POINT ( 'NONE', ( 37.96499143901794326, 190.9636352903536363, 106.2831835502989719 ) ) ; +#28222 = DIRECTION ( 'NONE', ( -0.6185863125140933505, -0.7857168535612664151, 0.000000000000000000 ) ) ; +#28223 = ORIENTED_EDGE ( 'NONE', *, *, #5754, .F. ) ; +#28224 = CARTESIAN_POINT ( 'NONE', ( 38.26442139451999935, 118.3961640203000059, 87.79339008044999559 ) ) ; +#28225 = CARTESIAN_POINT ( 'NONE', ( -15.53688711337808392, 141.8436893266793106, 28.08107123285647688 ) ) ; +#28226 = CARTESIAN_POINT ( 'NONE', ( 37.71190864537933862, 212.3970730851055748, 73.53572712575454773 ) ) ; +#28227 = DIRECTION ( 'NONE', ( -0.9999998268368293086, -0.0001323825425856265552, 0.0005734118708436176113 ) ) ; +#28228 = ORIENTED_EDGE ( 'NONE', *, *, #12349, .T. ) ; +#28229 = FACE_OUTER_BOUND ( 'NONE', #10019, .T. ) ; +#28230 = CARTESIAN_POINT ( 'NONE', ( 25.91387799687219129, 211.8752679534836432, 76.04289190268519860 ) ) ; +#28231 = FACE_OUTER_BOUND ( 'NONE', #1743, .T. ) ; +#28232 = CARTESIAN_POINT ( 'NONE', ( 42.83909608654821710, 114.0261269506707720, 121.8710131577738167 ) ) ; +#28233 = CARTESIAN_POINT ( 'NONE', ( -30.07053858951977432, 176.7377855870873873, 103.0399784982492264 ) ) ; +#28234 = ORIENTED_EDGE ( 'NONE', *, *, #20370, .T. ) ; +#28235 = EDGE_CURVE ( 'NONE', #29048, #25314, #4871, .T. ) ; +#28236 = CARTESIAN_POINT ( 'NONE', ( 12.64167983538768247, 177.0102573821494047, 103.4424840777840870 ) ) ; +#28237 = CARTESIAN_POINT ( 'NONE', ( 2.724721502837000209, 190.8511545057000092, 104.0546029546000000 ) ) ; +#28238 = CARTESIAN_POINT ( 'NONE', ( -22.49965381657531438, 154.0036946681026393, 95.56316798547172198 ) ) ; +#28239 = ORIENTED_EDGE ( 'NONE', *, *, #30044, .F. ) ; +#28240 = CIRCLE ( 'NONE', #22370, 2.500000000028349767 ) ; +#28241 = CARTESIAN_POINT ( 'NONE', ( -12.63793912156016042, 182.0618459091404873, 102.2059974569859975 ) ) ; +#28242 = ORIENTED_EDGE ( 'NONE', *, *, #1742, .T. ) ; +#28243 = AXIS2_PLACEMENT_3D ( 'NONE', #29301, #10700, #20287 ) ; +#28244 = PLANE ( 'NONE', #38434 ) ; +#28245 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #1296, #1104, #8045, #39315 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.877759422838638059, 4.066897489514542663 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9970211203892868079, 0.9970211203892868079, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#28246 = CARTESIAN_POINT ( 'NONE', ( -18.71851310314255556, 125.9964326179262883, 174.7342168340691444 ) ) ; +#28247 = CARTESIAN_POINT ( 'NONE', ( 2.812852758428999955, 191.2630064568000137, 104.0643451705000047 ) ) ; +#28248 = DIRECTION ( 'NONE', ( 0.0005884933334877639251, -0.2249510526608011762, 0.9743698874567060519 ) ) ; +#28249 = CARTESIAN_POINT ( 'NONE', ( -36.77540113530000099, 191.4363505423999925, 106.2577542721000015 ) ) ; +#28250 = ORIENTED_EDGE ( 'NONE', *, *, #23674, .T. ) ; +#28251 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#28252 = FACE_OUTER_BOUND ( 'NONE', #2742, .T. ) ; +#28253 = EDGE_CURVE ( 'NONE', #25168, #16126, #22418, .T. ) ; +#28254 = ADVANCED_FACE ( 'NONE', ( #40022 ), #33882, .F. ) ; +#28255 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#28256 = ORIENTED_EDGE ( 'NONE', *, *, #18528, .F. ) ; +#28257 = ORIENTED_EDGE ( 'NONE', *, *, #20059, .T. ) ; +#28258 = ORIENTED_EDGE ( 'NONE', *, *, #34225, .T. ) ; +#28259 = CYLINDRICAL_SURFACE ( 'NONE', #32197, 1.999999999999989564 ) ; +#28260 = CARTESIAN_POINT ( 'NONE', ( -19.46376889861871007, 126.0568456380973288, 176.8090460237677348 ) ) ; +#28261 = CONICAL_SURFACE ( 'NONE', #17780, 4.999999999873454115, 0.7853981633979292276 ) ; +#28262 = VERTEX_POINT ( 'NONE', #1148 ) ; +#28263 = CARTESIAN_POINT ( 'NONE', ( 39.95261991177000027, 119.3835613333999959, 89.61779218156000582 ) ) ; +#28264 = CARTESIAN_POINT ( 'NONE', ( 0.5441254074100964067, 211.4999999999614602, 73.05817544432547095 ) ) ; +#28265 = VECTOR ( 'NONE', #19204, 1000.000000000000227 ) ; +#28266 = DIRECTION ( 'NONE', ( -0.0006039748319391919761, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#28267 = CARTESIAN_POINT ( 'NONE', ( -38.01969208680999657, 119.2054080613999929, 87.30150489016999416 ) ) ; +#28268 = CARTESIAN_POINT ( 'NONE', ( -37.26053171017113641, 122.4594309094748326, 105.8893166679895472 ) ) ; +#28269 = ORIENTED_EDGE ( 'NONE', *, *, #28163, .T. ) ; +#28270 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250613436, 179.6252109630477207, 101.6466942237163522 ) ) ; +#28271 = VERTEX_POINT ( 'NONE', #22039 ) ; +#28272 = CARTESIAN_POINT ( 'NONE', ( -28.70875735419499364, 148.8778593096899669, 94.55457546971690874 ) ) ; +#28273 = LINE ( 'NONE', #3110, #19680 ) ; +#28274 = ORIENTED_EDGE ( 'NONE', *, *, #21153, .T. ) ; +#28275 = VERTEX_POINT ( 'NONE', #4200 ) ; +#28276 = CARTESIAN_POINT ( 'NONE', ( -15.99999263269153182, 160.7450692216915513, 96.77351201758563093 ) ) ; +#28277 = CARTESIAN_POINT ( 'NONE', ( 2.689650463064989339, 189.7940790364034740, 103.4687148295890040 ) ) ; +#28278 = DIRECTION ( 'NONE', ( -0.0005884949961246157971, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#28279 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11475, #40077, #17588, #36819 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 3.455345801775207831E-07, 0.001975602230082555786 ), + .UNSPECIFIED. ) ; +#28280 = ORIENTED_EDGE ( 'NONE', *, *, #12188, .F. ) ; +#28281 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 77.27946979429643193, 322.5967026918629017 ) ) ; +#28282 = CARTESIAN_POINT ( 'NONE', ( -39.67267316526923082, 108.4053246579875776, 179.2050514857695021 ) ) ; +#28283 = ORIENTED_EDGE ( 'NONE', *, *, #35630, .T. ) ; +#28284 = CARTESIAN_POINT ( 'NONE', ( 20.50100932471902482, 118.1127835883590365, 89.75563873136169946 ) ) ; +#28285 = CARTESIAN_POINT ( 'NONE', ( 36.12477503817289204, 191.5193954017357783, 103.8468415931941990 ) ) ; +#28286 = CARTESIAN_POINT ( 'NONE', ( -25.36579399085000119, 120.1305625512000006, 89.82939052176000416 ) ) ; +#28287 = CIRCLE ( 'NONE', #23700, 6.500000058541756331 ) ; +#28288 = EDGE_CURVE ( 'NONE', #27254, #38370, #25831, .T. ) ; +#28289 = ORIENTED_EDGE ( 'NONE', *, *, #31857, .F. ) ; +#28290 = VECTOR ( 'NONE', #39961, 1000.000000000000000 ) ; +#28291 = CARTESIAN_POINT ( 'NONE', ( -13.46516334634018541, 157.8278071510762572, 99.00633757409819680 ) ) ; +#28292 = CARTESIAN_POINT ( 'NONE', ( -13.50742204590874351, 123.6898730104831117, 91.29604175845440750 ) ) ; +#28293 = EDGE_CURVE ( 'NONE', #35987, #16019, #9968, .T. ) ; +#28294 = AXIS2_PLACEMENT_3D ( 'NONE', #480, #3744, #37907 ) ; +#28295 = ORIENTED_EDGE ( 'NONE', *, *, #13267, .T. ) ; +#28296 = CARTESIAN_POINT ( 'NONE', ( 16.17545524454269312, 122.0361947523238229, 178.1139273532624259 ) ) ; +#28297 = CARTESIAN_POINT ( 'NONE', ( -1.458415330454428505, 152.0517121853154379, 130.6798743964100993 ) ) ; +#28298 = EDGE_CURVE ( 'NONE', #20118, #17896, #22811, .T. ) ; +#28299 = ADVANCED_FACE ( 'NONE', ( #38554 ), #19544, .F. ) ; +#28300 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5870, #22031, #33667, #33872 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28302 = CARTESIAN_POINT ( 'NONE', ( 35.76606814934199718, 191.7746197043701386, 103.8954709317327172 ) ) ; +#28301 = CARTESIAN_POINT ( 'NONE', ( 36.15259226440387863, 192.0798216505441758, 104.3835126011738197 ) ) ; +#28303 = EDGE_CURVE ( 'NONE', #38350, #2098, #37964, .T. ) ; +#28304 = ORIENTED_EDGE ( 'NONE', *, *, #16998, .F. ) ; +#28305 = EDGE_CURVE ( 'NONE', #39104, #17992, #13664, .T. ) ; +#28306 = VERTEX_POINT ( 'NONE', #19740 ) ; +#28307 = CARTESIAN_POINT ( 'NONE', ( -15.87151776090180100, 128.5901718154909474, 173.0117519459708433 ) ) ; +#28308 = DIRECTION ( 'NONE', ( 0.0005884984005724823181, -0.2249510543433854981, 0.9743698870651902322 ) ) ; +#28309 = VERTEX_POINT ( 'NONE', #28571 ) ; +#28310 = ORIENTED_EDGE ( 'NONE', *, *, #26500, .F. ) ; +#28311 = DIRECTION ( 'NONE', ( 0.0005884928212895036660, -0.2249510522791091927, 0.9743698875451358710 ) ) ; +#28312 = CARTESIAN_POINT ( 'NONE', ( -23.00157826576616671, 118.1131156702000169, 87.27825658246501916 ) ) ; +#28313 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 77.27946979429631824, 312.5857197240631535 ) ) ; +#28314 = CARTESIAN_POINT ( 'NONE', ( 35.68643125140999928, 191.8664213346000054, 103.8907803534000038 ) ) ; +#28315 = CIRCLE ( 'NONE', #29591, 47.50000000003990408 ) ; +#28316 = ORIENTED_EDGE ( 'NONE', *, *, #12787, .T. ) ; +#28317 = ORIENTED_EDGE ( 'NONE', *, *, #21281, .F. ) ; +#28318 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; +#28319 = FACE_OUTER_BOUND ( 'NONE', #18324, .T. ) ; +#28320 = VECTOR ( 'NONE', #17212, 1000.000000000000114 ) ; +#28321 = CARTESIAN_POINT ( 'NONE', ( -25.99570828418999824, 122.1044024015999980, 88.02969383087000210 ) ) ; +#28322 = ORIENTED_EDGE ( 'NONE', *, *, #3892, .T. ) ; +#28323 = CIRCLE ( 'NONE', #38736, 5.500000000022846613 ) ; +#28324 = ADVANCED_FACE ( 'NONE', ( #28965 ), #21510, .F. ) ; +#28325 = CARTESIAN_POINT ( 'NONE', ( -16.85990575305292083, 127.4181457678018035, 171.9189068126523807 ) ) ; +#28326 = CYLINDRICAL_SURFACE ( 'NONE', #36544, 6.000000000000008882 ) ; +#28327 = ORIENTED_EDGE ( 'NONE', *, *, #16779, .F. ) ; +#28328 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; +#28329 = CARTESIAN_POINT ( 'NONE', ( -5.667037705184884366, 187.3709129604629595, 105.5860125638189118 ) ) ; +#28330 = CARTESIAN_POINT ( 'NONE', ( -0.6151120320699999811, 188.2150256863999971, 106.3550489248000019 ) ) ; +#28331 = CARTESIAN_POINT ( 'NONE', ( 16.92715356280326233, 133.1527996547432338, 149.4950069489673581 ) ) ; +#28332 = EDGE_CURVE ( 'NONE', #21146, #8372, #7721, .T. ) ; +#28333 = ORIENTED_EDGE ( 'NONE', *, *, #26137, .T. ) ; +#28334 = DIRECTION ( 'NONE', ( -0.0005884986055440120847, 0.2249510543433680121, -0.9743698870650705501 ) ) ; +#28335 = EDGE_LOOP ( 'NONE', ( #21873, #12651, #17930, #1377 ) ) ; +#28336 = CARTESIAN_POINT ( 'NONE', ( 42.26901360392582063, 75.77666427028830753, 289.7178605909170415 ) ) ; +#28337 = CARTESIAN_POINT ( 'NONE', ( -38.59856012205000297, 118.8379521557999965, 87.85035348418999490 ) ) ; +#28338 = FACE_OUTER_BOUND ( 'NONE', #9954, .T. ) ; +#28339 = EDGE_CURVE ( 'NONE', #22101, #10159, #38458, .T. ) ; +#28340 = ORIENTED_EDGE ( 'NONE', *, *, #30419, .F. ) ; +#28341 = VECTOR ( 'NONE', #21187, 1000.000000000000000 ) ; +#28342 = VECTOR ( 'NONE', #3521, 1000.000000000000000 ) ; +#28343 = DIRECTION ( 'NONE', ( -0.6088835995545407442, -0.7728434649458200134, -0.1788120266761852595 ) ) ; +#28344 = ORIENTED_EDGE ( 'NONE', *, *, #10892, .F. ) ; +#28345 = EDGE_CURVE ( 'NONE', #33884, #15381, #3403, .T. ) ; +#28346 = CARTESIAN_POINT ( 'NONE', ( 24.99968009405584723, 116.5768933708840649, 89.75284153560482991 ) ) ; +#28347 = AXIS2_PLACEMENT_3D ( 'NONE', #33323, #30072, #39452 ) ; +#28348 = PLANE ( 'NONE', #29210 ) ; +#28349 = ADVANCED_FACE ( 'NONE', ( #35270 ), #11042, .T. ) ; +#28350 = EDGE_LOOP ( 'NONE', ( #9852, #20989, #23508, #6535, #7620, #18054, #34314, #13880 ) ) ; +#28351 = ORIENTED_EDGE ( 'NONE', *, *, #25489, .F. ) ; +#28352 = DIRECTION ( 'NONE', ( -0.0005884949961245386019, 0.2249510543439047772, -0.9743698870671267942 ) ) ; +#28353 = CARTESIAN_POINT ( 'NONE', ( 5.666638401078818887, 184.0130092264801647, 102.6454035786637178 ) ) ; +#28354 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12547, #28503, #38099, #476 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999992929630487914 ), + .UNSPECIFIED. ) ; +#28355 = CARTESIAN_POINT ( 'NONE', ( -20.19472725636804000, 159.7949336108657405, 96.55668671736475517 ) ) ; +#28356 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30202, #2199, #11602, #9948 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28357 = CARTESIAN_POINT ( 'NONE', ( -36.18146673395180102, 116.0141564695149725, 90.28963753848354656 ) ) ; +#28358 = ORIENTED_EDGE ( 'NONE', *, *, #20907, .F. ) ; +#28359 = VERTEX_POINT ( 'NONE', #37755 ) ; +#28360 = CARTESIAN_POINT ( 'NONE', ( 39.71642354168957922, 182.5096340661373802, 106.7714012342299270 ) ) ; +#28361 = FACE_OUTER_BOUND ( 'NONE', #12884, .T. ) ; +#28362 = CARTESIAN_POINT ( 'NONE', ( 37.35431113053603269, 167.9917614804752759, 183.6110637893014825 ) ) ; +#28363 = ORIENTED_EDGE ( 'NONE', *, *, #36822, .F. ) ; +#28364 = CARTESIAN_POINT ( 'NONE', ( 19.98059076253610300, 209.7097557544199162, 73.04669817794425057 ) ) ; +#28365 = DIRECTION ( 'NONE', ( -0.6087611434179115433, 0.7728348325624404547, 0.1792657018023851023 ) ) ; +#28366 = VERTEX_POINT ( 'NONE', #3598 ) ; +#28367 = CARTESIAN_POINT ( 'NONE', ( -20.49823408210000153, 128.0735935753000092, 92.31233318296999357 ) ) ; +#28368 = DIRECTION ( 'NONE', ( -0.7933310414247657372, -0.5931044597393388962, -0.1373060761554398823 ) ) ; +#28369 = ORIENTED_EDGE ( 'NONE', *, *, #13067, .F. ) ; +#28370 = CARTESIAN_POINT ( 'NONE', ( 28.00973715401000419, 125.4209793305000034, 89.10502106993999405 ) ) ; +#28371 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#28372 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971553467 ) ) ; +#28373 = AXIS2_PLACEMENT_3D ( 'NONE', #27002, #14117, #7754 ) ; +#28374 = DIRECTION ( 'NONE', ( 0.9914448564834557054, 0.1271450465211625414, 0.02951666813228253847 ) ) ; +#28375 = CARTESIAN_POINT ( 'NONE', ( 4.722196207747476393, 124.5475539680846708, 88.40413725569121084 ) ) ; +#28376 = ORIENTED_EDGE ( 'NONE', *, *, #5566, .F. ) ; +#28377 = CARTESIAN_POINT ( 'NONE', ( 16.33425786393173595, 122.2176022978402870, 174.5993093248799255 ) ) ; +#28378 = CARTESIAN_POINT ( 'NONE', ( 31.79391164804994219, 225.9002260768944268, 73.03930135624560194 ) ) ; +#28379 = CARTESIAN_POINT ( 'NONE', ( -44.76913686494872735, 168.7247935234274507, 183.7603518044827808 ) ) ; +#28380 = EDGE_CURVE ( 'NONE', #40344, #34013, #31695, .T. ) ; +#28381 = CARTESIAN_POINT ( 'NONE', ( -26.00133084196312083, 118.1145346548141077, 87.28348844432062492 ) ) ; +#28382 = ORIENTED_EDGE ( 'NONE', *, *, #22709, .F. ) ; +#28383 = EDGE_CURVE ( 'NONE', #21313, #28523, #34526, .T. ) ; +#28384 = VERTEX_POINT ( 'NONE', #34867 ) ; +#28385 = CARTESIAN_POINT ( 'NONE', ( 38.37227342911298678, 118.9376377202380723, 90.24635654664764672 ) ) ; +#28386 = EDGE_CURVE ( 'NONE', #38190, #13026, #31847, .T. ) ; +#28387 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552357 ) ) ; +#28388 = CARTESIAN_POINT ( 'NONE', ( -34.95487766943205088, 217.7719116314000303, 76.07961649972587281 ) ) ; +#28389 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #5731, #21280, #8408, #27830 ), + ( #17771, #33728, #37015, #24151 ), + ( #30683, #40260, #2472, #39863 ), + ( #2676, #9010, #21491, #5925 ), + ( #12270, #24762, #37213, #9210 ), + ( #16469, #32045, #9407, #13229 ), + ( #10759, #16274, #32433, #19936 ), + ( #38360, #1144, #19540, #35663 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.09352946601170999963, 0.000000000000000000, 0.3333335556354999896, 0.6666667497720000224, 1.000000000000000000, 1.093335578620999948 ), + ( -0.2707488541708999996, 1.270751830638999991 ), + .UNSPECIFIED. ) ; +#28390 = CARTESIAN_POINT ( 'NONE', ( -9.337769819897999923, 135.1051653709000107, 91.10662228834000587 ) ) ; +#28391 = ORIENTED_EDGE ( 'NONE', *, *, #21332, .F. ) ; +#28392 = CARTESIAN_POINT ( 'NONE', ( -26.00499219198855982, 190.8675043533962992, 106.8127785445518612 ) ) ; +#28393 = ORIENTED_EDGE ( 'NONE', *, *, #38297, .F. ) ; +#28394 = EDGE_CURVE ( 'NONE', #17792, #5601, #36002, .T. ) ; +#28395 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749096068, 132.4103119504883637, 92.77713868752285009 ) ) ; +#28396 = ADVANCED_FACE ( 'NONE', ( #13234 ), #36518, .F. ) ; +#28397 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#28398 = CIRCLE ( 'NONE', #10769, 58.90509898902387675 ) ; +#28399 = ORIENTED_EDGE ( 'NONE', *, *, #16950, .T. ) ; +#28400 = DIRECTION ( 'NONE', ( -0.0006039748319386907495, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#28401 = CARTESIAN_POINT ( 'NONE', ( -25.99151835185281456, 191.8641524188973904, 103.9340199701208292 ) ) ; +#28402 = FACE_OUTER_BOUND ( 'NONE', #4841, .T. ) ; +#28403 = CARTESIAN_POINT ( 'NONE', ( 36.67721844215000004, 191.5565990098999976, 105.0176447302000042 ) ) ; +#28404 = VECTOR ( 'NONE', #16893, 1000.000000000000227 ) ; +#28406 = ORIENTED_EDGE ( 'NONE', *, *, #20042, .F. ) ; +#28405 = CARTESIAN_POINT ( 'NONE', ( 36.36316272580000231, 190.7132676102999937, 106.8883652936000033 ) ) ; +#28407 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #30868, #5499, #11656, #39845 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.1794458056510853106, 1.570796326794893227 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8450807331196341643, 0.8450807331196341643, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#28408 = ORIENTED_EDGE ( 'NONE', *, *, #39857, .F. ) ; +#28409 = ADVANCED_FACE ( 'NONE', ( #32436, #39160 ), #33025, .F. ) ; +#28410 = CARTESIAN_POINT ( 'NONE', ( -3.537750984983824232, 137.3463269818849426, 91.36396247942009552 ) ) ; +#28411 = CARTESIAN_POINT ( 'NONE', ( -10.03596943924098461, 167.8207392792199357, 101.4823675420411888 ) ) ; +#28412 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700560425843094, -0.2249510922124433321 ) ) ; +#28413 = ORIENTED_EDGE ( 'NONE', *, *, #33114, .F. ) ; +#28414 = DIRECTION ( 'NONE', ( 0.7856007465113973298, 0.6187337610642684727, -2.775557561562888984E-15 ) ) ; +#28415 = EDGE_LOOP ( 'NONE', ( #28215, #11685, #38019, #19140, #11815, #3144, #30758, #14148 ) ) ; +#28416 = CARTESIAN_POINT ( 'NONE', ( -3.191561267867959906, 128.9664370676184149, 89.42909670096250352 ) ) ; +#28417 = CARTESIAN_POINT ( 'NONE', ( 13.76428958134252412, 149.7303430850596726, 179.8030703197238722 ) ) ; +#28418 = ORIENTED_EDGE ( 'NONE', *, *, #27585, .F. ) ; +#28419 = FACE_OUTER_BOUND ( 'NONE', #8355, .T. ) ; +#28420 = CARTESIAN_POINT ( 'NONE', ( -9.152368346436000834, 130.1581468331999929, 92.53016161835999753 ) ) ; +#28421 = LINE ( 'NONE', #32097, #1168 ) ; +#28422 = DIRECTION ( 'NONE', ( 0.0002393071182786160318, 0.2252352986010024705, -0.9743043687658494711 ) ) ; +#28423 = CARTESIAN_POINT ( 'NONE', ( -20.00089539691495233, 118.1272453392662527, 87.27993277136866368 ) ) ; +#28424 = CARTESIAN_POINT ( 'NONE', ( 44.87593640575996545, 182.0270868175379064, 126.4518070426625087 ) ) ; +#28425 = VERTEX_POINT ( 'NONE', #26510 ) ; +#28426 = CARTESIAN_POINT ( 'NONE', ( 2.299083559809740773, 189.9861417232580436, 103.9812579833990043 ) ) ; +#28427 = AXIS2_PLACEMENT_3D ( 'NONE', #28270, #25610, #15976 ) ; +#28428 = CIRCLE ( 'NONE', #2959, 1.749999999999998446 ) ; +#28429 = LINE ( 'NONE', #6529, #31923 ) ; +#28430 = EDGE_CURVE ( 'NONE', #30562, #19329, #14083, .T. ) ; +#28431 = EDGE_CURVE ( 'NONE', #25244, #22597, #20768, .T. ) ; +#28432 = AXIS2_PLACEMENT_3D ( 'NONE', #9217, #37613, #13082 ) ; +#28433 = EDGE_LOOP ( 'NONE', ( #6385, #10949, #33166 ) ) ; +#28434 = PLANE ( 'NONE', #25779 ) ; +#28435 = ADVANCED_FACE ( 'NONE', ( #23041 ), #23640, .T. ) ; +#28436 = ORIENTED_EDGE ( 'NONE', *, *, #36640, .F. ) ; +#28437 = CARTESIAN_POINT ( 'NONE', ( 20.00164795315919974, 192.9502750275173355, 106.8376583096656418 ) ) ; +#28438 = EDGE_CURVE ( 'NONE', #25514, #31634, #13028, .T. ) ; +#28439 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 181.5925925342323808, 103.1272040707186051 ) ) ; +#28440 = LINE ( 'NONE', #18600, #20123 ) ; +#28441 = CARTESIAN_POINT ( 'NONE', ( -3.169881913554984720, 185.9062129263137138, 102.5746722649703315 ) ) ; +#28442 = EDGE_CURVE ( 'NONE', #27517, #17622, #27791, .T. ) ; +#28443 = CARTESIAN_POINT ( 'NONE', ( -35.81454439945957802, 108.4403536831198096, 169.8262657571169711 ) ) ; +#28444 = CARTESIAN_POINT ( 'NONE', ( -36.70169623595000274, 190.4202923789999886, 106.8599970589999941 ) ) ; +#28445 = ORIENTED_EDGE ( 'NONE', *, *, #40320, .T. ) ; +#28446 = CARTESIAN_POINT ( 'NONE', ( -5.631497921780000304, 112.1320600213999938, 152.4718672074000381 ) ) ; +#28447 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971574007 ) ) ; +#28448 = CYLINDRICAL_SURFACE ( 'NONE', #9212, 48.00000000000002132 ) ; +#28449 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#28450 = VECTOR ( 'NONE', #16492, 1000.000000000000000 ) ; +#28451 = ORIENTED_EDGE ( 'NONE', *, *, #2132, .F. ) ; +#28452 = EDGE_CURVE ( 'NONE', #1519, #9277, #1758, .T. ) ; +#28453 = CIRCLE ( 'NONE', #20583, 3.000000000000002220 ) ; +#28454 = ORIENTED_EDGE ( 'NONE', *, *, #14388, .F. ) ; +#28455 = CARTESIAN_POINT ( 'NONE', ( -29.94810852811952984, 104.1131156702273302, 87.28587219911912598 ) ) ; +#28456 = VECTOR ( 'NONE', #7659, 1000.000000000000114 ) ; +#28457 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142367503004439, 137.4659008082804519, 177.5714312369109393 ) ) ; +#28458 = AXIS2_PLACEMENT_3D ( 'NONE', #25065, #37512, #40168 ) ; +#28459 = EDGE_LOOP ( 'NONE', ( #34790, #27532, #37116, #14955 ) ) ; +#28460 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#28461 = LINE ( 'NONE', #6562, #33188 ) ; +#28462 = CARTESIAN_POINT ( 'NONE', ( -38.01110030706000487, 119.1986783965000001, 87.29992373471000633 ) ) ; +#28463 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700559946817386, 0.2249510924199318862 ) ) ; +#28464 = ORIENTED_EDGE ( 'NONE', *, *, #39114, .T. ) ; +#28465 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; +#28466 = ORIENTED_EDGE ( 'NONE', *, *, #21795, .F. ) ; +#28467 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#28468 = CARTESIAN_POINT ( 'NONE', ( 36.04411892353203228, 218.5902260770999987, 73.03673433779063373 ) ) ; +#28469 = ORIENTED_EDGE ( 'NONE', *, *, #814, .F. ) ; +#28470 = ORIENTED_EDGE ( 'NONE', *, *, #22668, .T. ) ; +#28471 = DIRECTION ( 'NONE', ( 0.0004161288024578961228, 0.5299192578740949955, 0.8480479980348919478 ) ) ; +#28472 = CARTESIAN_POINT ( 'NONE', ( 0.7394385361564065340, 188.6187616188480263, 103.1985492530441348 ) ) ; +#28473 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564570 ) ) ; +#28474 = EDGE_LOOP ( 'NONE', ( #15268, #14385, #30115, #31744 ) ) ; +#28475 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #39038, #2049, #23931, #4695 ), + .UNSPECIFIED., .F., .F. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.137875966956429785, 6.279468620546222013 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.3333333333333337034, 0.3333333333333337034, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#28476 = EDGE_CURVE ( 'NONE', #26158, #25434, #29729, .T. ) ; +#28477 = ORIENTED_EDGE ( 'NONE', *, *, #25079, .T. ) ; +#28478 = CARTESIAN_POINT ( 'NONE', ( 20.07473376121614450, 118.1084071564281430, 87.33016715071195790 ) ) ; +#28479 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#28480 = EDGE_CURVE ( 'NONE', #21867, #36048, #5214, .T. ) ; +#28481 = AXIS2_PLACEMENT_3D ( 'NONE', #31020, #9347, #37544 ) ; +#28482 = ORIENTED_EDGE ( 'NONE', *, *, #3575, .T. ) ; +#28483 = AXIS2_PLACEMENT_3D ( 'NONE', #20065, #14167, #17401 ) ; +#28484 = CARTESIAN_POINT ( 'NONE', ( -21.21281385531639430, 128.6733510584166140, 91.93807758298277122 ) ) ; +#28485 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17897, #18694, #30393, #40180, #9125, #14863, #3168, #5850, #27350, #15063 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28486 = CARTESIAN_POINT ( 'NONE', ( 36.20181100725926626, 191.4690138734401899, 103.8351635709739185 ) ) ; +#28487 = CARTESIAN_POINT ( 'NONE', ( -25.99978576141418429, 118.1122949349609286, 90.28348809642494643 ) ) ; +#28488 = AXIS2_PLACEMENT_3D ( 'NONE', #8070, #27109, #24648 ) ; +#28489 = ORIENTED_EDGE ( 'NONE', *, *, #33352, .T. ) ; +#28490 = LINE ( 'NONE', #2921, #25006 ) ; +#28491 = LINE ( 'NONE', #31769, #995 ) ; +#28492 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023852966 ) ) ; +#28493 = CARTESIAN_POINT ( 'NONE', ( -38.94661729375161485, 128.0727087836390865, 89.75751053642740374 ) ) ; +#28494 = ORIENTED_EDGE ( 'NONE', *, *, #4290, .F. ) ; +#28495 = CARTESIAN_POINT ( 'NONE', ( -25.50772789806992336, 207.4083919359153469, 77.09708259026270127 ) ) ; +#28496 = CARTESIAN_POINT ( 'NONE', ( 35.54494089926004108, 209.7096602146001487, 73.03703587511542139 ) ) ; +#28498 = CARTESIAN_POINT ( 'NONE', ( -2.935232621041004020, 190.8511156531020276, 106.7950609103722286 ) ) ; +#28497 = CARTESIAN_POINT ( 'NONE', ( -28.43520508893000098, 186.6528701677999891, 105.6701704825000121 ) ) ; +#28499 = VERTEX_POINT ( 'NONE', #38749 ) ; +#28500 = EDGE_CURVE ( 'NONE', #8772, #23153, #877, .T. ) ; +#28501 = LINE ( 'NONE', #9693, #21707 ) ; +#28502 = ORIENTED_EDGE ( 'NONE', *, *, #22684, .T. ) ; +#28503 = CARTESIAN_POINT ( 'NONE', ( -14.89266151782658021, 129.2859740412766882, 89.85203636143938866 ) ) ; +#28504 = VECTOR ( 'NONE', #38113, 1000.000000000000000 ) ; +#28505 = CARTESIAN_POINT ( 'NONE', ( 35.98181449372523844, 160.9880612539904234, 187.1235093347274017 ) ) ; +#28506 = CARTESIAN_POINT ( 'NONE', ( -6.035970131895957103, 136.6793194835712484, 94.29038707408911080 ) ) ; +#28507 = ORIENTED_EDGE ( 'NONE', *, *, #8065, .F. ) ; +#28508 = CIRCLE ( 'NONE', #29820, 22.00000000001089973 ) ; +#28509 = VECTOR ( 'NONE', #12389, 999.9999999999998863 ) ; +#28510 = ORIENTED_EDGE ( 'NONE', *, *, #36545, .T. ) ; +#28511 = LINE ( 'NONE', #15819, #14598 ) ; +#28512 = DIRECTION ( 'NONE', ( -0.0005884949961246006183, 0.2249510543439056653, -0.9743698870671265722 ) ) ; +#28513 = CARTESIAN_POINT ( 'NONE', ( 35.73033089362894543, 192.3272895366094986, 104.0378526287656342 ) ) ; +#28514 = ORIENTED_EDGE ( 'NONE', *, *, #20135, .F. ) ; +#28515 = ADVANCED_FACE ( 'NONE', ( #4613 ), #1549, .F. ) ; +#28516 = VERTEX_POINT ( 'NONE', #20349 ) ; +#28517 = CARTESIAN_POINT ( 'NONE', ( 43.54015349013348413, 114.1160320775752552, 121.8918845945049014 ) ) ; +#28518 = AXIS2_PLACEMENT_3D ( 'NONE', #34879, #25122, #37764 ) ; +#28519 = CARTESIAN_POINT ( 'NONE', ( -12.63727448935653186, 177.2390372512880958, 101.0505970525729680 ) ) ; +#28520 = CARTESIAN_POINT ( 'NONE', ( -3.501632090593860713, 185.3069955807334566, 105.1733482448064620 ) ) ; +#28521 = CYLINDRICAL_SURFACE ( 'NONE', #38574, 2.000000000000011546 ) ; +#28522 = ADVANCED_FACE ( 'NONE', ( #39359 ), #11072, .F. ) ; +#28523 = VERTEX_POINT ( 'NONE', #36709 ) ; +#28524 = CARTESIAN_POINT ( 'NONE', ( -23.89831259315023715, 121.1330467865301586, 177.8952988152876458 ) ) ; +#28525 = ORIENTED_EDGE ( 'NONE', *, *, #15088, .T. ) ; +#28526 = CARTESIAN_POINT ( 'NONE', ( -37.72956294166493052, 117.6505992105354750, 89.71937875289896169 ) ) ; +#28527 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #40099, #8647, #11498, #33362 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28528 = ADVANCED_FACE ( 'NONE', ( #8512 ), #30379, .F. ) ; +#28529 = CARTESIAN_POINT ( 'NONE', ( -15.99999342760827936, 185.2774429011668076, 102.4372551014714929 ) ) ; +#28530 = EDGE_CURVE ( 'NONE', #23376, #21600, #34557, .T. ) ; +#28531 = ORIENTED_EDGE ( 'NONE', *, *, #32621, .T. ) ; +#28532 = DIRECTION ( 'NONE', ( 0.0002393071182785211099, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#28533 = CARTESIAN_POINT ( 'NONE', ( 12.63852066807981345, 177.1933417902586427, 101.0667481637636627 ) ) ; +#28534 = DIRECTION ( 'NONE', ( 0.0005884949961289119482, -0.2249510543439059984, 0.9743698870671263501 ) ) ; +#28535 = AXIS2_PLACEMENT_3D ( 'NONE', #33607, #12155, #8892 ) ; +#28536 = ORIENTED_EDGE ( 'NONE', *, *, #25648, .T. ) ; +#28537 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7071067167009886800, -0.7071068456721004702 ) ) ; +#28538 = CARTESIAN_POINT ( 'NONE', ( 15.50147165697079465, 137.9484461010407870, 94.05722786790197176 ) ) ; +#28539 = VECTOR ( 'NONE', #17362, 1000.000000000000000 ) ; +#28540 = DIRECTION ( 'NONE', ( -0.6087614115774877543, 0.7730004600455409047, 0.1785492440296705396 ) ) ; +#28541 = CONICAL_SURFACE ( 'NONE', #17393, 2.503075499750329502, 0.7853981633711295540 ) ; +#28542 = CARTESIAN_POINT ( 'NONE', ( 42.56996684270875164, 189.7519616765065962, 106.3336315083538750 ) ) ; +#28543 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971563459 ) ) ; +#28544 = ORIENTED_EDGE ( 'NONE', *, *, #30184, .T. ) ; +#28545 = DIRECTION ( 'NONE', ( -0.0005884952295944862952, 0.2249510549294951034, -0.9743698869317914957 ) ) ; +#28546 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555410 ) ) ; +#28547 = CARTESIAN_POINT ( 'NONE', ( 2.546082943913467123, 205.5673828937494534, 76.29867481864103240 ) ) ; +#28548 = ORIENTED_EDGE ( 'NONE', *, *, #31299, .T. ) ; +#28549 = CARTESIAN_POINT ( 'NONE', ( 0.05361349798586999976, 83.21792371834001756, 88.76775218440999993 ) ) ; +#28550 = ORIENTED_EDGE ( 'NONE', *, *, #22940, .F. ) ; +#28551 = CARTESIAN_POINT ( 'NONE', ( -38.20405560926187860, 218.5902260770999987, 76.08157892182251203 ) ) ; +#28552 = CARTESIAN_POINT ( 'NONE', ( -26.47524647853921209, 122.9562979991939784, 88.05560927516995662 ) ) ; +#28553 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#28554 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#28555 = ORIENTED_EDGE ( 'NONE', *, *, #14999, .T. ) ; +#28556 = CARTESIAN_POINT ( 'NONE', ( 25.50051830703121780, 120.2145355607603534, 89.95699753438390189 ) ) ; +#28557 = ORIENTED_EDGE ( 'NONE', *, *, #11585, .T. ) ; +#28558 = ORIENTED_EDGE ( 'NONE', *, *, #2287, .T. ) ; +#28559 = CARTESIAN_POINT ( 'NONE', ( 37.17804754624985719, 145.4524169400428946, 280.9300640675564864 ) ) ; +#28560 = CARTESIAN_POINT ( 'NONE', ( 19.63521581173586483, 124.6513971846303548, 177.3953982281404080 ) ) ; +#28561 = CARTESIAN_POINT ( 'NONE', ( 39.74188351515407192, 169.2517364656017946, 164.2561587285271969 ) ) ; +#28562 = EDGE_CURVE ( 'NONE', #40342, #19998, #22200, .T. ) ; +#28563 = AXIS2_PLACEMENT_3D ( 'NONE', #21336, #19039, #30737 ) ; +#28564 = ORIENTED_EDGE ( 'NONE', *, *, #18889, .T. ) ; +#28565 = CARTESIAN_POINT ( 'NONE', ( -25.50991579498579398, 209.7152486954105086, 73.57374465072240355 ) ) ; +#28566 = DIRECTION ( 'NONE', ( -0.6983012566254244158, 0.000000000000000000, -0.7158039920225042207 ) ) ; +#28567 = ORIENTED_EDGE ( 'NONE', *, *, #22853, .F. ) ; +#28568 = DIRECTION ( 'NONE', ( -0.0006039748319391903498, -5.551115123125774025E-15, -0.9999998176071844824 ) ) ; +#28569 = CIRCLE ( 'NONE', #14186, 51.40509898897001761 ) ; +#28570 = EDGE_CURVE ( 'NONE', #89, #22666, #24870, .T. ) ; +#28571 = CARTESIAN_POINT ( 'NONE', ( -45.39754466565177182, 131.1270945138005573, 90.46656737203734622 ) ) ; +#28572 = ORIENTED_EDGE ( 'NONE', *, *, #18292, .T. ) ; +#28573 = CARTESIAN_POINT ( 'NONE', ( 21.05350619295907322, 128.5796794191466859, 92.23302540184623410 ) ) ; +#28574 = EDGE_CURVE ( 'NONE', #3175, #5370, #2854, .T. ) ; +#28575 = CARTESIAN_POINT ( 'NONE', ( 22.45660349583999960, 191.1065010712000003, 28.07991271570000080 ) ) ; +#28576 = CARTESIAN_POINT ( 'NONE', ( 41.29686553520478753, 130.6058778057362133, 336.5065907340476770 ) ) ; +#28577 = CYLINDRICAL_SURFACE ( 'NONE', #3285, 4.999999999999994671 ) ; +#28578 = EDGE_CURVE ( 'NONE', #24155, #9009, #24824, .T. ) ; +#28579 = CARTESIAN_POINT ( 'NONE', ( 4.030357199829833981, 135.8639809292952805, 91.01715860817544979 ) ) ; +#28580 = ADVANCED_FACE ( 'NONE', ( #21793 ), #2580, .F. ) ; +#28581 = ORIENTED_EDGE ( 'NONE', *, *, #30331, .T. ) ; +#28582 = CARTESIAN_POINT ( 'NONE', ( 16.22247671335948382, 122.0701589875174164, 174.5870958018068109 ) ) ; +#28583 = CARTESIAN_POINT ( 'NONE', ( 1.075851469382705705, 189.0669687373688532, 103.7034138247800144 ) ) ; +#28584 = CARTESIAN_POINT ( 'NONE', ( -20.89286847790088331, 136.3261294211067138, 91.13890976780785991 ) ) ; +#28585 = DIRECTION ( 'NONE', ( -0.0005884949961237983087, 0.2249510543439047772, -0.9743698870671267942 ) ) ; +#28586 = FACE_OUTER_BOUND ( 'NONE', #33727, .T. ) ; +#28587 = CARTESIAN_POINT ( 'NONE', ( 26.33447233267780163, 119.3314346165645361, 177.4911483211659800 ) ) ; +#28588 = CARTESIAN_POINT ( 'NONE', ( -3.168113297478124313, 183.4473166593645033, 105.0858980959790188 ) ) ; +#28589 = LINE ( 'NONE', #22860, #13915 ) ; +#28590 = ORIENTED_EDGE ( 'NONE', *, *, #5604, .T. ) ; +#28591 = CARTESIAN_POINT ( 'NONE', ( -25.67011802498781137, 190.9529943926732471, 106.4902118193780751 ) ) ; +#28592 = ORIENTED_EDGE ( 'NONE', *, *, #30352, .T. ) ; +#28593 = CONICAL_SURFACE ( 'NONE', #24697, 8.000001494568962812, 0.7853981633972983989 ) ; +#28594 = CONICAL_SURFACE ( 'NONE', #21431, 2.250000000041454840, 0.7853981633778843729 ) ; +#28595 = CARTESIAN_POINT ( 'NONE', ( -2.954012481561790970, 209.1419323005786737, 76.14255792608456375 ) ) ; +#28596 = LINE ( 'NONE', #7298, #6744 ) ; +#28597 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923337649, 154.4078842014294537, 95.29263736447251176 ) ) ; +#28598 = CARTESIAN_POINT ( 'NONE', ( 20.07207848722921995, 127.4214942189600919, 89.13229914059456860 ) ) ; +#28599 = CARTESIAN_POINT ( 'NONE', ( 20.11467720513346435, 118.1092215096106912, 90.14282840794432161 ) ) ; +#28600 = CARTESIAN_POINT ( 'NONE', ( 23.68617478976915081, 127.9132360811641149, 92.25176250337622719 ) ) ; +#28601 = EDGE_LOOP ( 'NONE', ( #23316, #16686, #16889, #24601 ) ) ; +#28602 = CARTESIAN_POINT ( 'NONE', ( -0.01811060958565999940, 134.7313760321000018, 93.83703417463999585 ) ) ; +#28603 = CARTESIAN_POINT ( 'NONE', ( 4.035676231391283508, 136.7932109853815064, 93.79744583368700717 ) ) ; +#28604 = ADVANCED_FACE ( 'NONE', ( #5424 ), #18488, .T. ) ; +#28605 = ADVANCED_FACE ( 'NONE', ( #24469 ), #5841, .F. ) ; +#28606 = DIRECTION ( 'NONE', ( -0.7933530821293331980, -0.5932640870757640572, -0.1364866662427067778 ) ) ; +#28607 = EDGE_LOOP ( 'NONE', ( #14047, #31956, #37900 ) ) ; +#28608 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#28609 = EDGE_CURVE ( 'NONE', #29452, #38073, #11933, .T. ) ; +#28610 = ORIENTED_EDGE ( 'NONE', *, *, #4290, .T. ) ; +#28611 = ADVANCED_FACE ( 'NONE', ( #29472 ), #1242, .F. ) ; +#28612 = PLANE ( 'NONE', #24456 ) ; +#28613 = LINE ( 'NONE', #7324, #17550 ) ; +#28614 = CARTESIAN_POINT ( 'NONE', ( 4.034499242442382894, 168.3851528797071921, 99.03841376523669737 ) ) ; +#28615 = DIRECTION ( 'NONE', ( 0.0005884949961138158424, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#28616 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#28617 = AXIS2_PLACEMENT_3D ( 'NONE', #8768, #33682, #5690 ) ; +#28618 = LINE ( 'NONE', #34515, #18114 ) ; +#28619 = CARTESIAN_POINT ( 'NONE', ( -19.31979924309097996, 124.8061162773214079, 177.8324071844828893 ) ) ; +#28620 = VECTOR ( 'NONE', #2410, 1000.000000000000000 ) ; +#28621 = PLANE ( 'NONE', #7304 ) ; +#28622 = ORIENTED_EDGE ( 'NONE', *, *, #11032, .T. ) ; +#28623 = EDGE_CURVE ( 'NONE', #6712, #12315, #25066, .T. ) ; +#28624 = ORIENTED_EDGE ( 'NONE', *, *, #14306, .T. ) ; +#28625 = CARTESIAN_POINT ( 'NONE', ( 12.64524264573559265, 177.0869176997347552, 103.5651634678102937 ) ) ; +#28626 = CARTESIAN_POINT ( 'NONE', ( 42.81943401670074678, 120.8435851937607453, 92.41077006796218996 ) ) ; +#28627 = CARTESIAN_POINT ( 'NONE', ( -18.84740034850127444, 125.0255721163971714, 178.4920410802416200 ) ) ; +#28628 = CARTESIAN_POINT ( 'NONE', ( -37.22558238367000882, 191.5599626881000006, 104.5530307740000069 ) ) ; +#28629 = ORIENTED_EDGE ( 'NONE', *, *, #2893, .T. ) ; +#28630 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#28631 = ORIENTED_EDGE ( 'NONE', *, *, #26091, .F. ) ; +#28632 = CARTESIAN_POINT ( 'NONE', ( -40.45668859077597546, 220.4002261445999693, 73.08293890851697938 ) ) ; +#28633 = EDGE_CURVE ( 'NONE', #21532, #38161, #34429, .T. ) ; +#28634 = FACE_OUTER_BOUND ( 'NONE', #10287, .T. ) ; +#28635 = DIRECTION ( 'NONE', ( -0.9914446600486813699, -0.1273122826258633877, -0.02879355402771318836 ) ) ; +#28636 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #19581, #32077, #4234, #20175 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.570713693309743864, 2.960011224583242839 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8455190531892258221, 0.8455190531892258221, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#28637 = CARTESIAN_POINT ( 'NONE', ( 30.06891677554877873, 175.2469091620284871, 100.6068511788076876 ) ) ; +#28638 = CIRCLE ( 'NONE', #11013, 1.999999999951510121 ) ; +#28639 = CARTESIAN_POINT ( 'NONE', ( -2.501018995718000237, 209.5694415279999987, 73.43744377689000657 ) ) ; +#28640 = CARTESIAN_POINT ( 'NONE', ( 38.65455852232000211, 118.3707348954999929, 89.51298033404999899 ) ) ; +#28641 = ORIENTED_EDGE ( 'NONE', *, *, #11037, .T. ) ; +#28642 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971573729 ) ) ; +#28643 = AXIS2_PLACEMENT_3D ( 'NONE', #22898, #22504, #38611 ) ; +#28644 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052565999616 ) ) ; +#28645 = CYLINDRICAL_SURFACE ( 'NONE', #34682, 3.000000000000000000 ) ; +#28646 = CONICAL_SURFACE ( 'NONE', #553, 2.503061127006177777, 0.7853981634091529163 ) ; +#28647 = CIRCLE ( 'NONE', #22762, 47.49999999998287592 ) ; +#28648 = LINE ( 'NONE', #7354, #2355 ) ; +#28649 = ORIENTED_EDGE ( 'NONE', *, *, #36059, .F. ) ; +#28650 = ORIENTED_EDGE ( 'NONE', *, *, #18107, .F. ) ; +#28651 = VERTEX_POINT ( 'NONE', #6424 ) ; +#28652 = CARTESIAN_POINT ( 'NONE', ( 20.50147137495634198, 190.9646546281344683, 106.2940065278771016 ) ) ; +#28653 = ADVANCED_FACE ( 'NONE', ( #1044 ), #31388, .T. ) ; +#28654 = ADVANCED_FACE ( 'NONE', ( #26014 ), #20879, .T. ) ; +#28655 = FACE_OUTER_BOUND ( 'NONE', #36634, .T. ) ; +#28656 = EDGE_CURVE ( 'NONE', #6112, #2318, #9791, .T. ) ; +#28657 = EDGE_CURVE ( 'NONE', #13040, #32811, #1447, .T. ) ; +#28658 = ORIENTED_EDGE ( 'NONE', *, *, #26259, .T. ) ; +#28659 = CARTESIAN_POINT ( 'NONE', ( -45.59279413748385679, 146.2345503595622347, 284.1924382399986939 ) ) ; +#28660 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#28661 = CARTESIAN_POINT ( 'NONE', ( -38.36815502355999996, 118.8281866406999967, 87.72028328499000338 ) ) ; +#28662 = DIRECTION ( 'NONE', ( 0.0005884949961247506718, -0.2249510543439066368, 0.9743698870671262391 ) ) ; +#28663 = ORIENTED_EDGE ( 'NONE', *, *, #32084, .T. ) ; +#28664 = EDGE_CURVE ( 'NONE', #30682, #7592, #20046, .T. ) ; +#28665 = CARTESIAN_POINT ( 'NONE', ( 15.95548590848913939, 122.4579714996872752, 172.0533845872113830 ) ) ; +#28666 = VERTEX_POINT ( 'NONE', #12563 ) ; +#28667 = CARTESIAN_POINT ( 'NONE', ( 37.42082352723856076, 132.6200669550715929, 336.9739440566017379 ) ) ; +#28668 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319114355331 ) ) ; +#28669 = ADVANCED_FACE ( 'NONE', ( #13532 ), #28326, .F. ) ; +#28670 = EDGE_LOOP ( 'NONE', ( #8245, #16335, #26658 ) ) ; +#28671 = CARTESIAN_POINT ( 'NONE', ( -14.89266160486395307, 136.5007287715515929, 91.51769391837629541 ) ) ; +#28672 = CARTESIAN_POINT ( 'NONE', ( 3.062676760987444347, 191.1124749746885811, 103.7728652716954514 ) ) ; +#28673 = CARTESIAN_POINT ( 'NONE', ( 43.11176529853025130, 93.58819903903858517, 291.5325055092823163 ) ) ; +#28674 = AXIS2_PLACEMENT_3D ( 'NONE', #14860, #6045, #21191 ) ; +#28675 = VECTOR ( 'NONE', #12302, 1000.000000000000114 ) ; +#28676 = ORIENTED_EDGE ( 'NONE', *, *, #32360, .T. ) ; +#28677 = CARTESIAN_POINT ( 'NONE', ( -21.17842536497620642, 213.4917284372353663, 73.07129532062806732 ) ) ; +#28678 = CARTESIAN_POINT ( 'NONE', ( 12.31735795870903161, 136.6817491452135016, 94.27986305550896873 ) ) ; +#28679 = ORIENTED_EDGE ( 'NONE', *, *, #30662, .T. ) ; +#28680 = CONICAL_SURFACE ( 'NONE', #3848, 7.999999999893429248, 0.7853981633973029508 ) ; +#28681 = LINE ( 'NONE', #22756, #24561 ) ; +#28682 = CARTESIAN_POINT ( 'NONE', ( 36.11816460276669716, 191.5234629219989131, 103.8477846469482415 ) ) ; +#28683 = CARTESIAN_POINT ( 'NONE', ( -25.95405152892999823, 121.2198833629000063, 90.60859627058000854 ) ) ; +#28684 = ORIENTED_EDGE ( 'NONE', *, *, #19167, .F. ) ; +#28685 = DIRECTION ( 'NONE', ( -0.0006039748319391919761, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#28686 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640315690, 0.2252353050503788645 ) ) ; +#28687 = CARTESIAN_POINT ( 'NONE', ( 38.64014645122774994, 77.14221734851339818, 291.0515339294258297 ) ) ; +#28688 = ORIENTED_EDGE ( 'NONE', *, *, #38066, .F. ) ; +#28689 = CARTESIAN_POINT ( 'NONE', ( 26.00396726516730084, 120.2363586782729925, 90.47612175240820420 ) ) ; +#28690 = FACE_OUTER_BOUND ( 'NONE', #19942, .T. ) ; +#28691 = CARTESIAN_POINT ( 'NONE', ( 35.71170796624453203, 209.7096579434202397, 73.20360198796264228 ) ) ; +#28693 = CARTESIAN_POINT ( 'NONE', ( -8.957660508846936764, 152.5474601094844900, 94.87668840795032565 ) ) ; +#28692 = CARTESIAN_POINT ( 'NONE', ( -12.63810004658400388, 184.1237364170421529, 102.1657915116017108 ) ) ; +#28694 = AXIS2_PLACEMENT_3D ( 'NONE', #10874, #35771, #4717 ) ; +#28695 = DIRECTION ( 'NONE', ( -0.0005884949961212385073, 0.2249510543439022514, -0.9743698870671273493 ) ) ; +#28696 = EDGE_LOOP ( 'NONE', ( #38228, #4702, #11706, #31482 ) ) ; +#28697 = CARTESIAN_POINT ( 'NONE', ( 15.59057381630712946, 147.4113417081824764, 179.2674225712011946 ) ) ; +#28698 = VECTOR ( 'NONE', #30137, 1000.000000000000114 ) ; +#28699 = CARTESIAN_POINT ( 'NONE', ( -31.70535868460997619, 226.4002260771022463, 73.57765341574507545 ) ) ; +#28700 = AXIS2_PLACEMENT_3D ( 'NONE', #2408, #33054, #14878 ) ; +#28701 = CARTESIAN_POINT ( 'NONE', ( 8.629804688381279121, 290.8783034154773759, 213.0387394798674165 ) ) ; +#28702 = EDGE_CURVE ( 'NONE', #28841, #37740, #37193, .T. ) ; +#28703 = EDGE_LOOP ( 'NONE', ( #16631, #4601, #11113, #38856 ) ) ; +#28704 = ADVANCED_FACE ( 'NONE', ( #18887 ), #6494, .T. ) ; +#28705 = VECTOR ( 'NONE', #22163, 999.9999999999998863 ) ; +#28706 = ORIENTED_EDGE ( 'NONE', *, *, #30053, .T. ) ; +#28707 = CARTESIAN_POINT ( 'NONE', ( 2.943104451508621544, 209.7096517725655644, 76.05672380837390278 ) ) ; +#28708 = DIRECTION ( 'NONE', ( -6.056093010559475298E-13, 0.9743700560245742714, 0.2249510922904529864 ) ) ; +#28709 = CARTESIAN_POINT ( 'NONE', ( -46.51510296192524407, 123.1642148636640570, 92.34525309360199685 ) ) ; +#28710 = CARTESIAN_POINT ( 'NONE', ( -2.814035348771000145, 190.9056005872000128, 106.6826603667999933 ) ) ; +#28711 = CARTESIAN_POINT ( 'NONE', ( 36.12231427442000609, 191.8632040566000114, 104.2147564600000038 ) ) ; +#28712 = ORIENTED_EDGE ( 'NONE', *, *, #22487, .T. ) ; +#28713 = EDGE_LOOP ( 'NONE', ( #20088, #19088, #32654, #34854 ) ) ; +#28714 = CARTESIAN_POINT ( 'NONE', ( -15.83142425403799969, 151.3373654620088757, 97.50908117948665677 ) ) ; +#28715 = CARTESIAN_POINT ( 'NONE', ( -5.639739516488999627, 174.3879284816999871, 152.4718672074000381 ) ) ; +#28716 = DIRECTION ( 'NONE', ( 0.6087613186456907188, -0.7729176985478710682, -0.1789074850089337476 ) ) ; +#28717 = FACE_OUTER_BOUND ( 'NONE', #32356, .T. ) ; +#28718 = ORIENTED_EDGE ( 'NONE', *, *, #19900, .T. ) ; +#28719 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265218904, -0.1368326740407753983 ) ) ; +#28720 = ORIENTED_EDGE ( 'NONE', *, *, #1637, .T. ) ; +#28721 = ORIENTED_EDGE ( 'NONE', *, *, #22841, .T. ) ; +#28722 = CARTESIAN_POINT ( 'NONE', ( -37.27437962779826108, 117.0177660251410430, 89.72826295827535148 ) ) ; +#28723 = CARTESIAN_POINT ( 'NONE', ( -15.99998654924659647, 185.5920200283469228, 102.5098809628851200 ) ) ; +#28724 = ORIENTED_EDGE ( 'NONE', *, *, #26919, .F. ) ; +#28725 = CARTESIAN_POINT ( 'NONE', ( 20.00153077817512326, 137.8436319123526914, 94.54354600521399732 ) ) ; +#28726 = AXIS2_PLACEMENT_3D ( 'NONE', #12672, #5936, #9820 ) ; +#28727 = EDGE_CURVE ( 'NONE', #10196, #34012, #9240, .T. ) ; +#28728 = CIRCLE ( 'NONE', #34032, 2.750000000059430239 ) ; +#28729 = CARTESIAN_POINT ( 'NONE', ( -1.750900962877000033, 189.6783647796999901, 105.7654186813000052 ) ) ; +#28730 = CARTESIAN_POINT ( 'NONE', ( -44.79177088925157335, 180.8389768040387366, 104.5088566725039527 ) ) ; +#28731 = AXIS2_PLACEMENT_3D ( 'NONE', #28353, #24494, #36954 ) ; +#28732 = ORIENTED_EDGE ( 'NONE', *, *, #22760, .T. ) ; +#28733 = PLANE ( 'NONE', #11237 ) ; +#28734 = AXIS2_PLACEMENT_3D ( 'NONE', #22473, #18564, #9392 ) ; +#28735 = LINE ( 'NONE', #3369, #29030 ) ; +#28736 = DIRECTION ( 'NONE', ( 0.0006039748319392047697, 1.154386647790520729E-15, 0.9999998176071845934 ) ) ; +#28737 = DIRECTION ( 'NONE', ( 1.026956297778271819E-13, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#28738 = CARTESIAN_POINT ( 'NONE', ( -40.67564690882122136, 188.1603015044537699, 107.8687550938168442 ) ) ; +#28739 = ORIENTED_EDGE ( 'NONE', *, *, #11562, .F. ) ; +#28740 = DIRECTION ( 'NONE', ( -0.0002393071182786160318, -0.2252352986010024705, 0.9743043687658494711 ) ) ; +#28741 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36034, #29924, #8247, #8668 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28742 = CARTESIAN_POINT ( 'NONE', ( -37.96017986806000266, 117.7251259182999945, 89.56172390870999322 ) ) ; +#28743 = ORIENTED_EDGE ( 'NONE', *, *, #36948, .T. ) ; +#28744 = ORIENTED_EDGE ( 'NONE', *, *, #23539, .T. ) ; +#28745 = CARTESIAN_POINT ( 'NONE', ( 10.97929769292734115, 158.8123032091548339, 96.31100024268565107 ) ) ; +#28746 = CARTESIAN_POINT ( 'NONE', ( -28.53208073851174476, 125.2791694434640135, 88.59312828080875590 ) ) ; +#28747 = CARTESIAN_POINT ( 'NONE', ( 23.69388335781209776, 131.0246890999723632, 89.88804818403849595 ) ) ; +#28748 = CARTESIAN_POINT ( 'NONE', ( -21.84296514512071852, 158.3842646686617854, 96.23200356538306721 ) ) ; +#28749 = ADVANCED_FACE ( 'NONE', ( #19833 ), #7781, .F. ) ; +#28750 = EDGE_CURVE ( 'NONE', #3973, #5945, #26413, .T. ) ; +#28751 = FACE_BOUND ( 'NONE', #15957, .T. ) ; +#28752 = EDGE_LOOP ( 'NONE', ( #33197, #2560, #5803, #16766 ) ) ; +#28753 = EDGE_LOOP ( 'NONE', ( #22551, #23641 ) ) ; +#28755 = CIRCLE ( 'NONE', #21595, 2.500000000050627946 ) ; +#28754 = CARTESIAN_POINT ( 'NONE', ( 2.559335146230606650, 190.6545083682405846, 106.2111020963487249 ) ) ; +#28756 = CIRCLE ( 'NONE', #18289, 4.500000002766396001 ) ; +#28757 = CARTESIAN_POINT ( 'NONE', ( -22.54153898917275711, 174.6477734237781476, 27.63001055752831547 ) ) ; +#28758 = AXIS2_PLACEMENT_3D ( 'NONE', #18176, #20436, #30069 ) ; +#28759 = ORIENTED_EDGE ( 'NONE', *, *, #3131, .F. ) ; +#28760 = LINE ( 'NONE', #16862, #21305 ) ; +#28761 = CONICAL_SURFACE ( 'NONE', #12413, 2.749999999950583973, 0.7853981633811774055 ) ; +#28762 = FACE_OUTER_BOUND ( 'NONE', #22019, .T. ) ; +#28763 = CARTESIAN_POINT ( 'NONE', ( 36.49000061041000009, 191.9055121536000001, 104.5102523057999946 ) ) ; +#28764 = ORIENTED_EDGE ( 'NONE', *, *, #10890, .F. ) ; +#28765 = CARTESIAN_POINT ( 'NONE', ( 39.06275665101696148, 183.6185769103316261, 102.5341710742749370 ) ) ; +#28766 = CARTESIAN_POINT ( 'NONE', ( 16.16550992384005170, 152.4595644213394223, 178.9888250856261607 ) ) ; +#28767 = VERTEX_POINT ( 'NONE', #21995 ) ; +#28768 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#28769 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#28770 = CARTESIAN_POINT ( 'NONE', ( 15.66829915461363143, 151.3691634012949692, 97.32665949641518921 ) ) ; +#28771 = CARTESIAN_POINT ( 'NONE', ( -25.99978576141418429, 118.1122949349609286, 90.28348809642494643 ) ) ; +#28772 = CARTESIAN_POINT ( 'NONE', ( -20.01736593119981222, 207.8686407175673594, 77.28911966098117148 ) ) ; +#28773 = VERTEX_POINT ( 'NONE', #25265 ) ; +#28774 = CARTESIAN_POINT ( 'NONE', ( -14.31599472567032549, 177.1946960966661777, 100.5701885340178450 ) ) ; +#28775 = ADVANCED_FACE ( 'NONE', ( #38263 ), #4099, .T. ) ; +#28776 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; +#28777 = CARTESIAN_POINT ( 'NONE', ( 94.27346847287640230, 222.2365666497040024, 195.1387431474686309 ) ) ; +#28778 = CARTESIAN_POINT ( 'NONE', ( -21.57450333036776513, 176.7766111650641676, 100.6491009196165436 ) ) ; +#28779 = ORIENTED_EDGE ( 'NONE', *, *, #33871, .F. ) ; +#28780 = CARTESIAN_POINT ( 'NONE', ( 38.45112143561028262, 119.0008945537455105, 90.24854934121363215 ) ) ; +#28781 = CARTESIAN_POINT ( 'NONE', ( -25.67828855867520232, 211.0902258593999932, 75.74375686936230068 ) ) ; +#28782 = CARTESIAN_POINT ( 'NONE', ( -26.00624846271685442, 190.8511609718977127, 106.8090059743847178 ) ) ; +#28783 = CARTESIAN_POINT ( 'NONE', ( 35.80518341334000354, 109.6131156991000069, 89.99615936003000627 ) ) ; +#28784 = CONICAL_SURFACE ( 'NONE', #5273, 2.502994749393338214, 0.7853981634319000538 ) ; +#28785 = CARTESIAN_POINT ( 'NONE', ( -31.91217790274522415, 174.0284854049060073, 102.4155994567338155 ) ) ; +#28786 = ORIENTED_EDGE ( 'NONE', *, *, #10705, .F. ) ; +#28787 = EDGE_CURVE ( 'NONE', #5771, #21181, #17376, .T. ) ; +#28788 = AXIS2_PLACEMENT_3D ( 'NONE', #28411, #19172, #15333 ) ; +#28789 = AXIS2_PLACEMENT_3D ( 'NONE', #18700, #34641, #34832 ) ; +#28790 = CARTESIAN_POINT ( 'NONE', ( 9.152368341089999859, 181.8773758343000395, 101.8936723023000042 ) ) ; +#28791 = EDGE_CURVE ( 'NONE', #33391, #11249, #23535, .T. ) ; +#28792 = CARTESIAN_POINT ( 'NONE', ( 16.29171451743032506, 127.7416981655566985, 175.3274352667909568 ) ) ; +#28793 = CARTESIAN_POINT ( 'NONE', ( 12.63969765807997625, 176.7434396814577440, 103.0154879366982641 ) ) ; +#28794 = CARTESIAN_POINT ( 'NONE', ( -25.99265238116858612, 191.7716299341333865, 103.9267712702834530 ) ) ; +#28795 = CARTESIAN_POINT ( 'NONE', ( 2.462157221798171314, 209.5677243469951634, 73.55701709285500556 ) ) ; +#28796 = CARTESIAN_POINT ( 'NONE', ( 36.06424597600000226, 192.4856413823000025, 105.0009491617999942 ) ) ; +#28797 = CARTESIAN_POINT ( 'NONE', ( 38.15044915630888767, 118.4868538170649970, 87.66883358155978101 ) ) ; +#28798 = EDGE_CURVE ( 'NONE', #38531, #29957, #39060, .T. ) ; +#28799 = EDGE_CURVE ( 'NONE', #31524, #11353, #39131, .T. ) ; +#28800 = FACE_OUTER_BOUND ( 'NONE', #17539, .T. ) ; +#28801 = ORIENTED_EDGE ( 'NONE', *, *, #18606, .T. ) ; +#28802 = ADVANCED_FACE ( 'NONE', ( #20671 ), #33262, .F. ) ; +#28803 = CARTESIAN_POINT ( 'NONE', ( -2.530585117517676785, 209.6188335209158424, 75.72670108198511230 ) ) ; +#28804 = ADVANCED_FACE ( 'NONE', ( #39669 ), #39801, .F. ) ; +#28805 = LINE ( 'NONE', #35307, #35967 ) ; +#28806 = FACE_OUTER_BOUND ( 'NONE', #2288, .T. ) ; +#28807 = VERTEX_POINT ( 'NONE', #33128 ) ; +#28808 = CARTESIAN_POINT ( 'NONE', ( 44.85744505170524832, 173.0251902600423932, 165.3610356716434922 ) ) ; +#28809 = AXIS2_PLACEMENT_3D ( 'NONE', #11832, #24514, #14701 ) ; +#28810 = ORIENTED_EDGE ( 'NONE', *, *, #34273, .T. ) ; +#28811 = CONICAL_SURFACE ( 'NONE', #35315, 3.500000265863834947, 0.7853981633209925484 ) ; +#28812 = VECTOR ( 'NONE', #3738, 1000.000000000000114 ) ; +#28813 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048993195, 181.0091974214194863, 104.5428127881379794 ) ) ; +#28814 = CARTESIAN_POINT ( 'NONE', ( -14.55129769576823939, 181.8820030174664737, 104.7313938035605787 ) ) ; +#28815 = DIRECTION ( 'NONE', ( 0.0005884949961248230966, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#28816 = AXIS2_PLACEMENT_3D ( 'NONE', #3244, #37595, #34707 ) ; +#28817 = VECTOR ( 'NONE', #19834, 1000.000000000000000 ) ; +#28818 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265227786, -0.1368326740407718733 ) ) ; +#28819 = CARTESIAN_POINT ( 'NONE', ( 44.72966403672144509, 105.5646547741824435, 174.3131243201257234 ) ) ; +#28820 = DIRECTION ( 'NONE', ( -0.7933308265452445607, -0.5932923437231208963, -0.1364932032467742196 ) ) ; +#28821 = VERTEX_POINT ( 'NONE', #8818 ) ; +#28822 = EDGE_LOOP ( 'NONE', ( #28759, #8350, #22775, #15450 ) ) ; +#28823 = CARTESIAN_POINT ( 'NONE', ( 37.18881986002047313, 185.3371258229277032, 105.5148290762721359 ) ) ; +#28824 = CARTESIAN_POINT ( 'NONE', ( -4.022778528374199247, 176.8352451414876043, 100.4809858824045961 ) ) ; +#28825 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#28826 = VERTEX_POINT ( 'NONE', #14546 ) ; +#28827 = CARTESIAN_POINT ( 'NONE', ( -37.98270182710000142, 190.9299589352999931, 103.6066259141999950 ) ) ; +#28828 = ORIENTED_EDGE ( 'NONE', *, *, #28799, .F. ) ; +#28829 = FACE_OUTER_BOUND ( 'NONE', #34019, .T. ) ; +#28830 = ORIENTED_EDGE ( 'NONE', *, *, #26064, .T. ) ; +#28831 = CARTESIAN_POINT ( 'NONE', ( 35.56284495376231547, 193.8169247290794601, 102.6814306726912776 ) ) ; +#28832 = ADVANCED_FACE ( 'NONE', ( #21293, #27030 ), #14947, .F. ) ; +#28833 = DIRECTION ( 'NONE', ( 0.0005884941600642186682, -0.2249510532593070877, 0.9743698873180307585 ) ) ; +#28834 = VECTOR ( 'NONE', #9263, 1000.000000000000114 ) ; +#28835 = CARTESIAN_POINT ( 'NONE', ( -12.63362340510167492, 177.0251879149293188, 103.4862258320118400 ) ) ; +#28836 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 134.8275956304323699, 92.30890876037859982 ) ) ; +#28837 = EDGE_CURVE ( 'NONE', #1363, #7316, #1864, .T. ) ; +#28838 = CIRCLE ( 'NONE', #3373, 2.000000001272049577 ) ; +#28839 = CARTESIAN_POINT ( 'NONE', ( 20.48060491281492546, 208.0678773903911178, 73.85355295145278376 ) ) ; +#28840 = CARTESIAN_POINT ( 'NONE', ( 38.66007910562999683, 118.3682276610000059, 89.51297402913000667 ) ) ; +#28841 = VERTEX_POINT ( 'NONE', #21083 ) ; +#28842 = EDGE_CURVE ( 'NONE', #8977, #14670, #35842, .T. ) ; +#28843 = FACE_OUTER_BOUND ( 'NONE', #21902, .T. ) ; +#28844 = CARTESIAN_POINT ( 'NONE', ( -36.61650759155055113, 191.3591673295911733, 106.3831752203444267 ) ) ; +#28845 = CARTESIAN_POINT ( 'NONE', ( -5.960622341254478762, 149.1452448442896923, 94.08941484461983862 ) ) ; +#28846 = CARTESIAN_POINT ( 'NONE', ( -20.50040440662989027, 193.7551219021977715, 103.6911811601128477 ) ) ; +#28847 = EDGE_LOOP ( 'NONE', ( #13394, #14372, #7162, #40023 ) ) ; +#28848 = ORIENTED_EDGE ( 'NONE', *, *, #28210, .T. ) ; +#28849 = EDGE_CURVE ( 'NONE', #17327, #22525, #30084, .T. ) ; +#28850 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3989, #19129, #4183, #35447 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28851 = ORIENTED_EDGE ( 'NONE', *, *, #26589, .T. ) ; +#28852 = DIRECTION ( 'NONE', ( 0.0005884949961265829735, -0.2249510543479622815, 0.9743698870661898770 ) ) ; +#28853 = CARTESIAN_POINT ( 'NONE', ( 15.50147165924775372, 160.1795853765612492, 99.18969171619460212 ) ) ; +#28854 = ORIENTED_EDGE ( 'NONE', *, *, #23687, .T. ) ; +#28855 = VERTEX_POINT ( 'NONE', #5324 ) ; +#28856 = FACE_BOUND ( 'NONE', #26605, .T. ) ; +#28857 = CARTESIAN_POINT ( 'NONE', ( -38.11719545559999744, 118.8155660612000020, 90.29080645717999687 ) ) ; +#28858 = CARTESIAN_POINT ( 'NONE', ( -38.12995955227000877, 119.0736919051999934, 87.44063144989000591 ) ) ; +#28859 = LINE ( 'NONE', #31940, #2781 ) ; +#28860 = VERTEX_POINT ( 'NONE', #23955 ) ; +#28861 = DIRECTION ( 'NONE', ( 0.0005884949961251158311, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#28862 = ORIENTED_EDGE ( 'NONE', *, *, #36736, .T. ) ; +#28863 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971556521 ) ) ; +#28864 = AXIS2_PLACEMENT_3D ( 'NONE', #29678, #1661, #7989 ) ; +#28865 = CARTESIAN_POINT ( 'NONE', ( 3.666638747417580557, 185.7959654145790864, 103.0582394725906568 ) ) ; +#28866 = VERTEX_POINT ( 'NONE', #39873 ) ; +#28867 = CARTESIAN_POINT ( 'NONE', ( -14.78542071362066679, 136.5876434558166750, 91.70874570386088465 ) ) ; +#28868 = CIRCLE ( 'NONE', #30833, 1.999999999975059284 ) ; +#28869 = CARTESIAN_POINT ( 'NONE', ( 36.06517739910999865, 192.1776130000999956, 106.5431043960000039 ) ) ; +#28870 = CARTESIAN_POINT ( 'NONE', ( 45.33292075665917054, 105.1136217838922988, 174.2090047145159701 ) ) ; +#28871 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6488, #8782, #9179, #9381 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28872 = ORIENTED_EDGE ( 'NONE', *, *, #37470, .T. ) ; +#28873 = CARTESIAN_POINT ( 'NONE', ( -25.50772789673414920, 207.4083919362629160, 77.09708259040941414 ) ) ; +#28874 = CARTESIAN_POINT ( 'NONE', ( -20.18676029030433838, 211.0871676712218630, 73.23727997610998841 ) ) ; +#28875 = ORIENTED_EDGE ( 'NONE', *, *, #2496, .F. ) ; +#28876 = CARTESIAN_POINT ( 'NONE', ( 3.062734419220130455, 191.5259964270285025, 103.8683342040099831 ) ) ; +#28877 = CARTESIAN_POINT ( 'NONE', ( 20.89286828480348035, 176.3842452922319524, 100.3618186666556369 ) ) ; +#28878 = CARTESIAN_POINT ( 'NONE', ( 16.41975760290100439, 151.3996119724024538, 184.5528527065874300 ) ) ; +#28879 = EDGE_CURVE ( 'NONE', #8051, #2542, #36413, .T. ) ; +#28880 = EDGE_CURVE ( 'NONE', #1598, #7297, #8417, .T. ) ; +#28881 = VERTEX_POINT ( 'NONE', #17583 ) ; +#28882 = EDGE_CURVE ( 'NONE', #31170, #31941, #34540, .T. ) ; +#28883 = CARTESIAN_POINT ( 'NONE', ( 2.548881393244593951, 189.3585829100690319, 106.4471705142469347 ) ) ; +#28884 = EDGE_CURVE ( 'NONE', #18267, #17189, #36529, .T. ) ; +#28885 = LINE ( 'NONE', #29089, #19260 ) ; +#28886 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#28887 = ORIENTED_EDGE ( 'NONE', *, *, #14389, .T. ) ; +#28888 = ORIENTED_EDGE ( 'NONE', *, *, #36939, .F. ) ; +#28889 = EDGE_CURVE ( 'NONE', #40149, #19772, #18585, .T. ) ; +#28890 = CARTESIAN_POINT ( 'NONE', ( 25.66702753569912332, 120.1660709880418096, 90.10665204569919240 ) ) ; +#28891 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #40256, #33517 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28892 = DIRECTION ( 'NONE', ( 0.0005884949961248781740, -0.2249510543439064425, 0.9743698870671262391 ) ) ; +#28894 = CARTESIAN_POINT ( 'NONE', ( -45.18925545272470856, 80.56898504508372127, 280.9798118546170258 ) ) ; +#28893 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673485204, 138.3983357652431039, 92.10969317386205546 ) ) ; +#28895 = VERTEX_POINT ( 'NONE', #40270 ) ; +#28896 = CIRCLE ( 'NONE', #5364, 4.499999998673683166 ) ; +#28897 = EDGE_CURVE ( 'NONE', #7776, #20110, #8737, .T. ) ; +#28898 = AXIS2_PLACEMENT_3D ( 'NONE', #34104, #12855, #37583 ) ; +#28899 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#28900 = EDGE_LOOP ( 'NONE', ( #11365, #14981, #12010, #26845 ) ) ; +#28901 = DIRECTION ( 'NONE', ( -0.6087614115774880874, 0.7730004600455407937, 0.1785492440296698458 ) ) ; +#28902 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927767006169, -0.0005734119022034026058 ) ) ; +#28903 = CARTESIAN_POINT ( 'NONE', ( 22.50029346827053089, 158.6816162529845826, 96.78702253161689839 ) ) ; +#28904 = ORIENTED_EDGE ( 'NONE', *, *, #16818, .T. ) ; +#28905 = VERTEX_POINT ( 'NONE', #28232 ) ; +#28906 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#28907 = EDGE_CURVE ( 'NONE', #15284, #17481, #30678, .T. ) ; +#28908 = CARTESIAN_POINT ( 'NONE', ( 43.18392532034716425, 82.25576545184350152, 280.9261012437979730 ) ) ; +#28909 = CARTESIAN_POINT ( 'NONE', ( -20.49970531676743235, 184.8492297950314480, 102.8542690818975132 ) ) ; +#28910 = CARTESIAN_POINT ( 'NONE', ( 36.08400100141000166, 192.2479736589999959, 104.3940943933999961 ) ) ; +#28911 = ORIENTED_EDGE ( 'NONE', *, *, #15806, .T. ) ; +#28912 = ORIENTED_EDGE ( 'NONE', *, *, #11115, .T. ) ; +#28913 = CARTESIAN_POINT ( 'NONE', ( 40.70212818817000766, 173.3563675979000323, 152.4718672074000381 ) ) ; +#28914 = CARTESIAN_POINT ( 'NONE', ( 20.31362792373948167, 209.7099901566150209, 73.37976260645619675 ) ) ; +#28915 = CARTESIAN_POINT ( 'NONE', ( -22.49852798328040038, 173.9502357504169936, 102.3918484913893252 ) ) ; +#28916 = DIRECTION ( 'NONE', ( -0.6087613512864371579, 0.7729391285148499158, 0.1788147667017893350 ) ) ; +#28917 = ORIENTED_EDGE ( 'NONE', *, *, #38473, .T. ) ; +#28918 = CARTESIAN_POINT ( 'NONE', ( 25.99886678296517672, 118.8155665066540934, 87.25209012101137773 ) ) ; +#28919 = ORIENTED_EDGE ( 'NONE', *, *, #39953, .F. ) ; +#28920 = AXIS2_PLACEMENT_3D ( 'NONE', #34605, #28902, #7210 ) ; +#28921 = CARTESIAN_POINT ( 'NONE', ( -36.99529868346930073, 116.5430723610914754, 89.73463934298317213 ) ) ; +#28922 = AXIS2_PLACEMENT_3D ( 'NONE', #28956, #10162, #22634 ) ; +#28923 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178915240083E-05, 0.0002331579774905574406 ) ) ; +#28924 = DIRECTION ( 'NONE', ( 0.7930615290754823299, -0.5935319944304117135, -0.1370152644339880932 ) ) ; +#28925 = VERTEX_POINT ( 'NONE', #33934 ) ; +#28926 = LINE ( 'NONE', #6427, #30809 ) ; +#28927 = CARTESIAN_POINT ( 'NONE', ( -45.59089670396822669, 145.5092601323765109, 287.3340147879176811 ) ) ; +#28928 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#28929 = ORIENTED_EDGE ( 'NONE', *, *, #13153, .F. ) ; +#28930 = FACE_OUTER_BOUND ( 'NONE', #37763, .T. ) ; +#28931 = EDGE_CURVE ( 'NONE', #906, #10693, #23497, .T. ) ; +#28932 = CARTESIAN_POINT ( 'NONE', ( -23.32853479928075657, 115.6131185455671044, 87.78168085064412196 ) ) ; +#28934 = ADVANCED_FACE ( 'NONE', ( #12888 ), #5740, .F. ) ; +#28933 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20998, #36941, #4830, #32847 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#28935 = CARTESIAN_POINT ( 'NONE', ( -3.893460979042727921, 148.0324882923159180, 129.7501302153316090 ) ) ; +#28936 = CARTESIAN_POINT ( 'NONE', ( -45.70040756943009086, 187.3695729804526309, 106.0171126674183739 ) ) ; +#28937 = DIRECTION ( 'NONE', ( -0.1305262373691799260, -0.9659798014921964215, -0.2232620085624539286 ) ) ; +#28938 = EDGE_LOOP ( 'NONE', ( #32228, #25987, #9964, #14164 ) ) ; +#28939 = CARTESIAN_POINT ( 'NONE', ( 33.59926631015442666, 82.65455085156807513, 286.9156910329689367 ) ) ; +#28940 = CARTESIAN_POINT ( 'NONE', ( -35.56888541235999668, 112.3660634750000042, 90.16795747465999966 ) ) ; +#28941 = VERTEX_POINT ( 'NONE', #15345 ) ; +#28942 = CARTESIAN_POINT ( 'NONE', ( -20.49846059232846684, 118.8155328640159070, 89.78014971369738362 ) ) ; +#28943 = CONICAL_SURFACE ( 'NONE', #3445, 2.503000000131598846, 0.7853981633979968402 ) ; +#28944 = ORIENTED_EDGE ( 'NONE', *, *, #27574, .F. ) ; +#28945 = CARTESIAN_POINT ( 'NONE', ( 10.60892767148880722, 158.9861580188522225, 96.35136148965206360 ) ) ; +#28946 = CARTESIAN_POINT ( 'NONE', ( -76.10925030609612918, 156.2403276578370708, 96.28296423947242033 ) ) ; +#28947 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; +#28948 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319368671214 ) ) ; +#28949 = CARTESIAN_POINT ( 'NONE', ( 30.05084667745524385, 127.2908262436609164, 89.53532598631991846 ) ) ; +#28951 = VERTEX_POINT ( 'NONE', #399 ) ; +#28950 = AXIS2_PLACEMENT_3D ( 'NONE', #7167, #29054, #21932 ) ; +#28952 = ORIENTED_EDGE ( 'NONE', *, *, #4597, .T. ) ; +#28953 = CARTESIAN_POINT ( 'NONE', ( -1.458415330454428283, 144.9404864492411207, 129.0359332385636151 ) ) ; +#28954 = EDGE_LOOP ( 'NONE', ( #11946, #32633, #33616, #24777 ) ) ; +#28955 = VERTEX_POINT ( 'NONE', #6522 ) ; +#28956 = CARTESIAN_POINT ( 'NONE', ( -13.49852954174652098, 151.4059594047230348, 97.18165546544217648 ) ) ; +#28957 = ADVANCED_FACE ( 'NONE', ( #6330 ), #199, .T. ) ; +#28958 = AXIS2_PLACEMENT_3D ( 'NONE', #34514, #9817, #40267 ) ; +#28959 = DIRECTION ( 'NONE', ( -0.0005884949961196883151, 0.2249510543439064425, -0.9743698870671262391 ) ) ; +#28960 = ORIENTED_EDGE ( 'NONE', *, *, #2171, .F. ) ; +#28961 = CARTESIAN_POINT ( 'NONE', ( -38.93778834861265636, 191.4135373867393355, 104.3808903904224508 ) ) ; +#28962 = CARTESIAN_POINT ( 'NONE', ( 20.31592050807716987, 207.5617839839853502, 77.13467258061730547 ) ) ; +#28963 = CARTESIAN_POINT ( 'NONE', ( 43.33738618907429441, 121.9452304551619193, 87.95443437753064586 ) ) ; +#28964 = CARTESIAN_POINT ( 'NONE', ( 2.952902371779212221, 209.6824931357368484, 76.05698180698200872 ) ) ; +#28965 = FACE_OUTER_BOUND ( 'NONE', #16169, .T. ) ; +#28966 = CARTESIAN_POINT ( 'NONE', ( 21.49855060081473468, 136.1244284095153603, 91.06673730668626376 ) ) ; +#28967 = ORIENTED_EDGE ( 'NONE', *, *, #674, .T. ) ; +#28968 = CARTESIAN_POINT ( 'NONE', ( 28.10661807784000032, 125.3262985144999959, 88.91197353779001844 ) ) ; +#28969 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218858604, 80.18001836396577175, 297.5295786860745579 ) ) ; +#28970 = FACE_OUTER_BOUND ( 'NONE', #25970, .T. ) ; +#28971 = CARTESIAN_POINT ( 'NONE', ( 22.78222448925487953, 163.9654955388074029, 100.5724953333896536 ) ) ; +#28972 = CARTESIAN_POINT ( 'NONE', ( 3.549667999360065274, 137.0383104860663650, 91.28856432241404661 ) ) ; +#28973 = ORIENTED_EDGE ( 'NONE', *, *, #34537, .F. ) ; +#28974 = CARTESIAN_POINT ( 'NONE', ( 2.562147501752185086, 194.2771767929999953, 102.8967287192001692 ) ) ; +#28975 = CARTESIAN_POINT ( 'NONE', ( 0.7210351870193272283, 189.0061775126145278, 103.6849341927780728 ) ) ; +#28976 = CIRCLE ( 'NONE', #32249, 2.499999999942751128 ) ; +#28977 = AXIS2_PLACEMENT_3D ( 'NONE', #12859, #21471, #33911 ) ; +#28978 = CARTESIAN_POINT ( 'NONE', ( 36.50235068108981551, 191.7558943553050597, 104.3539645039292338 ) ) ; +#28979 = CARTESIAN_POINT ( 'NONE', ( 25.99883959725927340, 118.3495095284676779, 87.25212951290748720 ) ) ; +#28980 = ADVANCED_FACE ( 'NONE', ( #9616 ), #17616, .F. ) ; +#28981 = CARTESIAN_POINT ( 'NONE', ( -25.61365638992000271, 191.7614508023000042, 104.3047066533000020 ) ) ; +#28982 = EDGE_CURVE ( 'NONE', #34116, #40341, #30894, .T. ) ; +#28983 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971545696 ) ) ; +#28984 = CARTESIAN_POINT ( 'NONE', ( -37.17549197171149444, 71.97997760090089514, 323.0191280695677278 ) ) ; +#28985 = AXIS2_PLACEMENT_3D ( 'NONE', #21129, #11938, #8874 ) ; +#28986 = PLANE ( 'NONE', #14091 ) ; +#28987 = ORIENTED_EDGE ( 'NONE', *, *, #1313, .F. ) ; +#28988 = CARTESIAN_POINT ( 'NONE', ( 21.21457940375938378, 183.3621723504481906, 102.4857529904703028 ) ) ; +#28989 = ORIENTED_EDGE ( 'NONE', *, *, #33805, .T. ) ; +#28990 = PLANE ( 'NONE', #38758 ) ; +#28991 = CARTESIAN_POINT ( 'NONE', ( -35.95435800709800844, 218.5902260770999987, 75.58022006963935269 ) ) ; +#28992 = LINE ( 'NONE', #13461, #15013 ) ; +#28993 = CARTESIAN_POINT ( 'NONE', ( 36.06465993625999999, 192.4996331442999917, 105.6863068227000184 ) ) ; +#28994 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178539432571E-05, -0.0002331579774923554001 ) ) ; +#28995 = FACE_OUTER_BOUND ( 'NONE', #14882, .T. ) ; +#28996 = DIRECTION ( 'NONE', ( -2.498001805435684678E-14, 0.9743700557921592953, 0.2249510932971531540 ) ) ; +#28997 = ORIENTED_EDGE ( 'NONE', *, *, #7042, .T. ) ; +#28998 = ORIENTED_EDGE ( 'NONE', *, *, #21274, .F. ) ; +#28999 = CARTESIAN_POINT ( 'NONE', ( -2.372094540712000210, 209.5677221608999901, 75.55993681610999602 ) ) ; +#29000 = ADVANCED_FACE ( 'NONE', ( #18189 ), #18997, .F. ) ; +#29001 = CARTESIAN_POINT ( 'NONE', ( 10.89673787447373954, 188.3452299077503937, 103.1293446006402093 ) ) ; +#29002 = VECTOR ( 'NONE', #33954, 1000.000000000000227 ) ; +#29003 = DIRECTION ( 'NONE', ( -0.7075337269008550312, -8.731295299227720714E-15, -0.7066795775298634341 ) ) ; +#29004 = LINE ( 'NONE', #16125, #38937 ) ; +#29005 = VERTEX_POINT ( 'NONE', #12282 ) ; +#29006 = FACE_OUTER_BOUND ( 'NONE', #4614, .T. ) ; +#29007 = VECTOR ( 'NONE', #31922, 1000.000000000000000 ) ; +#29008 = ORIENTED_EDGE ( 'NONE', *, *, #18682, .T. ) ; +#29009 = CARTESIAN_POINT ( 'NONE', ( -3.316502142368714878, 129.4074268280347155, 89.53098268898165202 ) ) ; +#29010 = CYLINDRICAL_SURFACE ( 'NONE', #17676, 6.000000000000001776 ) ; +#29011 = EDGE_LOOP ( 'NONE', ( #39884, #20948, #779, #3757 ) ) ; +#29012 = CARTESIAN_POINT ( 'NONE', ( -37.83775869347861942, 191.4135374006265806, 104.3802260088867513 ) ) ; +#29013 = EDGE_CURVE ( 'NONE', #38943, #4296, #9, .T. ) ; +#29014 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498896523, 179.0675991014397255, 104.0619761092555535 ) ) ; +#29015 = LINE ( 'NONE', #19787, #32657 ) ; +#29016 = DIRECTION ( 'NONE', ( 0.6087614115774879764, -0.7730004600455407937, -0.1785492440296699013 ) ) ; +#29017 = VERTEX_POINT ( 'NONE', #34138 ) ; +#29018 = ADVANCED_FACE ( 'NONE', ( #38413 ), #16920, .F. ) ; +#29019 = CARTESIAN_POINT ( 'NONE', ( 16.56066969684213319, 151.5369496897081376, 184.4389257082733025 ) ) ; +#29020 = CARTESIAN_POINT ( 'NONE', ( 30.06999065270167293, 177.5155566641962821, 100.8568524939294662 ) ) ; +#29021 = PLANE ( 'NONE', #35143 ) ; +#29022 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9848, #22320, #9639, #38036 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.007059153986243680776, 0.007984364839272745790 ), + .UNSPECIFIED. ) ; +#29023 = CARTESIAN_POINT ( 'NONE', ( -37.66357074801999971, 191.5193100856000115, 104.5557267436000046 ) ) ; +#29024 = ORIENTED_EDGE ( 'NONE', *, *, #8310, .F. ) ; +#29025 = CARTESIAN_POINT ( 'NONE', ( 22.49964039506791380, 136.6763645039129074, 180.9867425820801259 ) ) ; +#29026 = EDGE_CURVE ( 'NONE', #14528, #10049, #15528, .T. ) ; +#29027 = EDGE_CURVE ( 'NONE', #18640, #9446, #5225, .T. ) ; +#29028 = ADVANCED_FACE ( 'NONE', ( #1397 ), #35874, .F. ) ; +#29029 = CARTESIAN_POINT ( 'NONE', ( 36.70965854364384739, 115.7295922440460743, 89.70117536820643522 ) ) ; +#29030 = VECTOR ( 'NONE', #27953, 1000.000000000000227 ) ; +#29031 = CIRCLE ( 'NONE', #12713, 2.499999999924464866 ) ; +#29032 = DIRECTION ( 'NONE', ( 2.710505431213760483E-20, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#29033 = PLANE ( 'NONE', #13894 ) ; +#29034 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #34204, #9899 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29035 = VECTOR ( 'NONE', #3380, 1000.000000000000000 ) ; +#29036 = LINE ( 'NONE', #31411, #38491 ) ; +#29037 = FACE_OUTER_BOUND ( 'NONE', #5693, .T. ) ; +#29038 = FACE_OUTER_BOUND ( 'NONE', #27756, .T. ) ; +#29039 = CARTESIAN_POINT ( 'NONE', ( 20.48164290558045053, 206.1980406404009329, 75.23207116101302461 ) ) ; +#29040 = CARTESIAN_POINT ( 'NONE', ( 38.66577705699000234, 118.3794861341999933, 89.51282126978000520 ) ) ; +#29041 = ORIENTED_EDGE ( 'NONE', *, *, #19133, .T. ) ; +#29042 = CARTESIAN_POINT ( 'NONE', ( 1.447658033344545903, 144.9407251398178005, 129.0349007176305065 ) ) ; +#29043 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; +#29044 = LINE ( 'NONE', #25990, #32093 ) ; +#29046 = ORIENTED_EDGE ( 'NONE', *, *, #23533, .T. ) ; +#29045 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; +#29047 = ORIENTED_EDGE ( 'NONE', *, *, #26244, .T. ) ; +#29048 = VERTEX_POINT ( 'NONE', #7329 ) ; +#29049 = LINE ( 'NONE', #38637, #35263 ) ; +#29050 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13526, #32528, #35982, #13723, #32137, #7578, #23134, #1037 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 4 ), + ( 1.176960980475848905E-15, 0.0004331621789878069002, 0.0008663243579744368990, 0.001732648715947696788 ), + .UNSPECIFIED. ) ; +#29051 = CARTESIAN_POINT ( 'NONE', ( 22.11658944985360264, 129.6856566903868213, 90.09300832417258675 ) ) ; +#29052 = EDGE_LOOP ( 'NONE', ( #7017, #29695, #31826, #19336 ) ) ; +#29053 = VECTOR ( 'NONE', #38520, 1000.000000000000114 ) ; +#29054 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -5.029100735414826696E-18, -0.0006039748319369899615 ) ) ; +#29055 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5844, #24270, #12376, #12191, #27742, #2182, #34046, #21604, #6039, #14653, #8725, #21186, #36515, #8517, #33644, #5639, #10126, #12789, #16239, #37715 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999667766, 0.1874999999999595879, 0.2187499999999551747, 0.2343749999999428513, 0.2499999999999305000, 0.4999999999999613642, 0.6249999999999771294, 0.6874999999999816813, 0.7187499999999844569, 0.7343749999999844569, 0.7499999999999843459, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29056 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -5.029098237799274788E-18, 0.0006039748319384018096 ) ) ; +#29057 = CARTESIAN_POINT ( 'NONE', ( -38.12719533885000089, 119.0721968347999962, 87.43909598028000119 ) ) ; +#29058 = CARTESIAN_POINT ( 'NONE', ( 6.034202883963867059, 175.3568768315410011, 100.1305289580489557 ) ) ; +#29059 = VECTOR ( 'NONE', #6374, 1000.000000000000227 ) ; +#29060 = VECTOR ( 'NONE', #352, 1000.000000000000114 ) ; +#29061 = CARTESIAN_POINT ( 'NONE', ( 22.50176656424163824, 160.0672683219272017, 99.67592654435250665 ) ) ; +#29062 = VERTEX_POINT ( 'NONE', #28819 ) ; +#29063 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#29064 = EDGE_CURVE ( 'NONE', #15381, #15846, #13878, .T. ) ; +#29065 = ORIENTED_EDGE ( 'NONE', *, *, #37612, .T. ) ; +#29066 = LINE ( 'NONE', #32139, #6363 ) ; +#29067 = AXIS2_PLACEMENT_3D ( 'NONE', #39853, #22971, #23171 ) ; +#29068 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.110223024625155594E-14 ) ) ; +#29069 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -2.938175737920237887E-14, 0.0006039748320101188559 ) ) ; +#29070 = CARTESIAN_POINT ( 'NONE', ( 76.10689632611000377, 156.0201458301999935, 97.16650080654000021 ) ) ; +#29071 = DIRECTION ( 'NONE', ( 0.0006039748319379876444, 1.544770086762009064E-14, 0.9999998176071845934 ) ) ; +#29072 = ORIENTED_EDGE ( 'NONE', *, *, #17029, .F. ) ; +#29073 = EDGE_CURVE ( 'NONE', #3788, #32791, #19839, .T. ) ; +#29074 = CARTESIAN_POINT ( 'NONE', ( -0.6295527621319999545, 188.7401429372000052, 103.3599632786999933 ) ) ; +#29075 = CARTESIAN_POINT ( 'NONE', ( 3.166350953592421025, 126.8041585549839709, 88.92605846951083493 ) ) ; +#29076 = DIRECTION ( 'NONE', ( -1.445602896664413772E-14, -1.000000000000000000, 0.000000000000000000 ) ) ; +#29077 = CARTESIAN_POINT ( 'NONE', ( 18.99282617352092828, 148.1950018063203913, 184.7146606765990100 ) ) ; +#29078 = EDGE_CURVE ( 'NONE', #1820, #37645, #9667, .T. ) ; +#29079 = EDGE_LOOP ( 'NONE', ( #9271, #8703, #30763, #2333 ) ) ; +#29080 = CARTESIAN_POINT ( 'NONE', ( -21.21281380558005125, 182.9066539643694966, 104.4588199671594850 ) ) ; +#29081 = CARTESIAN_POINT ( 'NONE', ( 22.53027613144000085, 173.3942358358999911, 152.4718672074000381 ) ) ; +#29082 = ADVANCED_FACE ( 'NONE', ( #31700 ), #38509, .F. ) ; +#29083 = ORIENTED_EDGE ( 'NONE', *, *, #16229, .T. ) ; +#29084 = ADVANCED_FACE ( 'NONE', ( #16732 ), #593, .F. ) ; +#29085 = ADVANCED_FACE ( 'NONE', ( #22891 ), #38010, .F. ) ; +#29086 = PLANE ( 'NONE', #32362 ) ; +#29087 = ORIENTED_EDGE ( 'NONE', *, *, #35597, .T. ) ; +#29088 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 130.2931719330194369, 89.72259846333660960 ) ) ; +#29089 = CARTESIAN_POINT ( 'NONE', ( 23.68596773153945989, 129.9751393263009334, 92.21150139171207627 ) ) ; +#29090 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#29091 = CARTESIAN_POINT ( 'NONE', ( 23.68783464955822637, 130.1000560662577641, 92.41140855418669275 ) ) ; +#29092 = AXIS2_PLACEMENT_3D ( 'NONE', #2743, #37281, #34003 ) ; +#29093 = ORIENTED_EDGE ( 'NONE', *, *, #4934, .T. ) ; +#29094 = VECTOR ( 'NONE', #20894, 1000.000000000000114 ) ; +#29095 = AXIS2_PLACEMENT_3D ( 'NONE', #19461, #6585, #37475 ) ; +#29096 = EDGE_LOOP ( 'NONE', ( #11634, #1940, #11055, #35574, #17822, #37501, #13903, #27816, #4279, #23867, #23544, #22251 ) ) ; +#29097 = CARTESIAN_POINT ( 'NONE', ( 25.50048144128237482, 120.2040495201863877, 89.94428625009325629 ) ) ; +#29098 = DIRECTION ( 'NONE', ( -0.0001408393175929667886, 0.2255194967740913881, -0.9742386446549157197 ) ) ; +#29099 = VECTOR ( 'NONE', #29570, 1000.000000000000000 ) ; +#29101 = CARTESIAN_POINT ( 'NONE', ( 12.63943526404941409, 181.6152899297528336, 104.1402435535042770 ) ) ; +#29100 = FACE_OUTER_BOUND ( 'NONE', #12847, .T. ) ; +#29102 = EDGE_LOOP ( 'NONE', ( #27219, #32682 ) ) ; +#29103 = CYLINDRICAL_SURFACE ( 'NONE', #1390, 22.50000000000000000 ) ; +#29104 = ORIENTED_EDGE ( 'NONE', *, *, #25236, .T. ) ; +#29105 = CARTESIAN_POINT ( 'NONE', ( -22.49823373578500707, 127.0679975458287885, 92.08138095398328460 ) ) ; +#29106 = LINE ( 'NONE', #4134, #24076 ) ; +#29107 = ORIENTED_EDGE ( 'NONE', *, *, #34859, .F. ) ; +#29108 = VERTEX_POINT ( 'NONE', #25766 ) ; +#29109 = CARTESIAN_POINT ( 'NONE', ( 38.76540524925999875, 119.1021110644999936, 90.11972037454999906 ) ) ; +#29110 = CARTESIAN_POINT ( 'NONE', ( -5.676543322760370991, 181.0132184317505448, 104.5254537842582323 ) ) ; +#29111 = FACE_OUTER_BOUND ( 'NONE', #28696, .T. ) ; +#29112 = CARTESIAN_POINT ( 'NONE', ( -45.63015653918211001, 123.6493010396682592, 93.26116892431079464 ) ) ; +#29113 = CARTESIAN_POINT ( 'NONE', ( -2.557265648198999930, 190.9740655001999983, 106.4346615696999976 ) ) ; +#29114 = CARTESIAN_POINT ( 'NONE', ( 36.24932317171001017, 191.9578045599000120, 104.3871094435999964 ) ) ; +#29115 = EDGE_CURVE ( 'NONE', #18050, #21146, #29015, .T. ) ; +#29116 = ORIENTED_EDGE ( 'NONE', *, *, #26446, .T. ) ; +#29117 = EDGE_CURVE ( 'NONE', #18594, #37750, #15938, .T. ) ; +#29118 = EDGE_LOOP ( 'NONE', ( #12506, #18570, #32483, #19778 ) ) ; +#29119 = VECTOR ( 'NONE', #33470, 999.9999999999998863 ) ; +#29120 = FACE_OUTER_BOUND ( 'NONE', #23426, .T. ) ; +#29121 = EDGE_CURVE ( 'NONE', #35627, #1984, #1297, .T. ) ; +#29122 = CARTESIAN_POINT ( 'NONE', ( -23.36287322752248485, 134.3886336262885663, 93.64575589608618600 ) ) ; +#29123 = AXIS2_PLACEMENT_3D ( 'NONE', #32511, #38039, #29451 ) ; +#29124 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673776705, 151.8594835319893548, 95.21744457848066645 ) ) ; +#29125 = VECTOR ( 'NONE', #962, 1000.000000000000227 ) ; +#29126 = ORIENTED_EDGE ( 'NONE', *, *, #24430, .F. ) ; +#29127 = VERTEX_POINT ( 'NONE', #4669 ) ; +#29128 = CARTESIAN_POINT ( 'NONE', ( -12.63048181974366990, 130.3451622633888576, 92.83206449613362565 ) ) ; +#29129 = ORIENTED_EDGE ( 'NONE', *, *, #29669, .F. ) ; +#29130 = AXIS2_PLACEMENT_3D ( 'NONE', #23212, #32997, #32418 ) ; +#29131 = EDGE_CURVE ( 'NONE', #2995, #9290, #36363, .T. ) ; +#29132 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#29133 = CARTESIAN_POINT ( 'NONE', ( 9.176516921554000561, 134.5452385099999901, 93.53193153540000537 ) ) ; +#29134 = EDGE_LOOP ( 'NONE', ( #23478, #26392, #28952, #30674, #24243, #10075 ) ) ; +#29135 = CARTESIAN_POINT ( 'NONE', ( -6.666724428068700803, 120.3902201003022583, 87.45121955335277164 ) ) ; +#29136 = ADVANCED_FACE ( 'NONE', ( #33078 ), #26140, .T. ) ; +#29137 = CARTESIAN_POINT ( 'NONE', ( -2.112662471484000104, 189.1905130851999957, 106.2660147881999961 ) ) ; +#29138 = CARTESIAN_POINT ( 'NONE', ( -32.37225756577250024, 137.6262283585609794, 94.52490471072836442 ) ) ; +#29139 = CARTESIAN_POINT ( 'NONE', ( 25.99018610745488900, 211.0908525021142168, 73.04280463953621449 ) ) ; +#29140 = ORIENTED_EDGE ( 'NONE', *, *, #12450, .T. ) ; +#29141 = CYLINDRICAL_SURFACE ( 'NONE', #29736, 2.500000000000002220 ) ; +#29142 = CYLINDRICAL_SURFACE ( 'NONE', #2924, 6.000000000000008882 ) ; +#29143 = CARTESIAN_POINT ( 'NONE', ( -3.669581222385334573, 184.0117732734999834, 102.6507570781000851 ) ) ; +#29144 = EDGE_CURVE ( 'NONE', #1021, #28145, #9163, .T. ) ; +#29145 = CARTESIAN_POINT ( 'NONE', ( 45.50974939072701630, 131.1361171346210313, 90.41374468093005135 ) ) ; +#29146 = ORIENTED_EDGE ( 'NONE', *, *, #6909, .F. ) ; +#29147 = CARTESIAN_POINT ( 'NONE', ( 25.50041447495308233, 118.1134306400200416, 89.75249416949174019 ) ) ; +#29148 = AXIS2_PLACEMENT_3D ( 'NONE', #26600, #20432, #8180 ) ; +#29149 = AXIS2_PLACEMENT_3D ( 'NONE', #28150, #37726, #34644 ) ; +#29150 = CARTESIAN_POINT ( 'NONE', ( -38.04444379205944671, 118.4867705051282627, 87.71485106921780073 ) ) ; +#29151 = EDGE_LOOP ( 'NONE', ( #34354, #35450, #16353, #1100 ) ) ; +#29152 = ORIENTED_EDGE ( 'NONE', *, *, #25536, .F. ) ; +#29153 = CARTESIAN_POINT ( 'NONE', ( 13.46612284730906950, 158.3062971533392158, 96.19268454968825210 ) ) ; +#29154 = CARTESIAN_POINT ( 'NONE', ( 35.33426620396411977, 88.25255173735948233, 281.9959031066233024 ) ) ; +#29155 = VECTOR ( 'NONE', #23794, 1000.000000000000227 ) ; +#29156 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; +#29157 = ORIENTED_EDGE ( 'NONE', *, *, #25103, .F. ) ; +#29158 = ORIENTED_EDGE ( 'NONE', *, *, #5968, .T. ) ; +#29159 = FACE_BOUND ( 'NONE', #9835, .T. ) ; +#29160 = ORIENTED_EDGE ( 'NONE', *, *, #17518, .F. ) ; +#29161 = ORIENTED_EDGE ( 'NONE', *, *, #26594, .T. ) ; +#29162 = ORIENTED_EDGE ( 'NONE', *, *, #171, .T. ) ; +#29163 = CARTESIAN_POINT ( 'NONE', ( 5.668006812857668386, 188.0198015040569999, 103.3352605442849210 ) ) ; +#29164 = CARTESIAN_POINT ( 'NONE', ( 2.480024872728376462, 190.3696323296966568, 106.1306803042403146 ) ) ; +#29165 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391915424 ) ) ; +#29166 = CARTESIAN_POINT ( 'NONE', ( -40.55693163771468335, 184.9318016480985136, 102.3722900139845251 ) ) ; +#29167 = EDGE_LOOP ( 'NONE', ( #6666, #5681, #11483, #33686 ) ) ; +#29168 = EDGE_CURVE ( 'NONE', #17312, #38732, #5065, .T. ) ; +#29169 = VERTEX_POINT ( 'NONE', #36145 ) ; +#29170 = CARTESIAN_POINT ( 'NONE', ( -25.50990988232443257, 208.8372429855093912, 73.63742171263974967 ) ) ; +#29171 = ADVANCED_FACE ( 'NONE', ( #2434 ), #23287, .F. ) ; +#29172 = CARTESIAN_POINT ( 'NONE', ( -26.00155756584835132, 118.8155666110999960, 87.28349583687662516 ) ) ; +#29173 = CARTESIAN_POINT ( 'NONE', ( 36.38410872893999937, 191.7179417355000055, 104.2356371314999990 ) ) ; +#29174 = EDGE_CURVE ( 'NONE', #5222, #19726, #4866, .T. ) ; +#29175 = CARTESIAN_POINT ( 'NONE', ( 2.977108692617461472, 209.6085488725653079, 76.05914829704735780 ) ) ; +#29176 = EDGE_LOOP ( 'NONE', ( #30617, #3284, #19966, #26982, #37103, #4432, #16929, #9916, #26319, #3542 ) ) ; +#29177 = CARTESIAN_POINT ( 'NONE', ( -14.55306118018871508, 176.9194272080598296, 100.5067835523781667 ) ) ; +#29178 = EDGE_LOOP ( 'NONE', ( #33810, #2183, #20779, #183, #2428, #6641, #26008, #8456, #28555, #38095 ) ) ; +#29179 = AXIS2_PLACEMENT_3D ( 'NONE', #20544, #23835, #26913 ) ; +#29180 = CARTESIAN_POINT ( 'NONE', ( 28.45934412591282126, 181.0176348879864747, 104.5058915996823004 ) ) ; +#29181 = CARTESIAN_POINT ( 'NONE', ( 24.25829023881467705, 115.9286911914962417, 87.75294826888874411 ) ) ; +#29182 = AXIS2_PLACEMENT_3D ( 'NONE', #40061, #12076, #1851 ) ; +#29183 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971519328 ) ) ; +#29184 = DIRECTION ( 'NONE', ( -0.6087611427424929333, -0.7731004630501246977, -0.1781166615410725018 ) ) ; +#29185 = AXIS2_PLACEMENT_3D ( 'NONE', #29200, #35092, #38387 ) ; +#29186 = ORIENTED_EDGE ( 'NONE', *, *, #38556, .T. ) ; +#29188 = EDGE_CURVE ( 'NONE', #22653, #28262, #39831, .T. ) ; +#29187 = DIRECTION ( 'NONE', ( -0.0006039748319110907569, -0.000000000000000000, -0.9999998176071845934 ) ) ; +#29189 = CARTESIAN_POINT ( 'NONE', ( 0.8300031732345369839, 189.0179702984774508, 103.6899947345402211 ) ) ; +#29190 = CARTESIAN_POINT ( 'NONE', ( -2.935232621041004020, 190.8511156531020276, 106.7950609103722286 ) ) ; +#29191 = AXIS2_PLACEMENT_3D ( 'NONE', #35408, #7414, #19881 ) ; +#29192 = CARTESIAN_POINT ( 'NONE', ( 12.64200339761032410, 130.3171527467937381, 92.76750990966068855 ) ) ; +#29193 = CARTESIAN_POINT ( 'NONE', ( -25.61308620896999955, 191.8364462360999880, 104.3104845255000015 ) ) ; +#29194 = DIRECTION ( 'NONE', ( 0.0005884949961273644664, -0.2249510543439051102, 0.9743698870671265722 ) ) ; +#29195 = CARTESIAN_POINT ( 'NONE', ( 20.89286828480348035, 176.3842452922319524, 100.3618186666556369 ) ) ; +#29196 = EDGE_CURVE ( 'NONE', #468, #35577, #1604, .T. ) ; +#29197 = CARTESIAN_POINT ( 'NONE', ( 41.88489195034309631, 131.9654069037970885, 291.5332465100412378 ) ) ; +#29198 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988483757628, 156.3551877983847476, 95.75036263592852492 ) ) ; +#29199 = VERTEX_POINT ( 'NONE', #23694 ) ; +#29200 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; +#29201 = VERTEX_POINT ( 'NONE', #14704 ) ; +#29202 = CARTESIAN_POINT ( 'NONE', ( -27.08876248542915377, 119.4912842839333535, 171.3567424277059956 ) ) ; +#29203 = LINE ( 'NONE', #38199, #918 ) ; +#29204 = AXIS2_PLACEMENT_3D ( 'NONE', #24737, #14911, #31056 ) ; +#29205 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#29206 = CARTESIAN_POINT ( 'NONE', ( 20.23265938097805261, 118.1109138226942576, 90.02470701647605722 ) ) ; +#29207 = DIRECTION ( 'NONE', ( -0.0006039748319381367221, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#29208 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; +#29209 = CARTESIAN_POINT ( 'NONE', ( 36.22735687070999688, 192.3421510775999934, 106.2514255960000042 ) ) ; +#29210 = AXIS2_PLACEMENT_3D ( 'NONE', #15853, #34840, #3780 ) ; +#29211 = ORIENTED_EDGE ( 'NONE', *, *, #16137, .F. ) ; +#29212 = CARTESIAN_POINT ( 'NONE', ( -2.690858666602926164, 209.6642433610929004, 75.89346406803156242 ) ) ; +#29213 = CARTESIAN_POINT ( 'NONE', ( -24.42776677020912146, 104.1131156706543095, 87.28253805075753746 ) ) ; +#29214 = CARTESIAN_POINT ( 'NONE', ( 14.78718341405425818, 175.4478817342403545, 102.7150877355488063 ) ) ; +#29215 = CARTESIAN_POINT ( 'NONE', ( 19.28996579701385272, 152.1764298578125647, 190.8161490377309235 ) ) ; +#29216 = ORIENTED_EDGE ( 'NONE', *, *, #27525, .T. ) ; +#29217 = CARTESIAN_POINT ( 'NONE', ( 6.035627073997911651, 177.4672258935703439, 100.8988463399265925 ) ) ; +#29218 = CARTESIAN_POINT ( 'NONE', ( 25.50045020523564077, 118.3474758881666560, 89.75243582336268844 ) ) ; +#29219 = EDGE_CURVE ( 'NONE', #38692, #35411, #40343, .T. ) ; +#29220 = ORIENTED_EDGE ( 'NONE', *, *, #17462, .F. ) ; +#29221 = LINE ( 'NONE', #10617, #10832 ) ; +#29222 = CARTESIAN_POINT ( 'NONE', ( -4.020898715903520326, 130.4236660157353072, 89.76602547266925569 ) ) ; +#29223 = VERTEX_POINT ( 'NONE', #8146 ) ; +#29224 = CARTESIAN_POINT ( 'NONE', ( 36.45704065391474558, 191.6277635170577867, 106.3741589157719289 ) ) ; +#29225 = CARTESIAN_POINT ( 'NONE', ( -35.43627711891984688, 192.7868339519407357, 106.8766537076977698 ) ) ; +#29226 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552156487, 3.781093664149108639E-12, 291.5584375788758393 ) ) ; +#29227 = CARTESIAN_POINT ( 'NONE', ( 20.49980344970378354, 118.1127835573565221, 87.75514417896067698 ) ) ; +#29228 = EDGE_LOOP ( 'NONE', ( #35579, #16500, #17861, #32187 ) ) ; +#29229 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#29230 = CARTESIAN_POINT ( 'NONE', ( -3.696943479721821024, 176.2105024722404494, 100.3365558499248635 ) ) ; +#29231 = FACE_OUTER_BOUND ( 'NONE', #29703, .T. ) ; +#29232 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34111, #28009, #6106, #37399 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29233 = VECTOR ( 'NONE', #26013, 999.9999999999998863 ) ; +#29234 = FACE_OUTER_BOUND ( 'NONE', #20789, .T. ) ; +#29235 = VERTEX_POINT ( 'NONE', #5268 ) ; +#29236 = ORIENTED_EDGE ( 'NONE', *, *, #24629, .T. ) ; +#29237 = DIRECTION ( 'NONE', ( -3.562554695809820367E-15, 0.9743043966640313469, 0.2252353050503801690 ) ) ; +#29238 = AXIS2_PLACEMENT_3D ( 'NONE', #23672, #1580, #33056 ) ; +#29239 = EDGE_CURVE ( 'NONE', #10957, #10196, #14089, .T. ) ; +#29240 = CARTESIAN_POINT ( 'NONE', ( -20.00025820447960001, 138.1823733798348428, 91.56700283718186029 ) ) ; +#29241 = DIRECTION ( 'NONE', ( 0.7933533416835694130, -0.5930537051408201199, -0.1373964266575329052 ) ) ; +#29242 = PLANE ( 'NONE', #25483 ) ; +#29243 = CARTESIAN_POINT ( 'NONE', ( 26.18925920981000388, 190.6440021692999949, 106.8645677889000041 ) ) ; +#29244 = CARTESIAN_POINT ( 'NONE', ( 38.70471324126999946, 118.8378872794999950, 87.80369324603999814 ) ) ; +#29245 = CARTESIAN_POINT ( 'NONE', ( -3.535839359701232087, 174.6735602432432586, 103.0605886135060700 ) ) ; +#29246 = CARTESIAN_POINT ( 'NONE', ( 38.48039504585000259, 118.5505675456000034, 89.80824134200000231 ) ) ; +#29247 = VERTEX_POINT ( 'NONE', #1811 ) ; +#29248 = ADVANCED_FACE ( 'NONE', ( #26567 ), #39010, .F. ) ; +#29249 = DIRECTION ( 'NONE', ( 3.092411411307044243E-16, -0.9743043966640313469, -0.2252353050503803911 ) ) ; +#29250 = CARTESIAN_POINT ( 'NONE', ( -36.19105143935069435, 191.8150791350400652, 106.4328427572402802 ) ) ; +#29251 = CARTESIAN_POINT ( 'NONE', ( -35.95668941153999754, 225.9002260768999975, 73.08022102179975832 ) ) ; +#29253 = VERTEX_POINT ( 'NONE', #2024 ) ; +#29252 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.110223024625155594E-14 ) ) ; +#29254 = ORIENTED_EDGE ( 'NONE', *, *, #33879, .T. ) ; +#29255 = ORIENTED_EDGE ( 'NONE', *, *, #39168, .T. ) ; +#29256 = ORIENTED_EDGE ( 'NONE', *, *, #31058, .T. ) ; +#29257 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#29258 = CONICAL_SURFACE ( 'NONE', #14877, 2.499999999928965710, 0.7853981633629654180 ) ; +#29259 = LINE ( 'NONE', #22929, #2422 ) ; +#29260 = EDGE_CURVE ( 'NONE', #6533, #26636, #5209, .T. ) ; +#29261 = ADVANCED_FACE ( 'NONE', ( #7940 ), #39411, .F. ) ; +#29262 = CONICAL_SURFACE ( 'NONE', #27333, 6.000000000011055157, 0.7853981633778703841 ) ; +#29263 = ORIENTED_EDGE ( 'NONE', *, *, #9878, .T. ) ; +#29264 = EDGE_CURVE ( 'NONE', #1201, #22101, #16942, .T. ) ; +#29265 = CARTESIAN_POINT ( 'NONE', ( -14.15070617995141511, 188.2799498060330166, 103.1293216427133501 ) ) ; +#29266 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; +#29267 = LINE ( 'NONE', #1236, #24095 ) ; +#29268 = CARTESIAN_POINT ( 'NONE', ( -39.28820068017000011, 119.6036138029000142, 87.80684530786001574 ) ) ; +#29269 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; +#29270 = CARTESIAN_POINT ( 'NONE', ( -13.46321482478000142, 124.1316382070999964, 152.4718672074000381 ) ) ; +#29271 = ORIENTED_EDGE ( 'NONE', *, *, #37597, .T. ) ; +#29272 = CARTESIAN_POINT ( 'NONE', ( -2.435723678148116633, 191.9759150222000130, 106.4229192757972271 ) ) ; +#29273 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624403437, 0.1792657018023851578 ) ) ; +#29274 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.274821093756980468E-14, 0.9999998176071847045 ) ) ; +#29275 = DIRECTION ( 'NONE', ( -0.6087611434179118763, 0.7728348325624406767, 0.1792657018023830207 ) ) ; +#29276 = PLANE ( 'NONE', #11845 ) ; +#29277 = FACE_OUTER_BOUND ( 'NONE', #7496, .T. ) ; +#29278 = VERTEX_POINT ( 'NONE', #39214 ) ; +#29279 = VERTEX_POINT ( 'NONE', #9366 ) ; +#29280 = CARTESIAN_POINT ( 'NONE', ( 13.47343164508975377, 158.6809479346725595, 96.79232023565108989 ) ) ; +#29281 = CARTESIAN_POINT ( 'NONE', ( 3.333113635449135970, 126.7663220037077139, 89.08827443880241503 ) ) ; +#29282 = CARTESIAN_POINT ( 'NONE', ( 15.75014751337000263, 167.5737453454999866, 98.58743350925999493 ) ) ; +#29283 = EDGE_LOOP ( 'NONE', ( #9035, #20694, #13019 ) ) ; +#29284 = CARTESIAN_POINT ( 'NONE', ( -20.50037936456179821, 118.1134456052949560, 87.78011095654957785 ) ) ; +#29285 = LINE ( 'NONE', #16981, #23282 ) ; +#29286 = ORIENTED_EDGE ( 'NONE', *, *, #10086, .T. ) ; +#29287 = VECTOR ( 'NONE', #17685, 1000.000000000000114 ) ; +#29288 = ORIENTED_EDGE ( 'NONE', *, *, #30703, .T. ) ; +#29289 = ORIENTED_EDGE ( 'NONE', *, *, #32583, .T. ) ; +#29290 = CARTESIAN_POINT ( 'NONE', ( -27.25979547307461104, 188.5120705772432643, 103.1908285165064285 ) ) ; +#29291 = CARTESIAN_POINT ( 'NONE', ( 20.48555995111231809, 211.0898943587194481, 73.54694346759191603 ) ) ; +#29292 = VECTOR ( 'NONE', #34413, 1000.000000000000114 ) ; +#29293 = CARTESIAN_POINT ( 'NONE', ( -26.01062451896041949, 209.7096538831000032, 78.07421475979387537 ) ) ; +#29294 = ORIENTED_EDGE ( 'NONE', *, *, #33856, .F. ) ; +#29295 = EDGE_CURVE ( 'NONE', #36184, #13881, #4276, .T. ) ; +#29296 = CARTESIAN_POINT ( 'NONE', ( 26.00255769141890383, 120.1016707076159946, 90.44558059243480841 ) ) ; +#29297 = CARTESIAN_POINT ( 'NONE', ( -39.67864439245563801, 110.6878145009781207, 169.3185036007950828 ) ) ; +#29299 = CARTESIAN_POINT ( 'NONE', ( -37.29141526061891199, 118.0180923441248666, 123.5799244855521835 ) ) ; +#29298 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#29300 = EDGE_CURVE ( 'NONE', #37405, #25158, #38900, .T. ) ; +#29301 = CARTESIAN_POINT ( 'NONE', ( 0.5984374266184000479, 209.0000000000000000, 162.9824824849000322 ) ) ; +#29302 = ORIENTED_EDGE ( 'NONE', *, *, #3086, .T. ) ; +#29303 = CARTESIAN_POINT ( 'NONE', ( -16.78856485531536080, 122.2590524011903881, 174.8714234134831429 ) ) ; +#29304 = CARTESIAN_POINT ( 'NONE', ( -20.51998460911297784, 211.0905570173818546, 73.57089872868714053 ) ) ; +#29305 = ORIENTED_EDGE ( 'NONE', *, *, #26083, .T. ) ; +#29306 = EDGE_CURVE ( 'NONE', #32791, #3536, #3261, .T. ) ; +#29307 = EDGE_CURVE ( 'NONE', #20919, #9311, #2823, .T. ) ; +#29308 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3539, #19081, #686, #19683 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29309 = ORIENTED_EDGE ( 'NONE', *, *, #38782, .F. ) ; +#29310 = EDGE_CURVE ( 'NONE', #11222, #32939, #8216, .T. ) ; +#29311 = LINE ( 'NONE', #26252, #20469 ) ; +#29312 = AXIS2_PLACEMENT_3D ( 'NONE', #14138, #5516, #30486 ) ; +#29313 = EDGE_CURVE ( 'NONE', #28523, #16013, #31103, .T. ) ; +#29314 = FACE_OUTER_BOUND ( 'NONE', #9079, .T. ) ; +#29315 = CARTESIAN_POINT ( 'NONE', ( -2.557037456827000010, 190.9411552911000172, 106.4259169352999947 ) ) ; +#29316 = ORIENTED_EDGE ( 'NONE', *, *, #13568, .T. ) ; +#29317 = EDGE_LOOP ( 'NONE', ( #20386, #22330, #22012, #15670 ) ) ; +#29318 = AXIS2_PLACEMENT_3D ( 'NONE', #15160, #15738, #205 ) ; +#29319 = ORIENTED_EDGE ( 'NONE', *, *, #34537, .T. ) ; +#29320 = AXIS2_PLACEMENT_3D ( 'NONE', #263, #25643, #6400 ) ; +#29321 = CARTESIAN_POINT ( 'NONE', ( -12.63718745341644301, 177.5174336403395898, 100.8766356206245689 ) ) ; +#29322 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971565402 ) ) ; +#29323 = AXIS2_PLACEMENT_3D ( 'NONE', #14401, #38521, #32594 ) ; +#29324 = ORIENTED_EDGE ( 'NONE', *, *, #27809, .F. ) ; +#29325 = VERTEX_POINT ( 'NONE', #8769 ) ; +#29326 = CARTESIAN_POINT ( 'NONE', ( 30.06681124672108396, 135.0171899757494032, 90.93488900863064828 ) ) ; +#29327 = CARTESIAN_POINT ( 'NONE', ( -45.37719536161908707, 116.4273876275239701, 122.4606002128412285 ) ) ; +#29328 = ORIENTED_EDGE ( 'NONE', *, *, #1816, .F. ) ; +#29329 = CARTESIAN_POINT ( 'NONE', ( 39.70509503528159456, 119.3565270907554208, 89.75033746721189232 ) ) ; +#29330 = EDGE_CURVE ( 'NONE', #28905, #14957, #12616, .T. ) ; +#29331 = DIRECTION ( 'NONE', ( -0.1305262051655330657, 0.9658997629102444860, 0.2236080449693589878 ) ) ; +#29332 = PLANE ( 'NONE', #24170 ) ; +#29333 = CARTESIAN_POINT ( 'NONE', ( 32.61880616768083740, 141.6762977345059653, 282.0021323259457517 ) ) ; +#29334 = ORIENTED_EDGE ( 'NONE', *, *, #4217, .F. ) ; +#29335 = FACE_OUTER_BOUND ( 'NONE', #33464, .T. ) ; +#29336 = PLANE ( 'NONE', #21215 ) ; +#29337 = CARTESIAN_POINT ( 'NONE', ( 20.99281265120761830, 212.6262136629989925, 75.54565946750157934 ) ) ; +#29338 = AXIS2_PLACEMENT_3D ( 'NONE', #8558, #11407, #11214 ) ; +#29339 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21501, #6, #15734, #2692 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29340 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; +#29341 = ORIENTED_EDGE ( 'NONE', *, *, #9689, .F. ) ; +#29342 = EDGE_CURVE ( 'NONE', #24276, #33109, #20361, .T. ) ; +#29343 = VECTOR ( 'NONE', #6630, 1000.000000000000000 ) ; +#29344 = AXIS2_PLACEMENT_3D ( 'NONE', #7610, #10696, #26849 ) ; +#29345 = CARTESIAN_POINT ( 'NONE', ( -35.93638238082318992, 190.3639747181505584, 106.7025276796465221 ) ) ; +#29346 = VECTOR ( 'NONE', #18854, 999.9999999999998863 ) ; +#29347 = CARTESIAN_POINT ( 'NONE', ( -37.37212863889000403, 118.2131122468999962, 90.44578357401999824 ) ) ; +#29349 = ORIENTED_EDGE ( 'NONE', *, *, #14361, .T. ) ; +#29348 = EDGE_CURVE ( 'NONE', #17763, #8665, #31355, .T. ) ; +#29350 = CARTESIAN_POINT ( 'NONE', ( -4.036264727041273481, 174.7924093549539180, 102.5751288760997966 ) ) ; +#29351 = ORIENTED_EDGE ( 'NONE', *, *, #5767, .F. ) ; +#29352 = CARTESIAN_POINT ( 'NONE', ( -12.63809828823728232, 131.0198806733800438, 89.90888323108799796 ) ) ; +#29353 = ADVANCED_FACE ( 'NONE', ( #15497 ), #27989, .F. ) ; +#29354 = CARTESIAN_POINT ( 'NONE', ( -94.39863492640319009, 220.5914987861245038, 200.8703399042459807 ) ) ; +#29355 = CARTESIAN_POINT ( 'NONE', ( -20.00152015007030215, 160.4187917561418146, 96.70059905290261781 ) ) ; +#29356 = ORIENTED_EDGE ( 'NONE', *, *, #29751, .T. ) ; +#29357 = ORIENTED_EDGE ( 'NONE', *, *, #18908, .F. ) ; +#29358 = CARTESIAN_POINT ( 'NONE', ( -4.410460075269428515, 181.9951793858723761, 101.6724849349506741 ) ) ; +#29359 = ORIENTED_EDGE ( 'NONE', *, *, #31171, .F. ) ; +#29360 = ORIENTED_EDGE ( 'NONE', *, *, #12540, .F. ) ; +#29362 = EDGE_CURVE ( 'NONE', #23733, #11837, #11835, .T. ) ; +#29361 = CARTESIAN_POINT ( 'NONE', ( 5.667566726500820273, 188.1583619933900877, 103.2486785480823528 ) ) ; +#29363 = CARTESIAN_POINT ( 'NONE', ( -28.55615809014881989, 225.5077044902887735, 74.57575155991852967 ) ) ; +#29364 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#29365 = CARTESIAN_POINT ( 'NONE', ( 36.06343484178082548, 196.1181868591233410, 103.6579563381249471 ) ) ; +#29366 = ORIENTED_EDGE ( 'NONE', *, *, #12879, .F. ) ; +#29367 = CARTESIAN_POINT ( 'NONE', ( 23.36190162741788967, 177.7945445883550519, 100.6858769593398080 ) ) ; +#29368 = CARTESIAN_POINT ( 'NONE', ( 37.31808587042999648, 118.5177498127000035, 87.11908126231999461 ) ) ; +#29369 = DIRECTION ( 'NONE', ( -1.318389841742375916E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#29370 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23924, #5492, #5908, #8585 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29371 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474981270974893, 155.7928101626038426, 98.18628735352585579 ) ) ; +#29372 = AXIS2_PLACEMENT_3D ( 'NONE', #14851, #15048, #33840 ) ; +#29373 = ORIENTED_EDGE ( 'NONE', *, *, #4112, .F. ) ; +#29374 = CARTESIAN_POINT ( 'NONE', ( -28.45663166759245399, 131.0177812377234545, 89.91795229967709702 ) ) ; +#29375 = ORIENTED_EDGE ( 'NONE', *, *, #9047, .T. ) ; +#29376 = CONICAL_SURFACE ( 'NONE', #31976, 2.503152139042832847, 0.7853981633518120065 ) ; +#29377 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; +#29378 = CONICAL_SURFACE ( 'NONE', #18902, 2.503114778588952483, 0.7853981634133299083 ) ; +#29379 = DIRECTION ( 'NONE', ( -0.0004161288024540961568, -0.5299192578740949955, -0.8480479980348919478 ) ) ; +#29380 = CYLINDRICAL_SURFACE ( 'NONE', #15073, 4.000000000000000000 ) ; +#29381 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22822, #23017, #35250, #323 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29382 = CARTESIAN_POINT ( 'NONE', ( 45.34049352841594782, 186.1006523922279143, 106.0989781906799294 ) ) ; +#29383 = ORIENTED_EDGE ( 'NONE', *, *, #3066, .T. ) ; +#29384 = LINE ( 'NONE', #28974, #1738 ) ; +#29385 = CARTESIAN_POINT ( 'NONE', ( 0.8771784711739323281, 189.0248903872490018, 103.6920662537458355 ) ) ; +#29386 = DIRECTION ( 'NONE', ( -0.0005884949961238380989, 0.2249510543439045829, -0.9743698870671267942 ) ) ; +#29387 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 110.4872222533748243, 170.3180069646643915 ) ) ; +#29388 = EDGE_LOOP ( 'NONE', ( #26832, #14631, #16163, #22784 ) ) ; +#29389 = CARTESIAN_POINT ( 'NONE', ( -25.61331352295000130, 191.7885398544999873, 104.3073041621000101 ) ) ; +#29390 = CARTESIAN_POINT ( 'NONE', ( 13.50176809758824703, 126.1286536816045327, 91.84597050332364176 ) ) ; +#29391 = FACE_OUTER_BOUND ( 'NONE', #6551, .T. ) ; +#29392 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #29994, #8529, #27356, #11800 ), + ( #33653, #6052, #30808, #12387 ), + ( #30606, #2789, #18305, #21807 ), + ( #36938, #34056, #3171, #2600 ), + ( #5441, #36725, #115, #5654 ), + ( #18100, #40384, #39991, #12202 ), + ( #24884, #15652, #39784, #12577 ), + ( #9331, #37134, #28148, #27955 ), + ( #37336, #33451, #21414, #33850 ), + ( #5854, #34245, #6244, #15068 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.01471884533601999952, 0.000000000000000000, 0.2499920972522000073, 0.4999842007554999856, 0.7499763042585999573, 0.9999683887995000076, 1.000000000000000000, 1.015331287128000026 ), + ( 3.901540937544999784E-08, 1.000006391878000001 ), + .UNSPECIFIED. ) ; +#29393 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#29394 = EDGE_CURVE ( 'NONE', #2007, #38021, #14515, .T. ) ; +#29395 = ORIENTED_EDGE ( 'NONE', *, *, #28332, .T. ) ; +#29396 = CARTESIAN_POINT ( 'NONE', ( -15.66641274222027214, 174.4419466282511166, 100.2776428363426362 ) ) ; +#29397 = EDGE_CURVE ( 'NONE', #12309, #21808, #35472, .T. ) ; +#29398 = EDGE_CURVE ( 'NONE', #18716, #29610, #9824, .T. ) ; +#29399 = DIRECTION ( 'NONE', ( -6.938893903636092940E-15, -0.9743700557921582961, -0.2249510932971574007 ) ) ; +#29400 = AXIS2_PLACEMENT_3D ( 'NONE', #544, #10178, #19745 ) ; +#29401 = VECTOR ( 'NONE', #3748, 1000.000000000000000 ) ; +#29402 = CARTESIAN_POINT ( 'NONE', ( -20.49823408210000153, 188.6991459859000031, 106.3088473569000030 ) ) ; +#29403 = CARTESIAN_POINT ( 'NONE', ( 3.667423414729050535, 183.7129785219334224, 103.9457492209319014 ) ) ; +#29404 = EDGE_CURVE ( 'NONE', #38536, #10351, #14370, .T. ) ; +#29405 = AXIS2_PLACEMENT_3D ( 'NONE', #4178, #13014, #28947 ) ; +#29406 = CARTESIAN_POINT ( 'NONE', ( 36.26185541537999768, 190.7902229992999992, 106.9071729905000154 ) ) ; +#29407 = CARTESIAN_POINT ( 'NONE', ( -20.34738573694473729, 105.2139170220266777, 87.78007369431503548 ) ) ; +#29408 = AXIS2_PLACEMENT_3D ( 'NONE', #20207, #17745, #8578 ) ; +#29409 = CARTESIAN_POINT ( 'NONE', ( -43.57149710298272538, 121.9974123356087858, 87.84455874305574241 ) ) ; +#29410 = CYLINDRICAL_SURFACE ( 'NONE', #13554, 9.999999999999996447 ) ; +#29411 = PLANE ( 'NONE', #25619 ) ; +#29412 = LINE ( 'NONE', #22476, #27857 ) ; +#29413 = VERTEX_POINT ( 'NONE', #34678 ) ; +#29414 = ADVANCED_FACE ( 'NONE', ( #13037 ), #25518, .T. ) ; +#29415 = CARTESIAN_POINT ( 'NONE', ( -2.552137162834999806, 209.5516823602000045, 75.72668698761999906 ) ) ; +#29416 = CARTESIAN_POINT ( 'NONE', ( 35.55352078495887724, 112.9281706801280194, 87.24630913759760631 ) ) ; +#29417 = CARTESIAN_POINT ( 'NONE', ( 20.25014673412999855, 145.1862164384000096, 93.41614637723000669 ) ) ; +#29418 = ORIENTED_EDGE ( 'NONE', *, *, #7780, .F. ) ; +#29419 = CARTESIAN_POINT ( 'NONE', ( -39.42639396830977461, 119.7153704062085353, 90.39411697856569106 ) ) ; +#29420 = ORIENTED_EDGE ( 'NONE', *, *, #18634, .T. ) ; +#29421 = DIRECTION ( 'NONE', ( -0.6188015000093128881, 0.7855473910504855439, 0.000000000000000000 ) ) ; +#29422 = ORIENTED_EDGE ( 'NONE', *, *, #35628, .T. ) ; +#29423 = CARTESIAN_POINT ( 'NONE', ( 36.07534003772678233, 192.4911781188437487, 106.3697569404252334 ) ) ; +#29424 = CARTESIAN_POINT ( 'NONE', ( 45.27414284685049495, 117.1178614856958831, 122.5863626319347759 ) ) ; +#29425 = DIRECTION ( 'NONE', ( -0.6087611434178765712, -0.7731004625452565504, -0.1781166614241066204 ) ) ; +#29426 = CARTESIAN_POINT ( 'NONE', ( -43.94897559508903839, 113.3760414474846669, 85.85438606565890041 ) ) ; +#29427 = CARTESIAN_POINT ( 'NONE', ( -22.59416765712766306, 154.4034534036981654, 95.31341440929543296 ) ) ; +#29428 = ORIENTED_EDGE ( 'NONE', *, *, #3131, .T. ) ; +#29429 = VECTOR ( 'NONE', #6426, 1000.000000000000114 ) ; +#29430 = CARTESIAN_POINT ( 'NONE', ( 17.25783797889552673, 152.2862265970470617, 183.5735822442753147 ) ) ; +#29431 = AXIS2_PLACEMENT_3D ( 'NONE', #10760, #35268, #29566 ) ; +#29432 = PLANE ( 'NONE', #3559 ) ; +#29433 = LINE ( 'NONE', #11030, #13637 ) ; +#29434 = AXIS2_PLACEMENT_3D ( 'NONE', #23727, #27628, #33113 ) ; +#29435 = AXIS2_PLACEMENT_3D ( 'NONE', #22809, #22011, #19315 ) ; +#29436 = DIRECTION ( 'NONE', ( 0.0005884949961240561319, -0.2249510543439064147, 0.9743698870671262391 ) ) ; +#29437 = ORIENTED_EDGE ( 'NONE', *, *, #18499, .F. ) ; +#29438 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; +#29439 = DIRECTION ( 'NONE', ( -0.4300430038311932601, 0.3870104123855429012, 0.8156506332744531962 ) ) ; +#29440 = FACE_OUTER_BOUND ( 'NONE', #18802, .T. ) ; +#29441 = ADVANCED_FACE ( 'NONE', ( #35276 ), #1967, .F. ) ; +#29442 = CARTESIAN_POINT ( 'NONE', ( 18.72203975115986552, 148.1637263778248723, 183.9835433754430198 ) ) ; +#29443 = CARTESIAN_POINT ( 'NONE', ( 25.63308425969000126, 191.5931614552000042, 106.5131989830999970 ) ) ; +#29444 = LINE ( 'NONE', #11440, #4842 ) ; +#29445 = CARTESIAN_POINT ( 'NONE', ( 38.31967541772999652, 118.7379564658999982, 90.10272892278000256 ) ) ; +#29446 = ORIENTED_EDGE ( 'NONE', *, *, #4586, .F. ) ; +#29447 = DIRECTION ( 'NONE', ( -0.0005884949961204158147, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#29448 = DIRECTION ( 'NONE', ( -0.0005884949961246006183, 0.2249510543439056653, -0.9743698870671265722 ) ) ; +#29449 = LINE ( 'NONE', #22918, #22177 ) ; +#29450 = DIRECTION ( 'NONE', ( 0.0006039748319381690314, -1.159276051261448636E-15, 0.9999998176071845934 ) ) ; +#29451 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; +#29452 = VERTEX_POINT ( 'NONE', #22650 ) ; +#29453 = VERTEX_POINT ( 'NONE', #4012 ) ; +#29454 = AXIS2_PLACEMENT_3D ( 'NONE', #7557, #38632, #16948 ) ; +#29455 = ORIENTED_EDGE ( 'NONE', *, *, #6799, .T. ) ; +#29456 = FACE_OUTER_BOUND ( 'NONE', #24880, .T. ) ; +#29457 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25427, #16396, #31762, #31550 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29458 = AXIS2_PLACEMENT_3D ( 'NONE', #22441, #37966, #9562 ) ; +#29459 = CARTESIAN_POINT ( 'NONE', ( 5.658901668160544851, 123.6924101227050699, 91.28505159842420369 ) ) ; +#29460 = ORIENTED_EDGE ( 'NONE', *, *, #39082, .T. ) ; +#29461 = DIRECTION ( 'NONE', ( 5.165621017347116159E-14, -0.9743700557921582961, -0.2249510932971570121 ) ) ; +#29462 = EDGE_CURVE ( 'NONE', #5073, #4624, #19572, .T. ) ; +#29463 = CARTESIAN_POINT ( 'NONE', ( -38.50399426135000169, 118.5032430122000022, 89.70860371832000624 ) ) ; +#29464 = CARTESIAN_POINT ( 'NONE', ( -38.24270320005000201, 119.4332578602000154, 87.31799352362999400 ) ) ; +#29465 = CARTESIAN_POINT ( 'NONE', ( 1.752039179668178903, 151.6655327357930219, 130.5892088565730091 ) ) ; +#29466 = CARTESIAN_POINT ( 'NONE', ( -15.49852919459145184, 184.4001630190128367, 104.8001769099776652 ) ) ; +#29467 = EDGE_LOOP ( 'NONE', ( #24640, #13135, #32429, #18596 ) ) ; +#29468 = CARTESIAN_POINT ( 'NONE', ( -38.11441020723251683, 171.2555900315151121, 164.7874451303060823 ) ) ; +#29469 = VERTEX_POINT ( 'NONE', #7081 ) ; +#29470 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474974024143720, 155.7928101624922590, 98.18628735357600590 ) ) ; +#29471 = CARTESIAN_POINT ( 'NONE', ( 5.672806455269946646, 130.3093209897733971, 92.76044916600127976 ) ) ; +#29472 = FACE_OUTER_BOUND ( 'NONE', #21411, .T. ) ; +#29473 = CARTESIAN_POINT ( 'NONE', ( -3.169881913554984720, 185.9062129263137138, 102.5746722649703315 ) ) ; +#29474 = CARTESIAN_POINT ( 'NONE', ( -29.94659852274801892, 109.6131156702000027, 89.78587174306085217 ) ) ; +#29475 = ORIENTED_EDGE ( 'NONE', *, *, #27942, .T. ) ; +#29476 = CARTESIAN_POINT ( 'NONE', ( -1.067264757979980105, 188.6621860948839924, 103.2069977215000023 ) ) ; +#29477 = CARTESIAN_POINT ( 'NONE', ( -14.78542069845082807, 129.1241041573916561, 89.98565157148227911 ) ) ; +#29478 = CARTESIAN_POINT ( 'NONE', ( 2.685831263600999996, 190.9632241143999920, 106.4286715060000148 ) ) ; +#29479 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4001, #28962, #7069, #9962 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29480 = EDGE_LOOP ( 'NONE', ( #14838, #7596, #14216, #12606 ) ) ; +#29481 = CIRCLE ( 'NONE', #28809, 6.500000000066433969 ) ; +#29482 = DIRECTION ( 'NONE', ( 0.0005884949961256158652, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#29483 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2255194953558363191, 0.9742386449830560124 ) ) ; +#29484 = VERTEX_POINT ( 'NONE', #1153 ) ; +#29485 = CIRCLE ( 'NONE', #12485, 2.250000000020509816 ) ; +#29486 = ORIENTED_EDGE ( 'NONE', *, *, #32516, .T. ) ; +#29487 = VERTEX_POINT ( 'NONE', #26120 ) ; +#29488 = EDGE_CURVE ( 'NONE', #30170, #14055, #11109, .T. ) ; +#29489 = ADVANCED_FACE ( 'NONE', ( #31649 ), #5902, .F. ) ; +#29490 = CARTESIAN_POINT ( 'NONE', ( 12.63825826683999942, 182.0651920360970735, 102.1915037817528997 ) ) ; +#29491 = CARTESIAN_POINT ( 'NONE', ( 76.10630783110904929, 156.2450968845086550, 96.19213091948995498 ) ) ; +#29492 = ORIENTED_EDGE ( 'NONE', *, *, #20859, .T. ) ; +#29493 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19366, #13638, #28778, #23052 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999992928508356638 ), + .UNSPECIFIED. ) ; +#29494 = CARTESIAN_POINT ( 'NONE', ( -5.670689818969662177, 181.8882185760199093, 101.9226644025294490 ) ) ; +#29495 = VERTEX_POINT ( 'NONE', #10375 ) ; +#29496 = ADVANCED_FACE ( 'NONE', ( #950 ), #28577, .T. ) ; +#29497 = CARTESIAN_POINT ( 'NONE', ( 25.66769799861999957, 120.2588969794000064, 90.13975766321000549 ) ) ; +#29498 = DIRECTION ( 'NONE', ( 0.7072735235932094966, 0.6508952249435893123, 0.2758615032397236932 ) ) ; +#29500 = CARTESIAN_POINT ( 'NONE', ( 13.46793942647703801, 157.6314446051065943, 99.11578051374280562 ) ) ; +#29499 = CARTESIAN_POINT ( 'NONE', ( 20.50029387904210765, 120.2778657767349841, 87.92202505056270923 ) ) ; +#29501 = ORIENTED_EDGE ( 'NONE', *, *, #1642, .F. ) ; +#29502 = ORIENTED_EDGE ( 'NONE', *, *, #10888, .T. ) ; +#29503 = LINE ( 'NONE', #26046, #1199 ) ; +#29504 = ORIENTED_EDGE ( 'NONE', *, *, #26089, .F. ) ; +#29506 = VECTOR ( 'NONE', #5483, 1000.000000000000114 ) ; +#29505 = CYLINDRICAL_SURFACE ( 'NONE', #38728, 1.749999999999998446 ) ; +#29507 = EDGE_CURVE ( 'NONE', #35411, #10050, #15022, .T. ) ; +#29508 = VECTOR ( 'NONE', #17294, 1000.000000000000000 ) ; +#29509 = DIRECTION ( 'NONE', ( -3.469446951894384145E-15, 0.9743700557921587402, 0.2249510932971553745 ) ) ; +#29510 = CARTESIAN_POINT ( 'NONE', ( -46.21296508723837348, 123.3002630821660404, 92.78578120404377216 ) ) ; +#29511 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 1.005820108796730516E-17, 0.0006039748319389842430 ) ) ; +#29512 = EDGE_LOOP ( 'NONE', ( #16233, #10134, #11422, #30370 ) ) ; +#29513 = VERTEX_POINT ( 'NONE', #9975 ) ; +#29514 = DIRECTION ( 'NONE', ( -0.5987322044655852826, -0.8009492788783697526, 0.000000000000000000 ) ) ; +#29515 = EDGE_LOOP ( 'NONE', ( #391, #4906, #11093, #8439 ) ) ; +#29516 = VERTEX_POINT ( 'NONE', #16088 ) ; +#29517 = CARTESIAN_POINT ( 'NONE', ( 30.06443600138266703, 134.9229365128052507, 90.78414315763292564 ) ) ; +#29518 = CARTESIAN_POINT ( 'NONE', ( -37.85149864583512169, 117.8012976905560123, 89.71727313126454817 ) ) ; +#29519 = EDGE_CURVE ( 'NONE', #17526, #32940, #32034, .T. ) ; +#29520 = CARTESIAN_POINT ( 'NONE', ( -13.49852954173086417, 173.9514271942828145, 102.3866877817021503 ) ) ; +#29521 = CARTESIAN_POINT ( 'NONE', ( 2.731001113970879857, 190.9650871812991397, 106.4758074628583842 ) ) ; +#29522 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10780, #14250, #4422, #26724 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29523 = ORIENTED_EDGE ( 'NONE', *, *, #34490, .F. ) ; +#29524 = DIRECTION ( 'NONE', ( 0.9999998268367795706, 0.0001323825607408260941, -0.0005734119534792807889 ) ) ; +#29525 = ADVANCED_FACE ( 'NONE', ( #23238 ), #26930, .T. ) ; +#29526 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 132.9679238121742912, 90.36185680194377312 ) ) ; +#29527 = CARTESIAN_POINT ( 'NONE', ( 22.50176470574409393, 137.8371495728137575, 94.54045718443185820 ) ) ; +#29528 = LINE ( 'NONE', #1301, #31954 ) ; +#29529 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39695, #3091, #21108, #2715 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0006506470571234205429, 0.001755109801005554342 ), + .UNSPECIFIED. ) ; +#29530 = VERTEX_POINT ( 'NONE', #5023 ) ; +#29532 = EDGE_CURVE ( 'NONE', #38952, #6177, #17892, .T. ) ; +#29531 = CARTESIAN_POINT ( 'NONE', ( -23.65566532903961772, 115.6781942705080297, 87.78188130487900764 ) ) ; +#29533 = CIRCLE ( 'NONE', #6664, 2.499999999747368307 ) ; +#29534 = EDGE_CURVE ( 'NONE', #38443, #929, #28755, .T. ) ; +#29535 = CARTESIAN_POINT ( 'NONE', ( -44.46121984373956337, 189.2577286604973210, 103.8865186576782804 ) ) ; +#29536 = CARTESIAN_POINT ( 'NONE', ( -12.63088703835403237, 131.0198726340251199, 89.90887950976862442 ) ) ; +#29537 = EDGE_CURVE ( 'NONE', #27254, #35918, #1833, .T. ) ; +#29538 = CIRCLE ( 'NONE', #23679, 2.250000000020509816 ) ; +#29539 = EDGE_CURVE ( 'NONE', #31100, #36542, #8660, .T. ) ; +#29540 = AXIS2_PLACEMENT_3D ( 'NONE', #23070, #32670, #25951 ) ; +#29541 = VERTEX_POINT ( 'NONE', #7890 ) ; +#29542 = LINE ( 'NONE', #29345, #24758 ) ; +#29543 = CARTESIAN_POINT ( 'NONE', ( -35.30542352610000023, 113.0281073712999955, 90.42665468874000112 ) ) ; +#29544 = ORIENTED_EDGE ( 'NONE', *, *, #11777, .T. ) ; +#29545 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#29546 = ORIENTED_EDGE ( 'NONE', *, *, #2265, .F. ) ; +#29547 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#29548 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26421, #4724, #38865, #23349 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29549 = CARTESIAN_POINT ( 'NONE', ( 37.59860802954651149, 190.9741169367089242, 106.2840917320254732 ) ) ; +#29550 = DIRECTION ( 'NONE', ( -0.0006039748319380813194, -1.041532381956747772E-14, -0.9999998176071845934 ) ) ; +#29551 = EDGE_LOOP ( 'NONE', ( #38156, #15897, #17535, #18654 ) ) ; +#29552 = ORIENTED_EDGE ( 'NONE', *, *, #354, .T. ) ; +#29553 = CARTESIAN_POINT ( 'NONE', ( -37.31403596624686969, 185.5641699427571893, 107.6478458894942065 ) ) ; +#29554 = EDGE_LOOP ( 'NONE', ( #21743, #35702, #34060, #5879 ) ) ; +#29555 = ORIENTED_EDGE ( 'NONE', *, *, #35683, .T. ) ; +#29556 = ORIENTED_EDGE ( 'NONE', *, *, #6307, .T. ) ; +#29557 = DIRECTION ( 'NONE', ( 0.0006039748319481906373, 1.291365685536980129E-14, 0.9999998176071845934 ) ) ; +#29558 = EDGE_CURVE ( 'NONE', #32274, #30770, #18909, .T. ) ; +#29559 = PLANE ( 'NONE', #37854 ) ; +#29560 = ORIENTED_EDGE ( 'NONE', *, *, #3029, .T. ) ; +#29561 = EDGE_LOOP ( 'NONE', ( #19741, #28558, #2767, #10557 ) ) ; +#29562 = CARTESIAN_POINT ( 'NONE', ( -20.51880467302672173, 211.0905570380611493, 75.57084890002228406 ) ) ; +#29563 = CARTESIAN_POINT ( 'NONE', ( 38.06915235233999795, 118.5704106966999944, 87.56905173524000929 ) ) ; +#29565 = CIRCLE ( 'NONE', #5389, 3.500000000064008354 ) ; +#29564 = CARTESIAN_POINT ( 'NONE', ( 36.35611649474000018, 191.4884628071999941, 103.9475963394999951 ) ) ; +#29566 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#29567 = CARTESIAN_POINT ( 'NONE', ( 40.54675149425525404, 217.7719116180000185, 76.03401540786036605 ) ) ; +#29568 = EDGE_LOOP ( 'NONE', ( #26977, #37007, #8291, #14525, #250, #9534, #29921, #16652, #11308, #1718, #15499, #17218, #12068 ) ) ; +#29569 = AXIS2_PLACEMENT_3D ( 'NONE', #4115, #10687, #32162 ) ; +#29570 = DIRECTION ( 'NONE', ( 0.7933535325932939974, -0.5931614258681802143, -0.1369295263402624252 ) ) ; +#29571 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319364147923 ) ) ; +#29572 = ORIENTED_EDGE ( 'NONE', *, *, #28345, .F. ) ; +#29573 = EDGE_CURVE ( 'NONE', #7173, #15039, #39363, .T. ) ; +#29574 = CARTESIAN_POINT ( 'NONE', ( -6.038584421608743646, 134.3886675673123534, 93.63723382949044094 ) ) ; +#29575 = FACE_OUTER_BOUND ( 'NONE', #28149, .T. ) ; +#29576 = CARTESIAN_POINT ( 'NONE', ( 20.50028285398298777, 191.4126458000098978, 104.3447517631808097 ) ) ; +#29577 = FACE_OUTER_BOUND ( 'NONE', #39277, .T. ) ; +#29578 = ORIENTED_EDGE ( 'NONE', *, *, #11434, .T. ) ; +#29579 = DIRECTION ( 'NONE', ( -0.7933532970003751572, -0.5930762008556708098, -0.1372995488602872238 ) ) ; +#29580 = EDGE_CURVE ( 'NONE', #10930, #6111, #1331, .T. ) ; +#29581 = PLANE ( 'NONE', #37549 ) ; +#29582 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; +#29583 = ADVANCED_FACE ( 'NONE', ( #23440 ), #29380, .F. ) ; +#29584 = ORIENTED_EDGE ( 'NONE', *, *, #18358, .T. ) ; +#29585 = CARTESIAN_POINT ( 'NONE', ( -15.81543425933796065, 123.2981470472886656, 173.7034767455141662 ) ) ; +#29586 = VERTEX_POINT ( 'NONE', #23852 ) ; +#29587 = CARTESIAN_POINT ( 'NONE', ( -25.88994835531000049, 191.4519696899999985, 103.9944507113000043 ) ) ; +#29588 = FACE_OUTER_BOUND ( 'NONE', #22622, .T. ) ; +#29589 = CARTESIAN_POINT ( 'NONE', ( -19.99984748064912665, 127.7403057018771904, 89.15611954941233819 ) ) ; +#29590 = EDGE_CURVE ( 'NONE', #30729, #1120, #20805, .T. ) ; +#29591 = AXIS2_PLACEMENT_3D ( 'NONE', #16600, #20283, #19476 ) ; +#29592 = CARTESIAN_POINT ( 'NONE', ( 18.98780079260364317, 148.3242069017240681, 184.1917624428014904 ) ) ; +#29593 = ORIENTED_EDGE ( 'NONE', *, *, #13474, .T. ) ; +#29594 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041179293725575E-05, 0.0002331579774892958087 ) ) ; +#29595 = AXIS2_PLACEMENT_3D ( 'NONE', #36697, #30775, #25052 ) ; +#29596 = CARTESIAN_POINT ( 'NONE', ( 2.713260901989404950, 207.5618069885142347, 77.14516539463954814 ) ) ; +#29597 = VECTOR ( 'NONE', #11817, 1000.000000000000000 ) ; +#29598 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989907490, -0.1373964268091706076 ) ) ; +#29599 = CARTESIAN_POINT ( 'NONE', ( -3.740984982057359964, 137.3073912455885761, 91.56380801151034632 ) ) ; +#29600 = CARTESIAN_POINT ( 'NONE', ( -23.33152358916000324, 172.5096616001999905, 152.4718672074000381 ) ) ; +#29601 = DIRECTION ( 'NONE', ( 0.6087614115774889756, 0.7729348350621332298, 0.1788331191967985345 ) ) ; +#29602 = CARTESIAN_POINT ( 'NONE', ( -25.49601843126475487, 191.0768224934509192, 106.3476355555037571 ) ) ; +#29603 = FACE_OUTER_BOUND ( 'NONE', #5783, .T. ) ; +#29604 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22751, #7384, #10879, #38070 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29605 = CARTESIAN_POINT ( 'NONE', ( 20.07344744512846546, 117.3560877785396173, 90.25566097994942538 ) ) ; +#29606 = ORIENTED_EDGE ( 'NONE', *, *, #37957, .F. ) ; +#29607 = CARTESIAN_POINT ( 'NONE', ( -4.036264726651273449, 143.6503695269377943, 95.38542116098325607 ) ) ; +#29608 = CARTESIAN_POINT ( 'NONE', ( -15.49852919464750833, 127.1814504007330839, 91.59019381971197049 ) ) ; +#29609 = CARTESIAN_POINT ( 'NONE', ( 27.38172910116941949, 155.9316580491613706, 179.7942429727659146 ) ) ; +#29610 = VERTEX_POINT ( 'NONE', #1346 ) ; +#29611 = FACE_OUTER_BOUND ( 'NONE', #28670, .T. ) ; +#29612 = CARTESIAN_POINT ( 'NONE', ( 28.46384604140097352, 128.5894095540852504, 89.32293395223631194 ) ) ; +#29613 = EDGE_LOOP ( 'NONE', ( #14209, #33059, #26853, #5560 ) ) ; +#29614 = CARTESIAN_POINT ( 'NONE', ( 24.24964982527031054, 213.2746822943149425, 73.54367273967973517 ) ) ; +#29615 = ORIENTED_EDGE ( 'NONE', *, *, #15798, .F. ) ; +#29616 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#29617 = AXIS2_PLACEMENT_3D ( 'NONE', #1423, #16208, #13904 ) ; +#29618 = EDGE_CURVE ( 'NONE', #20941, #8704, #36095, .T. ) ; +#29619 = EDGE_CURVE ( 'NONE', #25425, #30682, #2783, .T. ) ; +#29620 = CARTESIAN_POINT ( 'NONE', ( 30.06891677554796161, 137.2464769733099104, 91.83375853871403649 ) ) ; +#29621 = ADVANCED_FACE ( 'NONE', ( #33031 ), #27137, .F. ) ; +#29622 = CARTESIAN_POINT ( 'NONE', ( -26.00142186005520983, 120.7678123865047297, 87.55007858260474052 ) ) ; +#29623 = AXIS2_PLACEMENT_3D ( 'NONE', #35761, #20441, #23734 ) ; +#29624 = EDGE_CURVE ( 'NONE', #127, #14712, #7613, .T. ) ; +#29625 = CARTESIAN_POINT ( 'NONE', ( -12.17913406779514496, 125.0348195299330030, 178.7841644720564602 ) ) ; +#29626 = DIRECTION ( 'NONE', ( -0.5989082241854605249, 0.8008175873178844384, 0.0003617255600147427190 ) ) ; +#29627 = ORIENTED_EDGE ( 'NONE', *, *, #25259, .F. ) ; +#29628 = ORIENTED_EDGE ( 'NONE', *, *, #28130, .F. ) ; +#29629 = CARTESIAN_POINT ( 'NONE', ( 17.25788389583062354, 152.5143575514096597, 182.5876268288973847 ) ) ; +#29630 = VECTOR ( 'NONE', #14231, 1000.000000000000000 ) ; +#29631 = CARTESIAN_POINT ( 'NONE', ( 29.40653848676928916, 157.5555674720174579, 201.9044920761300546 ) ) ; +#29632 = FACE_OUTER_BOUND ( 'NONE', #7391, .T. ) ; +#29633 = EDGE_CURVE ( 'NONE', #28118, #35790, #301, .T. ) ; +#29634 = VERTEX_POINT ( 'NONE', #28138 ) ; +#29635 = CARTESIAN_POINT ( 'NONE', ( -45.30255556275930928, 123.8777291761282129, 93.38906572069882372 ) ) ; +#29636 = ORIENTED_EDGE ( 'NONE', *, *, #11982, .F. ) ; +#29637 = ORIENTED_EDGE ( 'NONE', *, *, #20540, .F. ) ; +#29638 = CARTESIAN_POINT ( 'NONE', ( -20.00029466087617180, 160.7280592933503556, 96.77210435901376684 ) ) ; +#29639 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#29640 = CARTESIAN_POINT ( 'NONE', ( 16.16445611536306259, 152.0055496971487514, 180.9366119946107858 ) ) ; +#29641 = ADVANCED_FACE ( 'NONE', ( #25069 ), #27741, .T. ) ; +#29642 = CARTESIAN_POINT ( 'NONE', ( -21.21399079302519652, 183.3565551017309190, 102.5100844002234197 ) ) ; +#29643 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #5594, #18452 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29644 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#29645 = FACE_OUTER_BOUND ( 'NONE', #8912, .T. ) ; +#29646 = ADVANCED_FACE ( 'NONE', ( #15054 ), #5240, .F. ) ; +#29647 = CARTESIAN_POINT ( 'NONE', ( 4.035676231980001027, 136.7932109853310010, 93.79744583390555590 ) ) ; +#29648 = CARTESIAN_POINT ( 'NONE', ( 3.166265796306132696, 183.9718521032420711, 102.1242597203226836 ) ) ; +#29649 = AXIS2_PLACEMENT_3D ( 'NONE', #30705, #18595, #36824 ) ; +#29650 = AXIS2_PLACEMENT_3D ( 'NONE', #9166, #21642, #8972 ) ; +#29651 = ORIENTED_EDGE ( 'NONE', *, *, #27201, .F. ) ; +#29652 = FACE_OUTER_BOUND ( 'NONE', #22477, .T. ) ; +#29653 = CARTESIAN_POINT ( 'NONE', ( 37.65039792813953312, 188.7571058070083154, 106.2871081217155904 ) ) ; +#29654 = CARTESIAN_POINT ( 'NONE', ( 43.18716009838831127, 118.0176470502005941, 104.8323746835856838 ) ) ; +#29655 = LINE ( 'NONE', #7967, #26116 ) ; +#29656 = VECTOR ( 'NONE', #27868, 1000.000000000000114 ) ; +#29657 = CARTESIAN_POINT ( 'NONE', ( 28.46384604140102681, 184.1285027467652355, 102.1451462731230322 ) ) ; +#29658 = EDGE_LOOP ( 'NONE', ( #28376, #10738, #36033, #25667, #11481 ) ) ; +#29659 = VERTEX_POINT ( 'NONE', #30593 ) ; +#29660 = ORIENTED_EDGE ( 'NONE', *, *, #37288, .T. ) ; +#29661 = CARTESIAN_POINT ( 'NONE', ( -45.70040756943009086, 187.3695729804526309, 106.0171126674183739 ) ) ; +#29662 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001722, 123.6868832756584027, 91.30891139640375798 ) ) ; +#29663 = ORIENTED_EDGE ( 'NONE', *, *, #26544, .T. ) ; +#29664 = FACE_BOUND ( 'NONE', #8554, .T. ) ; +#29665 = LINE ( 'NONE', #30267, #23410 ) ; +#29666 = CARTESIAN_POINT ( 'NONE', ( 16.56169987041441161, 121.8384666780658563, 177.5555275195565059 ) ) ; +#29667 = VERTEX_POINT ( 'NONE', #6233 ) ; +#29668 = CARTESIAN_POINT ( 'NONE', ( -39.71442208983258837, 169.2236437704519574, 164.3192996581971101 ) ) ; +#29669 = EDGE_CURVE ( 'NONE', #11904, #25314, #2677, .T. ) ; +#29670 = EDGE_LOOP ( 'NONE', ( #22205, #3405, #22629, #17069 ) ) ; +#29672 = EDGE_CURVE ( 'NONE', #16662, #28384, #31528, .T. ) ; +#29671 = CARTESIAN_POINT ( 'NONE', ( 5.666470275070142115, 124.7419549499387159, 88.96160009709909389 ) ) ; +#29673 = FACE_OUTER_BOUND ( 'NONE', #13386, .T. ) ; +#29674 = EDGE_CURVE ( 'NONE', #34614, #25997, #9118, .T. ) ; +#29675 = CARTESIAN_POINT ( 'NONE', ( -14.78424366467106665, 136.1377412980438351, 93.65748546644259420 ) ) ; +#29676 = CARTESIAN_POINT ( 'NONE', ( 5.667647268251000625, 124.2920528385285053, 90.91033986944312062 ) ) ; +#29677 = CARTESIAN_POINT ( 'NONE', ( -20.49852807266789867, 190.9630690214611946, 106.3183227610936541 ) ) ; +#29678 = CARTESIAN_POINT ( 'NONE', ( -22.82602396999000405, 180.7017300104000128, 28.07991271570000080 ) ) ; +#29679 = ORIENTED_EDGE ( 'NONE', *, *, #3084, .F. ) ; +#29680 = ORIENTED_EDGE ( 'NONE', *, *, #10844, .F. ) ; +#29681 = CARTESIAN_POINT ( 'NONE', ( -1.679261953508219829, 188.9060477537240104, 103.2635922829680055 ) ) ; +#29682 = CARTESIAN_POINT ( 'NONE', ( 47.97518411862906618, 74.18940180350469404, 323.4777850570266082 ) ) ; +#29683 = AXIS2_PLACEMENT_3D ( 'NONE', #29438, #23493, #29237 ) ; +#29684 = CIRCLE ( 'NONE', #12062, 9.999999999999992895 ) ; +#29685 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#29686 = CARTESIAN_POINT ( 'NONE', ( 24.53348384866002974, 103.6131156702165157, 87.75296677365770392 ) ) ; +#29687 = EDGE_CURVE ( 'NONE', #32437, #8293, #21402, .T. ) ; +#29688 = AXIS2_PLACEMENT_3D ( 'NONE', #35343, #19812, #7349 ) ; +#29689 = EDGE_LOOP ( 'NONE', ( #33064, #7794, #22950, #5578 ) ) ; +#29690 = CARTESIAN_POINT ( 'NONE', ( 35.54748837207993262, 207.8686442303677211, 77.25557267504142089 ) ) ; +#29691 = CARTESIAN_POINT ( 'NONE', ( -25.93820646888479686, 211.8747973169839725, 76.07188810541477153 ) ) ; +#29692 = ORIENTED_EDGE ( 'NONE', *, *, #30053, .F. ) ; +#29693 = ORIENTED_EDGE ( 'NONE', *, *, #20847, .F. ) ; +#29694 = ADVANCED_FACE ( 'NONE', ( #33842 ), #34433, .T. ) ; +#29695 = ORIENTED_EDGE ( 'NONE', *, *, #21427, .F. ) ; +#29696 = ORIENTED_EDGE ( 'NONE', *, *, #5766, .F. ) ; +#29697 = CARTESIAN_POINT ( 'NONE', ( 3.064236136099508290, 190.8512031035150471, 106.7914583158460573 ) ) ; +#29698 = CARTESIAN_POINT ( 'NONE', ( -28.52494867685999935, 186.7521474632000036, 105.8641953606999948 ) ) ; +#29699 = CYLINDRICAL_SURFACE ( 'NONE', #23475, 2.250000000000011102 ) ; +#29700 = ADVANCED_FACE ( 'NONE', ( #18490 ), #7873, .F. ) ; +#29701 = VERTEX_POINT ( 'NONE', #40175 ) ; +#29702 = CARTESIAN_POINT ( 'NONE', ( -5.669730063980141566, 182.0627683792234848, 102.2020018026141486 ) ) ; +#29703 = EDGE_LOOP ( 'NONE', ( #39662, #31521, #8758, #28688 ) ) ; +#29704 = CARTESIAN_POINT ( 'NONE', ( 27.65426534970599803, 123.9758217684860000, 91.34070308701521412 ) ) ; +#29705 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9849, #18414, #220, #12700 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.004046376536929338630, 0.01004638012039786414 ), + .UNSPECIFIED. ) ; +#29706 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; +#29708 = CARTESIAN_POINT ( 'NONE', ( 39.42035703641028022, 114.3667165859880015, 151.6079144922757109 ) ) ; +#29707 = CARTESIAN_POINT ( 'NONE', ( 31.79365004200798595, 115.2698610323616890, 176.5535528959301530 ) ) ; +#29709 = AXIS2_PLACEMENT_3D ( 'NONE', #29992, #27354, #26732 ) ; +#29710 = ORIENTED_EDGE ( 'NONE', *, *, #1637, .F. ) ; +#29711 = FACE_OUTER_BOUND ( 'NONE', #29151, .T. ) ; +#29712 = ORIENTED_EDGE ( 'NONE', *, *, #32837, .F. ) ; +#29713 = AXIS2_PLACEMENT_3D ( 'NONE', #3578, #10151, #727 ) ; +#29714 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #36988, #12047, #15697, #11850 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.698067942813251685, 1.698162583727800268 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999992535913984, 0.9999999992535913984, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#29715 = ORIENTED_EDGE ( 'NONE', *, *, #21024, .T. ) ; +#29716 = CARTESIAN_POINT ( 'NONE', ( 9.153839578580999614, 181.3149981983999908, 104.3295970199999942 ) ) ; +#29717 = FACE_OUTER_BOUND ( 'NONE', #15612, .T. ) ; +#29718 = LINE ( 'NONE', #11925, #34388 ) ; +#29719 = CARTESIAN_POINT ( 'NONE', ( 20.50029382911849041, 160.6303866027595575, 97.23813965018092631 ) ) ; +#29720 = ORIENTED_EDGE ( 'NONE', *, *, #19800, .T. ) ; +#29721 = ORIENTED_EDGE ( 'NONE', *, *, #37717, .T. ) ; +#29722 = ORIENTED_EDGE ( 'NONE', *, *, #3846, .T. ) ; +#29723 = ADVANCED_FACE ( 'NONE', ( #21185 ), #11790, .F. ) ; +#29724 = DIRECTION ( 'NONE', ( 0.7933532411131102302, 0.5932638852154232811, 0.1364866195435443241 ) ) ; +#29725 = EDGE_CURVE ( 'NONE', #26291, #5530, #14952, .T. ) ; +#29726 = CARTESIAN_POINT ( 'NONE', ( 25.99912381358999980, 120.7769352125000069, 87.52069434298999795 ) ) ; +#29727 = ORIENTED_EDGE ( 'NONE', *, *, #4366, .T. ) ; +#29728 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#29729 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13821, #29783, #19940, #14240 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29730 = EDGE_CURVE ( 'NONE', #23378, #11983, #12375, .T. ) ; +#29731 = CARTESIAN_POINT ( 'NONE', ( 3.075283362363695705, 190.8485236763429782, 106.8022027959297446 ) ) ; +#29732 = ORIENTED_EDGE ( 'NONE', *, *, #7322, .F. ) ; +#29733 = LINE ( 'NONE', #1719, #13176 ) ; +#29734 = CIRCLE ( 'NONE', #27157, 2.749999999886777236 ) ; +#29735 = LINE ( 'NONE', #17437, #34297 ) ; +#29736 = AXIS2_PLACEMENT_3D ( 'NONE', #1508, #10728, #13592 ) ; +#29737 = CARTESIAN_POINT ( 'NONE', ( -41.34206624736095392, 120.4517752878489318, 90.39423589739264742 ) ) ; +#29738 = CARTESIAN_POINT ( 'NONE', ( 89.82620651468094763, 73.45072472530432606, 291.5042911573538618 ) ) ; +#29739 = ORIENTED_EDGE ( 'NONE', *, *, #29633, .F. ) ; +#29740 = AXIS2_PLACEMENT_3D ( 'NONE', #15810, #19074, #680 ) ; +#29741 = CARTESIAN_POINT ( 'NONE', ( 3.700917157829753279, 137.3198398098652433, 91.52446586985966803 ) ) ; +#29742 = CARTESIAN_POINT ( 'NONE', ( 19.73921667059327234, 149.8473492619755802, 180.1939462582248836 ) ) ; +#29743 = ADVANCED_FACE ( 'NONE', ( #10331 ), #30747, .F. ) ; +#29744 = ORIENTED_EDGE ( 'NONE', *, *, #15412, .T. ) ; +#29745 = CARTESIAN_POINT ( 'NONE', ( 33.24153725755936506, 80.65949370439929567, 289.2744314884981804 ) ) ; +#29747 = CARTESIAN_POINT ( 'NONE', ( -23.36173673102033632, 135.2906635749613997, 91.41449413045401684 ) ) ; +#29746 = DIRECTION ( 'NONE', ( 0.0005884949961231939744, -0.2249510543439056098, 0.9743698870671265722 ) ) ; +#29748 = EDGE_LOOP ( 'NONE', ( #31902, #32604, #38492, #26939 ) ) ; +#29749 = EDGE_LOOP ( 'NONE', ( #3139, #11081, #22305, #33578, #13076, #7083, #17566, #4868 ) ) ; +#29750 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825958228653913, 0.0005734119015069124312 ) ) ; +#29751 = EDGE_CURVE ( 'NONE', #30770, #15161, #24219, .T. ) ; +#29752 = CONICAL_SURFACE ( 'NONE', #14185, 2.503011032745954267, 0.7853981633441630139 ) ; +#29753 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921577410, 0.2249510932971590937 ) ) ; +#29754 = DIRECTION ( 'NONE', ( -0.1389764456053318442, -0.3254809698329895751, 0.9352794693798666126 ) ) ; +#29755 = CARTESIAN_POINT ( 'NONE', ( 16.29163119234463508, 147.3214335078221779, 179.2465642266784585 ) ) ; +#29756 = CARTESIAN_POINT ( 'NONE', ( -20.00029466087617180, 160.7280592933503556, 96.77210435901376684 ) ) ; +#29757 = VERTEX_POINT ( 'NONE', #26068 ) ; +#29758 = VERTEX_POINT ( 'NONE', #25268 ) ; +#29759 = FACE_OUTER_BOUND ( 'NONE', #12126, .T. ) ; +#29760 = ORIENTED_EDGE ( 'NONE', *, *, #2980, .F. ) ; +#29761 = CONICAL_SURFACE ( 'NONE', #3618, 7.999999999997401190, 0.7853981633973092791 ) ; +#29762 = VERTEX_POINT ( 'NONE', #22197 ) ; +#29763 = ORIENTED_EDGE ( 'NONE', *, *, #3889, .T. ) ; +#29764 = FACE_OUTER_BOUND ( 'NONE', #19079, .T. ) ; +#29765 = EDGE_CURVE ( 'NONE', #26024, #34687, #38128, .T. ) ; +#29766 = FACE_OUTER_BOUND ( 'NONE', #408, .T. ) ; +#29767 = CARTESIAN_POINT ( 'NONE', ( -2.851226056375999907, 209.7096532013000001, 76.06022722036999539 ) ) ; +#29768 = VECTOR ( 'NONE', #7723, 1000.000000000000000 ) ; +#29769 = ORIENTED_EDGE ( 'NONE', *, *, #31070, .T. ) ; +#29770 = CARTESIAN_POINT ( 'NONE', ( -5.669580876059291619, 126.6891943625079762, 89.41800251076365669 ) ) ; +#29771 = AXIS2_PLACEMENT_3D ( 'NONE', #35665, #17681, #33431 ) ; +#29773 = EDGE_CURVE ( 'NONE', #5743, #39814, #808, .T. ) ; +#29772 = CARTESIAN_POINT ( 'NONE', ( -18.98884698902605450, 125.5257020437638147, 175.6370175312684978 ) ) ; +#29774 = CARTESIAN_POINT ( 'NONE', ( -35.27986735535999685, 192.2622337511000126, 103.7793111048000014 ) ) ; +#29775 = CARTESIAN_POINT ( 'NONE', ( 37.74174011798000095, 190.9299051180000220, 103.5602631483999971 ) ) ; +#29776 = EDGE_CURVE ( 'NONE', #24276, #629, #19697, .T. ) ; +#29777 = FACE_OUTER_BOUND ( 'NONE', #25105, .T. ) ; +#29778 = ADVANCED_FACE ( 'NONE', ( #34630 ), #9928, .T. ) ; +#29779 = EDGE_LOOP ( 'NONE', ( #25039, #36710, #14073, #33132 ) ) ; +#29780 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -6.705467647123323749E-18, -0.0006039748319385910029 ) ) ; +#29781 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27187, #29427, #8147, #17533 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29782 = CARTESIAN_POINT ( 'NONE', ( 3.062029414146148376, 193.8169247290955752, 102.7010603508831252 ) ) ; +#29783 = CARTESIAN_POINT ( 'NONE', ( 19.99979080445197610, 118.3402007382070309, 87.25534304740426705 ) ) ; +#29784 = VERTEX_POINT ( 'NONE', #10529 ) ; +#29785 = CARTESIAN_POINT ( 'NONE', ( 0.5744871300181850771, 188.6022961663466617, 103.1948475296316587 ) ) ; +#29786 = CYLINDRICAL_SURFACE ( 'NONE', #33830, 2.000000000000014655 ) ; +#29787 = CARTESIAN_POINT ( 'NONE', ( 20.50053403162508658, 194.6757035433049055, 105.5170475396686811 ) ) ; +#29788 = CARTESIAN_POINT ( 'NONE', ( 19.06749373967776862, 124.7645831343390483, 178.7458660396097230 ) ) ; +#29789 = ORIENTED_EDGE ( 'NONE', *, *, #35365, .T. ) ; +#29790 = CARTESIAN_POINT ( 'NONE', ( -3.169881662145332513, 128.5839160399947332, 89.34077473205128683 ) ) ; +#29791 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455648834120, -31.54510897440487938, 136.4474729010643159 ) ) ; +#29792 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971546806 ) ) ; +#29793 = ORIENTED_EDGE ( 'NONE', *, *, #14407, .T. ) ; +#29794 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#29795 = ORIENTED_EDGE ( 'NONE', *, *, #28394, .F. ) ; +#29796 = CARTESIAN_POINT ( 'NONE', ( 44.09418427031000220, 97.50014108196999985, 154.5673021613000060 ) ) ; +#29797 = DIRECTION ( 'NONE', ( 0.0005884949961244758266, -0.2249510546964108848, 0.9743698869857442268 ) ) ; +#29798 = CIRCLE ( 'NONE', #13479, 2.000000000000011546 ) ; +#29799 = CARTESIAN_POINT ( 'NONE', ( 25.92984058226999977, 191.3539199937000035, 103.9362281880000154 ) ) ; +#29800 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950931402, 137.3532831589782575, 178.0585834213011083 ) ) ; +#29801 = CARTESIAN_POINT ( 'NONE', ( -26.71487369399972067, 123.8654304295266115, 90.83140486997200469 ) ) ; +#29802 = ORIENTED_EDGE ( 'NONE', *, *, #31677, .F. ) ; +#29803 = CONICAL_SURFACE ( 'NONE', #16065, 2.503171273173633082, 0.7853981633585357391 ) ; +#29804 = AXIS2_PLACEMENT_3D ( 'NONE', #38067, #28471, #10068 ) ; +#29805 = DIRECTION ( 'NONE', ( 0.6087614115774527823, 0.7729348350621608743, 0.1788331191968013101 ) ) ; +#29806 = CARTESIAN_POINT ( 'NONE', ( -26.00133086711789687, 118.1131156701862892, 87.28349311522542564 ) ) ; +#29807 = LINE ( 'NONE', #20171, #6806 ) ; +#29808 = ADVANCED_FACE ( 'NONE', ( #19101 ), #13746, .F. ) ; +#29809 = CARTESIAN_POINT ( 'NONE', ( 36.75673095752000563, 191.5503568576000362, 106.2292217633000035 ) ) ; +#29810 = CARTESIAN_POINT ( 'NONE', ( -15.99825050089035550, 126.1262029676268668, 91.86002998339648684 ) ) ; +#29811 = DIRECTION ( 'NONE', ( -0.9914447795421228449, -0.1272537940604324957, -0.02904687618137882441 ) ) ; +#29812 = CARTESIAN_POINT ( 'NONE', ( -38.51027449227886734, 118.9650952051504902, 87.72826332570426189 ) ) ; +#29813 = ORIENTED_EDGE ( 'NONE', *, *, #18123, .T. ) ; +#29814 = CARTESIAN_POINT ( 'NONE', ( 3.652177024044888309, 144.1910916277216472, 93.06085627818802664 ) ) ; +#29815 = EDGE_CURVE ( 'NONE', #36762, #24313, #31594, .T. ) ; +#29816 = PLANE ( 'NONE', #26846 ) ; +#29817 = AXIS2_PLACEMENT_3D ( 'NONE', #40442, #21859, #24943 ) ; +#29818 = VERTEX_POINT ( 'NONE', #31998 ) ; +#29819 = CARTESIAN_POINT ( 'NONE', ( 35.18456992010624163, 82.61260495581380781, 284.2600058304622053 ) ) ; +#29820 = AXIS2_PLACEMENT_3D ( 'NONE', #28457, #8705, #21163 ) ; +#29821 = EDGE_CURVE ( 'NONE', #37725, #29530, #30723, .T. ) ; +#29822 = VERTEX_POINT ( 'NONE', #3553 ) ; +#29823 = AXIS2_PLACEMENT_3D ( 'NONE', #39234, #36167, #1831 ) ; +#29824 = EDGE_CURVE ( 'NONE', #16409, #26164, #25878, .T. ) ; +#29825 = EDGE_CURVE ( 'NONE', #75, #5645, #18821, .T. ) ; +#29826 = DIRECTION ( 'NONE', ( 0.7855473026356903921, 0.6188014303620728018, -0.0004744508866335532646 ) ) ; +#29827 = VERTEX_POINT ( 'NONE', #3362 ) ; +#29828 = CARTESIAN_POINT ( 'NONE', ( 12.66848887859000072, 172.5096616001999905, 152.4718672074000381 ) ) ; +#29829 = AXIS2_PLACEMENT_3D ( 'NONE', #21949, #34393, #19249 ) ; +#29830 = CARTESIAN_POINT ( 'NONE', ( -14.78502443122015286, 175.7439026860171509, 101.4328847155116762 ) ) ; +#29831 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; +#29832 = AXIS2_PLACEMENT_3D ( 'NONE', #3813, #9369, #25521 ) ; +#29833 = CARTESIAN_POINT ( 'NONE', ( 3.668109984895000508, 129.8600137445999962, 92.71016498503001912 ) ) ; +#29834 = DIRECTION ( 'NONE', ( 0.0005884949961138158424, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#29835 = VERTEX_POINT ( 'NONE', #702 ) ; +#29836 = CARTESIAN_POINT ( 'NONE', ( -19.40198027091592081, 124.9165765156423760, 177.8474014814652264 ) ) ; +#29837 = CARTESIAN_POINT ( 'NONE', ( 12.63825826684001719, 182.0651920382574076, 102.1915037821187440 ) ) ; +#29838 = DIRECTION ( 'NONE', ( -0.0006039748319386693907, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#29839 = CARTESIAN_POINT ( 'NONE', ( 14.86381945347172895, 10.02083688679028661, 291.5495665607396063 ) ) ; +#29840 = EDGE_LOOP ( 'NONE', ( #16852, #26257, #16024, #36734 ) ) ; +#29841 = CYLINDRICAL_SURFACE ( 'NONE', #15317, 3.000000000000001332 ) ; +#29842 = CARTESIAN_POINT ( 'NONE', ( 23.00039803961572460, 115.6131156701970895, 89.75408929892711285 ) ) ; +#29843 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#29844 = CARTESIAN_POINT ( 'NONE', ( -30.11673734781999912, 185.5712258908999956, 102.7701824946000073 ) ) ; +#29845 = CARTESIAN_POINT ( 'NONE', ( 3.166377416628577190, 128.5876387387983186, 89.33781556475464924 ) ) ; +#29846 = CARTESIAN_POINT ( 'NONE', ( 24.95681190508087965, 159.0107988627873397, 180.5054692823873097 ) ) ; +#29847 = VECTOR ( 'NONE', #18882, 1000.000000000000000 ) ; +#29848 = CYLINDRICAL_SURFACE ( 'NONE', #39279, 2.000000000000014655 ) ; +#29849 = AXIS2_PLACEMENT_3D ( 'NONE', #38406, #34905, #13272 ) ; +#29850 = CARTESIAN_POINT ( 'NONE', ( 41.33957401875372284, 109.4463674645799500, 169.0514110310531919 ) ) ; +#29851 = VECTOR ( 'NONE', #39734, 1000.000000000000000 ) ; +#29852 = DIRECTION ( 'NONE', ( 0.0005884949961222661141, -0.2249510543439069699, 0.9743698870671262391 ) ) ; +#29853 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#29854 = CARTESIAN_POINT ( 'NONE', ( 38.63960300981000273, 118.6927473727999995, 89.80843469027999504 ) ) ; +#29855 = VERTEX_POINT ( 'NONE', #1102 ) ; +#29856 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#29857 = CARTESIAN_POINT ( 'NONE', ( -44.34810901449250764, 188.6498613026045064, 105.9697747766177258 ) ) ; +#29858 = ADVANCED_FACE ( 'NONE', ( #12989 ), #9180, .F. ) ; +#29859 = DIRECTION ( 'NONE', ( -0.6087614115774527823, 0.7730004600455669950, 0.1785492440296760075 ) ) ; +#29860 = CARTESIAN_POINT ( 'NONE', ( -23.00078011532012212, 115.1133396198523968, 87.28167119284988473 ) ) ; +#29861 = ADVANCED_FACE ( 'NONE', ( #18893 ), #666, .T. ) ; +#29862 = CARTESIAN_POINT ( 'NONE', ( -38.11718854129877343, 118.8155790694493561, 90.29079743518840928 ) ) ; +#29863 = ORIENTED_EDGE ( 'NONE', *, *, #22620, .F. ) ; +#29864 = ORIENTED_EDGE ( 'NONE', *, *, #32533, .T. ) ; +#29865 = ADVANCED_FACE ( 'NONE', ( #15834 ), #3961, .F. ) ; +#29866 = ORIENTED_EDGE ( 'NONE', *, *, #3288, .F. ) ; +#29867 = DIRECTION ( 'NONE', ( 0.0005884949961197505483, -0.2249510543439084409, 0.9743698870671257950 ) ) ; +#29868 = ADVANCED_FACE ( 'NONE', ( #13190 ), #22602, .T. ) ; +#29869 = CARTESIAN_POINT ( 'NONE', ( 18.76312242143445275, 124.3781087017529217, 178.6564478547896329 ) ) ; +#29870 = ORIENTED_EDGE ( 'NONE', *, *, #32532, .T. ) ; +#29871 = PLANE ( 'NONE', #29623 ) ; +#29872 = EDGE_CURVE ( 'NONE', #6999, #24745, #5674, .T. ) ; +#29873 = CARTESIAN_POINT ( 'NONE', ( 22.99138912207082441, 214.0899462551063266, 73.04463992848049259 ) ) ; +#29874 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927776843677, 0.0005734119022075554253 ) ) ; +#29875 = CARTESIAN_POINT ( 'NONE', ( -35.40078786029999947, 114.5765172629999995, 87.14831916340999385 ) ) ; +#29876 = EDGE_LOOP ( 'NONE', ( #32679, #18477, #22621, #4364, #8720, #18071, #31637, #14852 ) ) ; +#29877 = CARTESIAN_POINT ( 'NONE', ( -19.21669706698516222, 125.4524192385917729, 177.5306020213529337 ) ) ; +#29878 = AXIS2_PLACEMENT_3D ( 'NONE', #31140, #3109, #12510 ) ; +#29879 = VERTEX_POINT ( 'NONE', #35620 ) ; +#29880 = CARTESIAN_POINT ( 'NONE', ( -15.91977242095778422, 175.2217652188366799, 100.1156701095006269 ) ) ; +#29881 = CARTESIAN_POINT ( 'NONE', ( 5.335352931311528657, 188.3446295391898389, 103.1324850470098653 ) ) ; +#29882 = CARTESIAN_POINT ( 'NONE', ( 35.62841261737278131, 113.6507261092753680, 90.24626617076017965 ) ) ; +#29883 = AXIS2_PLACEMENT_3D ( 'NONE', #23563, #36441, #11710 ) ; +#29884 = CARTESIAN_POINT ( 'NONE', ( -12.63758390637487139, 181.3626882069777082, 104.3104898290644940 ) ) ; +#29885 = ORIENTED_EDGE ( 'NONE', *, *, #26446, .F. ) ; +#29886 = CARTESIAN_POINT ( 'NONE', ( -2.714642339597999943, 190.4530878461000043, 103.7849384411999978 ) ) ; +#29887 = CARTESIAN_POINT ( 'NONE', ( 0.6498165197299999862, 188.7395310661999872, 103.3612335093000212 ) ) ; +#29888 = CARTESIAN_POINT ( 'NONE', ( 28.33637912711604656, 124.4911283627940435, 91.45576088605962184 ) ) ; +#29889 = ORIENTED_EDGE ( 'NONE', *, *, #8520, .T. ) ; +#29890 = CARTESIAN_POINT ( 'NONE', ( 22.68744430041023818, 154.4094416041085367, 95.28744793558422543 ) ) ; +#29891 = EDGE_LOOP ( 'NONE', ( #891, #36003, #6822, #27933, #21237 ) ) ; +#29892 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12917, #6756, #3692, #34750 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.002118074346442883234 ), + .UNSPECIFIED. ) ; +#29893 = ORIENTED_EDGE ( 'NONE', *, *, #24062, .F. ) ; +#29894 = ORIENTED_EDGE ( 'NONE', *, *, #29064, .T. ) ; +#29895 = EDGE_LOOP ( 'NONE', ( #35633, #36471, #27885, #38308 ) ) ; +#29896 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#29897 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#29898 = EDGE_LOOP ( 'NONE', ( #10764, #23914, #19668, #7720 ) ) ; +#29899 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319377938974 ) ) ; +#29900 = ORIENTED_EDGE ( 'NONE', *, *, #37153, .F. ) ; +#29901 = EDGE_CURVE ( 'NONE', #14103, #7935, #20309, .T. ) ; +#29902 = CARTESIAN_POINT ( 'NONE', ( 26.12848274264259985, 121.2572229188339890, 90.71399663803099145 ) ) ; +#29903 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21819, #12597, #36741, #24703, #9146, #15477, #21629, #34260, #8753, #34070, #6067, #27766, #40404, #28357, #24496, #36956, #15663, #15864, #22027, #24906, #25099, #2994, #18924 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000002776, 0.1874999999999990841, 0.2187499999999993894, 0.2343749999999986955, 0.2499999999999979738, 0.3749999999999905076, 0.4374999999999874545, 0.4687499999999834022, 0.4999999999999792388, 0.6249999999999779066, 0.6874999999999801270, 0.7187499999999840128, 0.7499999999999880096, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29904 = EDGE_CURVE ( 'NONE', #28499, #410, #23524, .T. ) ; +#29905 = CONICAL_SURFACE ( 'NONE', #31210, 2.503003566838541527, 0.7853570728499476017 ) ; +#29906 = CARTESIAN_POINT ( 'NONE', ( 40.79660045530999923, 219.0860688542000219, 75.78386445958000195 ) ) ; +#29907 = EDGE_CURVE ( 'NONE', #12388, #3510, #1499, .T. ) ; +#29908 = CONICAL_SURFACE ( 'NONE', #1823, 8.000001721232548491, 0.7853981633972927368 ) ; +#29910 = CARTESIAN_POINT ( 'NONE', ( 40.22341809199669882, 84.46459415942207727, 281.4571872699962682 ) ) ; +#29909 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391912172 ) ) ; +#29911 = ORIENTED_EDGE ( 'NONE', *, *, #11982, .T. ) ; +#29912 = DIRECTION ( 'NONE', ( -0.0005884949961246437695, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#29913 = ORIENTED_EDGE ( 'NONE', *, *, #23908, .F. ) ; +#29914 = EDGE_CURVE ( 'NONE', #18505, #16566, #35259, .T. ) ; +#29915 = VERTEX_POINT ( 'NONE', #14599 ) ; +#29916 = CARTESIAN_POINT ( 'NONE', ( 43.65682646703121605, 93.15907832361875762, 291.5321763059946534 ) ) ; +#29917 = EDGE_CURVE ( 'NONE', #19724, #30529, #26667, .T. ) ; +#29918 = CARTESIAN_POINT ( 'NONE', ( -12.63767699504066577, 177.1899956602251507, 101.0812418388079834 ) ) ; +#29919 = CARTESIAN_POINT ( 'NONE', ( -28.25571780481785567, 186.4543157461568228, 105.2821206686522686 ) ) ; +#29920 = CARTESIAN_POINT ( 'NONE', ( 36.22641505778000237, 191.6139406055999928, 104.0139690017000191 ) ) ; +#29921 = ORIENTED_EDGE ( 'NONE', *, *, #27905, .F. ) ; +#29922 = ORIENTED_EDGE ( 'NONE', *, *, #2812, .T. ) ; +#29923 = ORIENTED_EDGE ( 'NONE', *, *, #16229, .F. ) ; +#29924 = CARTESIAN_POINT ( 'NONE', ( 20.16839244953768073, 190.8891819486728139, 106.6188877771056127 ) ) ; +#29925 = CARTESIAN_POINT ( 'NONE', ( 25.74260163869999829, 121.8290458033000050, 88.10601801296999724 ) ) ; +#29926 = ORIENTED_EDGE ( 'NONE', *, *, #13335, .T. ) ; +#29927 = EDGE_LOOP ( 'NONE', ( #3044, #20356, #6768, #30104 ) ) ; +#29928 = CARTESIAN_POINT ( 'NONE', ( -35.93453016941000300, 192.5815800178999950, 106.4047550415999979 ) ) ; +#29929 = AXIS2_PLACEMENT_3D ( 'NONE', #19744, #155, #28185 ) ; +#29930 = EDGE_LOOP ( 'NONE', ( #8497, #20652 ) ) ; +#29931 = CARTESIAN_POINT ( 'NONE', ( -22.78251873534900440, 164.0719396662763074, 100.1114352475750309 ) ) ; +#29932 = CARTESIAN_POINT ( 'NONE', ( 19.99999382154498662, 120.3902235794415816, 87.43511282661482653 ) ) ; +#29933 = CARTESIAN_POINT ( 'NONE', ( 15.83342446817142068, 126.7663492669746717, 89.08073393852320976 ) ) ; +#29934 = FACE_OUTER_BOUND ( 'NONE', #12339, .T. ) ; +#29935 = DIRECTION ( 'NONE', ( 0.6337575784460532935, -0.7735316317038959388, -0.0003827736967368305454 ) ) ; +#29936 = ORIENTED_EDGE ( 'NONE', *, *, #36315, .F. ) ; +#29937 = CYLINDRICAL_SURFACE ( 'NONE', #4907, 4.999999999999990230 ) ; +#29938 = CARTESIAN_POINT ( 'NONE', ( 30.18297412318279171, 127.2294757820334752, 89.35003157987318900 ) ) ; +#29939 = ORIENTED_EDGE ( 'NONE', *, *, #12694, .T. ) ; +#29940 = CARTESIAN_POINT ( 'NONE', ( 32.65325603764978979, 78.97532739632895016, 290.6005298003525468 ) ) ; +#29941 = EDGE_CURVE ( 'NONE', #14788, #28866, #16827, .T. ) ; +#29943 = ADVANCED_FACE ( 'NONE', ( #14391 ), #7493, .F. ) ; +#29942 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10339, #22410, #9732, #22211 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29944 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #24246, #28260, #18070, #12920 ), + .UNSPECIFIED., .F., .F. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.583410654013528429, 4.583439918374093480 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999286330876, 0.9999999999286330876, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#29945 = CARTESIAN_POINT ( 'NONE', ( -44.12605770667196481, 189.0087315190842503, 103.3156785504129118 ) ) ; +#29946 = ORIENTED_EDGE ( 'NONE', *, *, #36265, .F. ) ; +#29947 = AXIS2_PLACEMENT_3D ( 'NONE', #3054, #15148, #24360 ) ; +#29948 = ORIENTED_EDGE ( 'NONE', *, *, #10579, .T. ) ; +#29949 = CARTESIAN_POINT ( 'NONE', ( 76.10777906861902409, 155.6981007157128829, 98.63160672925188521 ) ) ; +#29950 = EDGE_LOOP ( 'NONE', ( #8288, #22283, #20543, #28828 ) ) ; +#29951 = CARTESIAN_POINT ( 'NONE', ( 2.333463758010000166, 209.5293504425999913, 75.42172714685999324 ) ) ; +#29952 = AXIS2_PLACEMENT_3D ( 'NONE', #9573, #17941, #14901 ) ; +#29953 = CARTESIAN_POINT ( 'NONE', ( 14.93318671104674777, 124.4798289405424612, 171.6828735292820625 ) ) ; +#29954 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#29955 = CONICAL_SURFACE ( 'NONE', #5126, 2.502999999931229791, 0.7853981633952228369 ) ; +#29956 = CARTESIAN_POINT ( 'NONE', ( 12.63986376608903406, 174.6822240277132039, 103.0527707682702783 ) ) ; +#29957 = VERTEX_POINT ( 'NONE', #2737 ) ; +#29958 = VERTEX_POINT ( 'NONE', #27693 ) ; +#29959 = CARTESIAN_POINT ( 'NONE', ( 13.76428958128341584, 125.4663756326080346, 174.1938355030713694 ) ) ; +#29960 = VERTEX_POINT ( 'NONE', #33991 ) ; +#29961 = EDGE_LOOP ( 'NONE', ( #16191, #9065, #15135, #4951 ) ) ; +#29962 = CARTESIAN_POINT ( 'NONE', ( 25.50879993301148829, 196.1181868571946438, 103.6643310760977670 ) ) ; +#29963 = CARTESIAN_POINT ( 'NONE', ( 36.03687122555673739, 218.5902260770998282, 61.03673652647002257 ) ) ; +#29964 = ORIENTED_EDGE ( 'NONE', *, *, #14580, .F. ) ; +#29965 = CARTESIAN_POINT ( 'NONE', ( 31.79421363390792266, 220.4002260770999726, 73.53930126515697907 ) ) ; +#29966 = CARTESIAN_POINT ( 'NONE', ( -35.89395010493000626, 191.7067202632000260, 104.0335547037000055 ) ) ; +#29967 = CARTESIAN_POINT ( 'NONE', ( 36.86023212634999879, 191.7079963920000125, 104.5047224584999981 ) ) ; +#29968 = ORIENTED_EDGE ( 'NONE', *, *, #19591, .T. ) ; +#29969 = CARTESIAN_POINT ( 'NONE', ( -25.66877846115464123, 120.6335317947693540, 87.84733053400728409 ) ) ; +#29970 = ADVANCED_FACE ( 'NONE', ( #22196 ), #6624, .T. ) ; +#29971 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#29972 = ORIENTED_EDGE ( 'NONE', *, *, #21342, .T. ) ; +#29973 = CARTESIAN_POINT ( 'NONE', ( -20.49852833730357560, 151.4051363130266168, 97.18569325580692464 ) ) ; +#29974 = CARTESIAN_POINT ( 'NONE', ( -23.35938884972302532, 176.8157736797523683, 103.1595155122197980 ) ) ; +#29975 = ORIENTED_EDGE ( 'NONE', *, *, #9588, .T. ) ; +#29976 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37643, #40101, #34166, #12913 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#29977 = CARTESIAN_POINT ( 'NONE', ( 0.6690589101043880049, 188.6123594706415076, 103.1971137079293470 ) ) ; +#29978 = CARTESIAN_POINT ( 'NONE', ( 23.65359131764347822, 115.6781963768868593, 87.75330774182334892 ) ) ; +#29979 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#29980 = CARTESIAN_POINT ( 'NONE', ( 35.55533445286192062, 109.6131156991000069, 90.24631030788441421 ) ) ; +#29981 = ORIENTED_EDGE ( 'NONE', *, *, #5244, .F. ) ; +#29982 = CARTESIAN_POINT ( 'NONE', ( -35.45484958738647663, 205.1071295951935838, 76.12626288493709126 ) ) ; +#29983 = AXIS2_PLACEMENT_3D ( 'NONE', #10221, #22691, #16515 ) ; +#29984 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; +#29985 = LINE ( 'NONE', #14046, #33233 ) ; +#29986 = AXIS2_PLACEMENT_3D ( 'NONE', #32450, #29386, #29792 ) ; +#29987 = ORIENTED_EDGE ( 'NONE', *, *, #24435, .T. ) ; +#29988 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#29989 = EDGE_LOOP ( 'NONE', ( #16583, #2701, #12141, #10872 ) ) ; +#29990 = CONICAL_SURFACE ( 'NONE', #6472, 2.502994266666827894, 0.7853981634117951360 ) ; +#29991 = CARTESIAN_POINT ( 'NONE', ( 8.330750845879437705, 150.6663524668997809, 97.16877009602183080 ) ) ; +#29992 = CARTESIAN_POINT ( 'NONE', ( 22.78222448783905918, 163.9654960800027652, 100.5724929892154620 ) ) ; +#29993 = AXIS2_PLACEMENT_3D ( 'NONE', #9479, #31558, #6997 ) ; +#29994 = CARTESIAN_POINT ( 'NONE', ( 35.42095112463999840, 112.3598550145000132, 90.38140071967001177 ) ) ; +#29995 = CARTESIAN_POINT ( 'NONE', ( 6.030013099936853749, 134.9861680000014701, 90.90411879691632180 ) ) ; +#29996 = ORIENTED_EDGE ( 'NONE', *, *, #30096, .F. ) ; +#29997 = EDGE_CURVE ( 'NONE', #25850, #4106, #6583, .T. ) ; +#29998 = EDGE_CURVE ( 'NONE', #12730, #8754, #2705, .T. ) ; +#29999 = CARTESIAN_POINT ( 'NONE', ( -6.037582702418865743, 135.2929569925057365, 91.40456025213514124 ) ) ; +#30000 = DIRECTION ( 'NONE', ( 0.0006039748319391906751, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#30001 = CARTESIAN_POINT ( 'NONE', ( 20.00182604067493131, 190.8514159882993511, 106.7812686061269716 ) ) ; +#30002 = EDGE_CURVE ( 'NONE', #19471, #17466, #4630, .T. ) ; +#30003 = DIRECTION ( 'NONE', ( -0.0005884949961243157984, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#30004 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; +#30005 = CARTESIAN_POINT ( 'NONE', ( 40.67183997101093951, 184.9339790117970210, 102.3237318327851710 ) ) ; +#30006 = CARTESIAN_POINT ( 'NONE', ( -38.36470799546496835, 118.8248470719471612, 87.72050125755728800 ) ) ; +#30007 = ORIENTED_EDGE ( 'NONE', *, *, #28288, .F. ) ; +#30009 = AXIS2_PLACEMENT_3D ( 'NONE', #36091, #8093, #7681 ) ; +#30008 = DIRECTION ( 'NONE', ( 1.294744789823872573E-10, -0.9743700558212509133, -0.2249510931711427575 ) ) ; +#30010 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385906776 ) ) ; +#30011 = VECTOR ( 'NONE', #33390, 1000.000000000000114 ) ; +#30012 = ORIENTED_EDGE ( 'NONE', *, *, #16731, .F. ) ; +#30013 = CARTESIAN_POINT ( 'NONE', ( 14.55485738440738963, 181.8858882541513537, 104.7147121319332825 ) ) ; +#30014 = CIRCLE ( 'NONE', #4542, 2.000000002172721558 ) ; +#30015 = VECTOR ( 'NONE', #27860, 1000.000000000000227 ) ; +#30016 = EDGE_LOOP ( 'NONE', ( #38664, #17852, #36659, #32057 ) ) ; +#30017 = EDGE_CURVE ( 'NONE', #35255, #572, #35619, .T. ) ; +#30018 = CARTESIAN_POINT ( 'NONE', ( 25.84397327880365935, 191.4423330798549898, 106.7096297072122013 ) ) ; +#30019 = FACE_OUTER_BOUND ( 'NONE', #26373, .T. ) ; +#30020 = CARTESIAN_POINT ( 'NONE', ( -18.61117187107760884, 125.1353300184083253, 178.8218272577300354 ) ) ; +#30021 = ORIENTED_EDGE ( 'NONE', *, *, #24214, .T. ) ; +#30022 = CARTESIAN_POINT ( 'NONE', ( 36.06506570308751947, 192.5918829023582930, 106.3581458348548807 ) ) ; +#30023 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927766006264, 0.0005734119022010027242 ) ) ; +#30024 = CARTESIAN_POINT ( 'NONE', ( -13.46635853387000026, 147.8787825985000097, 152.4718672074000381 ) ) ; +#30025 = CARTESIAN_POINT ( 'NONE', ( -12.63516111085457716, 130.0934455189878634, 92.42935276955371648 ) ) ; +#30026 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #24265, #18287, #12562, #2775 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.800309848272725333, 3.800390736461993324 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999994547583704, 0.9999999994547583704, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#30027 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#30028 = FACE_OUTER_BOUND ( 'NONE', #34883, .T. ) ; +#30029 = ORIENTED_EDGE ( 'NONE', *, *, #20732, .T. ) ; +#30030 = EDGE_LOOP ( 'NONE', ( #33416, #19044, #40348, #23684 ) ) ; +#30031 = CARTESIAN_POINT ( 'NONE', ( 30.05352354161590966, 104.1131156705860690, 87.24963271661329145 ) ) ; +#30032 = CARTESIAN_POINT ( 'NONE', ( -13.66810824591000006, 176.6274814210999864, 103.5177582616999956 ) ) ; +#30033 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#30034 = ADVANCED_FACE ( 'NONE', ( #897 ), #22284, .T. ) ; +#30035 = CARTESIAN_POINT ( 'NONE', ( -10.03773492422901370, 168.4955924422791043, 98.55925788090297601 ) ) ; +#30036 = ORIENTED_EDGE ( 'NONE', *, *, #10347, .F. ) ; +#30037 = CARTESIAN_POINT ( 'NONE', ( -23.85050479439979654, 156.8744767616792615, 186.1578534662776292 ) ) ; +#30038 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23350, #30090, #5535, #32740, #4928, #2080, #2487, #1666, #14555, #35779, #39469, #4725, #14761, #26827, #36418, #8424, #17385, #27245, #20882, #14346, #39676, #8624, #29888, #17181 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 4.334733740157455816E-05, 8.669467480314911633E-05, 0.0001733893496063294577, 0.0003467786992127401763, 0.0006935573984255927844, 0.001387114796851327816, 0.002774229593702839947, 0.003467786992128592868, 0.004161344390554346656, 0.004854901788980100011, 0.005548459187405853366 ), + .UNSPECIFIED. ) ; +#30039 = CARTESIAN_POINT ( 'NONE', ( -41.20667332552599760, 120.5418273977710868, 90.58599501078802518 ) ) ; +#30040 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; +#30041 = CARTESIAN_POINT ( 'NONE', ( -42.48820456521394817, 182.6260049196332602, 137.7617708393588885 ) ) ; +#30042 = LINE ( 'NONE', #20629, #19014 ) ; +#30043 = AXIS2_PLACEMENT_3D ( 'NONE', #4416, #37971, #35075 ) ; +#30044 = EDGE_CURVE ( 'NONE', #31534, #33783, #19349, .T. ) ; +#30045 = AXIS2_PLACEMENT_3D ( 'NONE', #24810, #39915, #46 ) ; +#30046 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#30047 = CIRCLE ( 'NONE', #28731, 2.000000000000011546 ) ; +#30048 = CARTESIAN_POINT ( 'NONE', ( -28.46560972492484609, 127.9063310723858535, 92.28167137666822839 ) ) ; +#30049 = AXIS2_PLACEMENT_3D ( 'NONE', #27198, #30040, #29843 ) ; +#30050 = EDGE_CURVE ( 'NONE', #34375, #1422, #5271, .T. ) ; +#30051 = EDGE_CURVE ( 'NONE', #35141, #27835, #12755, .T. ) ; +#30052 = CARTESIAN_POINT ( 'NONE', ( -21.25263179906144728, 151.3572514703366778, 27.73455668113730965 ) ) ; +#30053 = EDGE_CURVE ( 'NONE', #24492, #37430, #12059, .T. ) ; +#30054 = LINE ( 'NONE', #33704, #26559 ) ; +#30055 = EDGE_CURVE ( 'NONE', #34777, #650, #24743, .T. ) ; +#30056 = CARTESIAN_POINT ( 'NONE', ( 38.17628665576000913, 118.2980305818999938, 87.79568836177999458 ) ) ; +#30057 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825965039104825, 0.0005734119013517169133 ) ) ; +#30058 = CARTESIAN_POINT ( 'NONE', ( 38.94288640132000268, 118.9460699731999966, 89.82301361787001781 ) ) ; +#30059 = VERTEX_POINT ( 'NONE', #10578 ) ; +#30060 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#30061 = CARTESIAN_POINT ( 'NONE', ( -23.36147737338983177, 177.1885760160717211, 101.0873909945826341 ) ) ; +#30062 = FACE_OUTER_BOUND ( 'NONE', #30087, .T. ) ; +#30063 = CARTESIAN_POINT ( 'NONE', ( 35.67174478196999843, 112.8596397694000188, 87.36414130154000190 ) ) ; +#30064 = CARTESIAN_POINT ( 'NONE', ( -5.509042010817696955, 134.9596946440107956, 180.7415265967344169 ) ) ; +#30065 = ORIENTED_EDGE ( 'NONE', *, *, #36022, .T. ) ; +#30066 = ORIENTED_EDGE ( 'NONE', *, *, #28452, .F. ) ; +#30067 = CARTESIAN_POINT ( 'NONE', ( -2.915586116141384743, 190.7752836099844274, 103.6986292183714227 ) ) ; +#30068 = ORIENTED_EDGE ( 'NONE', *, *, #4798, .T. ) ; +#30069 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825908426682013, 0.0005734119026547008927 ) ) ; +#30070 = DIRECTION ( 'NONE', ( -1.001359783477163956E-17, 0.9743043966640315690, 0.2252353050503800580 ) ) ; +#30071 = ORIENTED_EDGE ( 'NONE', *, *, #15141, .T. ) ; +#30072 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#30073 = AXIS2_PLACEMENT_3D ( 'NONE', #29931, #7636, #17023 ) ; +#30074 = ADVANCED_FACE ( 'NONE', ( #33226 ), #35887, .F. ) ; +#30075 = AXIS2_PLACEMENT_3D ( 'NONE', #3597, #16079, #28568 ) ; +#30076 = CARTESIAN_POINT ( 'NONE', ( -39.44282146501851116, 161.9553710365894119, 194.9383616928014646 ) ) ; +#30077 = CARTESIAN_POINT ( 'NONE', ( -13.49688601046059588, 187.5020877889633653, 105.8020847638134256 ) ) ; +#30078 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989907490, -0.1373964268091705798 ) ) ; +#30079 = ORIENTED_EDGE ( 'NONE', *, *, #19367, .T. ) ; +#30080 = DIRECTION ( 'NONE', ( 0.0006039748319375912600, 1.387265140328410610E-14, 0.9999998176071847045 ) ) ; +#30081 = AXIS2_PLACEMENT_3D ( 'NONE', #21539, #40112, #5368 ) ; +#30082 = ORIENTED_EDGE ( 'NONE', *, *, #19769, .F. ) ; +#30083 = FACE_OUTER_BOUND ( 'NONE', #2397, .T. ) ; +#30084 = LINE ( 'NONE', #5113, #26748 ) ; +#30085 = CARTESIAN_POINT ( 'NONE', ( -19.37104535314951903, 147.8320913697636172, 183.5553890942303497 ) ) ; +#30086 = ORIENTED_EDGE ( 'NONE', *, *, #21529, .F. ) ; +#30087 = EDGE_LOOP ( 'NONE', ( #32779, #35461, #4190, #13418 ) ) ; +#30088 = CARTESIAN_POINT ( 'NONE', ( -26.08849602176999838, 190.2333037056999956, 103.7122373673999931 ) ) ; +#30089 = CARTESIAN_POINT ( 'NONE', ( 0.5732490465848030237, 188.9966601621639768, 103.7032449934750105 ) ) ; +#30090 = CARTESIAN_POINT ( 'NONE', ( 25.99312043943056594, 120.1143596994206177, 90.44671930700148721 ) ) ; +#30091 = ADVANCED_FACE ( 'NONE', ( #1765 ), #1154, .T. ) ; +#30092 = ORIENTED_EDGE ( 'NONE', *, *, #40057, .F. ) ; +#30093 = LINE ( 'NONE', #26628, #881 ) ; +#30094 = EDGE_LOOP ( 'NONE', ( #27462, #36648, #17882, #1244 ) ) ; +#30095 = EDGE_CURVE ( 'NONE', #37167, #7200, #39891, .T. ) ; +#30096 = EDGE_CURVE ( 'NONE', #16955, #25532, #30597, .T. ) ; +#30097 = EDGE_LOOP ( 'NONE', ( #1844, #18661, #30187, #14251, #10419, #21270, #19758, #25211, #33512, #23885 ) ) ; +#30098 = VERTEX_POINT ( 'NONE', #29980 ) ; +#30099 = CARTESIAN_POINT ( 'NONE', ( 3.061557430615667652, 191.9759150222000130, 101.9195982364086888 ) ) ; +#30100 = LINE ( 'NONE', #14565, #36527 ) ; +#30101 = EDGE_CURVE ( 'NONE', #3073, #31048, #31034, .T. ) ; +#30102 = CARTESIAN_POINT ( 'NONE', ( -25.99154556069859012, 196.5784392978119968, 103.8908015619487060 ) ) ; +#30103 = AXIS2_PLACEMENT_3D ( 'NONE', #20225, #6956, #20027 ) ; +#30104 = ORIENTED_EDGE ( 'NONE', *, *, #40206, .T. ) ; +#30105 = CARTESIAN_POINT ( 'NONE', ( -20.49842948179519553, 118.5814959395139283, 89.78014270750621506 ) ) ; +#30106 = ORIENTED_EDGE ( 'NONE', *, *, #17551, .F. ) ; +#30107 = VECTOR ( 'NONE', #22431, 1000.000000000000000 ) ; +#30108 = CARTESIAN_POINT ( 'NONE', ( 26.06569843707619683, 120.9038867973739855, 90.63414402004558212 ) ) ; +#30109 = AXIS2_PLACEMENT_3D ( 'NONE', #22745, #31946, #9870 ) ; +#30110 = FACE_OUTER_BOUND ( 'NONE', #30789, .T. ) ; +#30112 = DIRECTION ( 'NONE', ( 0.0004161288024522937249, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#30111 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#30113 = ORIENTED_EDGE ( 'NONE', *, *, #14905, .T. ) ; +#30114 = ORIENTED_EDGE ( 'NONE', *, *, #18481, .F. ) ; +#30115 = ORIENTED_EDGE ( 'NONE', *, *, #15055, .T. ) ; +#30116 = DIRECTION ( 'NONE', ( -0.0006039748319382907873, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#30117 = CARTESIAN_POINT ( 'NONE', ( 30.06995708077950269, 134.8478347379656270, 93.33259620158477787 ) ) ; +#30118 = LINE ( 'NONE', #18229, #21563 ) ; +#30119 = CARTESIAN_POINT ( 'NONE', ( 36.42656940490999773, 191.8204547590999880, 104.3694610780000005 ) ) ; +#30120 = ORIENTED_EDGE ( 'NONE', *, *, #24629, .F. ) ; +#30121 = ORIENTED_EDGE ( 'NONE', *, *, #27633, .F. ) ; +#30122 = LINE ( 'NONE', #1708, #20727 ) ; +#30123 = AXIS2_PLACEMENT_3D ( 'NONE', #24101, #2820, #8561 ) ; +#30124 = CARTESIAN_POINT ( 'NONE', ( 27.86721609982999937, 124.8039940644000012, 88.44928661843999862 ) ) ; +#30125 = AXIS2_PLACEMENT_3D ( 'NONE', #35231, #7234, #17025 ) ; +#30126 = ORIENTED_EDGE ( 'NONE', *, *, #21053, .F. ) ; +#30127 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#30128 = CIRCLE ( 'NONE', #32719, 59.40509898897001051 ) ; +#30129 = ADVANCED_FACE ( 'NONE', ( #29577 ), #23441, .T. ) ; +#30130 = EDGE_LOOP ( 'NONE', ( #941, #9903, #29889, #38485 ) ) ; +#30131 = ADVANCED_FACE ( 'NONE', ( #17280 ), #36096, .F. ) ; +#30132 = CARTESIAN_POINT ( 'NONE', ( 36.04562886062198857, 218.5902260770999987, 75.53673388173362468 ) ) ; +#30133 = ORIENTED_EDGE ( 'NONE', *, *, #12967, .T. ) ; +#30134 = CARTESIAN_POINT ( 'NONE', ( -16.26709548105753811, 147.3187592549000158, 179.2581322910629069 ) ) ; +#30135 = CARTESIAN_POINT ( 'NONE', ( -46.08467315290042876, 125.4204749030748758, 88.80740376148220605 ) ) ; +#30136 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825920524828662, 0.0005734119023723335557 ) ) ; +#30137 = DIRECTION ( 'NONE', ( 0.0005559617645653921157, -0.3907311284892677761, 0.9205046855589706922 ) ) ; +#30138 = EDGE_CURVE ( 'NONE', #31409, #37905, #18315, .T. ) ; +#30139 = ORIENTED_EDGE ( 'NONE', *, *, #30327, .F. ) ; +#30140 = CARTESIAN_POINT ( 'NONE', ( 25.99063927089856563, 207.3563238408722782, 73.60442922372433827 ) ) ; +#30141 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23666, #26951, #4836, #21005 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30142 = CARTESIAN_POINT ( 'NONE', ( -22.63609548443118413, 177.7106153948775500, 100.6943230432614342 ) ) ; +#30143 = CARTESIAN_POINT ( 'NONE', ( 25.50924745143719718, 191.9344736266071436, 104.4056993596765039 ) ) ; +#30144 = EDGE_CURVE ( 'NONE', #36696, #16013, #7225, .T. ) ; +#30145 = VERTEX_POINT ( 'NONE', #26121 ) ; +#30146 = LINE ( 'NONE', #27098, #3180 ) ; +#30148 = FACE_OUTER_BOUND ( 'NONE', #5966, .T. ) ; +#30147 = CARTESIAN_POINT ( 'NONE', ( 14.27573290317919330, 135.8449083118874228, 91.00656752237129865 ) ) ; +#30149 = ORIENTED_EDGE ( 'NONE', *, *, #35590, .T. ) ; +#30150 = CIRCLE ( 'NONE', #27590, 2.499999999556782981 ) ; +#30151 = ADVANCED_FACE ( 'NONE', ( #11364 ), #35933, .F. ) ; +#30152 = ORIENTED_EDGE ( 'NONE', *, *, #13550, .T. ) ; +#30153 = AXIS2_PLACEMENT_3D ( 'NONE', #38144, #26843, #33556 ) ; +#30154 = CARTESIAN_POINT ( 'NONE', ( 38.65087382282330708, 118.5394481973313816, 89.66228983010682896 ) ) ; +#30155 = VERTEX_POINT ( 'NONE', #32640 ) ; +#30156 = CARTESIAN_POINT ( 'NONE', ( 15.99974815555098218, 138.5019114137554936, 91.61902897505088106 ) ) ; +#30157 = DIRECTION ( 'NONE', ( -0.0004161288024658205565, 0.8480480897788525985, -0.5299191110530538928 ) ) ; +#30158 = CARTESIAN_POINT ( 'NONE', ( 37.09326454176861176, 191.1521966848744398, 106.3078452960112656 ) ) ; +#30159 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554023 ) ) ; +#30160 = ORIENTED_EDGE ( 'NONE', *, *, #12409, .F. ) ; +#30161 = EDGE_LOOP ( 'NONE', ( #1909, #37369, #18844, #23577 ) ) ; +#30162 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#30163 = ORIENTED_EDGE ( 'NONE', *, *, #12396, .T. ) ; +#30164 = ORIENTED_EDGE ( 'NONE', *, *, #10432, .F. ) ; +#30165 = CARTESIAN_POINT ( 'NONE', ( 36.06343484149106615, 196.1181868591261264, 103.6579563381262972 ) ) ; +#30166 = CARTESIAN_POINT ( 'NONE', ( -20.00011757681407687, 142.7751936262870629, 92.62737297394311042 ) ) ; +#30167 = CARTESIAN_POINT ( 'NONE', ( 2.781577460637000065, 209.6623454612000330, 73.22349077734000389 ) ) ; +#30168 = CARTESIAN_POINT ( 'NONE', ( -2.954045212696999823, 209.2037278823000293, 76.12424252725000429 ) ) ; +#30169 = ORIENTED_EDGE ( 'NONE', *, *, #24337, .T. ) ; +#30170 = VERTEX_POINT ( 'NONE', #18296 ) ; +#30171 = FACE_OUTER_BOUND ( 'NONE', #752, .T. ) ; +#30172 = CARTESIAN_POINT ( 'NONE', ( -36.28576886329999951, 191.9717759737999927, 104.5605806779000204 ) ) ; +#30173 = CARTESIAN_POINT ( 'NONE', ( 36.96191343238999849, 191.2461813283000254, 103.8994397653000021 ) ) ; +#30174 = ORIENTED_EDGE ( 'NONE', *, *, #29306, .T. ) ; +#30175 = CARTESIAN_POINT ( 'NONE', ( -25.66780912439000062, 120.7136169122999974, 87.87971206257999768 ) ) ; +#30176 = ORIENTED_EDGE ( 'NONE', *, *, #40004, .F. ) ; +#30177 = ORIENTED_EDGE ( 'NONE', *, *, #21429, .T. ) ; +#30178 = DIRECTION ( 'NONE', ( -1.183724029337065647E-10, -0.9743700557655629035, -0.2249510934123543637 ) ) ; +#30179 = CARTESIAN_POINT ( 'NONE', ( -23.35635573182313607, 131.0183818788550241, 89.91503395410319399 ) ) ; +#30180 = EDGE_LOOP ( 'NONE', ( #3260, #5647, #17249, #3325 ) ) ; +#30181 = CARTESIAN_POINT ( 'NONE', ( -14.21481790486992658, 199.9748479675046440, 27.79156831219690815 ) ) ; +#30182 = EDGE_CURVE ( 'NONE', #22954, #29758, #37395, .T. ) ; +#30183 = VECTOR ( 'NONE', #13487, 1000.000000000000227 ) ; +#30184 = EDGE_CURVE ( 'NONE', #30155, #14229, #18089, .T. ) ; +#30185 = CARTESIAN_POINT ( 'NONE', ( 37.99861263456919147, 119.0703074402329946, 87.24831694550429972 ) ) ; +#30186 = CARTESIAN_POINT ( 'NONE', ( -3.535986895436823207, 167.8052092920482039, 101.4748507491612912 ) ) ; +#30187 = ORIENTED_EDGE ( 'NONE', *, *, #31911, .T. ) ; +#30188 = AXIS2_PLACEMENT_3D ( 'NONE', #4093, #10468, #6767 ) ; +#30189 = CARTESIAN_POINT ( 'NONE', ( -35.93819496000456581, 196.1181868592477144, 103.7014435179352603 ) ) ; +#30190 = CARTESIAN_POINT ( 'NONE', ( 2.219713491779890635, 189.8798548279868328, 103.9373167649446401 ) ) ; +#30191 = LINE ( 'NONE', #16879, #22815 ) ; +#30192 = APPROVAL ( #15127, '未' ) ; +#30193 = EDGE_LOOP ( 'NONE', ( #17254, #32552, #17848, #7347 ) ) ; +#30194 = CARTESIAN_POINT ( 'NONE', ( 37.28139524443679420, 185.5739301951794289, 107.6056048166977916 ) ) ; +#30195 = ORIENTED_EDGE ( 'NONE', *, *, #39857, .T. ) ; +#30196 = EDGE_LOOP ( 'NONE', ( #20968, #15659, #11417, #24546 ) ) ; +#30197 = CARTESIAN_POINT ( 'NONE', ( 8.471855203514563115, 150.6175905705881064, 96.98637658383512417 ) ) ; +#30198 = CARTESIAN_POINT ( 'NONE', ( -2.449345313868760865, 209.1926399313205422, 73.58232963557692585 ) ) ; +#30199 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#30200 = LINE ( 'NONE', #2196, #1682 ) ; +#30201 = ORIENTED_EDGE ( 'NONE', *, *, #24391, .F. ) ; +#30202 = CARTESIAN_POINT ( 'NONE', ( 15.99998384348811875, 126.8035267017516787, 88.91816380576780432 ) ) ; +#30203 = ADVANCED_FACE ( 'NONE', ( #39771 ), #5926, .F. ) ; +#30204 = CYLINDRICAL_SURFACE ( 'NONE', #6145, 7.000000000000007994 ) ; +#30205 = CARTESIAN_POINT ( 'NONE', ( -3.707115906001695382, 137.3147537657612816, 91.53070687509357128 ) ) ; +#30206 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32019, #40397, #18710, #38722, #23209, #38934, #35643, #20117, #12160, #17454, #14409, #26895, #30154, #14617, #11550, #36477, #16012, #13169 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.007812500000031027264, 0.01562500000006205453, 0.03125000000009766493, 0.06250000000008840151, 0.1250000000000698885, 0.2500000000000857092, 0.5000000000000646150, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30207 = CARTESIAN_POINT ( 'NONE', ( 19.46069570751975064, 126.1537043193212071, 176.3650766102145155 ) ) ; +#30208 = CARTESIAN_POINT ( 'NONE', ( 32.54675005397223231, 175.7420487377131906, 100.2065144811790418 ) ) ; +#30209 = CARTESIAN_POINT ( 'NONE', ( -14.55306309020423505, 135.7870933973037211, 91.01063163966807679 ) ) ; +#30210 = CARTESIAN_POINT ( 'NONE', ( 20.00245300826521344, 117.7233654573207673, 90.25570385881030688 ) ) ; +#30211 = VERTEX_POINT ( 'NONE', #27138 ) ; +#30212 = CARTESIAN_POINT ( 'NONE', ( 39.06524929025407999, 190.3639766107277751, 106.6572273908310677 ) ) ; +#30213 = VECTOR ( 'NONE', #17397, 1000.000000000000114 ) ; +#30214 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#30215 = ORIENTED_EDGE ( 'NONE', *, *, #20087, .F. ) ; +#30216 = FACE_OUTER_BOUND ( 'NONE', #13549, .T. ) ; +#30217 = ORIENTED_EDGE ( 'NONE', *, *, #675, .T. ) ; +#30218 = CARTESIAN_POINT ( 'NONE', ( -39.09419349104000219, 119.9285908000999967, 87.53984484766000662 ) ) ; +#30219 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.894780628693970840E-14, -0.9999998176071847045 ) ) ; +#30220 = ORIENTED_EDGE ( 'NONE', *, *, #6261, .T. ) ; +#30221 = CARTESIAN_POINT ( 'NONE', ( 35.72162228762299208, 191.8765893896865862, 106.8996286655296331 ) ) ; +#30222 = CARTESIAN_POINT ( 'NONE', ( 4.035087735728000169, 137.3597734203999892, 92.90194316321000656 ) ) ; +#30223 = DIRECTION ( 'NONE', ( -7.723605449956060566E-15, -1.000000000000000000, 7.732940816592896770E-15 ) ) ; +#30224 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19403, #31904, #3063, #22699 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 4.581999207909093208, 4.582002206190092686 ), + .UNSPECIFIED. ) ; +#30225 = EDGE_CURVE ( 'NONE', #23133, #21095, #39839, .T. ) ; +#30226 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22769, #1071, #29299, #19477 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 3.911707216971325806E-06, 0.001107709280090561979 ), + .UNSPECIFIED. ) ; +#30227 = EDGE_CURVE ( 'NONE', #11066, #16199, #13996, .T. ) ; +#30228 = CARTESIAN_POINT ( 'NONE', ( -22.53834600676000477, 152.8497889692000058, 28.07991271570000080 ) ) ; +#30229 = CARTESIAN_POINT ( 'NONE', ( 29.75539532201830895, 185.8818174615954035, 102.8912523119488043 ) ) ; +#30230 = ORIENTED_EDGE ( 'NONE', *, *, #33974, .F. ) ; +#30231 = CARTESIAN_POINT ( 'NONE', ( 38.67185976444999795, 118.8147476325000156, 87.79798927129999697 ) ) ; +#30232 = CARTESIAN_POINT ( 'NONE', ( 76.10748482112096269, 155.8105762428848209, 98.14442178571832187 ) ) ; +#30233 = CARTESIAN_POINT ( 'NONE', ( 26.00773787884236654, 191.9759150222000130, 101.9057393183920510 ) ) ; +#30234 = CARTESIAN_POINT ( 'NONE', ( -20.18406416472224052, 207.7152079537316069, 77.22406492501946218 ) ) ; +#30235 = ORIENTED_EDGE ( 'NONE', *, *, #25674, .T. ) ; +#30236 = CIRCLE ( 'NONE', #12595, 6.000000000000001776 ) ; +#30237 = CARTESIAN_POINT ( 'NONE', ( -20.50650306240503440, 198.0404403167238740, 94.04479409490431863 ) ) ; +#30238 = CARTESIAN_POINT ( 'NONE', ( -42.84416203867576911, 121.1162828388086155, 91.10151243711948155 ) ) ; +#30239 = CARTESIAN_POINT ( 'NONE', ( 6.034689397599763083, 134.7209248247105506, 93.42369219423338222 ) ) ; +#30240 = CARTESIAN_POINT ( 'NONE', ( -28.02720713106999995, 124.8179244407999988, 91.17684134897000092 ) ) ; +#30241 = AXIS2_PLACEMENT_3D ( 'NONE', #35177, #32543, #1452 ) ; +#30242 = CARTESIAN_POINT ( 'NONE', ( -24.42746481139502279, 103.6131156702177094, 87.78253795974556795 ) ) ; +#30243 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; +#30244 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3391, #31026, #37353, #6459 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30245 = CARTESIAN_POINT ( 'NONE', ( -25.73720508646628957, 209.7105442809424005, 73.34683674680479726 ) ) ; +#30246 = DIRECTION ( 'NONE', ( 0.0004161288024444326629, -0.8480480898058072592, 0.5299191110099175095 ) ) ; +#30247 = CALENDAR_DATE ( 2025, 24, 6 ) ; +#30248 = CARTESIAN_POINT ( 'NONE', ( 38.91850419312000042, 118.6194549561000002, 89.51573056895999514 ) ) ; +#30249 = CARTESIAN_POINT ( 'NONE', ( 15.93615458542151764, 126.1689532666872253, 88.77169389726503823 ) ) ; +#30250 = CARTESIAN_POINT ( 'NONE', ( 16.94389310934299786, 122.7108572845141907, 172.1118440547324724 ) ) ; +#30251 = CARTESIAN_POINT ( 'NONE', ( -13.49987458195000123, 124.7394176561793273, 88.97259030854483797 ) ) ; +#30252 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#30253 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971542088 ) ) ; +#30254 = ORIENTED_EDGE ( 'NONE', *, *, #19216, .T. ) ; +#30255 = ORIENTED_EDGE ( 'NONE', *, *, #16319, .T. ) ; +#30256 = CARTESIAN_POINT ( 'NONE', ( -2.803546274881732803, 190.2883312291301081, 103.5861397132776887 ) ) ; +#30257 = ORIENTED_EDGE ( 'NONE', *, *, #1407, .T. ) ; +#30258 = CARTESIAN_POINT ( 'NONE', ( 39.06385346271000714, 191.4135373863498444, 104.3337793579115100 ) ) ; +#30259 = CONICAL_SURFACE ( 'NONE', #216, 3.003184325552035627, 0.7853589132226472813 ) ; +#30260 = EDGE_CURVE ( 'NONE', #37740, #15715, #11582, .T. ) ; +#30261 = CARTESIAN_POINT ( 'NONE', ( -75.44083865550381063, 196.3268239558178152, 191.1601047369532580 ) ) ; +#30262 = AXIS2_PLACEMENT_3D ( 'NONE', #25856, #6412, #35214 ) ; +#30263 = EDGE_LOOP ( 'NONE', ( #29418, #27893, #31629, #11478 ) ) ; +#30264 = PLANE ( 'NONE', #2879 ) ; +#30265 = EDGE_CURVE ( 'NONE', #1820, #20853, #24058, .T. ) ; +#30266 = AXIS2_PLACEMENT_3D ( 'NONE', #23284, #34912, #6929 ) ; +#30267 = CARTESIAN_POINT ( 'NONE', ( 43.53522454855391999, 122.0089639019850409, 87.79461535567980945 ) ) ; +#30268 = CARTESIAN_POINT ( 'NONE', ( -20.18442483482148120, 205.2604112295805692, 76.18245618944183661 ) ) ; +#30269 = ORIENTED_EDGE ( 'NONE', *, *, #42, .T. ) ; +#30270 = DIRECTION ( 'NONE', ( -0.1305263947813612435, -0.9659212020967549162, -0.2235153050807486830 ) ) ; +#30271 = EDGE_LOOP ( 'NONE', ( #19038, #12275, #23834, #3794 ) ) ; +#30272 = CARTESIAN_POINT ( 'NONE', ( 5.015777457169973808, 188.2825131376439742, 103.1183373587086152 ) ) ; +#30273 = EDGE_CURVE ( 'NONE', #7388, #7259, #36928, .T. ) ; +#30274 = ADVANCED_FACE ( 'NONE', ( #21798 ), #33843, .F. ) ; +#30275 = CARTESIAN_POINT ( 'NONE', ( -39.77033354370986729, 163.8648153409711199, 187.7699382718473089 ) ) ; +#30276 = CARTESIAN_POINT ( 'NONE', ( 12.31576967652000043, 135.2953866536457781, 91.39403621976647685 ) ) ; +#30277 = CARTESIAN_POINT ( 'NONE', ( -12.63752829087790452, 181.3391861866521708, 104.3251754955068549 ) ) ; +#30278 = ORIENTED_EDGE ( 'NONE', *, *, #8236, .T. ) ; +#30279 = EDGE_CURVE ( 'NONE', #7552, #35389, #29055, .T. ) ; +#30280 = ORIENTED_EDGE ( 'NONE', *, *, #31760, .T. ) ; +#30281 = CARTESIAN_POINT ( 'NONE', ( -28.27857295063000009, 187.7633331748000103, 102.8796472078000050 ) ) ; +#30282 = CARTESIAN_POINT ( 'NONE', ( 0.5626226327078748257, 189.0115755308770531, 103.6989479033729680 ) ) ; +#30283 = CARTESIAN_POINT ( 'NONE', ( -36.31535185967262436, 190.8511613781771530, 106.8152324789805903 ) ) ; +#30284 = ORIENTED_EDGE ( 'NONE', *, *, #30906, .T. ) ; +#30285 = VERTEX_POINT ( 'NONE', #28725 ) ; +#30286 = LINE ( 'NONE', #15357, #17217 ) ; +#30287 = VERTEX_POINT ( 'NONE', #25070 ) ; +#30288 = AXIS2_PLACEMENT_3D ( 'NONE', #39174, #20775, #5432 ) ; +#30289 = VECTOR ( 'NONE', #29447, 1000.000000000000000 ) ; +#30290 = ORIENTED_EDGE ( 'NONE', *, *, #8913, .T. ) ; +#30291 = ORIENTED_EDGE ( 'NONE', *, *, #5684, .F. ) ; +#30292 = AXIS2_PLACEMENT_3D ( 'NONE', #25914, #18578, #6323 ) ; +#30293 = CARTESIAN_POINT ( 'NONE', ( -37.93481815207000807, 190.9222121061999928, 106.5159675105000048 ) ) ; +#30294 = CARTESIAN_POINT ( 'NONE', ( -6.679083190205946056E-14, 155.6803346354327289, 98.67347229705578115 ) ) ; +#30295 = CARTESIAN_POINT ( 'NONE', ( 39.76265845619285244, 165.1578649273459973, 181.9301569360012252 ) ) ; +#30296 = VECTOR ( 'NONE', #5732, 1000.000000000000114 ) ; +#30297 = EDGE_CURVE ( 'NONE', #626, #27523, #27535, .T. ) ; +#30298 = ORIENTED_EDGE ( 'NONE', *, *, #31895, .F. ) ; +#30299 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178587041921E-05, -0.0002331579774917524482 ) ) ; +#30300 = ORIENTED_EDGE ( 'NONE', *, *, #5815, .F. ) ; +#30301 = CARTESIAN_POINT ( 'NONE', ( 25.89572839478000077, 120.9676170113999945, 90.47270357463001744 ) ) ; +#30302 = FACE_OUTER_BOUND ( 'NONE', #9260, .T. ) ; +#30303 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26949, #5448, #33051, #5038 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30305 = CARTESIAN_POINT ( 'NONE', ( -38.98349917073630166, 208.8862087839809476, 28.69844958122075340 ) ) ; +#30304 = CARTESIAN_POINT ( 'NONE', ( -25.51008961762496341, 210.1735744387999887, 73.57367795469900784 ) ) ; +#30306 = EDGE_LOOP ( 'NONE', ( #24510, #37190, #26333, #29628 ) ) ; +#30307 = ORIENTED_EDGE ( 'NONE', *, *, #23682, .F. ) ; +#30308 = EDGE_CURVE ( 'NONE', #3137, #29487, #28926, .T. ) ; +#30309 = DIRECTION ( 'NONE', ( -0.0006039748319384701143, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#30310 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32674, #980, #38403, #10608 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 1.482755031588850025, 1.482761572412980344 ), + .UNSPECIFIED. ) ; +#30311 = ORIENTED_EDGE ( 'NONE', *, *, #2167, .F. ) ; +#30312 = CARTESIAN_POINT ( 'NONE', ( -13.47112979352495543, 158.6774517721759139, 96.80778692315055878 ) ) ; +#30313 = EDGE_CURVE ( 'NONE', #13401, #3242, #37518, .T. ) ; +#30314 = CARTESIAN_POINT ( 'NONE', ( -15.99998354555182090, 127.4301387325058812, 89.08215018471784674 ) ) ; +#30315 = DIRECTION ( 'NONE', ( 0.0006039748319389841346, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#30316 = CARTESIAN_POINT ( 'NONE', ( 12.63733492464552910, 130.8755352229478603, 89.98668270653696766 ) ) ; +#30317 = ORIENTED_EDGE ( 'NONE', *, *, #5237, .F. ) ; +#30318 = CIRCLE ( 'NONE', #10732, 6.500001283309376099 ) ; +#30319 = VECTOR ( 'NONE', #36337, 1000.000000000000114 ) ; +#30320 = EDGE_CURVE ( 'NONE', #16053, #24926, #21762, .T. ) ; +#30321 = ORIENTED_EDGE ( 'NONE', *, *, #20856, .F. ) ; +#30322 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #40262, #23949, #30268, #2065 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30323 = EDGE_LOOP ( 'NONE', ( #5195, #25609, #34555, #7768 ) ) ; +#30324 = CARTESIAN_POINT ( 'NONE', ( -2.389131445052671499, 190.4669456657243245, 104.1095116572825248 ) ) ; +#30325 = CARTESIAN_POINT ( 'NONE', ( -59.17051632422617757, 248.4236826516141718, 201.1548740838363187 ) ) ; +#30326 = AXIS2_PLACEMENT_3D ( 'NONE', #18759, #18366, #31065 ) ; +#30327 = EDGE_CURVE ( 'NONE', #3435, #26700, #22199, .T. ) ; +#30328 = CARTESIAN_POINT ( 'NONE', ( 26.81146780509000038, 123.8575906589999960, 88.40256404721999672 ) ) ; +#30329 = VERTEX_POINT ( 'NONE', #34434 ) ; +#30330 = CARTESIAN_POINT ( 'NONE', ( 35.85095044413336041, 209.7096532900772559, 75.73246956629850501 ) ) ; +#30331 = EDGE_CURVE ( 'NONE', #24195, #14326, #12473, .T. ) ; +#30332 = CARTESIAN_POINT ( 'NONE', ( 0.7554937491704000196, 188.5901081920000024, 106.0612825900000047 ) ) ; +#30333 = CARTESIAN_POINT ( 'NONE', ( 5.667266162990448386, 130.4719365712317654, 90.24229930473130423 ) ) ; +#30334 = CARTESIAN_POINT ( 'NONE', ( 13.49909370106398576, 124.5554084217246213, 88.65691245320910241 ) ) ; +#30335 = CARTESIAN_POINT ( 'NONE', ( -3.668109984895000508, 124.1783413802999974, 91.40287821750001740 ) ) ; +#30336 = CARTESIAN_POINT ( 'NONE', ( 4.988793577564046622, 148.2075385567467833, 93.86631507789503814 ) ) ; +#30337 = ORIENTED_EDGE ( 'NONE', *, *, #27675, .T. ) ; +#30338 = CARTESIAN_POINT ( 'NONE', ( 25.99030105615392827, 209.7097546603872900, 73.04280869622928662 ) ) ; +#30339 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709481474, 92.27946979429643193, 322.5205145037750754 ) ) ; +#30340 = CARTESIAN_POINT ( 'NONE', ( -44.80682199002519894, 71.18588162383781537, 322.8408877984866763 ) ) ; +#30341 = LOCAL_TIME ( 14, 25, 27.00000000000000000, #3034 ) ; +#30342 = AXIS2_PLACEMENT_3D ( 'NONE', #38763, #22460, #28983 ) ; +#30343 = AXIS2_PLACEMENT_3D ( 'NONE', #2596, #11798, #24279 ) ; +#30344 = EDGE_LOOP ( 'NONE', ( #11995, #16552, #20084, #15023 ) ) ; +#30345 = DIRECTION ( 'NONE', ( -0.7066775280858015318, -9.360549773363750444E-05, 0.7075357676729508993 ) ) ; +#30346 = ORIENTED_EDGE ( 'NONE', *, *, #21145, .T. ) ; +#30347 = AXIS2_PLACEMENT_3D ( 'NONE', #19717, #31622, #34653 ) ; +#30348 = CARTESIAN_POINT ( 'NONE', ( -37.29435884442529670, 164.6092402323636463, 198.2106787237848948 ) ) ; +#30349 = EDGE_LOOP ( 'NONE', ( #36086, #27248 ) ) ; +#30350 = ORIENTED_EDGE ( 'NONE', *, *, #2090, .F. ) ; +#30351 = EDGE_LOOP ( 'NONE', ( #15431, #27434, #4236, #14486 ) ) ; +#30352 = EDGE_CURVE ( 'NONE', #12627, #40149, #22313, .T. ) ; +#30353 = LINE ( 'NONE', #2349, #18593 ) ; +#30354 = ADVANCED_FACE ( 'NONE', ( #32000 ), #13241, .F. ) ; +#30355 = DIRECTION ( 'NONE', ( 1.355448645614934247E-15, 0.9743700557918348881, 0.2249510932985576139 ) ) ; +#30356 = FACE_OUTER_BOUND ( 'NONE', #11492, .T. ) ; +#30357 = EDGE_CURVE ( 'NONE', #19028, #6998, #26230, .T. ) ; +#30358 = FACE_OUTER_BOUND ( 'NONE', #10913, .T. ) ; +#30359 = VERTEX_POINT ( 'NONE', #34631 ) ; +#30360 = VERTEX_POINT ( 'NONE', #3163 ) ; +#30361 = FACE_OUTER_BOUND ( 'NONE', #14159, .T. ) ; +#30362 = ORIENTED_EDGE ( 'NONE', *, *, #11777, .F. ) ; +#30363 = ORIENTED_EDGE ( 'NONE', *, *, #25511, .F. ) ; +#30364 = DIRECTION ( 'NONE', ( 0.0005884949961232180437, -0.2249510543439044996, 0.9743698870671267942 ) ) ; +#30365 = EDGE_CURVE ( 'NONE', #9881, #4160, #25681, .T. ) ; +#30366 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265236668, 0.1368326740407682096 ) ) ; +#30367 = CARTESIAN_POINT ( 'NONE', ( -23.36589107377781005, 134.9158523539519194, 90.81477344275025132 ) ) ; +#30368 = ADVANCED_FACE ( 'NONE', ( #31596 ), #3555, .F. ) ; +#30369 = ORIENTED_EDGE ( 'NONE', *, *, #9925, .T. ) ; +#30370 = ORIENTED_EDGE ( 'NONE', *, *, #15378, .T. ) ; +#30371 = CARTESIAN_POINT ( 'NONE', ( 24.57257244294000031, 109.6131156702000027, 152.4718672074000381 ) ) ; +#30372 = CARTESIAN_POINT ( 'NONE', ( -35.93694266037999796, 191.6740185698999994, 104.0281987147999985 ) ) ; +#30373 = CARTESIAN_POINT ( 'NONE', ( -26.00154085324000164, 120.8070833447000041, 87.55874384822999446 ) ) ; +#30374 = CIRCLE ( 'NONE', #16633, 6.000000000000007994 ) ; +#30375 = EDGE_CURVE ( 'NONE', #22363, #9812, #34824, .T. ) ; +#30376 = ORIENTED_EDGE ( 'NONE', *, *, #36407, .F. ) ; +#30377 = CARTESIAN_POINT ( 'NONE', ( -77.86614104348858234, 192.3476576144325350, 194.3451165138085912 ) ) ; +#30378 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049006696, 187.6642686534657969, 106.0792573255290279 ) ) ; +#30379 = PLANE ( 'NONE', #40440 ) ; +#30380 = ORIENTED_EDGE ( 'NONE', *, *, #18837, .T. ) ; +#30381 = AXIS2_PLACEMENT_3D ( 'NONE', #37327, #9523, #10334 ) ; +#30382 = CARTESIAN_POINT ( 'NONE', ( 2.856426491790444722, 190.1159510835748563, 103.5429241319047122 ) ) ; +#30383 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38532, #9747, #6855, #16455 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0001360695803370404959, 0.001188674531724661070 ), + .UNSPECIFIED. ) ; +#30384 = CONICAL_SURFACE ( 'NONE', #3594, 51.90509899251598824, 0.7853981633973070586 ) ; +#30385 = CARTESIAN_POINT ( 'NONE', ( 0.5623190733617040582, 188.6124699482102756, 103.1972064621602527 ) ) ; +#30386 = CARTESIAN_POINT ( 'NONE', ( 39.43357611201896873, 119.6599139514868000, 90.33369661064041622 ) ) ; +#30387 = EDGE_LOOP ( 'NONE', ( #24299, #31539, #30725, #26964 ) ) ; +#30388 = EDGE_CURVE ( 'NONE', #21808, #13881, #39765, .T. ) ; +#30389 = CARTESIAN_POINT ( 'NONE', ( -19.35108328216286466, 125.8813528276864986, 176.2931328289076873 ) ) ; +#30390 = CARTESIAN_POINT ( 'NONE', ( 2.527886776962242177, 190.6140954227784619, 104.1491054897084751 ) ) ; +#30391 = CARTESIAN_POINT ( 'NONE', ( -13.49684457966274920, 188.3420920579488040, 103.1432733986002006 ) ) ; +#30392 = ORIENTED_EDGE ( 'NONE', *, *, #29115, .F. ) ; +#30393 = CARTESIAN_POINT ( 'NONE', ( 25.92457966006830361, 117.3337153156629853, 90.25212704270869324 ) ) ; +#30394 = VERTEX_POINT ( 'NONE', #7842 ) ; +#30395 = CARTESIAN_POINT ( 'NONE', ( 40.92026568130903286, 127.3697701065169525, 89.54698672993396258 ) ) ; +#30396 = CARTESIAN_POINT ( 'NONE', ( -2.455535015344930905, 209.0643992532682489, 73.60343043103465277 ) ) ; +#30397 = DIRECTION ( 'NONE', ( -0.0005884950603321816021, 0.2249510543244929717, -0.9743698870715694627 ) ) ; +#30398 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#30399 = CARTESIAN_POINT ( 'NONE', ( -38.94544030374902377, 127.6228066749847159, 91.70625031055864440 ) ) ; +#30400 = ORIENTED_EDGE ( 'NONE', *, *, #912, .T. ) ; +#30401 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#30402 = VECTOR ( 'NONE', #36015, 1000.000000000000114 ) ; +#30403 = AXIS2_PLACEMENT_3D ( 'NONE', #24432, #6000, #21759 ) ; +#30404 = DIRECTION ( 'NONE', ( 0.7933308265452475583, 0.5932923437231171215, 0.1364932032467733869 ) ) ; +#30405 = CARTESIAN_POINT ( 'NONE', ( -2.938441476483304005, 191.9759150222000130, 101.9232220854011928 ) ) ; +#30406 = VECTOR ( 'NONE', #8010, 999.9999999999998863 ) ; +#30407 = CIRCLE ( 'NONE', #14748, 2.749999999872844381 ) ; +#30408 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#30410 = AXIS2_PLACEMENT_3D ( 'NONE', #36509, #8923, #5212 ) ; +#30409 = LINE ( 'NONE', #2987, #2930 ) ; +#30411 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #12402, #3387 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30412 = ADVANCED_FACE ( 'NONE', ( #23592 ), #35832, .F. ) ; +#30413 = CARTESIAN_POINT ( 'NONE', ( -20.80881105757926619, 183.3190328663897901, 104.5537767167631813 ) ) ; +#30414 = DIRECTION ( 'NONE', ( 1.908195823574476760E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#30415 = CARTESIAN_POINT ( 'NONE', ( -37.03430921788798003, 164.9912417531061806, 195.6638442139325207 ) ) ; +#30416 = ADVANCED_FACE ( 'NONE', ( #22997 ), #8603, .T. ) ; +#30417 = CIRCLE ( 'NONE', #38888, 1.999999999912203341 ) ; +#30418 = CARTESIAN_POINT ( 'NONE', ( 41.20592959029892199, 166.0079942228585708, 183.1534114321898130 ) ) ; +#30419 = EDGE_CURVE ( 'NONE', #27010, #23072, #28245, .T. ) ; +#30420 = CARTESIAN_POINT ( 'NONE', ( -35.60463239281441616, 192.3272979397512188, 104.0809358108204350 ) ) ; +#30421 = ORIENTED_EDGE ( 'NONE', *, *, #21201, .F. ) ; +#30422 = VERTEX_POINT ( 'NONE', #7639 ) ; +#30423 = CARTESIAN_POINT ( 'NONE', ( 26.96435332582821687, 119.8033593921229425, 171.4421629884936067 ) ) ; +#30424 = CARTESIAN_POINT ( 'NONE', ( -32.48647373867155608, 136.7094953407745095, 91.23441627737952331 ) ) ; +#30425 = ADVANCED_FACE ( 'NONE', ( #17230 ), #4565, .T. ) ; +#30426 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20044, #23340, #2479, #20667 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0001754148665578480321, 0.0002047026810873128701 ), + .UNSPECIFIED. ) ; +#30427 = ORIENTED_EDGE ( 'NONE', *, *, #1479, .F. ) ; +#30428 = CARTESIAN_POINT ( 'NONE', ( -38.86369644165072401, 118.8228811219059793, 89.72077589445396484 ) ) ; +#30429 = CARTESIAN_POINT ( 'NONE', ( -19.99970941558080284, 118.1131156714892114, 90.27986793006986943 ) ) ; +#30430 = ORIENTED_EDGE ( 'NONE', *, *, #10656, .F. ) ; +#30431 = CARTESIAN_POINT ( 'NONE', ( -39.69380504816999888, 119.8651302025999996, 87.86311136131999433 ) ) ; +#30432 = EDGE_CURVE ( 'NONE', #3941, #20872, #37322, .T. ) ; +#30433 = CARTESIAN_POINT ( 'NONE', ( 16.24136348069641045, 152.0504431525023676, 181.0538646986893809 ) ) ; +#30434 = CARTESIAN_POINT ( 'NONE', ( 36.66403270979058249, 190.6919956248356982, 106.7344084553361512 ) ) ; +#30435 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; +#30436 = EDGE_LOOP ( 'NONE', ( #29492, #4959, #14663, #15302 ) ) ; +#30437 = LINE ( 'NONE', #18133, #23580 ) ; +#30438 = AXIS2_PLACEMENT_3D ( 'NONE', #29965, #11159, #33425 ) ; +#30439 = LINE ( 'NONE', #12613, #20491 ) ; +#30440 = CARTESIAN_POINT ( 'NONE', ( 36.06476242627000062, 193.5538913732000026, 105.8560347722000046 ) ) ; +#30441 = EDGE_CURVE ( 'NONE', #24020, #29762, #26869, .T. ) ; +#30442 = CIRCLE ( 'NONE', #12140, 2.000000000000011546 ) ; +#30443 = CARTESIAN_POINT ( 'NONE', ( -14.38825339673138259, 10.02132158114557114, 291.5672340797456172 ) ) ; +#30444 = LINE ( 'NONE', #12236, #11947 ) ; +#30445 = VECTOR ( 'NONE', #17706, 1000.000000000000000 ) ; +#30446 = VERTEX_POINT ( 'NONE', #10931 ) ; +#30447 = CARTESIAN_POINT ( 'NONE', ( 39.54773932386999746, 120.6021275922999934, 87.32418019465001180 ) ) ; +#30448 = CARTESIAN_POINT ( 'NONE', ( 25.74196636718000164, 210.3999399800999868, 75.79295708133000176 ) ) ; +#30449 = DIRECTION ( 'NONE', ( 0.6087608094795160518, -0.7729396873201688223, -0.1788141957654486303 ) ) ; +#30450 = CARTESIAN_POINT ( 'NONE', ( 21.57626858038420181, 182.0286742890524181, 104.5723846802734300 ) ) ; +#30451 = CONICAL_SURFACE ( 'NONE', #16701, 5.000000000038869352, 0.7853981633647073579 ) ; +#30452 = ORIENTED_EDGE ( 'NONE', *, *, #34529, .T. ) ; +#30453 = CARTESIAN_POINT ( 'NONE', ( 22.07808152764010856, 150.7554441681027129, 27.80156222623680762 ) ) ; +#30454 = CARTESIAN_POINT ( 'NONE', ( -41.44595535608001313, 120.6173858629433369, 90.60358358051291816 ) ) ; +#30455 = LINE ( 'NONE', #23706, #32666 ) ; +#30456 = FACE_OUTER_BOUND ( 'NONE', #9158, .T. ) ; +#30457 = CARTESIAN_POINT ( 'NONE', ( 13.67163921588000086, 181.5029510073999859, 104.6268367889000075 ) ) ; +#30458 = CARTESIAN_POINT ( 'NONE', ( 22.31312662366504540, 116.2335386298891393, 182.3227435278615474 ) ) ; +#30459 = CARTESIAN_POINT ( 'NONE', ( -21.21399091018682981, 129.1232532189451376, 89.98933777676734280 ) ) ; +#30460 = CARTESIAN_POINT ( 'NONE', ( -37.17455842349777129, 80.91246596882704978, 284.1870184124936145 ) ) ; +#30461 = CALENDAR_DATE ( 2025, 24, 6 ) ; +#30462 = CARTESIAN_POINT ( 'NONE', ( 38.75341522189999921, 118.7918142041999943, 89.81188645496000333 ) ) ; +#30463 = CARTESIAN_POINT ( 'NONE', ( 30.05084665326030446, 185.2025551396338585, 102.9053044902910869 ) ) ; +#30464 = CARTESIAN_POINT ( 'NONE', ( 17.19707752705298276, 122.6006626263945947, 172.0864319364189612 ) ) ; +#30465 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825942860899101, 0.0005734119018572840726 ) ) ; +#30466 = CONICAL_SURFACE ( 'NONE', #25246, 5.999999999758601099, 0.7853981633778982507 ) ; +#30467 = LINE ( 'NONE', #9196, #9769 ) ; +#30468 = CARTESIAN_POINT ( 'NONE', ( 36.20192395120999862, 112.8316120500000039, 87.89471584367001356 ) ) ; +#30469 = EDGE_CURVE ( 'NONE', #32409, #16053, #10722, .T. ) ; +#30470 = AXIS2_PLACEMENT_3D ( 'NONE', #8954, #12017, #28168 ) ; +#30471 = CARTESIAN_POINT ( 'NONE', ( 13.46857904157075403, 158.4311794591165494, 96.39256747411997139 ) ) ; +#30472 = VECTOR ( 'NONE', #37137, 1000.000000000000114 ) ; +#30473 = ORIENTED_EDGE ( 'NONE', *, *, #32302, .T. ) ; +#30474 = EDGE_LOOP ( 'NONE', ( #17260, #37621, #3704, #30430 ) ) ; +#30475 = ORIENTED_EDGE ( 'NONE', *, *, #11330, .T. ) ; +#30476 = LINE ( 'NONE', #19872, #10798 ) ; +#30477 = ORIENTED_EDGE ( 'NONE', *, *, #32669, .T. ) ; +#30478 = CARTESIAN_POINT ( 'NONE', ( 20.46042542853685120, 126.8635651546206020, 91.53723576583463739 ) ) ; +#30479 = CIRCLE ( 'NONE', #2398, 2.499999999985527577 ) ; +#30480 = CARTESIAN_POINT ( 'NONE', ( 16.04422245830440374, 152.0461280324277311, 184.5382697652126467 ) ) ; +#30481 = FACE_OUTER_BOUND ( 'NONE', #32227, .T. ) ; +#30482 = CONICAL_SURFACE ( 'NONE', #33724, 3.499999999950266005, 0.7853981633778703841 ) ; +#30483 = EDGE_CURVE ( 'NONE', #30145, #40336, #23191, .T. ) ; +#30484 = EDGE_LOOP ( 'NONE', ( #31311, #15349, #14342, #3001 ) ) ; +#30485 = CARTESIAN_POINT ( 'NONE', ( 15.50029467836134778, 127.6324160061193567, 89.62297635127647766 ) ) ; +#30486 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323826000612104178, 0.0005734119005250372597 ) ) ; +#30487 = CARTESIAN_POINT ( 'NONE', ( -18.79252570011861678, 125.8499160133713133, 175.1155745579973484 ) ) ; +#30488 = ORIENTED_EDGE ( 'NONE', *, *, #29872, .F. ) ; +#30489 = FACE_OUTER_BOUND ( 'NONE', #2535, .T. ) ; +#30490 = LINE ( 'NONE', #6131, #27327 ) ; +#30491 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971557631 ) ) ; +#30492 = CARTESIAN_POINT ( 'NONE', ( -3.787588882752000341, 140.7274741751000136, 92.40128261844999713 ) ) ; +#30493 = CARTESIAN_POINT ( 'NONE', ( -3.336546828080732663, 186.7822604252457097, 102.7770212601688655 ) ) ; +#30494 = CARTESIAN_POINT ( 'NONE', ( -20.39708600605234068, 212.6012170711696001, 76.07084295526449580 ) ) ; +#30495 = ORIENTED_EDGE ( 'NONE', *, *, #26643, .T. ) ; +#30496 = ORIENTED_EDGE ( 'NONE', *, *, #16975, .T. ) ; +#30497 = EDGE_CURVE ( 'NONE', #12419, #29005, #13987, .T. ) ; +#30498 = CARTESIAN_POINT ( 'NONE', ( -26.18286805740000034, 188.6943569864000381, 103.8843509396999991 ) ) ; +#30499 = CARTESIAN_POINT ( 'NONE', ( 0.9447797691695138944, 189.0460019304039747, 103.7072988499540003 ) ) ; +#30500 = CARTESIAN_POINT ( 'NONE', ( -35.51435415167420473, 192.1311557781389467, 106.9413281154107551 ) ) ; +#30501 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27915, #40339, #12342, #24845 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30502 = CIRCLE ( 'NONE', #32438, 40.50000000001669065 ) ; +#30503 = ORIENTED_EDGE ( 'NONE', *, *, #33229, .F. ) ; +#30504 = CARTESIAN_POINT ( 'NONE', ( -3.536105410441011010, 136.6754134117661863, 94.28792821396773149 ) ) ; +#30505 = AXIS2_PLACEMENT_3D ( 'NONE', #17055, #14223, #23827 ) ; +#30506 = ORIENTED_EDGE ( 'NONE', *, *, #34450, .T. ) ; +#30507 = CIRCLE ( 'NONE', #33752, 2.000002475912143751 ) ; +#30508 = FACE_OUTER_BOUND ( 'NONE', #29052, .T. ) ; +#30509 = VECTOR ( 'NONE', #17214, 1000.000000000000227 ) ; +#30510 = EDGE_CURVE ( 'NONE', #1901, #20812, #33388, .T. ) ; +#30511 = ORIENTED_EDGE ( 'NONE', *, *, #11721, .F. ) ; +#30512 = ORIENTED_EDGE ( 'NONE', *, *, #31446, .F. ) ; +#30513 = CARTESIAN_POINT ( 'NONE', ( -36.55077431165999968, 191.6726824183000133, 104.1988125334000017 ) ) ; +#30514 = CARTESIAN_POINT ( 'NONE', ( -20.01880829891733171, 206.1769743876099312, 74.49881186909658481 ) ) ; +#30515 = CARTESIAN_POINT ( 'NONE', ( -37.19949496103398445, 191.0620094574575774, 106.3403951867547335 ) ) ; +#30516 = ORIENTED_EDGE ( 'NONE', *, *, #12280, .F. ) ; +#30517 = LINE ( 'NONE', #2502, #2330 ) ; +#30518 = ORIENTED_EDGE ( 'NONE', *, *, #16786, .T. ) ; +#30519 = CARTESIAN_POINT ( 'NONE', ( 25.76080190021000504, 121.9504149108000064, 90.35745116152999401 ) ) ; +#30520 = CARTESIAN_POINT ( 'NONE', ( -35.43806428669827824, 192.3002664666033468, 103.9163745585288297 ) ) ; +#30521 = EDGE_CURVE ( 'NONE', #37452, #27517, #29733, .T. ) ; +#30523 = CARTESIAN_POINT ( 'NONE', ( 37.59407280179000566, 112.0479120775361821, 151.0714151308390854 ) ) ; +#30522 = DIRECTION ( 'NONE', ( 0.0005884949927976746440, -0.2249510782047483837, 0.9743698815584175277 ) ) ; +#30524 = VERTEX_POINT ( 'NONE', #30134 ) ; +#30525 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38808, #30234, #36154, #20832 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30526 = VERTEX_POINT ( 'NONE', #27503 ) ; +#30527 = EDGE_CURVE ( 'NONE', #38835, #7316, #33381, .T. ) ; +#30528 = VECTOR ( 'NONE', #13755, 1000.000000000000227 ) ; +#30529 = VERTEX_POINT ( 'NONE', #40127 ) ; +#30530 = CARTESIAN_POINT ( 'NONE', ( 38.94172870169000333, 119.2287965852000013, 90.13226831520999838 ) ) ; +#30531 = CARTESIAN_POINT ( 'NONE', ( 19.98232544185748694, 209.7096131673859816, 76.04619115725449774 ) ) ; +#30532 = CARTESIAN_POINT ( 'NONE', ( 13.00137693451448584, 181.6895106735664172, 101.5913994261357942 ) ) ; +#30533 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971579558 ) ) ; +#30534 = CARTESIAN_POINT ( 'NONE', ( -25.49121842733731569, 191.8361208170296379, 104.4329317390898950 ) ) ; +#30535 = CARTESIAN_POINT ( 'NONE', ( 12.63887439035699956, 130.9170872642954748, 89.96071735129629587 ) ) ; +#30536 = CARTESIAN_POINT ( 'NONE', ( -38.98458235476000056, 201.0912482656999885, 26.89884147244999824 ) ) ; +#30537 = VERTEX_POINT ( 'NONE', #21553 ) ; +#30538 = EDGE_LOOP ( 'NONE', ( #34499, #4912, #10360, #36674, #12036, #11728, #14221, #32546, #11311, #20288, #37159, #3294, #33566, #26021 ) ) ; +#30539 = DIRECTION ( 'NONE', ( -0.000000000000000000, -1.000000000000000000, -0.000000000000000000 ) ) ; +#30540 = CARTESIAN_POINT ( 'NONE', ( 25.57814583233000505, 121.8237546048000013, 88.27603067743000054 ) ) ; +#30541 = ORIENTED_EDGE ( 'NONE', *, *, #24527, .T. ) ; +#30542 = CARTESIAN_POINT ( 'NONE', ( -25.49121842733731569, 191.8361208170296379, 104.4329317390898950 ) ) ; +#30543 = CARTESIAN_POINT ( 'NONE', ( 0.5641662327143323052, 188.3672386194435262, 106.2403187889907770 ) ) ; +#30544 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; +#30545 = PLANE ( 'NONE', #16666 ) ; +#30546 = DIRECTION ( 'NONE', ( -0.0005884949961254158299, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#30547 = CARTESIAN_POINT ( 'NONE', ( -31.91335489270172232, 174.4783875135883875, 100.4668596826281970 ) ) ; +#30548 = ORIENTED_EDGE ( 'NONE', *, *, #24197, .T. ) ; +#30549 = CYLINDRICAL_SURFACE ( 'NONE', #38844, 17.00000000000406430 ) ; +#30550 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23751, #18592, #12475, #40079 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.001042251736472776759, 0.001064276280997240517 ), + .UNSPECIFIED. ) ; +#30551 = VECTOR ( 'NONE', #19971, 1000.000000000000114 ) ; +#30552 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; +#30553 = EDGE_CURVE ( 'NONE', #2503, #39956, #35999, .T. ) ; +#30554 = ORIENTED_EDGE ( 'NONE', *, *, #33494, .F. ) ; +#30555 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14816, #9080, #31164, #21764 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 5.250277230495868265E-07, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30556 = FACE_OUTER_BOUND ( 'NONE', #595, .T. ) ; +#30557 = ORIENTED_EDGE ( 'NONE', *, *, #405, .T. ) ; +#30558 = ADVANCED_FACE ( 'NONE', ( #5792 ), #25586, .F. ) ; +#30559 = EDGE_CURVE ( 'NONE', #16409, #1699, #35835, .T. ) ; +#30560 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#30561 = EDGE_CURVE ( 'NONE', #27781, #1537, #18374, .T. ) ; +#30562 = VERTEX_POINT ( 'NONE', #2916 ) ; +#30563 = ORIENTED_EDGE ( 'NONE', *, *, #29398, .T. ) ; +#30564 = CARTESIAN_POINT ( 'NONE', ( 22.50176470575384613, 184.2926722047558030, 105.2655616184450196 ) ) ; +#30565 = EDGE_CURVE ( 'NONE', #1021, #13145, #5145, .T. ) ; +#30566 = ORIENTED_EDGE ( 'NONE', *, *, #17436, .T. ) ; +#30567 = CARTESIAN_POINT ( 'NONE', ( 2.608838527522000295, 209.5011064695000016, 75.68136822124000673 ) ) ; +#30568 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18917, #2796, #36949, #24694 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30569 = CARTESIAN_POINT ( 'NONE', ( -22.78251873534911098, 147.5076487179167657, 96.28726666134990353 ) ) ; +#30570 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#30571 = ORIENTED_EDGE ( 'NONE', *, *, #36322, .F. ) ; +#30572 = VERTEX_POINT ( 'NONE', #18246 ) ; +#30573 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319403346168 ) ) ; +#30574 = VERTEX_POINT ( 'NONE', #39516 ) ; +#30575 = ORIENTED_EDGE ( 'NONE', *, *, #22625, .T. ) ; +#30576 = DIRECTION ( 'NONE', ( 0.7075337269008549201, 8.710880586812428391E-15, 0.7066795775298635451 ) ) ; +#30577 = DIRECTION ( 'NONE', ( 0.0002393071182786160318, 0.2252352986010024705, -0.9743043687658494711 ) ) ; +#30578 = CYLINDRICAL_SURFACE ( 'NONE', #19963, 2.500000000000000888 ) ; +#30579 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#30580 = CARTESIAN_POINT ( 'NONE', ( 2.620676500973129208, 209.6192316634764268, 73.39025550097103689 ) ) ; +#30581 = ORIENTED_EDGE ( 'NONE', *, *, #1490, .T. ) ; +#30582 = EDGE_LOOP ( 'NONE', ( #14684, #5174, #23235, #35731 ) ) ; +#30583 = DIRECTION ( 'NONE', ( -2.168404344927432685E-16, -1.000000000000000000, 6.938893903767784591E-15 ) ) ; +#30584 = CARTESIAN_POINT ( 'NONE', ( -36.08623042272999726, 192.5000881635999974, 104.5331338456000054 ) ) ; +#30585 = VERTEX_POINT ( 'NONE', #11940 ) ; +#30586 = CARTESIAN_POINT ( 'NONE', ( -25.83472006383999897, 120.7707320335999981, 87.72146630243001653 ) ) ; +#30587 = ORIENTED_EDGE ( 'NONE', *, *, #24623, .T. ) ; +#30588 = ORIENTED_EDGE ( 'NONE', *, *, #307, .T. ) ; +#30589 = EDGE_CURVE ( 'NONE', #8704, #33884, #24628, .T. ) ; +#30590 = DIRECTION ( 'NONE', ( 0.0002393071182786170076, 0.2252352986010032476, -0.9743043687658492491 ) ) ; +#30591 = CARTESIAN_POINT ( 'NONE', ( -40.76671320591064784, 189.8685293510188501, 106.8201389809352690 ) ) ; +#30592 = VERTEX_POINT ( 'NONE', #27901 ) ; +#30593 = CARTESIAN_POINT ( 'NONE', ( 30.17614589098232258, 126.7625099796061932, 88.90012650384656467 ) ) ; +#30594 = CARTESIAN_POINT ( 'NONE', ( 39.53555642364394629, 119.7153706430301554, 90.34642614193101906 ) ) ; +#30595 = DIRECTION ( 'NONE', ( 0.7933533411653341805, -0.5930537057989598848, -0.1373964268091485141 ) ) ; +#30596 = FACE_OUTER_BOUND ( 'NONE', #3532, .T. ) ; +#30597 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4417, #38968, #32445, #1979 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30598 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989907490, -0.1373964268091706076 ) ) ; +#30599 = EDGE_CURVE ( 'NONE', #24414, #11920, #5583, .T. ) ; +#30600 = ORIENTED_EDGE ( 'NONE', *, *, #26306, .T. ) ; +#30601 = CARTESIAN_POINT ( 'NONE', ( -37.26053171017113641, 182.4107432069956474, 119.7485912024541506 ) ) ; +#30602 = ORIENTED_EDGE ( 'NONE', *, *, #8007, .F. ) ; +#30603 = VERTEX_POINT ( 'NONE', #8259 ) ; +#30604 = DIRECTION ( 'NONE', ( 1.026956297800417606E-13, 0.9743700557921590732, 0.2249510932971540700 ) ) ; +#30605 = LINE ( 'NONE', #3370, #17947 ) ; +#30606 = CARTESIAN_POINT ( 'NONE', ( 35.41497335244000055, 113.0343134727000205, 90.38372467985999492 ) ) ; +#30607 = ADVANCED_FACE ( 'NONE', ( #36461 ), #28811, .F. ) ; +#30608 = DIRECTION ( 'NONE', ( -0.7857167656192536320, 0.6185862421878159934, 0.0004745532380132037723 ) ) ; +#30609 = CARTESIAN_POINT ( 'NONE', ( 6.033127994686249274, 135.1723769864917415, 91.20211310550756423 ) ) ; +#30610 = ORIENTED_EDGE ( 'NONE', *, *, #4865, .T. ) ; +#30611 = EDGE_CURVE ( 'NONE', #1021, #10263, #17834, .T. ) ; +#30612 = AXIS2_PLACEMENT_3D ( 'NONE', #24974, #34521, #19002 ) ; +#30613 = AXIS2_PLACEMENT_3D ( 'NONE', #3083, #15558, #12482 ) ; +#30614 = CARTESIAN_POINT ( 'NONE', ( -6.038838517186622568, 135.1212689757913950, 91.12980290360583524 ) ) ; +#30615 = EDGE_CURVE ( 'NONE', #11261, #27866, #16801, .T. ) ; +#30616 = FACE_OUTER_BOUND ( 'NONE', #34391, .T. ) ; +#30617 = ORIENTED_EDGE ( 'NONE', *, *, #30599, .F. ) ; +#30618 = DIRECTION ( 'NONE', ( 0.0005884949961203373185, -0.2249510543439093846, 0.9743698870671255730 ) ) ; +#30619 = CARTESIAN_POINT ( 'NONE', ( 22.50071842841086678, 154.4094130781474803, 95.28756121982962668 ) ) ; +#30620 = CARTESIAN_POINT ( 'NONE', ( 26.00889011773534065, 191.8021148264478768, 103.9029935424293853 ) ) ; +#30621 = DIRECTION ( 'NONE', ( 1.561251128379117234E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#30622 = DIRECTION ( 'NONE', ( 0.0005884949961229807118, -0.2249510543439059429, 0.9743698870671263501 ) ) ; +#30623 = CARTESIAN_POINT ( 'NONE', ( -3.669581222385323027, 126.6894591277999922, 89.41685568642002124 ) ) ; +#30624 = ORIENTED_EDGE ( 'NONE', *, *, #1096, .T. ) ; +#30625 = VERTEX_POINT ( 'NONE', #31907 ) ; +#30626 = CARTESIAN_POINT ( 'NONE', ( 0.6795524081307224851, 188.9999999395514862, 105.7358963014655728 ) ) ; +#30627 = CARTESIAN_POINT ( 'NONE', ( 13.47345847663963880, 153.8080446478709575, 95.66732164731912746 ) ) ; +#30628 = ORIENTED_EDGE ( 'NONE', *, *, #12148, .F. ) ; +#30629 = CARTESIAN_POINT ( 'NONE', ( -23.36256910961311206, 135.1032017342878078, 91.11449304548321493 ) ) ; +#30630 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8097, #16681, #29978, #29181, #35671, #14243, #1152, #23045, #23437, #23643 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30631 = ORIENTED_EDGE ( 'NONE', *, *, #34371, .F. ) ; +#30632 = CARTESIAN_POINT ( 'NONE', ( -38.29920341924000127, 119.0013441654000133, 87.58334976871999800 ) ) ; +#30633 = AXIS2_PLACEMENT_3D ( 'NONE', #32050, #22643, #7274 ) ; +#30634 = CARTESIAN_POINT ( 'NONE', ( -3.677662715490698453, 143.5677092796093177, 95.73393933775022902 ) ) ; +#30635 = FACE_OUTER_BOUND ( 'NONE', #18097, .T. ) ; +#30636 = EDGE_LOOP ( 'NONE', ( #26699, #22893, #33636, #39075 ) ) ; +#30637 = CYLINDRICAL_SURFACE ( 'NONE', #30123, 9.999999999999996447 ) ; +#30638 = VECTOR ( 'NONE', #353, 1000.000000000000114 ) ; +#30639 = CARTESIAN_POINT ( 'NONE', ( 3.655486316165832417, 167.8522820322272082, 101.3586486882937692 ) ) ; +#30640 = CARTESIAN_POINT ( 'NONE', ( -25.61982903191000105, 190.9959539028000393, 106.4567112378999951 ) ) ; +#30641 = CARTESIAN_POINT ( 'NONE', ( -24.48834041483651447, 115.4756765368858566, 90.28257518319199448 ) ) ; +#30642 = CONICAL_SURFACE ( 'NONE', #584, 30.49999999999573319, 0.7853981633972993981 ) ; +#30643 = CARTESIAN_POINT ( 'NONE', ( -5.675054657474391639, 124.3656264979204167, 88.36836997283377571 ) ) ; +#30644 = ORIENTED_EDGE ( 'NONE', *, *, #16683, .F. ) ; +#30645 = CARTESIAN_POINT ( 'NONE', ( 2.563028759935935597, 191.4135359453850072, 104.3558246061316339 ) ) ; +#30646 = FACE_OUTER_BOUND ( 'NONE', #1265, .T. ) ; +#30647 = CARTESIAN_POINT ( 'NONE', ( 36.58205298002189920, 191.7114058399030512, 104.3498827429378935 ) ) ; +#30648 = ADVANCED_FACE ( 'NONE', ( #20003 ), #6938, .T. ) ; +#30649 = ADVANCED_FACE ( 'NONE', ( #29234 ), #10024, .T. ) ; +#30650 = CARTESIAN_POINT ( 'NONE', ( -17.26273596142550204, 152.7387145730194504, 181.5933280602652076 ) ) ; +#30651 = ORIENTED_EDGE ( 'NONE', *, *, #30320, .T. ) ; +#30652 = EDGE_CURVE ( 'NONE', #410, #24414, #19262, .T. ) ; +#30653 = EDGE_LOOP ( 'NONE', ( #29948, #7985, #22318, #7251 ) ) ; +#30654 = DIRECTION ( 'NONE', ( 0.4261581047166934644, -0.4480007095713214871, -0.7859291533006447228 ) ) ; +#30655 = CYLINDRICAL_SURFACE ( 'NONE', #23225, 2.250000000000011102 ) ; +#30656 = CARTESIAN_POINT ( 'NONE', ( 19.45332703025135146, 148.3679948532157482, 180.6096929009134158 ) ) ; +#30657 = CARTESIAN_POINT ( 'NONE', ( -36.05505683567000119, 191.5962994020999872, 104.0132945296000031 ) ) ; +#30658 = CARTESIAN_POINT ( 'NONE', ( -23.02059183176825741, 214.0904033191889084, 73.07235108223721909 ) ) ; +#30659 = EDGE_CURVE ( 'NONE', #9058, #4088, #25977, .T. ) ; +#30660 = CARTESIAN_POINT ( 'NONE', ( -25.98804079021204672, 209.7098732596503794, 73.09630377377690991 ) ) ; +#30661 = CARTESIAN_POINT ( 'NONE', ( 29.62444488996374403, 185.2955461510884732, 104.9796392865966652 ) ) ; +#30662 = EDGE_CURVE ( 'NONE', #28666, #18813, #37974, .T. ) ; +#30663 = VECTOR ( 'NONE', #32341, 1000.000000000000000 ) ; +#30664 = CARTESIAN_POINT ( 'NONE', ( 38.50589746725999873, 118.6516391838000004, 87.79297567035000327 ) ) ; +#30665 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; +#30666 = LINE ( 'NONE', #34109, #39603 ) ; +#30667 = DIRECTION ( 'NONE', ( -0.9999998268366268039, -0.0001323826607561396436, 0.0005734121968886058199 ) ) ; +#30668 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#30669 = AXIS2_PLACEMENT_3D ( 'NONE', #24878, #8522, #36931 ) ; +#30670 = CARTESIAN_POINT ( 'NONE', ( 25.49993254952412514, 120.4394916964541551, 88.98262338670512861 ) ) ; +#30671 = CARTESIAN_POINT ( 'NONE', ( 37.18383917477999745, 191.3394645145000084, 104.9785211344999993 ) ) ; +#30672 = AXIS2_PLACEMENT_3D ( 'NONE', #3329, #35193, #260 ) ; +#30673 = CARTESIAN_POINT ( 'NONE', ( 36.67096985404000264, 191.2363461959999995, 106.4436279980999984 ) ) ; +#30674 = ORIENTED_EDGE ( 'NONE', *, *, #28339, .T. ) ; +#30675 = ORIENTED_EDGE ( 'NONE', *, *, #30659, .T. ) ; +#30676 = ADVANCED_FACE ( 'NONE', ( #22505 ), #15958, .F. ) ; +#30677 = CARTESIAN_POINT ( 'NONE', ( -6.045835231059395021, 134.9182589738620095, 90.80491324842614631 ) ) ; +#30678 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34516, #2691, #3059, #15541, #40073, #28035 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30679 = ORIENTED_EDGE ( 'NONE', *, *, #25675, .F. ) ; +#30680 = CARTESIAN_POINT ( 'NONE', ( -23.36090843875937395, 177.5203768732290257, 100.8800585087934394 ) ) ; +#30681 = CARTESIAN_POINT ( 'NONE', ( -20.00006126831510400, 120.3902141372887087, 87.45929000627990035 ) ) ; +#30682 = VERTEX_POINT ( 'NONE', #38613 ) ; +#30683 = CARTESIAN_POINT ( 'NONE', ( -39.27942170210999961, 119.7579698461999982, 90.54247500236000690 ) ) ; +#30684 = PLANE ( 'NONE', #12664 ) ; +#30685 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#30686 = FACE_OUTER_BOUND ( 'NONE', #23522, .T. ) ; +#30687 = ORIENTED_EDGE ( 'NONE', *, *, #18705, .F. ) ; +#30688 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28496, #28691, #31563, #471 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30689 = CARTESIAN_POINT ( 'NONE', ( -43.21068176890801027, 118.0105506722982369, 104.8630716126889126 ) ) ; +#30690 = CARTESIAN_POINT ( 'NONE', ( 23.36441916942174402, 176.9663247858313753, 103.3637569773408842 ) ) ; +#30691 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #28264, #6966 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30692 = DIRECTION ( 'NONE', ( -0.0005884965853139737055, 0.2249510543436361309, -0.9743698870662287348 ) ) ; +#30693 = CARTESIAN_POINT ( 'NONE', ( -3.470756533003450439, 187.1137718651480668, 102.8536377798947967 ) ) ; +#30694 = CARTESIAN_POINT ( 'NONE', ( 43.18716009838831127, 118.0176470502005941, 104.8323746835856838 ) ) ; +#30695 = VERTEX_POINT ( 'NONE', #7335 ) ; +#30696 = VERTEX_POINT ( 'NONE', #19794 ) ; +#30697 = VECTOR ( 'NONE', #9567, 1000.000000000000114 ) ; +#30698 = CARTESIAN_POINT ( 'NONE', ( -25.62560591737999971, 191.4791926512000089, 104.2632692198000086 ) ) ; +#30699 = AXIS2_PLACEMENT_3D ( 'NONE', #31179, #21981, #24860 ) ; +#30700 = CARTESIAN_POINT ( 'NONE', ( 2.027256735944490629, 189.6370327888450049, 103.8799177752640190 ) ) ; +#30701 = CARTESIAN_POINT ( 'NONE', ( -22.49962777877401265, 154.4034663070004285, 95.31336199324331915 ) ) ; +#30702 = CONICAL_SURFACE ( 'NONE', #16937, 2.502997798619384540, 0.7853981633682427521 ) ; +#30703 = EDGE_CURVE ( 'NONE', #12815, #5743, #20724, .T. ) ; +#30704 = ORIENTED_EDGE ( 'NONE', *, *, #39073, .T. ) ; +#30705 = CARTESIAN_POINT ( 'NONE', ( 35.56237297027564637, 191.9759150222000130, 101.8999685582079593 ) ) ; +#30706 = ADVANCED_FACE ( 'NONE', ( #26178 ), #15778, .T. ) ; +#30707 = ORIENTED_EDGE ( 'NONE', *, *, #3997, .F. ) ; +#30708 = AXIS2_PLACEMENT_3D ( 'NONE', #36783, #13598, #31613 ) ; +#30709 = CARTESIAN_POINT ( 'NONE', ( -43.57149722038838036, 121.9974985178074434, 87.84418581487720701 ) ) ; +#30710 = PLANE ( 'NONE', #26231 ) ; +#30711 = CARTESIAN_POINT ( 'NONE', ( -37.60461463224000056, 190.9112647455999934, 106.5131070789000063 ) ) ; +#30712 = DIRECTION ( 'NONE', ( -0.6087614810001780175, 0.7729390313185915407, 0.1788147452386051883 ) ) ; +#30713 = DIRECTION ( 'NONE', ( 0.7075227810178097432, -0.1590644159616022568, 0.6885564798298096090 ) ) ; +#30714 = ORIENTED_EDGE ( 'NONE', *, *, #6994, .T. ) ; +#30715 = CARTESIAN_POINT ( 'NONE', ( 46.08149850379091106, 185.2364904696372037, 105.4692177053970852 ) ) ; +#30716 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386905326 ) ) ; +#30717 = CARTESIAN_POINT ( 'NONE', ( -25.66663111670890984, 118.8155669158736174, 89.94995278256749316 ) ) ; +#30718 = ORIENTED_EDGE ( 'NONE', *, *, #19856, .T. ) ; +#30719 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#30720 = DIRECTION ( 'NONE', ( -0.0002393071182785116774, -0.2252352986010041080, 0.9743043687658491381 ) ) ; +#30722 = CARTESIAN_POINT ( 'NONE', ( -6.045835231059395021, 134.9182589738620095, 90.80491324842614631 ) ) ; +#30721 = CARTESIAN_POINT ( 'NONE', ( 39.05501141494404038, 128.0727085485270038, 89.71040052552025656 ) ) ; +#30723 = CIRCLE ( 'NONE', #39186, 10.00000000000000533 ) ; +#30724 = EDGE_CURVE ( 'NONE', #2177, #30359, #39018, .T. ) ; +#30725 = ORIENTED_EDGE ( 'NONE', *, *, #20856, .T. ) ; +#30726 = VECTOR ( 'NONE', #14270, 1000.000000000000114 ) ; +#30727 = CARTESIAN_POINT ( 'NONE', ( 20.17891932135707833, 117.0898005074367063, 87.25559673040211806 ) ) ; +#30728 = AXIS2_PLACEMENT_3D ( 'NONE', #30951, #27507, #30136 ) ; +#30729 = VERTEX_POINT ( 'NONE', #33489 ) ; +#30730 = CARTESIAN_POINT ( 'NONE', ( -30.18611280629168903, 127.2214839853137107, 89.38464791844357649 ) ) ; +#30731 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; +#30732 = CARTESIAN_POINT ( 'NONE', ( 30.83664601630805180, 129.3587224879779853, 89.49911075836023144 ) ) ; +#30733 = CYLINDRICAL_SURFACE ( 'NONE', #30081, 4.999999999999990230 ) ; +#30734 = DIRECTION ( 'NONE', ( -0.0005884949961248538879, 0.2249510543439045551, -0.9743698870671267942 ) ) ; +#30735 = ORIENTED_EDGE ( 'NONE', *, *, #25634, .F. ) ; +#30736 = VERTEX_POINT ( 'NONE', #14296 ) ; +#30737 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391919761 ) ) ; +#30738 = DIRECTION ( 'NONE', ( -0.0005884949952376201335, 0.2255194585879184699, -0.9742384859323988122 ) ) ; +#30739 = ORIENTED_EDGE ( 'NONE', *, *, #32360, .F. ) ; +#30740 = CARTESIAN_POINT ( 'NONE', ( -35.93599395966710119, 191.2079282146110302, 106.8919311732110060 ) ) ; +#30741 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12979, #10113, #32190, #25462, #3753, #22788, #26058, #34812, #25256, #22188 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999501510, 0.3749999999999252265, 0.4374999999999437117, 0.4999999999999622524, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30742 = FACE_OUTER_BOUND ( 'NONE', #39930, .T. ) ; +#30743 = EDGE_CURVE ( 'NONE', #32426, #9253, #36380, .T. ) ; +#30744 = CARTESIAN_POINT ( 'NONE', ( 0.5638623032898999465, 189.0000161160999994, 105.7369849321000004 ) ) ; +#30745 = EDGE_CURVE ( 'NONE', #13713, #17189, #116, .T. ) ; +#30746 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971550969 ) ) ; +#30747 = CONICAL_SURFACE ( 'NONE', #24867, 2.499995733429277056, 0.7853981633661824002 ) ; +#30748 = VECTOR ( 'NONE', #10520, 1000.000000000000227 ) ; +#30749 = CARTESIAN_POINT ( 'NONE', ( 3.045988519791387628, 209.1419319775010877, 76.13893608185537687 ) ) ; +#30750 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -5.046468293990521964E-15, -0.0006039748319388752807 ) ) ; +#30751 = CARTESIAN_POINT ( 'NONE', ( 3.927688557146990167, 146.4071203614214767, 93.45129659090066809 ) ) ; +#30752 = VECTOR ( 'NONE', #22124, 1000.000000000000000 ) ; +#30753 = VERTEX_POINT ( 'NONE', #13888 ) ; +#30754 = CARTESIAN_POINT ( 'NONE', ( 25.99034337665942118, 208.7353210334150617, 73.11451777455893364 ) ) ; +#30755 = AXIS2_PLACEMENT_3D ( 'NONE', #1750, #20751, #33207 ) ; +#30756 = CYLINDRICAL_SURFACE ( 'NONE', #17977, 9.000000000000003553 ) ; +#30757 = DIRECTION ( 'NONE', ( 0.0001408410614214824043, -0.2255194958243955106, 0.9742386448745018468 ) ) ; +#30758 = ORIENTED_EDGE ( 'NONE', *, *, #2644, .T. ) ; +#30759 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; +#30760 = EDGE_LOOP ( 'NONE', ( #7428, #25086, #11822, #17783 ) ) ; +#30762 = CARTESIAN_POINT ( 'NONE', ( -16.42286345479342913, 121.5140989012041359, 177.3183312225191059 ) ) ; +#30761 = CARTESIAN_POINT ( 'NONE', ( -15.49852919254797179, 185.3436308334966895, 105.0179936564814511 ) ) ; +#30763 = ORIENTED_EDGE ( 'NONE', *, *, #27586, .F. ) ; +#30764 = ORIENTED_EDGE ( 'NONE', *, *, #14918, .F. ) ; +#30765 = ORIENTED_EDGE ( 'NONE', *, *, #24793, .T. ) ; +#30766 = CARTESIAN_POINT ( 'NONE', ( 2.581782723837000137, 209.5968814416000328, 75.67889051560000269 ) ) ; +#30767 = CARTESIAN_POINT ( 'NONE', ( 3.417962904437000127, 127.0758678244000066, 91.81096914418000665 ) ) ; +#30768 = DIRECTION ( 'NONE', ( 0.6087611434178765712, 0.7731004625452565504, 0.1781166614241066204 ) ) ; +#30769 = CARTESIAN_POINT ( 'NONE', ( 12.64110264230791181, 177.6556643415725318, 100.7778556750161982 ) ) ; +#30770 = VERTEX_POINT ( 'NONE', #39224 ) ; +#30771 = AXIS2_PLACEMENT_3D ( 'NONE', #26165, #29616, #4666 ) ; +#30772 = ORIENTED_EDGE ( 'NONE', *, *, #11161, .T. ) ; +#30773 = EDGE_LOOP ( 'NONE', ( #38547, #25833, #16870, #36879 ) ) ; +#30774 = VERTEX_POINT ( 'NONE', #23702 ) ; +#30776 = VECTOR ( 'NONE', #39313, 1000.000000000000227 ) ; +#30775 = DIRECTION ( 'NONE', ( -0.0005884949961208581692, 0.2249510543439069699, -0.9743698870671261281 ) ) ; +#30777 = AXIS2_PLACEMENT_3D ( 'NONE', #25699, #38149, #10148 ) ; +#30778 = PLANE ( 'NONE', #19990 ) ; +#30779 = CARTESIAN_POINT ( 'NONE', ( -16.53681909317384324, 122.5194902194745055, 174.6067105814985609 ) ) ; +#30780 = EDGE_LOOP ( 'NONE', ( #11579, #14336, #28239, #13761 ) ) ; +#30781 = ORIENTED_EDGE ( 'NONE', *, *, #36774, .F. ) ; +#30782 = AXIS2_PLACEMENT_3D ( 'NONE', #36745, #27174, #17519 ) ; +#30783 = VERTEX_POINT ( 'NONE', #20204 ) ; +#30784 = CARTESIAN_POINT ( 'NONE', ( -5.673458782793131761, 123.7518939737303327, 91.25343359375852970 ) ) ; +#30785 = AXIS2_PLACEMENT_3D ( 'NONE', #15534, #388, #19181 ) ; +#30786 = CARTESIAN_POINT ( 'NONE', ( 20.48123591540864652, 210.6297143866032400, 75.54543465911078215 ) ) ; +#30787 = CARTESIAN_POINT ( 'NONE', ( -28.12721690162999977, 125.1825297727000077, 88.74162087477000682 ) ) ; +#30788 = EDGE_CURVE ( 'NONE', #39273, #10263, #36371, .T. ) ; +#30789 = EDGE_LOOP ( 'NONE', ( #13911, #32087, #29793, #15681 ) ) ; +#30790 = DIRECTION ( 'NONE', ( -0.0008702530711002103318, 0.2253087760482092305, -0.9742870203873447155 ) ) ; +#30791 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9334763082618803276, -0.3586390691402302489 ) ) ; +#30792 = ORIENTED_EDGE ( 'NONE', *, *, #8601, .F. ) ; +#30793 = EDGE_CURVE ( 'NONE', #14254, #25874, #18748, .T. ) ; +#30794 = CARTESIAN_POINT ( 'NONE', ( -77.87588430178237786, 193.2350846156091109, 190.4447722601752844 ) ) ; +#30795 = EDGE_CURVE ( 'NONE', #34342, #33812, #26253, .T. ) ; +#30796 = DIRECTION ( 'NONE', ( 0.0005884949961222661141, -0.2249510543439069699, 0.9743698870671262391 ) ) ; +#30797 = EDGE_CURVE ( 'NONE', #33368, #27481, #30525, .T. ) ; +#30798 = ADVANCED_FACE ( 'NONE', ( #7740 ), #2089, .F. ) ; +#30799 = CARTESIAN_POINT ( 'NONE', ( -39.59665107658459959, 119.3565288389648629, 89.79823649497362226 ) ) ; +#30800 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178536755269E-05, 0.0002331579774905574406 ) ) ; +#30801 = ORIENTED_EDGE ( 'NONE', *, *, #27962, .T. ) ; +#30802 = CARTESIAN_POINT ( 'NONE', ( -32.37402305108282263, 174.4007230276914697, 99.93605550448263841 ) ) ; +#30803 = VERTEX_POINT ( 'NONE', #35728 ) ; +#30804 = ORIENTED_EDGE ( 'NONE', *, *, #22812, .F. ) ; +#30805 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#30806 = VECTOR ( 'NONE', #12130, 1000.000000000000114 ) ; +#30807 = DIRECTION ( 'NONE', ( -0.7075337269147008445, -1.085056246983001043E-14, -0.7066795775160008564 ) ) ; +#30808 = CARTESIAN_POINT ( 'NONE', ( 35.93394892565999754, 112.3993893374999971, 89.86828732537999542 ) ) ; +#30809 = VECTOR ( 'NONE', #6831, 1000.000000000000000 ) ; +#30810 = AXIS2_PLACEMENT_3D ( 'NONE', #6058, #2977, #40390 ) ; +#30811 = FACE_OUTER_BOUND ( 'NONE', #2354, .T. ) ; +#30812 = ORIENTED_EDGE ( 'NONE', *, *, #38352, .T. ) ; +#30813 = DIRECTION ( 'NONE', ( -1.786199550476174780E-15, 0.9743043966640313469, 0.2252353050503801690 ) ) ; +#30814 = FACE_OUTER_BOUND ( 'NONE', #17379, .T. ) ; +#30815 = VERTEX_POINT ( 'NONE', #32695 ) ; +#30816 = DIRECTION ( 'NONE', ( -0.0004161288024553938926, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#30817 = CARTESIAN_POINT ( 'NONE', ( 26.03373140117899709, 191.5260202047026041, 103.8544635878054976 ) ) ; +#30818 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749907037, 179.6299767372991312, 101.6260513917314796 ) ) ; +#30819 = LINE ( 'NONE', #11609, #34435 ) ; +#30820 = CARTESIAN_POINT ( 'NONE', ( 26.03550245107076933, 190.8511564191358900, 106.7775725292634945 ) ) ; +#30821 = ORIENTED_EDGE ( 'NONE', *, *, #34688, .T. ) ; +#30822 = LINE ( 'NONE', #24910, #4744 ) ; +#30823 = FACE_OUTER_BOUND ( 'NONE', #8175, .T. ) ; +#30824 = ADVANCED_FACE ( 'NONE', ( #39419 ), #4676, .F. ) ; +#30825 = ORIENTED_EDGE ( 'NONE', *, *, #20380, .F. ) ; +#30826 = LINE ( 'NONE', #37551, #10911 ) ; +#30827 = CARTESIAN_POINT ( 'NONE', ( -34.95638760652211374, 220.4002260770999726, 73.57961695561236581 ) ) ; +#30828 = AXIS2_PLACEMENT_3D ( 'NONE', #7941, #39011, #20615 ) ; +#30829 = ORIENTED_EDGE ( 'NONE', *, *, #35590, .F. ) ; +#30830 = DIRECTION ( 'NONE', ( -0.0005884949961233868539, 0.2249510543439054988, -0.9743698870671265722 ) ) ; +#30831 = AXIS2_PLACEMENT_3D ( 'NONE', #14711, #11640, #24114 ) ; +#30832 = EDGE_CURVE ( 'NONE', #32868, #35062, #14100, .T. ) ; +#30833 = AXIS2_PLACEMENT_3D ( 'NONE', #1319, #22222, #13407 ) ; +#30834 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#30835 = ORIENTED_EDGE ( 'NONE', *, *, #4582, .T. ) ; +#30836 = CYLINDRICAL_SURFACE ( 'NONE', #24923, 9.000000000000003553 ) ; +#30837 = EDGE_CURVE ( 'NONE', #6247, #3459, #781, .T. ) ; +#30838 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15116, #1163, #15893, #28588 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30839 = DIRECTION ( 'NONE', ( 0.0005884949961259158639, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#30840 = CARTESIAN_POINT ( 'NONE', ( -25.60907744188000379, 191.2754202488000033, 106.5082922742000022 ) ) ; +#30841 = CARTESIAN_POINT ( 'NONE', ( 25.49921952841093642, 118.5814822561333415, 87.75235346248901180 ) ) ; +#30842 = EDGE_CURVE ( 'NONE', #23779, #5998, #21248, .T. ) ; +#30843 = CARTESIAN_POINT ( 'NONE', ( -5.670781729043352648, 124.5528706720611183, 88.66790470360065513 ) ) ; +#30844 = ORIENTED_EDGE ( 'NONE', *, *, #18656, .F. ) ; +#30845 = ADVANCED_FACE ( 'NONE', ( #27996 ), #9175, .T. ) ; +#30846 = VERTEX_POINT ( 'NONE', #40430 ) ; +#30847 = CARTESIAN_POINT ( 'NONE', ( 15.12415969602515986, 146.0659008074709106, 180.8278994957862551 ) ) ; +#30848 = DIRECTION ( 'NONE', ( 0.7069870866307323976, -0.6508451585901298131, -0.2767125564140127114 ) ) ; +#30849 = CARTESIAN_POINT ( 'NONE', ( 22.49960432933178822, 158.3069096095373993, 96.18736459073451783 ) ) ; +#30850 = DIRECTION ( 'NONE', ( -0.6087611434179104331, -0.7731004625452351231, -0.1781166614240846935 ) ) ; +#30851 = ORIENTED_EDGE ( 'NONE', *, *, #34137, .T. ) ; +#30852 = ORIENTED_EDGE ( 'NONE', *, *, #858, .F. ) ; +#30853 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#30854 = DIRECTION ( 'NONE', ( -0.0006039748319386906410, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#30855 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#30856 = PLANE ( 'NONE', #4111 ) ; +#30857 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971565125 ) ) ; +#30858 = VECTOR ( 'NONE', #11614, 1000.000000000000114 ) ; +#30859 = AXIS2_PLACEMENT_3D ( 'NONE', #25884, #6632, #16243 ) ; +#30860 = CARTESIAN_POINT ( 'NONE', ( -5.668107805537519361, 123.6871559675325898, 91.29388376821638929 ) ) ; +#30861 = CIRCLE ( 'NONE', #7994, 2.000000000000011546 ) ; +#30862 = CARTESIAN_POINT ( 'NONE', ( -3.418257151934999793, 184.3972769734000394, 105.0487905064999978 ) ) ; +#30863 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; +#30864 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2252353050503803633, 0.9743043966640312359 ) ) ; +#30865 = DIRECTION ( 'NONE', ( 0.7066795774896457161, -3.556111233149506773E-18, -0.7075337269410242325 ) ) ; +#30866 = CYLINDRICAL_SURFACE ( 'NONE', #17851, 6.000000000000001776 ) ; +#30867 = LINE ( 'NONE', #31257, #12691 ) ; +#30868 = CARTESIAN_POINT ( 'NONE', ( -41.93243227727202793, 132.0857236358559135, 291.5838700735885709 ) ) ; +#30869 = CARTESIAN_POINT ( 'NONE', ( 37.96500113043519775, 190.9605824516280279, 106.2964067674099908 ) ) ; +#30870 = ORIENTED_EDGE ( 'NONE', *, *, #17436, .F. ) ; +#30871 = CARTESIAN_POINT ( 'NONE', ( 36.24487234395000002, 190.8173657113999866, 106.9127831590000000 ) ) ; +#30872 = ORIENTED_EDGE ( 'NONE', *, *, #25259, .T. ) ; +#30873 = VERTEX_POINT ( 'NONE', #5894 ) ; +#30874 = ORIENTED_EDGE ( 'NONE', *, *, #32216, .F. ) ; +#30875 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; +#30876 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5883, #17931, #18336, #14893 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.002841761714416722335 ), + .UNSPECIFIED. ) ; +#30877 = DIRECTION ( 'NONE', ( 9.113420628105814676E-11, 0.9743700558127087463, 0.2249510932081433268 ) ) ; +#30878 = EDGE_CURVE ( 'NONE', #23019, #39678, #33902, .T. ) ; +#30879 = EDGE_CURVE ( 'NONE', #982, #3120, #13203, .T. ) ; +#30880 = CARTESIAN_POINT ( 'NONE', ( -40.95578253733000196, 217.7719116638000401, 74.58324062236999907 ) ) ; +#30881 = EDGE_CURVE ( 'NONE', #11228, #24036, #28218, .T. ) ; +#30882 = EDGE_CURVE ( 'NONE', #31599, #16953, #27407, .T. ) ; +#30883 = ORIENTED_EDGE ( 'NONE', *, *, #25340, .T. ) ; +#30884 = DIRECTION ( 'NONE', ( 0.9999998184837881610, 0.000000000000000000, -0.0006025216930823954712 ) ) ; +#30885 = LINE ( 'NONE', #18773, #14280 ) ; +#30886 = CARTESIAN_POINT ( 'NONE', ( 47.33272938907029470, 69.51964883234494152, 321.8667867251971302 ) ) ; +#30887 = AXIS2_PLACEMENT_3D ( 'NONE', #4388, #35648, #7661 ) ; +#30888 = ORIENTED_EDGE ( 'NONE', *, *, #18944, .T. ) ; +#30889 = EDGE_CURVE ( 'NONE', #9009, #6112, #18404, .T. ) ; +#30890 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; +#30891 = CARTESIAN_POINT ( 'NONE', ( -45.39773774286052088, 124.2994142384970218, 88.45363130071420699 ) ) ; +#30892 = DIRECTION ( 'NONE', ( 0.7075229215369458480, 9.360719862056602573E-05, 0.7066903895890456200 ) ) ; +#30893 = AXIS2_PLACEMENT_3D ( 'NONE', #21979, #21585, #21166 ) ; +#30894 = LINE ( 'NONE', #22294, #11099 ) ; +#30895 = CARTESIAN_POINT ( 'NONE', ( -23.01879311717446086, 214.0903458147471383, 76.07243274013872281 ) ) ; +#30896 = ADVANCED_FACE ( 'NONE', ( #8777 ), #24523, .T. ) ; +#30897 = ORIENTED_EDGE ( 'NONE', *, *, #18798, .T. ) ; +#30898 = CARTESIAN_POINT ( 'NONE', ( -28.40995515711000152, 186.9781618348000052, 103.2258058761999990 ) ) ; +#30899 = CONICAL_SURFACE ( 'NONE', #13287, 2.499999999755544877, 0.7853981633651736516 ) ; +#30900 = CARTESIAN_POINT ( 'NONE', ( 2.840598881635000073, 190.4675684574999934, 103.7878333129000055 ) ) ; +#30901 = CARTESIAN_POINT ( 'NONE', ( 3.047144816660192657, 209.7096538831000032, 78.05666459524968559 ) ) ; +#30902 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27573, #39999, #8950, #9342 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999909300445012361 ), + .UNSPECIFIED. ) ; +#30903 = VERTEX_POINT ( 'NONE', #27794 ) ; +#30904 = LINE ( 'NONE', #2876, #20519 ) ; +#30905 = EDGE_LOOP ( 'NONE', ( #32148, #33966, #40080, #38252 ) ) ; +#30906 = EDGE_CURVE ( 'NONE', #15817, #8959, #26531, .T. ) ; +#30907 = LINE ( 'NONE', #28439, #7340 ) ; +#30908 = CARTESIAN_POINT ( 'NONE', ( -37.93624021805000268, 191.4653865237999923, 104.1593327167000069 ) ) ; +#30909 = LINE ( 'NONE', #18208, #33240 ) ; +#30910 = CARTESIAN_POINT ( 'NONE', ( 20.50153854971994960, 118.8155953598612484, 89.75541792533370256 ) ) ; +#30911 = ORIENTED_EDGE ( 'NONE', *, *, #123, .T. ) ; +#30912 = CARTESIAN_POINT ( 'NONE', ( -20.89111388057672158, 175.7038788979348283, 103.3088927995675590 ) ) ; +#30913 = CARTESIAN_POINT ( 'NONE', ( -1.216627282320019932, 189.1585234522316341, 105.7841143928696823 ) ) ; +#30914 = CIRCLE ( 'NONE', #36109, 8.000000000000007105 ) ; +#30915 = EDGE_LOOP ( 'NONE', ( #20717, #21634, #16242, #28801, #11711, #27220, #15293, #5144 ) ) ; +#30916 = CARTESIAN_POINT ( 'NONE', ( 28.52919418227002879, 125.2871234584923883, 88.56050369811191558 ) ) ; +#30917 = CARTESIAN_POINT ( 'NONE', ( 37.63914288645734274, 212.5463740004862245, 75.70243813626552765 ) ) ; +#30918 = CARTESIAN_POINT ( 'NONE', ( -15.74838202838000178, 184.8155507445000012, 105.1528037194999996 ) ) ; +#30919 = VECTOR ( 'NONE', #27273, 1000.000000000000000 ) ; +#30921 = CARTESIAN_POINT ( 'NONE', ( 16.22118037345659403, 122.3444927893303174, 173.3954680681185039 ) ) ; +#30920 = CARTESIAN_POINT ( 'NONE', ( 28.46561152642233949, 127.9145563745610872, 92.24604368512542862 ) ) ; +#30922 = VECTOR ( 'NONE', #23960, 999.9999999999998863 ) ; +#30923 = VERTEX_POINT ( 'NONE', #37182 ) ; +#30924 = EDGE_CURVE ( 'NONE', #31880, #14883, #20201, .T. ) ; +#30925 = CARTESIAN_POINT ( 'NONE', ( -13.49852954173680430, 160.1760870560666774, 99.20639934581299713 ) ) ; +#30926 = EDGE_CURVE ( 'NONE', #6128, #8723, #27053, .T. ) ; +#30927 = ADVANCED_FACE ( 'NONE', ( #15693 ), #34189, .F. ) ; +#30928 = ORIENTED_EDGE ( 'NONE', *, *, #32607, .T. ) ; +#30929 = CARTESIAN_POINT ( 'NONE', ( -26.07387125551695561, 121.1687737160897740, 90.72159716644539174 ) ) ; +#30930 = CARTESIAN_POINT ( 'NONE', ( 14.02725226625147847, 182.0693359945237546, 101.6784694239287319 ) ) ; +#30931 = CARTESIAN_POINT ( 'NONE', ( 36.04442091094806244, 218.5902260770999987, 73.53673424655958968 ) ) ; +#30932 = CARTESIAN_POINT ( 'NONE', ( 29.52631484424119890, 130.7952929006900717, 89.83156063865355634 ) ) ; +#30933 = CARTESIAN_POINT ( 'NONE', ( -34.95668960139003900, 225.9002260769516965, 73.07961704682827531 ) ) ; +#30934 = VERTEX_POINT ( 'NONE', #32061 ) ; +#30935 = ORIENTED_EDGE ( 'NONE', *, *, #15898, .T. ) ; +#30936 = PLANE ( 'NONE', #26615 ) ; +#30937 = FACE_OUTER_BOUND ( 'NONE', #24912, .T. ) ; +#30938 = DIRECTION ( 'NONE', ( 0.1305262373691798983, -0.9659583596717404852, -0.2233547598295697878 ) ) ; +#30939 = EDGE_CURVE ( 'NONE', #2592, #8692, #25600, .T. ) ; +#30940 = EDGE_LOOP ( 'NONE', ( #39305, #15275 ) ) ; +#30941 = CARTESIAN_POINT ( 'NONE', ( 15.53173119598054264, 162.3883494940283185, 152.4706590695620605 ) ) ; +#30942 = AXIS2_PLACEMENT_3D ( 'NONE', #3316, #6986, #25627 ) ; +#30943 = VECTOR ( 'NONE', #11654, 1000.000000000000000 ) ; +#30944 = LINE ( 'NONE', #2914, #29287 ) ; +#30945 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #14363, #38879 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30946 = VECTOR ( 'NONE', #11061, 1000.000000000000114 ) ; +#30947 = CARTESIAN_POINT ( 'NONE', ( 2.880315910408000057, 190.5847237225000299, 106.5537292353999987 ) ) ; +#30948 = CARTESIAN_POINT ( 'NONE', ( -94.40216589637994105, 221.9412051121879301, 195.0241205818432491 ) ) ; +#30949 = ADVANCED_FACE ( 'NONE', ( #31450 ), #23647, .F. ) ; +#30950 = DIRECTION ( 'NONE', ( 0.0005884949961241158715, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#30951 = CARTESIAN_POINT ( 'NONE', ( 23.36337295639098244, 183.5654497021793645, 104.5839965068618227 ) ) ; +#30952 = CARTESIAN_POINT ( 'NONE', ( -20.89285664280696864, 129.6089482465050366, 89.58812326051432251 ) ) ; +#30953 = ORIENTED_EDGE ( 'NONE', *, *, #14592, .F. ) ; +#30954 = CARTESIAN_POINT ( 'NONE', ( 25.99887565026168090, 119.3449815503509228, 87.25209341632874782 ) ) ; +#30955 = CARTESIAN_POINT ( 'NONE', ( 21.70190315701263017, 123.1837599801819465, 176.5257127422096914 ) ) ; +#30956 = LINE ( 'NONE', #27908, #3211 ) ; +#30957 = ORIENTED_EDGE ( 'NONE', *, *, #15816, .T. ) ; +#30958 = CARTESIAN_POINT ( 'NONE', ( -5.662686464640452222, 188.3429660633563287, 103.1387990589197869 ) ) ; +#30959 = ORIENTED_EDGE ( 'NONE', *, *, #24156, .T. ) ; +#30961 = CARTESIAN_POINT ( 'NONE', ( 35.58101881484880380, 192.1430711721313855, 103.8930328919773274 ) ) ; +#30960 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566790 ) ) ; +#30962 = ORIENTED_EDGE ( 'NONE', *, *, #22432, .F. ) ; +#30963 = ORIENTED_EDGE ( 'NONE', *, *, #11825, .T. ) ; +#30964 = AXIS2_PLACEMENT_3D ( 'NONE', #4061, #16532, #1006 ) ; +#30965 = CONICAL_SURFACE ( 'NONE', #6777, 5.999999999929134908, 0.7853981633778842619 ) ; +#30966 = ORIENTED_EDGE ( 'NONE', *, *, #7321, .T. ) ; +#30967 = CARTESIAN_POINT ( 'NONE', ( -23.36160748208693150, 137.2394037007878183, 91.86439624240760793 ) ) ; +#30968 = CARTESIAN_POINT ( 'NONE', ( -45.03708708209951084, 124.0713768683079081, 93.45577792510331960 ) ) ; +#30969 = CARTESIAN_POINT ( 'NONE', ( -12.63793204807000770, 135.2920832175974510, 91.40834497109533174 ) ) ; +#30970 = EDGE_CURVE ( 'NONE', #37138, #13070, #6513, .T. ) ; +#30971 = EDGE_LOOP ( 'NONE', ( #26971, #28322, #35481, #23253 ) ) ; +#30973 = ADVANCED_FACE ( 'NONE', ( #3415 ), #34704, .F. ) ; +#30972 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6790, #19060, #31557, #19257 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#30974 = EDGE_LOOP ( 'NONE', ( #15329, #9458, #4952, #111 ) ) ; +#30975 = ORIENTED_EDGE ( 'NONE', *, *, #20468, .F. ) ; +#30976 = DIRECTION ( 'NONE', ( 0.0005884949961216158097, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#30977 = CARTESIAN_POINT ( 'NONE', ( 4.035087735728000169, 174.6768175980000137, 101.5172632219999969 ) ) ; +#30978 = DIRECTION ( 'NONE', ( 0.0005884956407902205500, -0.2249510534665960237, 0.9743698872692800883 ) ) ; +#30979 = DIRECTION ( 'NONE', ( -0.0005884949961224158425, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#30980 = FACE_OUTER_BOUND ( 'NONE', #217, .T. ) ; +#30981 = ORIENTED_EDGE ( 'NONE', *, *, #19991, .T. ) ; +#30982 = VERTEX_POINT ( 'NONE', #10586 ) ; +#30983 = FACE_OUTER_BOUND ( 'NONE', #2130, .T. ) ; +#30984 = DIRECTION ( 'NONE', ( -0.1305262453914154686, 0.9659761156053645603, 0.2232779508683992165 ) ) ; +#30985 = CARTESIAN_POINT ( 'NONE', ( 39.74198101999568422, 169.1998828075846575, 164.4809833079056887 ) ) ; +#30986 = CARTESIAN_POINT ( 'NONE', ( -26.66109084696000053, 123.9341801008000061, 88.62365338252001834 ) ) ; +#30987 = ORIENTED_EDGE ( 'NONE', *, *, #17309, .F. ) ; +#30988 = ORIENTED_EDGE ( 'NONE', *, *, #35597, .F. ) ; +#30989 = CARTESIAN_POINT ( 'NONE', ( 20.05333031552076051, 184.3083097996710933, 105.2176979012920697 ) ) ; +#30990 = CARTESIAN_POINT ( 'NONE', ( 20.48580071746687281, 209.7097554882793702, 78.04612426987789320 ) ) ; +#30991 = CARTESIAN_POINT ( 'NONE', ( -40.91725980310987865, 188.6757777993018692, 107.4960952986480152 ) ) ; +#30992 = ORIENTED_EDGE ( 'NONE', *, *, #29078, .T. ) ; +#30993 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#30994 = CARTESIAN_POINT ( 'NONE', ( 14.55306318046054592, 176.9232825744718411, 100.4900915860747403 ) ) ; +#30995 = VECTOR ( 'NONE', #20218, 1000.000000000000000 ) ; +#30996 = EDGE_CURVE ( 'NONE', #21098, #39629, #10457, .T. ) ; +#30997 = DIRECTION ( 'NONE', ( -0.0005884949961239134509, 0.2249510543439059707, -0.9743698870671263501 ) ) ; +#30998 = AXIS2_PLACEMENT_3D ( 'NONE', #13248, #16295, #26730 ) ; +#30999 = AXIS2_PLACEMENT_3D ( 'NONE', #30232, #5274, #2232 ) ; +#31000 = FACE_OUTER_BOUND ( 'NONE', #25626, .T. ) ; +#31001 = ORIENTED_EDGE ( 'NONE', *, *, #4215, .F. ) ; +#31002 = LINE ( 'NONE', #11796, #2114 ) ; +#31003 = CONICAL_SURFACE ( 'NONE', #4172, 6.502999999940457521, 0.7853981633531327278 ) ; +#31004 = CARTESIAN_POINT ( 'NONE', ( 36.55249482085380208, 80.25314331434174164, 289.8258038402724992 ) ) ; +#31005 = CARTESIAN_POINT ( 'NONE', ( -37.63159775036000099, 118.5781719367000022, 87.39224945975999503 ) ) ; +#31006 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#31007 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#31008 = VERTEX_POINT ( 'NONE', #6683 ) ; +#31009 = CARTESIAN_POINT ( 'NONE', ( -43.19369327228462652, 172.6130766527593892, 183.6332436169467712 ) ) ; +#31010 = ORIENTED_EDGE ( 'NONE', *, *, #26416, .T. ) ; +#31011 = EDGE_CURVE ( 'NONE', #7592, #7007, #25616, .T. ) ; +#31012 = CARTESIAN_POINT ( 'NONE', ( -38.37822306518999937, 118.5483362540999934, 89.85072421485999428 ) ) ; +#31013 = EDGE_LOOP ( 'NONE', ( #25139, #6241, #7763, #8741 ) ) ; +#31014 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930882562 ) ) ; +#31015 = CARTESIAN_POINT ( 'NONE', ( -32.65040898612480191, 153.0051697192221241, 291.5764532040477093 ) ) ; +#31016 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749098554, 179.1800746285791206, 103.5747911657629601 ) ) ; +#31017 = CARTESIAN_POINT ( 'NONE', ( 23.36273455199158278, 177.2438047235408760, 101.0299531551032146 ) ) ; +#31018 = EDGE_CURVE ( 'NONE', #26136, #13855, #29493, .T. ) ; +#31019 = ADVANCED_FACE ( 'NONE', ( #35083 ), #13045, .T. ) ; +#31020 = CARTESIAN_POINT ( 'NONE', ( 31.84188692585000169, 220.4002260771000010, 152.4718672074000381 ) ) ; +#31021 = VERTEX_POINT ( 'NONE', #25733 ) ; +#31022 = AXIS2_PLACEMENT_3D ( 'NONE', #4575, #13993, #17442 ) ; +#31023 = EDGE_CURVE ( 'NONE', #5506, #26460, #38375, .T. ) ; +#31024 = ORIENTED_EDGE ( 'NONE', *, *, #19759, .F. ) ; +#31025 = CARTESIAN_POINT ( 'NONE', ( -19.70060805389840297, 149.2630956751775955, 182.5538467380586098 ) ) ; +#31026 = CARTESIAN_POINT ( 'NONE', ( -32.66145081237952041, 191.5260128943200471, 103.8899145187908175 ) ) ; +#31027 = CIRCLE ( 'NONE', #36203, 2.500000000045985438 ) ; +#31028 = FACE_OUTER_BOUND ( 'NONE', #18462, .T. ) ; +#31029 = AXIS2_PLACEMENT_3D ( 'NONE', #903, #13390, #38323 ) ; +#31030 = ORIENTED_EDGE ( 'NONE', *, *, #33811, .T. ) ; +#31031 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; +#31032 = VECTOR ( 'NONE', #6450, 1000.000000000000114 ) ; +#31033 = ORIENTED_EDGE ( 'NONE', *, *, #6121, .F. ) ; +#31035 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524157562, 149.3470289647612219, 130.0514119197758305 ) ) ; +#31034 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #14246, #10976, #13829, #16685 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 6.160373448998780255, 6.403395894008630407 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9950843936374926813, 0.9950843936374926813, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#31036 = LINE ( 'NONE', #9359, #26722 ) ; +#31037 = ORIENTED_EDGE ( 'NONE', *, *, #26154, .T. ) ; +#31038 = CARTESIAN_POINT ( 'NONE', ( -38.82926470596208901, 119.3584309079524246, 90.32664788632943953 ) ) ; +#31039 = CARTESIAN_POINT ( 'NONE', ( 3.760861305702880131, 167.8747276737439620, 101.2555565256170951 ) ) ; +#31040 = CARTESIAN_POINT ( 'NONE', ( -25.35577217468999933, 191.5262698070999932, 106.2802080165999996 ) ) ; +#31041 = CARTESIAN_POINT ( 'NONE', ( 30.07825772506129525, 177.1204444582162409, 103.6051399121813859 ) ) ; +#31042 = CARTESIAN_POINT ( 'NONE', ( 4.017041573755003370, 124.9646835441209021, 88.50086511966965475 ) ) ; +#31043 = ORIENTED_EDGE ( 'NONE', *, *, #10960, .T. ) ; +#31044 = CARTESIAN_POINT ( 'NONE', ( 21.59709472431439181, 115.2762503876805624, 188.9250028067568508 ) ) ; +#31045 = CARTESIAN_POINT ( 'NONE', ( 37.32096841862673386, 164.8291704540998523, 197.3151593714009380 ) ) ; +#31046 = CARTESIAN_POINT ( 'NONE', ( -15.94435338216056230, 121.6615746736106303, 175.4535042054991436 ) ) ; +#31047 = CARTESIAN_POINT ( 'NONE', ( -45.82946015665383754, 124.9267195748215755, 91.89216530322958931 ) ) ; +#31048 = VERTEX_POINT ( 'NONE', #6481 ) ; +#31049 = ORIENTED_EDGE ( 'NONE', *, *, #7413, .T. ) ; +#31050 = CARTESIAN_POINT ( 'NONE', ( 38.22623376675434059, 118.8155667128057615, 90.24469678293085906 ) ) ; +#31051 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26771, #11225, #36152, #8150 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31052 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#31053 = PLANE ( 'NONE', #4573 ) ; +#31054 = AXIS2_PLACEMENT_3D ( 'NONE', #28465, #21737, #21938 ) ; +#31055 = CONICAL_SURFACE ( 'NONE', #12116, 2.499999999913497195, 0.7853981633683820851 ) ; +#31056 = DIRECTION ( 'NONE', ( -0.7933533411653045375, 0.5930537057989968552, 0.1373964268091591723 ) ) ; +#31057 = CARTESIAN_POINT ( 'NONE', ( -26.03762553832000037, 190.4430459227999961, 106.7148042862000068 ) ) ; +#31058 = EDGE_CURVE ( 'NONE', #29757, #19715, #13246, .T. ) ; +#31059 = AXIS2_PLACEMENT_3D ( 'NONE', #35499, #38402, #6707 ) ; +#31060 = CARTESIAN_POINT ( 'NONE', ( 6.035817316620117445, 176.7425654412684537, 103.0192746809948403 ) ) ; +#31061 = EDGE_CURVE ( 'NONE', #12211, #4391, #13842, .T. ) ; +#31062 = APPROVAL_ROLE ( '' ) ; +#31063 = CARTESIAN_POINT ( 'NONE', ( 20.50029381459107825, 138.3995138255986603, 92.10573732912574485 ) ) ; +#31064 = PLANE ( 'NONE', #28977 ) ; +#31065 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921571859, -0.2249510932971622024 ) ) ; +#31066 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11902, #9030, #39687, #33757 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999909299021982889 ), + .UNSPECIFIED. ) ; +#31067 = FACE_OUTER_BOUND ( 'NONE', #22964, .T. ) ; +#31068 = CARTESIAN_POINT ( 'NONE', ( 36.18931259780619314, 192.0080012320809999, 104.3455603723210174 ) ) ; +#31069 = EDGE_CURVE ( 'NONE', #36902, #604, #32111, .T. ) ; +#31070 = EDGE_CURVE ( 'NONE', #39281, #20961, #26324, .T. ) ; +#31071 = ORIENTED_EDGE ( 'NONE', *, *, #558, .F. ) ; +#31073 = EDGE_LOOP ( 'NONE', ( #17569, #35729, #34726, #35374 ) ) ; +#31072 = CARTESIAN_POINT ( 'NONE', ( 36.82112145928000047, 191.5024862555000027, 106.2217677218000063 ) ) ; +#31074 = ORIENTED_EDGE ( 'NONE', *, *, #8645, .F. ) ; +#31075 = EDGE_LOOP ( 'NONE', ( #32745, #15391, #26258, #11695 ) ) ; +#31076 = EDGE_CURVE ( 'NONE', #604, #24326, #5228, .T. ) ; +#31077 = CARTESIAN_POINT ( 'NONE', ( 31.54582148684999865, 177.9538242463000302, 164.9590253462000362 ) ) ; +#31078 = ADVANCED_FACE ( 'NONE', ( #4625 ), #16881, .T. ) ; +#31079 = CARTESIAN_POINT ( 'NONE', ( -20.24140383769758955, 184.9064092065293892, 102.6020569953306705 ) ) ; +#31080 = VECTOR ( 'NONE', #21276, 1000.000000000000227 ) ; +#31081 = CARTESIAN_POINT ( 'NONE', ( -32.50869459978976295, 175.9851385237510328, 100.3019280490168512 ) ) ; +#31082 = AXIS2_PLACEMENT_3D ( 'NONE', #18812, #15567, #28255 ) ; +#31083 = ORIENTED_EDGE ( 'NONE', *, *, #8308, .F. ) ; +#31084 = VECTOR ( 'NONE', #14054, 1000.000000000000114 ) ; +#31085 = CARTESIAN_POINT ( 'NONE', ( 42.93478411035056297, 121.9318606513537020, 87.77717731540884927 ) ) ; +#31086 = CARTESIAN_POINT ( 'NONE', ( 3.667815741532966189, 126.2406713581920599, 91.36142183184406917 ) ) ; +#31087 = PLANE ( 'NONE', #6604 ) ; +#31088 = VERTEX_POINT ( 'NONE', #11180 ) ; +#31089 = AXIS2_PLACEMENT_3D ( 'NONE', #3049, #9603, #18768 ) ; +#31090 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825948087824765, 0.0005734119017360681013 ) ) ; +#31091 = DIRECTION ( 'NONE', ( -0.000000000000000000, -1.000000000000000000, 0.000000000000000000 ) ) ; +#31092 = AXIS2_PLACEMENT_3D ( 'NONE', #30990, #39763, #2956 ) ; +#31093 = CARTESIAN_POINT ( 'NONE', ( -20.00004361580415591, 118.8155695144462669, 87.27991261026372172 ) ) ; +#31094 = CARTESIAN_POINT ( 'NONE', ( -24.42746481139502279, 103.6131156702177094, 87.78253795974556795 ) ) ; +#31095 = EDGE_LOOP ( 'NONE', ( #14655, #22281, #24239, #4456 ) ) ; +#31096 = CARTESIAN_POINT ( 'NONE', ( 16.00151820029350702, 137.8265450205371394, 94.54185288967525480 ) ) ; +#31097 = CARTESIAN_POINT ( 'NONE', ( 2.553143702803999826, 190.9977876359000106, 104.2699393190000023 ) ) ; +#31098 = CARTESIAN_POINT ( 'NONE', ( 16.24603267945985507, 152.0453547567774706, 181.0525560685096593 ) ) ; +#31099 = EDGE_LOOP ( 'NONE', ( #12024, #6014, #32924, #7140, #8031, #19619 ) ) ; +#31100 = VERTEX_POINT ( 'NONE', #23654 ) ; +#31101 = CARTESIAN_POINT ( 'NONE', ( -38.45417236430746755, 119.6409147006968823, 87.33694759259822149 ) ) ; +#31102 = ORIENTED_EDGE ( 'NONE', *, *, #25439, .F. ) ; +#31103 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31442, #6084, #15881, #34282, #24318, #40423, #18536, #12235, #6278, #31041 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000001353917, 0.3750000000002030598, 0.4375000000002060019, 0.5000000000002089440, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31104 = ADVANCED_FACE ( 'NONE', ( #20780 ), #22347, .F. ) ; +#31105 = VECTOR ( 'NONE', #1336, 999.9999999999998863 ) ; +#31106 = EDGE_CURVE ( 'NONE', #3689, #21726, #12915, .T. ) ; +#31107 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #5223, #24475, #2184, #14858 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.609997058757503652, 4.712388980384670134 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9012658660484214046, 0.9012658660484214046, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#31108 = VECTOR ( 'NONE', #35959, 1000.000000000000000 ) ; +#31109 = CARTESIAN_POINT ( 'NONE', ( 12.31198009898977297, 134.9205818654068025, 90.79431936396761671 ) ) ; +#31110 = VECTOR ( 'NONE', #7441, 1000.000000000000000 ) ; +#31111 = CARTESIAN_POINT ( 'NONE', ( -37.21730312380855565, 191.0563982775359477, 106.3396948499198658 ) ) ; +#31112 = EDGE_CURVE ( 'NONE', #12877, #35118, #26942, .T. ) ; +#31113 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524656274, 149.3470289647502511, 130.0514119197545142 ) ) ; +#31114 = CARTESIAN_POINT ( 'NONE', ( -5.670666054933423794, 181.8752443071280709, 101.9019012075243609 ) ) ; +#31115 = CARTESIAN_POINT ( 'NONE', ( -2.371600584370171738, 190.4347757011841509, 106.1523463772184215 ) ) ; +#31116 = VERTEX_POINT ( 'NONE', #14661 ) ; +#31117 = AXIS2_PLACEMENT_3D ( 'NONE', #32280, #13075, #9809 ) ; +#31118 = EDGE_CURVE ( 'NONE', #24370, #39941, #6009, .T. ) ; +#31119 = CYLINDRICAL_SURFACE ( 'NONE', #9405, 6.000000000000008882 ) ; +#31120 = CARTESIAN_POINT ( 'NONE', ( 37.56516904143808233, 212.6956748481447335, 75.86914951168479604 ) ) ; +#31121 = DIRECTION ( 'NONE', ( -0.7933532970003740470, -0.5930762008556723641, -0.1372995488602875569 ) ) ; +#31123 = CARTESIAN_POINT ( 'NONE', ( 36.05382442437669965, 112.9281706447458760, 87.74600877593400128 ) ) ; +#31122 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 1.739499925770551072E-30, 0.0006039748319385906776 ) ) ; +#31124 = ORIENTED_EDGE ( 'NONE', *, *, #35974, .F. ) ; +#31125 = EDGE_CURVE ( 'NONE', #3122, #22426, #2752, .T. ) ; +#31126 = ORIENTED_EDGE ( 'NONE', *, *, #25537, .T. ) ; +#31127 = DIRECTION ( 'NONE', ( 0.0004161288024631969499, -0.8480480897833772014, 0.5299191110458129073 ) ) ; +#31128 = LINE ( 'NONE', #3098, #5415 ) ; +#31129 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2431, #27394, #24315, #24721, #40025, #24921 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 4.416197448658278450E-07, 0.001508600510335431381, 0.003016759400925997196 ), + .UNSPECIFIED. ) ; +#31130 = ORIENTED_EDGE ( 'NONE', *, *, #25306, .T. ) ; +#31131 = CARTESIAN_POINT ( 'NONE', ( -39.69723568842041317, 114.7507352566516943, 151.7663457455989544 ) ) ; +#31132 = DIRECTION ( 'NONE', ( -2.775557561558865794E-15, -0.9743700557921587402, -0.2249510932971555965 ) ) ; +#31133 = CARTESIAN_POINT ( 'NONE', ( 15.83500089607693617, 184.3280936476482452, 105.1067149263252105 ) ) ; +#31134 = DIRECTION ( 'NONE', ( -6.681078215644284579E-11, 0.9743700557771369786, 0.2249510933622214381 ) ) ; +#31135 = ORIENTED_EDGE ( 'NONE', *, *, #17794, .F. ) ; +#31136 = LINE ( 'NONE', #25811, #14719 ) ; +#31137 = VERTEX_POINT ( 'NONE', #36102 ) ; +#31138 = AXIS2_PLACEMENT_3D ( 'NONE', #6222, #31182, #21392 ) ; +#31139 = CARTESIAN_POINT ( 'NONE', ( 5.663463790603415760, 124.4575615037363860, 88.50647768129195470 ) ) ; +#31140 = CARTESIAN_POINT ( 'NONE', ( -1.762796035792233207, 151.6652447683722471, 130.5904578368917441 ) ) ; +#31141 = AXIS2_PLACEMENT_3D ( 'NONE', #14741, #8609, #5729 ) ; +#31142 = FACE_OUTER_BOUND ( 'NONE', #34662, .T. ) ; +#31143 = CARTESIAN_POINT ( 'NONE', ( -13.49836187949013322, 187.2925309095741113, 105.4667247238223524 ) ) ; +#31144 = ORIENTED_EDGE ( 'NONE', *, *, #28656, .F. ) ; +#31145 = LINE ( 'NONE', #30941, #16067 ) ; +#31146 = CARTESIAN_POINT ( 'NONE', ( 0.7586617867642599933, 188.6208944900433835, 103.1990300548870181 ) ) ; +#31147 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 132.9726895863779532, 90.34121396988804520 ) ) ; +#31148 = EDGE_LOOP ( 'NONE', ( #21686, #33286 ) ) ; +#31149 = CARTESIAN_POINT ( 'NONE', ( 2.729957264165000286, 190.8363048546000016, 106.4417122540999969 ) ) ; +#31150 = CARTESIAN_POINT ( 'NONE', ( 13.49481983871936386, 124.3681642032378534, 88.35737770391504853 ) ) ; +#31151 = CARTESIAN_POINT ( 'NONE', ( 36.28566749807773562, 191.4195153028702236, 103.8236852762196492 ) ) ; +#31152 = CARTESIAN_POINT ( 'NONE', ( -25.36508458611999828, 120.1656809584000030, 89.83749781794000455 ) ) ; +#31153 = EDGE_CURVE ( 'NONE', #24029, #20341, #10781, .T. ) ; +#31154 = EDGE_CURVE ( 'NONE', #25978, #23623, #30150, .T. ) ; +#31155 = ORIENTED_EDGE ( 'NONE', *, *, #20608, .T. ) ; +#31156 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557843820720, -0.2249510933308394578 ) ) ; +#31157 = EDGE_CURVE ( 'NONE', #12808, #33829, #35336, .T. ) ; +#31158 = CARTESIAN_POINT ( 'NONE', ( -16.54012570822575157, 121.8328361328813543, 177.5596287226420316 ) ) ; +#31159 = EDGE_CURVE ( 'NONE', #796, #39798, #36683, .T. ) ; +#31160 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -7.515125404477462028E-16, 0.0006039748319388944710 ) ) ; +#31161 = CARTESIAN_POINT ( 'NONE', ( -20.11801462494291215, 127.0926108250165498, 91.96276686944507617 ) ) ; +#31162 = VERTEX_POINT ( 'NONE', #39178 ) ; +#31163 = AXIS2_PLACEMENT_3D ( 'NONE', #15017, #39942, #8784 ) ; +#31164 = CARTESIAN_POINT ( 'NONE', ( 32.36006137438955221, 209.7096916965322180, 73.03895941624857358 ) ) ; +#31165 = ORIENTED_EDGE ( 'NONE', *, *, #29618, .T. ) ; +#31166 = VECTOR ( 'NONE', #32282, 1000.000000000000114 ) ; +#31167 = CIRCLE ( 'NONE', #2454, 1.999999999953854024 ) ; +#31169 = CARTESIAN_POINT ( 'NONE', ( 0.5623190733617040582, 188.6124699482102756, 103.1972064621602527 ) ) ; +#31168 = DIRECTION ( 'NONE', ( 0.0005884949961237983087, -0.2249510543439047772, 0.9743698870671267942 ) ) ; +#31170 = VERTEX_POINT ( 'NONE', #35894 ) ; +#31171 = EDGE_CURVE ( 'NONE', #11449, #39475, #7695, .T. ) ; +#31172 = EDGE_LOOP ( 'NONE', ( #32299, #14199, #17131, #16861 ) ) ; +#31173 = CARTESIAN_POINT ( 'NONE', ( 2.835810955472000572, 209.6480747013999917, 75.93553738705000455 ) ) ; +#31174 = DIRECTION ( 'NONE', ( -0.0005884949961206489182, 0.2249510543439051102, -0.9743698870671265722 ) ) ; +#31175 = VERTEX_POINT ( 'NONE', #29387 ) ; +#31176 = ORIENTED_EDGE ( 'NONE', *, *, #6264, .F. ) ; +#31177 = CARTESIAN_POINT ( 'NONE', ( 35.04524256069624499, 220.4002260770989778, 73.53733772514158318 ) ) ; +#31178 = FACE_OUTER_BOUND ( 'NONE', #20981, .T. ) ; +#31179 = CARTESIAN_POINT ( 'NONE', ( 29.05442967595000070, 110.6131156702000027, 88.75023641814000541 ) ) ; +#31180 = ORIENTED_EDGE ( 'NONE', *, *, #22077, .F. ) ; +#31181 = ORIENTED_EDGE ( 'NONE', *, *, #21051, .F. ) ; +#31182 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#31183 = CARTESIAN_POINT ( 'NONE', ( -30.07038801301974473, 136.6761377446392487, 94.30416869774899169 ) ) ; +#31184 = CARTESIAN_POINT ( 'NONE', ( -26.52264724072000135, 123.9893196918000058, 88.80742175707999309 ) ) ; +#31185 = ORIENTED_EDGE ( 'NONE', *, *, #17296, .F. ) ; +#31186 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749898865, 177.4376441116277761, 101.1199114316599577 ) ) ; +#31187 = CARTESIAN_POINT ( 'NONE', ( 40.86755754141834274, 188.5902530340942178, 107.5428458308915509 ) ) ; +#31188 = VERTEX_POINT ( 'NONE', #19952 ) ; +#31189 = VECTOR ( 'NONE', #27282, 1000.000000000000114 ) ; +#31190 = CARTESIAN_POINT ( 'NONE', ( 39.01707480719999666, 142.5739022138000109, 26.89884147244999824 ) ) ; +#31191 = CARTESIAN_POINT ( 'NONE', ( -38.90215727773150434, 162.5678425802583433, 197.7383679064734565 ) ) ; +#31192 = AXIS2_PLACEMENT_3D ( 'NONE', #20174, #17509, #26151 ) ; +#31193 = CARTESIAN_POINT ( 'NONE', ( -45.05010495504543400, 181.2316974417921074, 101.8628679662392642 ) ) ; +#31194 = CARTESIAN_POINT ( 'NONE', ( 27.78438839505666991, 188.0117751643121267, 103.0420822765563855 ) ) ; +#31195 = ORIENTED_EDGE ( 'NONE', *, *, #814, .T. ) ; +#31196 = CARTESIAN_POINT ( 'NONE', ( 12.63825826684001719, 182.0651920382574076, 102.1915037821187440 ) ) ; +#31197 = VERTEX_POINT ( 'NONE', #1355 ) ; +#31198 = ADVANCED_FACE ( 'NONE', ( #8108 ), #9942, .F. ) ; +#31199 = CARTESIAN_POINT ( 'NONE', ( -23.36170564740040234, 182.0604262685139361, 102.2121465934016129 ) ) ; +#31200 = EDGE_CURVE ( 'NONE', #11920, #11101, #40196, .T. ) ; +#31201 = FACE_OUTER_BOUND ( 'NONE', #27334, .T. ) ; +#31202 = CARTESIAN_POINT ( 'NONE', ( -14.29753817416625061, 182.6906998136370532, 102.1811316074132350 ) ) ; +#31203 = CARTESIAN_POINT ( 'NONE', ( 45.10956928938049515, 115.5709318062878168, 128.3132131271731851 ) ) ; +#31204 = ORIENTED_EDGE ( 'NONE', *, *, #35082, .F. ) ; +#31205 = FACE_OUTER_BOUND ( 'NONE', #23277, .T. ) ; +#31206 = ORIENTED_EDGE ( 'NONE', *, *, #14956, .T. ) ; +#31207 = CARTESIAN_POINT ( 'NONE', ( 47.95567328239271632, 139.9374889060051146, 291.1737358715798791 ) ) ; +#31208 = EDGE_LOOP ( 'NONE', ( #13512, #38159, #7820, #20580 ) ) ; +#31209 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971598709 ) ) ; +#31210 = AXIS2_PLACEMENT_3D ( 'NONE', #35769, #13930, #26411 ) ; +#31211 = CARTESIAN_POINT ( 'NONE', ( 22.53675382576999908, 124.4626272919999934, 152.4718672074000381 ) ) ; +#31212 = CARTESIAN_POINT ( 'NONE', ( -37.09602284966847208, 164.9667323745490251, 195.9811478980911374 ) ) ; +#31213 = DIRECTION ( 'NONE', ( 0.6087613186456907188, 0.7730177010543248795, 0.1784749023741044327 ) ) ; +#31214 = CARTESIAN_POINT ( 'NONE', ( 45.25615125966712782, 130.4019898035445522, 92.63912118957520647 ) ) ; +#31215 = CONICAL_SURFACE ( 'NONE', #13587, 2.749999999892358549, 0.7853981634430725611 ) ; +#31216 = ORIENTED_EDGE ( 'NONE', *, *, #26188, .T. ) ; +#31217 = EDGE_LOOP ( 'NONE', ( #13912, #5615, #19973, #27433, #22793, #20918, #7455, #13004 ) ) ; +#31218 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; +#31219 = CARTESIAN_POINT ( 'NONE', ( 1.273934745427919069, 189.1300036437734207, 105.7744582827584310 ) ) ; +#31220 = ADVANCED_FACE ( 'NONE', ( #5031 ), #15647, .F. ) ; +#31221 = CARTESIAN_POINT ( 'NONE', ( -37.39932010222903358, 212.8449755639020111, 76.08109288175667473 ) ) ; +#31222 = VERTEX_POINT ( 'NONE', #31196 ) ; +#31223 = CARTESIAN_POINT ( 'NONE', ( -23.36258829528358660, 135.1161733599290642, 91.13525200680678040 ) ) ; +#31224 = ORIENTED_EDGE ( 'NONE', *, *, #10166, .F. ) ; +#31225 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596101196, 128.5887768395678563, 89.32567453973172178 ) ) ; +#31226 = CARTESIAN_POINT ( 'NONE', ( -5.668459040265249271, 130.7309778812349350, 90.08599464117959599 ) ) ; +#31227 = VERTEX_POINT ( 'NONE', #2968 ) ; +#31228 = CARTESIAN_POINT ( 'NONE', ( 28.52226708450999837, 125.2835602215999984, 88.55890939917999560 ) ) ; +#31229 = CARTESIAN_POINT ( 'NONE', ( 25.57447242411126709, 211.0902261055813085, 73.45914216482992742 ) ) ; +#31230 = CARTESIAN_POINT ( 'NONE', ( -25.64662748966999928, 190.7220139133999908, 106.3869458739000038 ) ) ; +#31231 = CARTESIAN_POINT ( 'NONE', ( 45.31782503891692926, 120.7229189729074363, 105.4582906007348271 ) ) ; +#31232 = LINE ( 'NONE', #21645, #37389 ) ; +#31233 = ORIENTED_EDGE ( 'NONE', *, *, #16786, .F. ) ; +#31234 = CARTESIAN_POINT ( 'NONE', ( -35.43878503052407325, 193.8169247181471349, 102.7243139024822511 ) ) ; +#31235 = CARTESIAN_POINT ( 'NONE', ( -37.89691480486764164, 119.0726142382651886, 87.29510449627004220 ) ) ; +#31236 = LINE ( 'NONE', #12622, #14962 ) ; +#31237 = AXIS2_PLACEMENT_3D ( 'NONE', #26514, #17275, #5021 ) ; +#31238 = CARTESIAN_POINT ( 'NONE', ( 21.83140111251249493, 182.3124853075107978, 104.2956521028678054 ) ) ; +#31239 = EDGE_LOOP ( 'NONE', ( #18521, #37417, #1343, #5312 ) ) ; +#31240 = EDGE_CURVE ( 'NONE', #39849, #37286, #28896, .T. ) ; +#31241 = ORIENTED_EDGE ( 'NONE', *, *, #38519, .T. ) ; +#31242 = LINE ( 'NONE', #34884, #34893 ) ; +#31243 = ADVANCED_FACE ( 'NONE', ( #21804 ), #7990, .F. ) ; +#31244 = CARTESIAN_POINT ( 'NONE', ( 3.045964837637491485, 205.1071438019466484, 76.10297588903854660 ) ) ; +#31245 = VECTOR ( 'NONE', #20079, 1000.000000000000227 ) ; +#31246 = DIRECTION ( 'NONE', ( 0.0006039748319377988848, 1.383702340315400350E-14, 0.9999998176071845934 ) ) ; +#31247 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#31248 = ORIENTED_EDGE ( 'NONE', *, *, #2590, .F. ) ; +#31249 = CARTESIAN_POINT ( 'NONE', ( -25.83629999435114044, 190.9265745077870520, 106.6552633789108313 ) ) ; +#31250 = EDGE_LOOP ( 'NONE', ( #35157, #17211, #16661, #17614, #32026 ) ) ; +#31251 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19585, #4239, #4653, #19976, #34903, #6917, #19390, #31883, #16715, #13268, #32473, #10808, #784, #4448, #25754, #38207, #22686, #16904, #29416 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999980849, 0.1875000000000007772, 0.2187499999999994171, 0.2499999999999980571, 0.3749999999999963363, 0.4999999999999946709, 0.6249999999999930056, 0.6874999999999921174, 0.7499999999999912292, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31252 = DIRECTION ( 'NONE', ( 0.0005884949961256158652, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#31253 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#31254 = DIRECTION ( 'NONE', ( -3.092411411307044243E-16, 0.9743043966640313469, 0.2252353050503803911 ) ) ; +#31255 = EDGE_LOOP ( 'NONE', ( #25821, #29739, #35668, #30821 ) ) ; +#31256 = DIRECTION ( 'NONE', ( -0.0005884949961223030854, 0.2249510543439056098, -0.9743698870671265722 ) ) ; +#31257 = CARTESIAN_POINT ( 'NONE', ( -39.33474900027506749, 121.5592670194013181, 123.6449446999658335 ) ) ; +#31258 = CARTESIAN_POINT ( 'NONE', ( -31.70384873206000265, 225.9002260769261738, 76.07765295985980458 ) ) ; +#31259 = CARTESIAN_POINT ( 'NONE', ( 36.19055948864460959, 192.0350829726729955, 106.4100390531919942 ) ) ; +#31260 = ORIENTED_EDGE ( 'NONE', *, *, #9211, .T. ) ; +#31261 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16219, #16611, #25250, #28707 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31262 = CARTESIAN_POINT ( 'NONE', ( 36.51684498022000014, 190.9760849982000082, 106.6659581011000029 ) ) ; +#31263 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #13263, #9443, #24798, #3833 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.841040618783368998, 4.841135276510147634 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999992533261661, 0.9999999992533261661, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#31264 = EDGE_LOOP ( 'NONE', ( #36253, #20029, #30149, #40284, #27280, #3351, #38309, #31548, #33085 ) ) ; +#31265 = ORIENTED_EDGE ( 'NONE', *, *, #20859, .F. ) ; +#31267 = AXIS2_PLACEMENT_3D ( 'NONE', #15387, #2723, #37455 ) ; +#31266 = DIRECTION ( 'NONE', ( -0.0005884949961246157971, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#31268 = EDGE_CURVE ( 'NONE', #5125, #12157, #39690, .T. ) ; +#31269 = CARTESIAN_POINT ( 'NONE', ( 20.48079242901865982, 211.0898936264048587, 74.87825877592972290 ) ) ; +#31270 = AXIS2_PLACEMENT_3D ( 'NONE', #26574, #23905, #17738 ) ; +#31271 = CYLINDRICAL_SURFACE ( 'NONE', #6976, 1.749999999999998446 ) ; +#31272 = AXIS2_PLACEMENT_3D ( 'NONE', #20111, #14210, #11137 ) ; +#31273 = CIRCLE ( 'NONE', #20825, 2.499999999963690378 ) ; +#31274 = ORIENTED_EDGE ( 'NONE', *, *, #24037, .F. ) ; +#31275 = LINE ( 'NONE', #28225, #22491 ) ; +#31276 = CARTESIAN_POINT ( 'NONE', ( 17.14832387282329407, 126.1996735828056728, 179.0783422476870044 ) ) ; +#31277 = CARTESIAN_POINT ( 'NONE', ( 22.00487102077426371, 128.4742142609961775, 175.4981782972427595 ) ) ; +#31278 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; +#31279 = EDGE_LOOP ( 'NONE', ( #31799, #21776, #14351, #25812 ) ) ; +#31280 = CARTESIAN_POINT ( 'NONE', ( -18.76885123896627050, 125.8224625306723112, 175.1047239809785765 ) ) ; +#31281 = EDGE_CURVE ( 'NONE', #5648, #34131, #32388, .T. ) ; +#31282 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26629, #38663, #10883, #1056, #17185, #35573, #20262, #29691, #10683, #38466 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31283 = CARTESIAN_POINT ( 'NONE', ( 41.44965782246524810, 121.0516445706251289, 87.74591107882081076 ) ) ; +#31284 = CYLINDRICAL_SURFACE ( 'NONE', #14098, 1.999999999999989342 ) ; +#31285 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 82.27946979429631824, 312.5857197240630967 ) ) ; +#31286 = EDGE_LOOP ( 'NONE', ( #39203, #26577, #31949, #27052 ) ) ; +#31287 = EDGE_LOOP ( 'NONE', ( #34370, #1252, #29939, #10651 ) ) ; +#31288 = EDGE_CURVE ( 'NONE', #8100, #13786, #15790, .T. ) ; +#31289 = CARTESIAN_POINT ( 'NONE', ( 12.64067740912175708, 176.9725557677797099, 103.3821496526897761 ) ) ; +#31290 = CARTESIAN_POINT ( 'NONE', ( 2.549404638957319502, 190.8267260001289856, 104.2255130234709952 ) ) ; +#31291 = CARTESIAN_POINT ( 'NONE', ( -22.78469271946612196, 158.3009118758265004, 96.21332883968871386 ) ) ; +#31292 = EDGE_CURVE ( 'NONE', #18171, #19279, #37733, .T. ) ; +#31293 = ORIENTED_EDGE ( 'NONE', *, *, #23313, .T. ) ; +#31294 = LINE ( 'NONE', #25577, #269 ) ; +#31295 = ORIENTED_EDGE ( 'NONE', *, *, #11918, .T. ) ; +#31296 = EDGE_CURVE ( 'NONE', #9326, #25855, #8934, .T. ) ; +#31297 = EDGE_CURVE ( 'NONE', #37905, #38246, #18095, .T. ) ; +#31298 = AXIS2_PLACEMENT_3D ( 'NONE', #14034, #10570, #11167 ) ; +#31299 = EDGE_CURVE ( 'NONE', #20395, #29818, #24881, .T. ) ; +#31300 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5115, #24771, #18586, #30494, #3258, #15347, #21892, #24571, #14949, #30895 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.0005627318540861992423, 0.2504220488905646302, 0.5002813659270430868, 0.7501406829635215434, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31301 = CARTESIAN_POINT ( 'NONE', ( -20.51978786315646630, 209.7094320854081104, 73.57086927696296641 ) ) ; +#31302 = CIRCLE ( 'NONE', #10410, 6.500000000082215124 ) ; +#31303 = VECTOR ( 'NONE', #20072, 1000.000000000000000 ) ; +#31304 = CARTESIAN_POINT ( 'NONE', ( 20.48253891412411321, 207.4083879957671002, 77.06951181954761410 ) ) ; +#31305 = AXIS2_PLACEMENT_3D ( 'NONE', #23363, #14168, #38475 ) ; +#31306 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971565125 ) ) ; +#31307 = CARTESIAN_POINT ( 'NONE', ( -3.336448430802661402, 185.8690661594090159, 102.7372488050839507 ) ) ; +#31308 = CARTESIAN_POINT ( 'NONE', ( -21.09369801935529765, 136.1618710054223982, 91.10110626354527597 ) ) ; +#31309 = CARTESIAN_POINT ( 'NONE', ( -12.64175801402573995, 134.2925017664874190, 93.70056500962402879 ) ) ; +#31310 = CARTESIAN_POINT ( 'NONE', ( -2.148764250739064074, 189.9651423557504870, 106.0171960769523878 ) ) ; +#31311 = ORIENTED_EDGE ( 'NONE', *, *, #10532, .T. ) ; +#31312 = PLANE ( 'NONE', #3506 ) ; +#31313 = CARTESIAN_POINT ( 'NONE', ( 39.04675176836854433, 209.7096538831000316, 76.03492163576670748 ) ) ; +#31314 = PLANE ( 'NONE', #2678 ) ; +#31315 = DIRECTION ( 'NONE', ( 0.0006039748319387072293, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#31316 = ORIENTED_EDGE ( 'NONE', *, *, #9879, .F. ) ; +#31317 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #14059, #23459, #20170, #32852 ), + ( #39190, #17299, #21309, #24388 ), + ( #33347, #15364, #9236, #18406 ), + ( #33756, #24785, #17799, #5544 ), + ( #37235, #11697, #36835, #21711 ), + ( #6148, #21515, #39889, #8840 ), + ( #30513, #9029, #5755, #27469 ), + ( #11901, #18206, #40090, #8638 ), + ( #5345, #36630, #21099, #30711 ), + ( #30908, #12100, #27858, #30293 ), + ( #15170, #2703, #34154, #18004 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.06423221000888999777, 0.000000000000000000, 0.1249986728208000025, 0.2499983718750999895, 0.3749980709294999937, 0.4999977699838000222, 0.7499971680925999751, 1.000000000000000000, 1.044138764985000023 ), + ( -0.0006364018616687999860, 0.9999999836310999868 ), + .UNSPECIFIED. ) ; +#31318 = EDGE_LOOP ( 'NONE', ( #21091, #17969, #21106, #28454 ) ) ; +#31319 = CARTESIAN_POINT ( 'NONE', ( 20.50411903244052780, 118.8156269615539742, 94.25541629140380451 ) ) ; +#31320 = LINE ( 'NONE', #33618, #21337 ) ; +#31321 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #16810, #21070, #29303, #5307, #5505, #35399, #20855 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 4 ), + ( -0.001262858050230576809, 0.000000000000000000, 2.768544891470852386E-05 ), + .UNSPECIFIED. ) ; +#31322 = ORIENTED_EDGE ( 'NONE', *, *, #9281, .T. ) ; +#31323 = ORIENTED_EDGE ( 'NONE', *, *, #21799, .F. ) ; +#31324 = CARTESIAN_POINT ( 'NONE', ( 35.04524255441999969, 226.4002260771000010, 73.53733772517999512 ) ) ; +#31325 = VECTOR ( 'NONE', #2072, 1000.000000000000114 ) ; +#31326 = CARTESIAN_POINT ( 'NONE', ( 23.67925056556238772, 134.2473364980823476, 93.71096924780141535 ) ) ; +#31327 = CARTESIAN_POINT ( 'NONE', ( -3.169906973560626895, 184.1222312815566795, 102.1628149875517408 ) ) ; +#31328 = CARTESIAN_POINT ( 'NONE', ( -12.63885304198008086, 135.0706950218433633, 91.05405041975734548 ) ) ; +#31329 = EDGE_LOOP ( 'NONE', ( #23330, #25365, #40015, #17674 ) ) ; +#31330 = CARTESIAN_POINT ( 'NONE', ( 17.27169409178496551, 122.3510092884824729, 172.9162538931327902 ) ) ; +#31331 = EDGE_CURVE ( 'NONE', #31589, #25100, #28485, .T. ) ; +#31332 = CIRCLE ( 'NONE', #10440, 6.000000000012134294 ) ; +#31333 = ORIENTED_EDGE ( 'NONE', *, *, #38109, .T. ) ; +#31334 = CIRCLE ( 'NONE', #13065, 5.499999999599896938 ) ; +#31335 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971558741 ) ) ; +#31336 = CARTESIAN_POINT ( 'NONE', ( 26.00773787888504529, 191.9759150222000130, 101.9057393184010323 ) ) ; +#31337 = AXIS2_PLACEMENT_3D ( 'NONE', #3675, #31501, #31306 ) ; +#31338 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971549582 ) ) ; +#31339 = VERTEX_POINT ( 'NONE', #27560 ) ; +#31340 = EDGE_CURVE ( 'NONE', #4072, #13020, #31002, .T. ) ; +#31341 = CARTESIAN_POINT ( 'NONE', ( 20.31560735737901524, 205.4141931770509473, 76.22222318449824741 ) ) ; +#31342 = CARTESIAN_POINT ( 'NONE', ( 1.143504943582302813, 188.6809584813572371, 103.2126644868193068 ) ) ; +#31343 = CARTESIAN_POINT ( 'NONE', ( -23.36229215089216993, 181.4106142796427719, 104.2858048007022944 ) ) ; +#31344 = EDGE_CURVE ( 'NONE', #23170, #6189, #19709, .T. ) ; +#31345 = ORIENTED_EDGE ( 'NONE', *, *, #13841, .T. ) ; +#31346 = LINE ( 'NONE', #12731, #34185 ) ; +#31347 = ORIENTED_EDGE ( 'NONE', *, *, #1800, .T. ) ; +#31348 = ADVANCED_FACE ( 'NONE', ( #33650 ), #2593, .F. ) ; +#31349 = LINE ( 'NONE', #9472, #21284 ) ; +#31350 = CARTESIAN_POINT ( 'NONE', ( 36.49036606398971827, 191.3180990208740582, 103.8001478455694979 ) ) ; +#31351 = CARTESIAN_POINT ( 'NONE', ( 16.14865643636807846, 151.1202562712145152, 184.8374432047714606 ) ) ; +#31352 = VERTEX_POINT ( 'NONE', #24481 ) ; +#31353 = CARTESIAN_POINT ( 'NONE', ( -28.25571780481785567, 186.4543157461568228, 105.2821206686522686 ) ) ; +#31354 = CARTESIAN_POINT ( 'NONE', ( -4.410790214992264424, 124.6726707417136879, 88.43853883911272362 ) ) ; +#31355 = CIRCLE ( 'NONE', #32001, 2.750000000059430239 ) ; +#31356 = CONICAL_SURFACE ( 'NONE', #36579, 2.500000095127406841, 0.7853981633778667204 ) ; +#31357 = ORIENTED_EDGE ( 'NONE', *, *, #40229, .F. ) ; +#31358 = AXIS2_PLACEMENT_3D ( 'NONE', #16260, #22422, #38152 ) ; +#31359 = AXIS2_PLACEMENT_3D ( 'NONE', #8471, #5386, #40129 ) ; +#31360 = CARTESIAN_POINT ( 'NONE', ( -39.58538553044007102, 75.03979799197465184, 323.7269989125918528 ) ) ; +#31361 = CYLINDRICAL_SURFACE ( 'NONE', #25731, 51.40509898897001761 ) ; +#31363 = CARTESIAN_POINT ( 'NONE', ( 15.94108644203163294, 147.2333410478985911, 179.8333394151990490 ) ) ; +#31362 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250615212, 179.6252109630535472, 101.6466942236910569 ) ) ; +#31364 = ORIENTED_EDGE ( 'NONE', *, *, #24946, .T. ) ; +#31365 = CARTESIAN_POINT ( 'NONE', ( 14.93318671017543231, 151.7188427972803311, 177.9798661502222217 ) ) ; +#31366 = ORIENTED_EDGE ( 'NONE', *, *, #25354, .T. ) ; +#31367 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#31368 = DIRECTION ( 'NONE', ( 0.7942820423213362568, 0.5918950211223029667, 0.1370267171630251968 ) ) ; +#31369 = ORIENTED_EDGE ( 'NONE', *, *, #23260, .F. ) ; +#31370 = ORIENTED_EDGE ( 'NONE', *, *, #24089, .F. ) ; +#31371 = FACE_OUTER_BOUND ( 'NONE', #10078, .T. ) ; +#31372 = CARTESIAN_POINT ( 'NONE', ( -35.44716532913142260, 113.1977046342314708, 87.28919349165808228 ) ) ; +#31373 = CARTESIAN_POINT ( 'NONE', ( 22.78078928741000198, 153.8098031069565650, 95.66210622461615287 ) ) ; +#31374 = CARTESIAN_POINT ( 'NONE', ( 2.939226598809902669, 209.7173956323443917, 73.05673022523419036 ) ) ; +#31375 = EDGE_CURVE ( 'NONE', #27269, #18813, #2641, .T. ) ; +#31376 = ORIENTED_EDGE ( 'NONE', *, *, #10745, .F. ) ; +#31377 = ADVANCED_FACE ( 'NONE', ( #28930 ), #28733, .T. ) ; +#31378 = EDGE_LOOP ( 'NONE', ( #11916, #22014, #39042, #39326, #28987 ) ) ; +#31379 = CARTESIAN_POINT ( 'NONE', ( 25.99026500172996990, 210.1701206109333384, 73.04280661359497628 ) ) ; +#31380 = EDGE_CURVE ( 'NONE', #30585, #8845, #13395, .T. ) ; +#31381 = CARTESIAN_POINT ( 'NONE', ( 20.15421560565993531, 128.2853077194433524, 89.25774530750982194 ) ) ; +#31382 = ADVANCED_FACE ( 'NONE', ( #9729 ), #24978, .F. ) ; +#31383 = FACE_OUTER_BOUND ( 'NONE', #36242, .T. ) ; +#31384 = AXIS2_PLACEMENT_3D ( 'NONE', #30132, #4563, #20096 ) ; +#31385 = ORIENTED_EDGE ( 'NONE', *, *, #3031, .F. ) ; +#31386 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 92.27946979429643193, 322.5967026918627312 ) ) ; +#31387 = CARTESIAN_POINT ( 'NONE', ( -23.02004673814065683, 213.5902071504527839, 73.57250091739375364 ) ) ; +#31388 = PLANE ( 'NONE', #22836 ) ; +#31389 = AXIS2_PLACEMENT_3D ( 'NONE', #29371, #10171, #31845 ) ; +#31390 = EDGE_LOOP ( 'NONE', ( #12255, #36293, #627, #12114 ) ) ; +#31391 = ADVANCED_FACE ( 'NONE', ( #18901 ), #25687, .T. ) ; +#31392 = VECTOR ( 'NONE', #30768, 1000.000000000000114 ) ; +#31393 = CONICAL_SURFACE ( 'NONE', #26818, 2.249999999984611421, 0.7853981634347277918 ) ; +#31394 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921578520, 0.2249510932971594823 ) ) ; +#31395 = CARTESIAN_POINT ( 'NONE', ( 16.67763860462360981, 127.2204759592696917, 176.3528348589679524 ) ) ; +#31396 = EDGE_CURVE ( 'NONE', #20878, #31222, #19311, .T. ) ; +#31397 = CARTESIAN_POINT ( 'NONE', ( -0.3312283176345999780, 188.8545265543999960, 105.8569945315000069 ) ) ; +#31398 = DIRECTION ( 'NONE', ( -0.1634997390362193104, 0.3413656262119397766, -0.9256010720477901854 ) ) ; +#31399 = VERTEX_POINT ( 'NONE', #3563 ) ; +#31400 = CARTESIAN_POINT ( 'NONE', ( -42.83981852382991917, 113.7604137494400476, 123.0507168651698038 ) ) ; +#31401 = FACE_OUTER_BOUND ( 'NONE', #13927, .T. ) ; +#31402 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1115, #17604, #10541, #30102 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31403 = DIRECTION ( 'NONE', ( 0.6337890847338583100, -0.7735059121120007042, 0.000000000000000000 ) ) ; +#31404 = CARTESIAN_POINT ( 'NONE', ( 30.06995708078038376, 134.8478347390543490, 93.33259620325232220 ) ) ; +#31405 = EDGE_CURVE ( 'NONE', #23621, #18764, #24590, .T. ) ; +#31406 = DIRECTION ( 'NONE', ( -0.7855473026356898369, -0.6188014303620734680, 0.0004744508866335558125 ) ) ; +#31407 = VERTEX_POINT ( 'NONE', #35029 ) ; +#31408 = LINE ( 'NONE', #314, #28509 ) ; +#31409 = VERTEX_POINT ( 'NONE', #31600 ) ; +#31410 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 5.029100215316657124E-18, 0.0006039748319386160479 ) ) ; +#31411 = CARTESIAN_POINT ( 'NONE', ( 25.49273537670188361, 207.4083917605166789, 77.06627999559708542 ) ) ; +#31412 = CARTESIAN_POINT ( 'NONE', ( -38.35588822081000160, 118.5258381726000181, 89.84986101129000247 ) ) ; +#31413 = CIRCLE ( 'NONE', #18985, 22.50000000000898837 ) ; +#31414 = ORIENTED_EDGE ( 'NONE', *, *, #1415, .T. ) ; +#31415 = DIRECTION ( 'NONE', ( 0.6088160902985568779, -0.7729595817128234181, -0.1785397805306046526 ) ) ; +#31416 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1505, #23194, #29737, #4158 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31417 = VECTOR ( 'NONE', #36959, 1000.000000000000227 ) ; +#31418 = CARTESIAN_POINT ( 'NONE', ( 39.06422788861904394, 183.0561992322088543, 104.9700959750892366 ) ) ; +#31419 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; +#31420 = AXIS2_PLACEMENT_3D ( 'NONE', #26760, #10619, #4664 ) ; +#31421 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825977240376177, 0.0005734119010670563803 ) ) ; +#31422 = CARTESIAN_POINT ( 'NONE', ( 12.59458203848999958, 191.9910753069000293, 28.07991271570000080 ) ) ; +#31423 = LINE ( 'NONE', #30623, #34971 ) ; +#31424 = EDGE_LOOP ( 'NONE', ( #16121, #13189, #12499 ) ) ; +#31425 = EDGE_LOOP ( 'NONE', ( #20527, #21939, #34986, #20886, #33422, #8731, #4524 ) ) ; +#31426 = ORIENTED_EDGE ( 'NONE', *, *, #13926, .F. ) ; +#31427 = FACE_OUTER_BOUND ( 'NONE', #30653, .T. ) ; +#31428 = CARTESIAN_POINT ( 'NONE', ( -2.695352837891999975, 201.9934155195000187, 90.48001809261999995 ) ) ; +#31429 = VERTEX_POINT ( 'NONE', #31808 ) ; +#31430 = CARTESIAN_POINT ( 'NONE', ( -13.84340190104143353, 154.7500563556122017, 161.1767822654394422 ) ) ; +#31431 = EDGE_CURVE ( 'NONE', #26477, #9324, #23627, .T. ) ; +#31432 = ADVANCED_FACE ( 'NONE', ( #9935 ), #7308, .F. ) ; +#31433 = EDGE_LOOP ( 'NONE', ( #8214, #8148, #1255, #17 ) ) ; +#31434 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#31435 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#31436 = ORIENTED_EDGE ( 'NONE', *, *, #29174, .T. ) ; +#31437 = CARTESIAN_POINT ( 'NONE', ( 20.95020508879656163, 128.6695385774041256, 92.42488413635012989 ) ) ; +#31438 = ADVANCED_FACE ( 'NONE', ( #7039 ), #32006, .T. ) ; +#31439 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#31440 = CARTESIAN_POINT ( 'NONE', ( -5.663464557155529988, 131.0206703453534374, 89.90489628355439322 ) ) ; +#31441 = CIRCLE ( 'NONE', #11862, 5.000000000028509639 ) ; +#31442 = CARTESIAN_POINT ( 'NONE', ( 30.07023774425934803, 176.7457471811506764, 103.0054930552473564 ) ) ; +#31443 = CARTESIAN_POINT ( 'NONE', ( 44.24772793393911030, 122.2367175089034959, 90.92567871579780103 ) ) ; +#31444 = ORIENTED_EDGE ( 'NONE', *, *, #7321, .F. ) ; +#31446 = EDGE_CURVE ( 'NONE', #1973, #30753, #13196, .T. ) ; +#31445 = CARTESIAN_POINT ( 'NONE', ( -13.00577321180114865, 177.7894282964912804, 100.7067019652760678 ) ) ; +#31447 = AXIS2_PLACEMENT_3D ( 'NONE', #32510, #7157, #34941 ) ; +#31448 = CARTESIAN_POINT ( 'NONE', ( -37.84078032415512638, 119.0089722949934696, 87.29331153112032382 ) ) ; +#31449 = PLANE ( 'NONE', #22176 ) ; +#31450 = FACE_OUTER_BOUND ( 'NONE', #32777, .T. ) ; +#31451 = EDGE_LOOP ( 'NONE', ( #30718, #6959, #580, #10542 ) ) ; +#31452 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; +#31453 = CARTESIAN_POINT ( 'NONE', ( 19.43523103776308503, 149.2156397595460930, 181.3139216008023880 ) ) ; +#31454 = CARTESIAN_POINT ( 'NONE', ( -34.05013329931477273, 81.71494582553067687, 291.5791093625203985 ) ) ; +#31455 = LINE ( 'NONE', #3620, #20305 ) ; +#31456 = EDGE_CURVE ( 'NONE', #15358, #3283, #29538, .T. ) ; +#31457 = CARTESIAN_POINT ( 'NONE', ( 43.33709577780441435, 121.3453068284270699, 90.54570139316727762 ) ) ; +#31458 = CARTESIAN_POINT ( 'NONE', ( -26.29133475941970133, 188.3528585319050137, 105.7175370394109848 ) ) ; +#31459 = ORIENTED_EDGE ( 'NONE', *, *, #26361, .F. ) ; +#31460 = CARTESIAN_POINT ( 'NONE', ( -16.53001031479427141, 121.8780329720448066, 177.6173573199974953 ) ) ; +#31461 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 171.7660675377210282, 184.4841745997615021 ) ) ; +#31462 = VERTEX_POINT ( 'NONE', #9526 ) ; +#31463 = CARTESIAN_POINT ( 'NONE', ( -10.03596943924095797, 143.5372728157101676, 95.87608654283346254 ) ) ; +#31464 = CARTESIAN_POINT ( 'NONE', ( 20.33446643993600134, 127.3604678021566201, 89.38718315066802234 ) ) ; +#31465 = CARTESIAN_POINT ( 'NONE', ( 37.68745077890000772, 191.4215636083000049, 104.2998648217000124 ) ) ; +#31466 = CARTESIAN_POINT ( 'NONE', ( 36.09277602024999965, 191.9597434480999993, 106.5195528529000057 ) ) ; +#31467 = ORIENTED_EDGE ( 'NONE', *, *, #17259, .F. ) ; +#31468 = ORIENTED_EDGE ( 'NONE', *, *, #16990, .T. ) ; +#31469 = VECTOR ( 'NONE', #40227, 1000.000000000000114 ) ; +#31470 = DIRECTION ( 'NONE', ( 0.6096989917424270322, -0.7722987078273715333, -0.1783867858235026471 ) ) ; +#31471 = AXIS2_PLACEMENT_3D ( 'NONE', #30862, #31253, #12642 ) ; +#31472 = CARTESIAN_POINT ( 'NONE', ( 30.05382551810999914, 103.6131156702000027, 87.74963262557000121 ) ) ; +#31473 = CARTESIAN_POINT ( 'NONE', ( -23.36013624460098725, 136.6770260652199624, 94.30032095887112575 ) ) ; +#31474 = ORIENTED_EDGE ( 'NONE', *, *, #14785, .T. ) ; +#31475 = DIRECTION ( 'NONE', ( -0.0005884949961217841863, 0.2249510543439048882, -0.9743698870671267942 ) ) ; +#31476 = EDGE_CURVE ( 'NONE', #20455, #30422, #5070, .T. ) ; +#31478 = ADVANCED_FACE ( 'NONE', ( #37721 ), #26278, .F. ) ; +#31477 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32649, #20783, #5232, #14866 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31479 = ORIENTED_EDGE ( 'NONE', *, *, #24534, .T. ) ; +#31480 = CARTESIAN_POINT ( 'NONE', ( 39.77041188632269098, 161.5626287739675888, 197.5124357450602588 ) ) ; +#31481 = CARTESIAN_POINT ( 'NONE', ( 12.64209925790531308, 131.0231129754641302, 89.89439459407216759 ) ) ; +#31482 = ORIENTED_EDGE ( 'NONE', *, *, #2216, .F. ) ; +#31483 = CARTESIAN_POINT ( 'NONE', ( -18.79252570011861678, 125.8499160133713133, 175.1155745579973484 ) ) ; +#31484 = DIRECTION ( 'NONE', ( 0.1695469893270771522, -1.252670582138759957E-14, -0.9855221044756550253 ) ) ; +#31485 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; +#31486 = CARTESIAN_POINT ( 'NONE', ( 23.67925056556238772, 134.2473364980823476, 93.71096924780141535 ) ) ; +#31487 = ORIENTED_EDGE ( 'NONE', *, *, #31240, .F. ) ; +#31488 = ORIENTED_EDGE ( 'NONE', *, *, #3985, .F. ) ; +#31489 = CARTESIAN_POINT ( 'NONE', ( -25.50922756583905837, 191.3757872987501969, 104.3640622938216183 ) ) ; +#31490 = CARTESIAN_POINT ( 'NONE', ( 1.316320443139440188, 189.1529878064920069, 103.7382684573219933 ) ) ; +#31491 = CARTESIAN_POINT ( 'NONE', ( -22.49967939491756752, 153.8038087509543743, 95.68807059495395606 ) ) ; +#31492 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #23923, #30459 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31493 = ORIENTED_EDGE ( 'NONE', *, *, #7014, .T. ) ; +#31494 = VERTEX_POINT ( 'NONE', #27490 ) ; +#31495 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748615741, 179.1800746285439345, 103.5747911658197893 ) ) ; +#31496 = ORIENTED_EDGE ( 'NONE', *, *, #30970, .F. ) ; +#31497 = CIRCLE ( 'NONE', #13857, 6.000000000128157041 ) ; +#31498 = AXIS2_PLACEMENT_3D ( 'NONE', #27375, #11813, #17511 ) ; +#31499 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566235 ) ) ; +#31500 = DIRECTION ( 'NONE', ( -0.0005884949961204411851, 0.2249510543439063592, -0.9743698870671264611 ) ) ; +#31501 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#31502 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #33429, #1545, #20141, #17476 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.570796326794964726, 3.376412948467386599 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7462717963450533620, 0.7462717963450533620, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#31503 = CARTESIAN_POINT ( 'NONE', ( -39.73142568412256992, 175.7232364642230777, 136.1664758066176830 ) ) ; +#31504 = CARTESIAN_POINT ( 'NONE', ( -3.088327906531000089, 208.7573243651999917, 73.01289067924000165 ) ) ; +#31505 = CARTESIAN_POINT ( 'NONE', ( -1.935624522227932909, 189.6762913120315943, 105.9337518142968975 ) ) ; +#31506 = VERTEX_POINT ( 'NONE', #8865 ) ; +#31507 = EDGE_CURVE ( 'NONE', #5465, #23779, #18028, .T. ) ; +#31508 = CARTESIAN_POINT ( 'NONE', ( -35.95487748704000097, 206.4002260771000010, 76.08022047462002035 ) ) ; +#31509 = CARTESIAN_POINT ( 'NONE', ( -36.58309918135517336, 191.3840766415999042, 106.3867753853837712 ) ) ; +#31510 = CARTESIAN_POINT ( 'NONE', ( -45.15281646518302239, 105.2939582111126242, 174.2284691125232143 ) ) ; +#31511 = CARTESIAN_POINT ( 'NONE', ( -2.455538055765680738, 209.0000002601700544, 73.61629604161946361 ) ) ; +#31512 = ORIENTED_EDGE ( 'NONE', *, *, #33213, .T. ) ; +#31513 = EDGE_CURVE ( 'NONE', #31352, #8754, #40313, .T. ) ; +#31514 = ORIENTED_EDGE ( 'NONE', *, *, #18529, .T. ) ; +#31515 = CARTESIAN_POINT ( 'NONE', ( 25.53626815854681098, 191.3673954314083119, 104.3312944428767253 ) ) ; +#31516 = CIRCLE ( 'NONE', #7360, 51.40509898897001051 ) ; +#31517 = CARTESIAN_POINT ( 'NONE', ( 22.61860768848664449, 115.1133264115357377, 87.25412321976182284 ) ) ; +#31518 = DIRECTION ( 'NONE', ( 0.9914447019871154287, -0.1270494721560660734, -0.02993049492649695054 ) ) ; +#31519 = FACE_OUTER_BOUND ( 'NONE', #18531, .T. ) ; +#31520 = EDGE_CURVE ( 'NONE', #18145, #19730, #16723, .T. ) ; +#31521 = ORIENTED_EDGE ( 'NONE', *, *, #17029, .T. ) ; +#31522 = AXIS2_PLACEMENT_3D ( 'NONE', #25519, #22250, #22847 ) ; +#31523 = EDGE_CURVE ( 'NONE', #28425, #7038, #2725, .T. ) ; +#31524 = VERTEX_POINT ( 'NONE', #25207 ) ; +#31525 = EDGE_CURVE ( 'NONE', #7165, #17944, #15771, .T. ) ; +#31526 = CARTESIAN_POINT ( 'NONE', ( 12.63633280683901106, 127.9124608697227927, 92.25512031180861072 ) ) ; +#31527 = AXIS2_PLACEMENT_3D ( 'NONE', #24982, #31500, #5951 ) ; +#31528 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18295, #2963, #12566, #24471, #37516, #14855, #2583, #24875, #21997, #27553 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999779066, 0.3749999999999668598, 0.4374999999999613642, 0.4999999999999558131, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31529 = CARTESIAN_POINT ( 'NONE', ( -20.33397659309266814, 196.2711692071578682, 103.7581375276250242 ) ) ; +#31530 = CARTESIAN_POINT ( 'NONE', ( -35.95425951663850839, 207.4083918145487075, 77.10339231471580490 ) ) ; +#31531 = CARTESIAN_POINT ( 'NONE', ( 21.21457940375938378, 183.3621723504481906, 102.4857529904703028 ) ) ; +#31532 = VERTEX_POINT ( 'NONE', #21119 ) ; +#31533 = CARTESIAN_POINT ( 'NONE', ( -45.92783482638418491, 124.8424006619797098, 91.58171271578800088 ) ) ; +#31534 = VERTEX_POINT ( 'NONE', #6372 ) ; +#31535 = ORIENTED_EDGE ( 'NONE', *, *, #40461, .T. ) ; +#31536 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#31537 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#31538 = CARTESIAN_POINT ( 'NONE', ( 42.51832847222295442, 128.8459892653891075, 92.45259438658834483 ) ) ; +#31539 = ORIENTED_EDGE ( 'NONE', *, *, #9784, .F. ) ; +#31540 = CARTESIAN_POINT ( 'NONE', ( -2.436965057049000016, 190.9999858852999921, 104.2634334619999947 ) ) ; +#31541 = CARTESIAN_POINT ( 'NONE', ( 3.064870483804259305, 190.8403612114580028, 103.7100415233180826 ) ) ; +#31542 = CARTESIAN_POINT ( 'NONE', ( -26.00969531629161224, 206.5435593458424535, 74.17353529082527075 ) ) ; +#31543 = LINE ( 'NONE', #9669, #7702 ) ; +#31544 = ORIENTED_EDGE ( 'NONE', *, *, #39138, .T. ) ; +#31545 = EDGE_LOOP ( 'NONE', ( #9504, #2766, #28274, #8156, #11149, #8574 ) ) ; +#31546 = PLANE ( 'NONE', #9401 ) ; +#31547 = CARTESIAN_POINT ( 'NONE', ( 42.97429946896744468, 67.83849343097567441, 322.0145824706445978 ) ) ; +#31548 = ORIENTED_EDGE ( 'NONE', *, *, #2120, .T. ) ; +#31549 = LINE ( 'NONE', #22556, #36950 ) ; +#31550 = CARTESIAN_POINT ( 'NONE', ( -25.99225322733968113, 193.8169247290872761, 102.7186084094945926 ) ) ; +#31551 = CARTESIAN_POINT ( 'NONE', ( -25.62183731277999854, 120.1108274837000209, 90.08866940772999499 ) ) ; +#31552 = AXIS2_PLACEMENT_3D ( 'NONE', #32171, #32367, #4127 ) ; +#31553 = ORIENTED_EDGE ( 'NONE', *, *, #7861, .F. ) ; +#31554 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; +#31555 = VECTOR ( 'NONE', #37307, 1000.000000000000227 ) ; +#31556 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #64, #5994 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31557 = CARTESIAN_POINT ( 'NONE', ( 26.00061531446862517, 118.3483399336666793, 90.25208111907872421 ) ) ; +#31558 = DIRECTION ( 'NONE', ( -0.0005884949961189803310, 0.2249510543439054433, -0.9743698870671265722 ) ) ; +#31559 = CIRCLE ( 'NONE', #13257, 2.499999999488756064 ) ; +#31560 = EDGE_LOOP ( 'NONE', ( #17440, #23140, #33137, #12355, #39249, #4649, #10972, #24497 ) ) ; +#31561 = ADVANCED_FACE ( 'NONE', ( #18825 ), #16445, .F. ) ; +#31562 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; +#31563 = CARTESIAN_POINT ( 'NONE', ( 35.87847517210509096, 209.7096558782537556, 73.37016786902755427 ) ) ; +#31565 = DIRECTION ( 'NONE', ( 0.6087613186456907188, 0.7730177010543248795, 0.1784749023741044327 ) ) ; +#31564 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775456658 ) ) ; +#31566 = VERTEX_POINT ( 'NONE', #12314 ) ; +#31567 = ADVANCED_FACE ( 'NONE', ( #21735 ), #33979, .T. ) ; +#31568 = ORIENTED_EDGE ( 'NONE', *, *, #28907, .T. ) ; +#31569 = CARTESIAN_POINT ( 'NONE', ( -35.95517947438523976, 209.7096537232000344, 75.58022056590567672 ) ) ; +#31570 = EDGE_CURVE ( 'NONE', #17481, #31838, #27499, .T. ) ; +#31571 = CARTESIAN_POINT ( 'NONE', ( 39.11549366608129930, 162.5504968431983457, 191.0044786453397307 ) ) ; +#31572 = LINE ( 'NONE', #30969, #1852 ) ; +#31573 = EDGE_LOOP ( 'NONE', ( #4263, #6141, #2969, #8394, #32579, #320, #25107 ) ) ; +#31574 = EDGE_CURVE ( 'NONE', #24177, #32425, #40115, .T. ) ; +#31575 = ORIENTED_EDGE ( 'NONE', *, *, #19557, .F. ) ; +#31576 = ADVANCED_FACE ( 'NONE', ( #9457 ), #28074, .T. ) ; +#31577 = CARTESIAN_POINT ( 'NONE', ( 44.93626489333781393, 188.5078210156812304, 105.6925916894777799 ) ) ; +#31578 = EDGE_CURVE ( 'NONE', #3435, #2188, #15389, .T. ) ; +#31579 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#31580 = LINE ( 'NONE', #25456, #20685 ) ; +#31581 = CARTESIAN_POINT ( 'NONE', ( 33.54411937952203715, 218.5902260770999987, 73.03824427483441184 ) ) ; +#31582 = AXIS2_PLACEMENT_3D ( 'NONE', #8387, #20845, #29856 ) ; +#31583 = VERTEX_POINT ( 'NONE', #9056 ) ; +#31584 = EDGE_LOOP ( 'NONE', ( #5632, #21696, #13614, #18805, #39653 ) ) ; +#31585 = CARTESIAN_POINT ( 'NONE', ( -8.048542123480551425, 150.7617452742509556, 97.54278737913534769 ) ) ; +#31586 = CARTESIAN_POINT ( 'NONE', ( 20.41579965800398000, 128.8293016962263380, 89.38317824560692770 ) ) ; +#31587 = AXIS2_PLACEMENT_3D ( 'NONE', #34954, #6368, #19437 ) ; +#31588 = CARTESIAN_POINT ( 'NONE', ( -20.49874983313576848, 118.1134457197417902, 89.11340909896085805 ) ) ; +#31589 = VERTEX_POINT ( 'NONE', #37457 ) ; +#31590 = ORIENTED_EDGE ( 'NONE', *, *, #11233, .T. ) ; +#31591 = CONICAL_SURFACE ( 'NONE', #4122, 6.499999999937051243, 0.7853981633647675320 ) ; +#31592 = CARTESIAN_POINT ( 'NONE', ( 26.00820986244454858, 193.8169247290949784, 102.6872014327978775 ) ) ; +#31593 = ORIENTED_EDGE ( 'NONE', *, *, #39682, .F. ) ; +#31594 = LINE ( 'NONE', #13385, #4599 ) ; +#31595 = ORIENTED_EDGE ( 'NONE', *, *, #26500, .T. ) ; +#31596 = FACE_OUTER_BOUND ( 'NONE', #4245, .T. ) ; +#31597 = CARTESIAN_POINT ( 'NONE', ( -26.00143740904770695, 120.6419526453365165, 87.52101428342558620 ) ) ; +#31598 = CARTESIAN_POINT ( 'NONE', ( 16.99952089899044694, 136.5640433068810182, 181.4726123975704297 ) ) ; +#31599 = VERTEX_POINT ( 'NONE', #21935 ) ; +#31600 = CARTESIAN_POINT ( 'NONE', ( -35.43806428669827824, 192.3002664666033468, 103.9163745585288297 ) ) ; +#31601 = DIRECTION ( 'NONE', ( -0.7933533411653073131, 0.5930537057989939687, 0.1373964268091565077 ) ) ; +#31602 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #10101, #873 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31603 = CARTESIAN_POINT ( 'NONE', ( 19.98430243908310899, 211.4692376108927760, 73.04643406448599308 ) ) ; +#31604 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250612370, 132.8554482850432237, 90.84904174543585498 ) ) ; +#31605 = CARTESIAN_POINT ( 'NONE', ( -24.42746480248211682, 109.6131156702000027, 87.78253795969705209 ) ) ; +#31606 = ORIENTED_EDGE ( 'NONE', *, *, #34752, .T. ) ; +#31607 = AXIS2_PLACEMENT_3D ( 'NONE', #8426, #37233, #5751 ) ; +#31608 = AXIS2_PLACEMENT_3D ( 'NONE', #14286, #24104, #23480 ) ; +#31609 = CARTESIAN_POINT ( 'NONE', ( -30.07831637853678686, 134.9151858147922667, 90.81876078434068233 ) ) ; +#31610 = EDGE_CURVE ( 'NONE', #16151, #40272, #4041, .T. ) ; +#31611 = ORIENTED_EDGE ( 'NONE', *, *, #6390, .F. ) ; +#31612 = ADVANCED_FACE ( 'NONE', ( #22133 ), #27612, .F. ) ; +#31614 = ADVANCED_FACE ( 'NONE', ( #32334 ), #22540, .F. ) ; +#31613 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319387940739 ) ) ; +#31615 = AXIS2_PLACEMENT_3D ( 'NONE', #9037, #24991, #34544 ) ; +#31616 = CARTESIAN_POINT ( 'NONE', ( 21.70246180708700123, 182.6954656095747396, 102.1604887804233641 ) ) ; +#31618 = ORIENTED_EDGE ( 'NONE', *, *, #9588, .F. ) ; +#31617 = EDGE_CURVE ( 'NONE', #11920, #22363, #15805, .T. ) ; +#31619 = FACE_OUTER_BOUND ( 'NONE', #23723, .T. ) ; +#31620 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#31621 = ORIENTED_EDGE ( 'NONE', *, *, #33114, .T. ) ; +#31622 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#31623 = EDGE_CURVE ( 'NONE', #32971, #34336, #18671, .T. ) ; +#31624 = FACE_OUTER_BOUND ( 'NONE', #23521, .T. ) ; +#31625 = FACE_OUTER_BOUND ( 'NONE', #2858, .T. ) ; +#31626 = CARTESIAN_POINT ( 'NONE', ( -21.61917713407146380, 158.4572069570291148, 96.24870846027548055 ) ) ; +#31627 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #3880, #13905 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31628 = DIRECTION ( 'NONE', ( -0.0006039748319383739456, 3.094196748328522329E-15, -0.9999998176071845934 ) ) ; +#31629 = ORIENTED_EDGE ( 'NONE', *, *, #19046, .F. ) ; +#31630 = ORIENTED_EDGE ( 'NONE', *, *, #39389, .T. ) ; +#31631 = EDGE_CURVE ( 'NONE', #4072, #36231, #34956, .T. ) ; +#31632 = PLANE ( 'NONE', #34136 ) ; +#31633 = CARTESIAN_POINT ( 'NONE', ( -45.25641640995738868, 187.0376772300918162, 105.9402203223797585 ) ) ; +#31634 = VERTEX_POINT ( 'NONE', #22935 ) ; +#31635 = CARTESIAN_POINT ( 'NONE', ( -38.93802797675191840, 191.1637323145700122, 103.9811187850653340 ) ) ; +#31636 = DIRECTION ( 'NONE', ( 0.0006039748319385305044, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#31637 = ORIENTED_EDGE ( 'NONE', *, *, #39187, .T. ) ; +#31638 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385907860 ) ) ; +#31639 = ADVANCED_FACE ( 'NONE', ( #16771 ), #20388, .F. ) ; +#31640 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#31641 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825930922507203, 0.0005734119021363929484 ) ) ; +#31642 = ORIENTED_EDGE ( 'NONE', *, *, #28380, .F. ) ; +#31643 = CARTESIAN_POINT ( 'NONE', ( 28.08889367328000120, 125.1496492417999917, 88.70009216949001996 ) ) ; +#31644 = VECTOR ( 'NONE', #33899, 1000.000000000000000 ) ; +#31645 = AXIS2_PLACEMENT_3D ( 'NONE', #18135, #33887, #15097 ) ; +#31646 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971537924 ) ) ; +#31647 = CARTESIAN_POINT ( 'NONE', ( 30.02511232208999914, 191.9910753069000293, 28.07991271570000080 ) ) ; +#31648 = AXIS2_PLACEMENT_3D ( 'NONE', #34895, #19379, #31874 ) ; +#31649 = FACE_OUTER_BOUND ( 'NONE', #9341, .T. ) ; +#31650 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319379894875 ) ) ; +#31651 = VERTEX_POINT ( 'NONE', #9865 ) ; +#31652 = FACE_OUTER_BOUND ( 'NONE', #10686, .T. ) ; +#31653 = CARTESIAN_POINT ( 'NONE', ( 1.085475968734386676, 189.0695496040855517, 103.7041505517462241 ) ) ; +#31654 = CARTESIAN_POINT ( 'NONE', ( -2.849829047465823884, 190.2190360668230653, 106.6490825001534404 ) ) ; +#31655 = CARTESIAN_POINT ( 'NONE', ( 12.63720056867337682, 130.2028334981800981, 92.58456458875848227 ) ) ; +#31656 = DIRECTION ( 'NONE', ( 0.0005884949961256158652, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#31657 = CARTESIAN_POINT ( 'NONE', ( 32.37049208056998140, 174.4092940747139551, 99.89893022217735563 ) ) ; +#31658 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#31659 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #23053, #19565, #20162, #39180 ), + ( #16883, #11183, #10587, #35684 ), + ( #32062, #32255, #14255, #10388 ), + ( #1567, #20366, #29193, #32648 ), + ( #4022, #32843, #16489, #32454 ), + ( #1777, #19953, #4627, #7487 ), + ( #23656, #7288, #29389, #36103 ), + ( #13639, #26526, #28981, #16692 ), + ( #4824, #26130, #38762, #14049 ), + ( #958, #1161, #13447, #38376 ), + ( #17087, #22855, #17289, #4425 ), + ( #38568, #1357, #35477, #13838 ), + ( #10782, #29587, #23246, #38979 ), + ( #10985, #15261, #8113, #21198 ), + ( #20992, #39376, #33848, #33651 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.01205588739532000020, 0.000000000000000000, 0.01570492664887999934, 0.03132662402703000060, 0.06257001878335000100, 0.1250568082959999938, 0.1875435978084999955, 0.2500303873211999761, 0.3750039663465000173, 0.4999775453717000273, 0.7499247034221999675, 1.000000000000000000, 1.559246406558000064 ), + ( -0.2722091963193000175, 1.270754018114000017 ), + .UNSPECIFIED. ) ; +#31660 = DIRECTION ( 'NONE', ( 0.7692168386926722112, 0.6301897592057729147, -0.1056708212508138262 ) ) ; +#31661 = CARTESIAN_POINT ( 'NONE', ( -25.53897216374099699, 190.4810016023160131, 106.2066927615159955 ) ) ; +#31662 = ORIENTED_EDGE ( 'NONE', *, *, #6808, .T. ) ; +#31663 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#31664 = EDGE_CURVE ( 'NONE', #30923, #27237, #31497, .T. ) ; +#31665 = ADVANCED_FACE ( 'NONE', ( #19641 ), #9966, .F. ) ; +#31666 = EDGE_CURVE ( 'NONE', #16952, #1321, #28859, .T. ) ; +#31667 = CONICAL_SURFACE ( 'NONE', #32327, 2.503079361083045296, 0.7853981633955212649 ) ; +#31668 = CARTESIAN_POINT ( 'NONE', ( 20.48673967653602901, 211.0896571907997554, 75.54495990469186495 ) ) ; +#31669 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17321, #17529, #5471, #1601 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31670 = CARTESIAN_POINT ( 'NONE', ( 14.24259403095196319, 124.1280741090887574, 175.6403682132716426 ) ) ; +#31671 = CARTESIAN_POINT ( 'NONE', ( 31.79177788329871746, 115.2378434783073544, 176.5461507620590567 ) ) ; +#31672 = AXIS2_PLACEMENT_3D ( 'NONE', #16244, #712, #28146 ) ; +#31673 = CIRCLE ( 'NONE', #36204, 51.90509898893394336 ) ; +#31674 = ORIENTED_EDGE ( 'NONE', *, *, #27808, .F. ) ; +#31675 = FACE_OUTER_BOUND ( 'NONE', #14857, .T. ) ; +#31676 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490303348942, 156.2427122711440575, 96.23754757945233962 ) ) ; +#31677 = EDGE_CURVE ( 'NONE', #29541, #11287, #1035, .T. ) ; +#31678 = CARTESIAN_POINT ( 'NONE', ( 28.18621395003418328, 187.0539859719742140, 103.3338670887423376 ) ) ; +#31679 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178570903572E-05, -0.0002331579774915885982 ) ) ; +#31680 = AXIS2_PLACEMENT_3D ( 'NONE', #32417, #20328, #29547 ) ; +#31681 = CARTESIAN_POINT ( 'NONE', ( 3.600895702622226136, 143.5595025811426524, 95.80631016907535979 ) ) ; +#31682 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971544308 ) ) ; +#31683 = ORIENTED_EDGE ( 'NONE', *, *, #38832, .T. ) ; +#31684 = EDGE_LOOP ( 'NONE', ( #12976, #339 ) ) ; +#31685 = EDGE_CURVE ( 'NONE', #3241, #16069, #9656, .T. ) ; +#31686 = DIRECTION ( 'NONE', ( -0.2342984846413009858, -0.04020344573792828530, 0.9713330546447944691 ) ) ; +#31687 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6352, #37834, #27657, #28055 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31688 = FACE_OUTER_BOUND ( 'NONE', #34365, .T. ) ; +#31689 = CARTESIAN_POINT ( 'NONE', ( -38.20586753382468004, 218.5902260770999987, 73.08157946901140178 ) ) ; +#31690 = CARTESIAN_POINT ( 'NONE', ( 41.37348633212936022, 109.4896380203848025, 169.0614224528716818 ) ) ; +#31691 = VERTEX_POINT ( 'NONE', #31531 ) ; +#31692 = CARTESIAN_POINT ( 'NONE', ( -16.85990575305292083, 127.4181457678018035, 171.9189068126523807 ) ) ; +#31693 = ORIENTED_EDGE ( 'NONE', *, *, #3475, .F. ) ; +#31694 = CARTESIAN_POINT ( 'NONE', ( -25.99734782917291298, 118.8155664120999973, 94.28348731542803307 ) ) ; +#31695 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34670, #13029, #6670, #25513 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31696 = CYLINDRICAL_SURFACE ( 'NONE', #14457, 6.000000000000008882 ) ; +#31697 = EDGE_LOOP ( 'NONE', ( #4446, #22174, #16300, #32549 ) ) ; +#31698 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -1.674357682623054533E-18, 0.0006039748319388627039 ) ) ; +#31699 = DIRECTION ( 'NONE', ( 0.0006039748319387941823, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#31700 = FACE_OUTER_BOUND ( 'NONE', #16857, .T. ) ; +#31701 = CARTESIAN_POINT ( 'NONE', ( 75.33557036604483415, 196.2212959549355560, 191.1727427149328093 ) ) ; +#31702 = CIRCLE ( 'NONE', #10160, 7.499999999987333688 ) ; +#31703 = ORIENTED_EDGE ( 'NONE', *, *, #10031, .F. ) ; +#31704 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; +#31705 = CARTESIAN_POINT ( 'NONE', ( 42.83485424785748563, 120.8183422764421948, 92.52881085981866249 ) ) ; +#31706 = AXIS2_PLACEMENT_3D ( 'NONE', #20246, #35559, #32733 ) ; +#31707 = CIRCLE ( 'NONE', #23193, 2.749999999872844381 ) ; +#31708 = PLANE ( 'NONE', #14285 ) ; +#31709 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#31710 = CIRCLE ( 'NONE', #12119, 6.000000000000007994 ) ; +#31711 = VERTEX_POINT ( 'NONE', #3490 ) ; +#31712 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#31713 = VERTEX_POINT ( 'NONE', #13524 ) ; +#31714 = CARTESIAN_POINT ( 'NONE', ( 12.68911377202444690, 149.1576569327452830, 181.5431584767406719 ) ) ; +#31715 = DIRECTION ( 'NONE', ( -0.0005884949961257719903, 0.2249510543439054711, -0.9743698870671265722 ) ) ; +#31716 = ADVANCED_FACE ( 'NONE', ( #19828 ), #11185, .F. ) ; +#31717 = ADVANCED_FACE ( 'NONE', ( #437 ), #38055, .F. ) ; +#31718 = CARTESIAN_POINT ( 'NONE', ( -12.63071249806800722, 177.0758676880871292, 103.5673281599171816 ) ) ; +#31719 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#31720 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384538513 ) ) ; +#31721 = CARTESIAN_POINT ( 'NONE', ( 38.14137417362000093, 118.9128982934000049, 90.39730654139999899 ) ) ; +#31722 = ORIENTED_EDGE ( 'NONE', *, *, #36736, .F. ) ; +#31723 = CARTESIAN_POINT ( 'NONE', ( 30.05533549523401149, 104.1131156702010969, 90.24963216969922541 ) ) ; +#31724 = CARTESIAN_POINT ( 'NONE', ( 35.04494061520995274, 225.9002260770261330, 73.03733781633900435 ) ) ; +#31725 = DIRECTION ( 'NONE', ( 0.0005884962718225328912, -0.2249510543436811782, 0.9743698870664077027 ) ) ; +#31726 = ORIENTED_EDGE ( 'NONE', *, *, #8299, .T. ) ; +#31727 = CIRCLE ( 'NONE', #14654, 22.50000000000000000 ) ; +#31728 = AXIS2_PLACEMENT_3D ( 'NONE', #27999, #40434, #18744 ) ; +#31729 = VERTEX_POINT ( 'NONE', #31743 ) ; +#31730 = FACE_OUTER_BOUND ( 'NONE', #5257, .T. ) ; +#31731 = CARTESIAN_POINT ( 'NONE', ( 28.46511207851075653, 181.6173849797036439, 104.1311689223658448 ) ) ; +#31732 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989907490, 0.1373964268091706076 ) ) ; +#31733 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384538513 ) ) ; +#31734 = VECTOR ( 'NONE', #21792, 1000.000000000000000 ) ; +#31735 = ORIENTED_EDGE ( 'NONE', *, *, #31525, .T. ) ; +#31736 = ORIENTED_EDGE ( 'NONE', *, *, #11651, .T. ) ; +#31737 = PLANE ( 'NONE', #25061 ) ; +#31738 = ADVANCED_FACE ( 'NONE', ( #16178 ), #3700, .F. ) ; +#31739 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22651, #32245, #19357, #18947 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.004218741086469320230, 0.004610302917384741239 ), + .UNSPECIFIED. ) ; +#31740 = CARTESIAN_POINT ( 'NONE', ( -38.60375092211999970, 119.0085671394000002, 90.10761541063000379 ) ) ; +#31741 = CARTESIAN_POINT ( 'NONE', ( -38.04037173331000332, 119.2271231706999970, 87.30284227318999513 ) ) ; +#31742 = CARTESIAN_POINT ( 'NONE', ( -23.36190354062885888, 137.3525714946963774, 91.37421276297489214 ) ) ; +#31743 = CARTESIAN_POINT ( 'NONE', ( 16.57242805487306470, 121.7393926975746155, 178.0454114939713861 ) ) ; +#31744 = ORIENTED_EDGE ( 'NONE', *, *, #37515, .T. ) ; +#31745 = CARTESIAN_POINT ( 'NONE', ( -19.40399956016737804, 125.0084816723671395, 177.4278432361402054 ) ) ; +#31746 = ORIENTED_EDGE ( 'NONE', *, *, #3356, .F. ) ; +#31747 = CARTESIAN_POINT ( 'NONE', ( -20.01736593119981222, 207.8686407175673594, 77.28911966098117148 ) ) ; +#31748 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; +#31749 = ORIENTED_EDGE ( 'NONE', *, *, #6316, .T. ) ; +#31750 = VERTEX_POINT ( 'NONE', #10057 ) ; +#31751 = FACE_OUTER_BOUND ( 'NONE', #6784, .T. ) ; +#31752 = CARTESIAN_POINT ( 'NONE', ( 0.8901324790414124610, 188.6335715761424865, 103.2018773863535728 ) ) ; +#31753 = LINE ( 'NONE', #38659, #26028 ) ; +#31754 = EDGE_CURVE ( 'NONE', #9013, #15229, #15746, .T. ) ; +#31755 = ORIENTED_EDGE ( 'NONE', *, *, #11696, .T. ) ; +#31756 = CARTESIAN_POINT ( 'NONE', ( 20.32319569345560595, 118.1108005801726506, 87.57833703372055822 ) ) ; +#31757 = CARTESIAN_POINT ( 'NONE', ( -42.83388826220544132, 121.9349074780233195, 87.82968285981074530 ) ) ; +#31758 = ORIENTED_EDGE ( 'NONE', *, *, #38166, .T. ) ; +#31759 = VECTOR ( 'NONE', #20788, 1000.000000000000000 ) ; +#31760 = EDGE_CURVE ( 'NONE', #4754, #7856, #11063, .T. ) ; +#31761 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319411731388 ) ) ; +#31762 = CARTESIAN_POINT ( 'NONE', ( -25.82554725903140636, 193.9703421726525789, 102.7836296653337484 ) ) ; +#31763 = CARTESIAN_POINT ( 'NONE', ( -26.05208678994999971, 122.4317902912000022, 90.62476585039999577 ) ) ; +#31764 = CIRCLE ( 'NONE', #21955, 5.499999999957825736 ) ; +#31765 = ORIENTED_EDGE ( 'NONE', *, *, #9416, .T. ) ; +#31766 = EDGE_CURVE ( 'NONE', #10320, #29452, #35247, .T. ) ; +#31767 = CARTESIAN_POINT ( 'NONE', ( -16.54564866400918532, 121.8302699986925148, 177.5519171002900407 ) ) ; +#31768 = EDGE_CURVE ( 'NONE', #24320, #13773, #26026, .T. ) ; +#31769 = CARTESIAN_POINT ( 'NONE', ( 22.15443392043009752, 115.2196822810860510, 152.7520160474520026 ) ) ; +#31770 = CARTESIAN_POINT ( 'NONE', ( 39.72476718210158708, 169.1831314395676031, 164.4948153179034307 ) ) ; +#31771 = EDGE_LOOP ( 'NONE', ( #34811, #22401, #23761, #3318 ) ) ; +#31772 = CARTESIAN_POINT ( 'NONE', ( -15.49839344145972397, 153.4668451609490205, 95.09289564923821558 ) ) ; +#31773 = LINE ( 'NONE', #33708, #4784 ) ; +#31774 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26802, #4903, #14529, #33320, #17356, #27011, #21072, #1848, #33515, #14327, #5310, #30680, #11251, #2059, #17767, #2673, #39449 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000001060818, 0.1875000000001437184, 0.2187500000001966760, 0.2343750000002728651, 0.2500000000003490541, 0.3750000000003807510, 0.4375000000003967382, 0.4687500000004181100, 0.5000000000004395373, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31776 = CARTESIAN_POINT ( 'NONE', ( -13.49899752757120019, 187.7917310252263974, 103.4871798716026916 ) ) ; +#31775 = DIRECTION ( 'NONE', ( -1.387778780819091104E-15, 0.9743700557921587402, 0.2249510932971557908 ) ) ; +#31777 = ORIENTED_EDGE ( 'NONE', *, *, #23760, .T. ) ; +#31778 = DIRECTION ( 'NONE', ( 0.0005884949961233809992, -0.2249510543439078580, 0.9743698870671259060 ) ) ; +#31779 = ORIENTED_EDGE ( 'NONE', *, *, #27414, .T. ) ; +#31780 = FACE_OUTER_BOUND ( 'NONE', #14253, .T. ) ; +#31781 = VECTOR ( 'NONE', #28318, 1000.000000000000227 ) ; +#31782 = CARTESIAN_POINT ( 'NONE', ( 21.72804141255551968, 135.8412665901933281, 91.00123227078390187 ) ) ; +#31783 = ORIENTED_EDGE ( 'NONE', *, *, #121, .F. ) ; +#31784 = CIRCLE ( 'NONE', #33713, 5.499999999909167769 ) ; +#31785 = AXIS2_PLACEMENT_3D ( 'NONE', #26337, #19571, #14265 ) ; +#31786 = ORIENTED_EDGE ( 'NONE', *, *, #18216, .F. ) ; +#31787 = CARTESIAN_POINT ( 'NONE', ( 45.19898052048043979, 188.2352433429451537, 105.6199565309152746 ) ) ; +#31788 = CARTESIAN_POINT ( 'NONE', ( 21.44693687352840783, 182.5616219828937687, 101.7876413893260974 ) ) ; +#31789 = CARTESIAN_POINT ( 'NONE', ( 29.78094669178764065, 126.4966683339110460, 91.40475166325242640 ) ) ; +#31790 = CARTESIAN_POINT ( 'NONE', ( 35.83803577802999740, 191.9457902004000118, 104.0590614479000067 ) ) ; +#31791 = AXIS2_PLACEMENT_3D ( 'NONE', #19392, #22280, #35105 ) ; +#31792 = VERTEX_POINT ( 'NONE', #29466 ) ; +#31793 = ORIENTED_EDGE ( 'NONE', *, *, #21396, .T. ) ; +#31794 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 136.7477301991403920, 291.5295797804309359 ) ) ; +#31795 = CARTESIAN_POINT ( 'NONE', ( -23.36591346911345468, 134.3034081359250251, 93.69901219035510564 ) ) ; +#31796 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971570953 ) ) ; +#31797 = VERTEX_POINT ( 'NONE', #4911 ) ; +#31798 = CARTESIAN_POINT ( 'NONE', ( 39.05618840431949934, 127.6228066749279577, 91.65913928136414768 ) ) ; +#31799 = ORIENTED_EDGE ( 'NONE', *, *, #18682, .F. ) ; +#31800 = EDGE_CURVE ( 'NONE', #16377, #1321, #19844, .T. ) ; +#31801 = DIRECTION ( 'NONE', ( -0.5987319960703951782, -0.8009494346596170988, 0.000000000000000000 ) ) ; +#31802 = DIRECTION ( 'NONE', ( 7.677760455957277161E-18, -1.000000000000000000, 1.271205131337255403E-14 ) ) ; +#31803 = ADVANCED_FACE ( 'NONE', ( #23132 ), #10786, .F. ) ; +#31804 = CARTESIAN_POINT ( 'NONE', ( -48.18910981145552341, 141.1918910709570980, 290.9667924317506049 ) ) ; +#31805 = CARTESIAN_POINT ( 'NONE', ( -75.43109585695218300, 195.4393986266478578, 195.0604493770005945 ) ) ; +#31806 = CONICAL_SURFACE ( 'NONE', #17413, 2.499999999939590101, 0.7853981634430725611 ) ; +#31807 = ORIENTED_EDGE ( 'NONE', *, *, #34133, .F. ) ; +#31808 = CARTESIAN_POINT ( 'NONE', ( -40.95638651214006387, 217.7719116656250264, 73.58324080466826445 ) ) ; +#31809 = ORIENTED_EDGE ( 'NONE', *, *, #38211, .F. ) ; +#31811 = ADVANCED_FACE ( 'NONE', ( #6325 ), #24964, .F. ) ; +#31810 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971551802 ) ) ; +#31812 = AXIS2_PLACEMENT_3D ( 'NONE', #25758, #13669, #13865 ) ; +#31813 = EDGE_CURVE ( 'NONE', #15187, #14638, #20116, .T. ) ; +#31814 = CARTESIAN_POINT ( 'NONE', ( 22.99138912207082441, 214.0899462551063266, 73.04463992848049259 ) ) ; +#31815 = CIRCLE ( 'NONE', #3709, 6.499999999944858331 ) ; +#31816 = DIRECTION ( 'NONE', ( -0.7066795774897113303, 3.556110865384900083E-18, 0.7075337269409588403 ) ) ; +#31817 = ADVANCED_FACE ( 'NONE', ( #36610 ), #8614, .T. ) ; +#31818 = EDGE_CURVE ( 'NONE', #34948, #28895, #9012, .T. ) ; +#31819 = CARTESIAN_POINT ( 'NONE', ( 5.958856854324413810, 148.4719693777741725, 97.00569074539359349 ) ) ; +#31820 = VERTEX_POINT ( 'NONE', #14942 ) ; +#31821 = VECTOR ( 'NONE', #21117, 1000.000000000000227 ) ; +#31822 = CARTESIAN_POINT ( 'NONE', ( 20.59009467808899529, 212.9326083685893138, 76.04786435846743586 ) ) ; +#31823 = CARTESIAN_POINT ( 'NONE', ( 33.37602094669033193, 84.06324503389978986, 284.1448219155665242 ) ) ; +#31824 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#31825 = ORIENTED_EDGE ( 'NONE', *, *, #40086, .F. ) ; +#31826 = ORIENTED_EDGE ( 'NONE', *, *, #35576, .F. ) ; +#31827 = CARTESIAN_POINT ( 'NONE', ( 39.80107749601363309, 119.4152471894954601, 89.76382462946382645 ) ) ; +#31828 = CARTESIAN_POINT ( 'NONE', ( -27.33572494190097757, 124.2741252816392858, 88.36037343900612484 ) ) ; +#31829 = CARTESIAN_POINT ( 'NONE', ( 35.04524256069796451, 220.4002260770999726, 73.53733772521300693 ) ) ; +#31830 = CARTESIAN_POINT ( 'NONE', ( 23.36282490288553859, 177.5222052319614363, 100.8559891474603916 ) ) ; +#31831 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971538202 ) ) ; +#31832 = EDGE_LOOP ( 'NONE', ( #3246, #21646, #5772 ) ) ; +#31833 = ORIENTED_EDGE ( 'NONE', *, *, #1246, .T. ) ; +#31834 = CARTESIAN_POINT ( 'NONE', ( 2.107992061087183622, 189.7122439190391958, 105.9414811856116927 ) ) ; +#31835 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26292, #32812, #14417, #38731, #35653, #36070, #8286, #14629, #23219, #11557, #20536, #36487 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 4 ), + ( 1.387778780781445521E-17, 0.0001130297836568479959, 0.0002260595673136821140, 0.0004521191346273053017, 0.0009042382692545467438, 0.001808476538509029737 ), + .UNSPECIFIED. ) ; +#31836 = LINE ( 'NONE', #3994, #37277 ) ; +#31837 = CIRCLE ( 'NONE', #28563, 2.499999999999997335 ) ; +#31838 = VERTEX_POINT ( 'NONE', #17982 ) ; +#31839 = CARTESIAN_POINT ( 'NONE', ( -45.98416322616978391, 186.8584405881918542, 105.3861271832789583 ) ) ; +#31840 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26340, #11388, #38772, #1999 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31841 = CARTESIAN_POINT ( 'NONE', ( 21.98581530479853541, 129.8239281020156568, 89.95395906820830589 ) ) ; +#31842 = CARTESIAN_POINT ( 'NONE', ( 36.02656720897999776, 191.4402619432999870, 103.6984301366999972 ) ) ; +#31843 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #31819, #39482 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31844 = ORIENTED_EDGE ( 'NONE', *, *, #29078, .F. ) ; +#31845 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825945353352502, 0.0005734119018001440160 ) ) ; +#31846 = CARTESIAN_POINT ( 'NONE', ( -37.27925446228768891, 172.2690084905978267, 165.2355064606533688 ) ) ; +#31847 = LINE ( 'NONE', #3802, #28046 ) ; +#31848 = ORIENTED_EDGE ( 'NONE', *, *, #24736, .T. ) ; +#31849 = CARTESIAN_POINT ( 'NONE', ( -39.32442775238350663, 119.6599143282171411, 90.38126434724790670 ) ) ; +#31850 = EDGE_CURVE ( 'NONE', #529, #7159, #24072, .T. ) ; +#31851 = LINE ( 'NONE', #3806, #10097 ) ; +#31852 = CARTESIAN_POINT ( 'NONE', ( -75.99035305782904004, 156.3451282303881555, 95.79393540400387508 ) ) ; +#31853 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; +#31854 = CARTESIAN_POINT ( 'NONE', ( 43.53560975226982777, 121.3918131887250524, 90.46069063649885322 ) ) ; +#31855 = ORIENTED_EDGE ( 'NONE', *, *, #15093, .F. ) ; +#31856 = CARTESIAN_POINT ( 'NONE', ( -13.73975480748715938, 125.4641165511624621, 174.2036076504717244 ) ) ; +#31857 = EDGE_CURVE ( 'NONE', #21705, #6809, #18384, .T. ) ; +#31858 = CARTESIAN_POINT ( 'NONE', ( 0.5667676650968811458, 188.9999965746388000, 103.6932924457196918 ) ) ; +#31859 = FACE_OUTER_BOUND ( 'NONE', #26224, .T. ) ; +#31860 = ADVANCED_FACE ( 'NONE', ( #11671 ), #33732, .T. ) ; +#31861 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35548, #4495, #1433, #32916 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31862 = CARTESIAN_POINT ( 'NONE', ( -17.26187419364011078, 152.0564478534674038, 184.5517043374173340 ) ) ; +#31863 = PLANE ( 'NONE', #24503 ) ; +#31864 = DIRECTION ( 'NONE', ( -0.0005884949961204437871, 0.2249510543439066645, -0.9743698870671262391 ) ) ; +#31865 = CARTESIAN_POINT ( 'NONE', ( 75.31247730783820771, 195.3485392357280261, 195.0764703131155500 ) ) ; +#31866 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#31867 = ADVANCED_FACE ( 'NONE', ( #27444 ), #26225, .F. ) ; +#31868 = CARTESIAN_POINT ( 'NONE', ( -26.28844936523910292, 188.3519279905150086, 105.7138994502329723 ) ) ; +#31869 = ORIENTED_EDGE ( 'NONE', *, *, #18297, .F. ) ; +#31870 = CARTESIAN_POINT ( 'NONE', ( 23.68470175345883888, 128.4763013119720085, 89.81285948505966132 ) ) ; +#31871 = DIRECTION ( 'NONE', ( -0.0005884949961211176188, 0.2249510543439072752, -0.9743698870671261281 ) ) ; +#31872 = ORIENTED_EDGE ( 'NONE', *, *, #35402, .F. ) ; +#31873 = CARTESIAN_POINT ( 'NONE', ( -35.93631444865729918, 190.8511581158954300, 106.8150028089617081 ) ) ; +#31874 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825944461171208, 0.0005734119018205528209 ) ) ; +#31875 = PLANE ( 'NONE', #34565 ) ; +#31876 = CARTESIAN_POINT ( 'NONE', ( 36.06383752871749948, 192.3744905196089974, 104.3246838901409888 ) ) ; +#31877 = DIRECTION ( 'NONE', ( 0.0005884949961658158049, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#31878 = CARTESIAN_POINT ( 'NONE', ( 0.5984374305236895841, 211.0000000000000000, 162.9824824848976448 ) ) ; +#31879 = CARTESIAN_POINT ( 'NONE', ( 21.21575625058384063, 175.4487304674486552, 102.7114009836462003 ) ) ; +#31880 = VERTEX_POINT ( 'NONE', #14749 ) ; +#31881 = ORIENTED_EDGE ( 'NONE', *, *, #1878, .T. ) ; +#31882 = CARTESIAN_POINT ( 'NONE', ( -2.531805045932999931, 209.6150325076999934, 75.72670028419000232 ) ) ; +#31883 = CARTESIAN_POINT ( 'NONE', ( 36.70167842581782480, 117.3142576294874573, 87.24561739792864046 ) ) ; +#31884 = PLANE ( 'NONE', #39587 ) ; +#31885 = VERTEX_POINT ( 'NONE', #37019 ) ; +#31886 = CARTESIAN_POINT ( 'NONE', ( 6.037490238918274521, 177.7058967128525921, 100.7497073300592234 ) ) ; +#31887 = ORIENTED_EDGE ( 'NONE', *, *, #23244, .T. ) ; +#31888 = CARTESIAN_POINT ( 'NONE', ( 20.50147089296921266, 119.8278772667796090, 89.87074392140300461 ) ) ; +#31889 = LINE ( 'NONE', #13275, #8595 ) ; +#31890 = EDGE_CURVE ( 'NONE', #10482, #35056, #34328, .T. ) ; +#31891 = LINE ( 'NONE', #590, #17989 ) ; +#31892 = EDGE_CURVE ( 'NONE', #36032, #20264, #25019, .T. ) ; +#31893 = AXIS2_PLACEMENT_3D ( 'NONE', #40322, #3504, #37669 ) ; +#31895 = EDGE_CURVE ( 'NONE', #2995, #1454, #31441, .T. ) ; +#31894 = DIRECTION ( 'NONE', ( -0.0005884949961246006183, 0.2249510543439056653, -0.9743698870671265722 ) ) ; +#31896 = CARTESIAN_POINT ( 'NONE', ( -44.69076577494958258, 186.0129530593780487, 106.6282315781383119 ) ) ; +#31897 = ADVANCED_FACE ( 'NONE', ( #11880, #40465, #15340 ), #39661, .F. ) ; +#31898 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178582662422E-05, 0.0002331579774919529443 ) ) ; +#31899 = CARTESIAN_POINT ( 'NONE', ( 21.97072628506042591, 177.4133455279457223, 100.5987514716936175 ) ) ; +#31900 = CONICAL_SURFACE ( 'NONE', #18148, 8.000001494568962812, 0.7853981633972983989 ) ; +#31901 = DIRECTION ( 'NONE', ( 0.7942818278044005975, 0.5920830005357868853, 0.1362134299408100657 ) ) ; +#31902 = ORIENTED_EDGE ( 'NONE', *, *, #32714, .T. ) ; +#31903 = ORIENTED_EDGE ( 'NONE', *, *, #26017, .T. ) ; +#31904 = CARTESIAN_POINT ( 'NONE', ( 15.95614559854525361, 121.8890334969419769, 174.5201005345669216 ) ) ; +#31905 = CARTESIAN_POINT ( 'NONE', ( 30.07122368478816199, 177.6509743871843909, 100.7722334953168826 ) ) ; +#31906 = CARTESIAN_POINT ( 'NONE', ( -14.74892900667990503, 122.6387602747236514, 152.1279856558663823 ) ) ; +#31907 = CARTESIAN_POINT ( 'NONE', ( -29.20104124293470349, 162.9607637445586192, 100.3719287999282130 ) ) ; +#31908 = ORIENTED_EDGE ( 'NONE', *, *, #34586, .T. ) ; +#31909 = DIRECTION ( 'NONE', ( 0.7072759766253134961, 0.1592272936566852259, -0.6887723585071316990 ) ) ; +#31910 = EDGE_LOOP ( 'NONE', ( #12943, #8447, #31606, #32545 ) ) ; +#31911 = EDGE_CURVE ( 'NONE', #33584, #35348, #4990, .T. ) ; +#31912 = CARTESIAN_POINT ( 'NONE', ( -20.33319487501234235, 138.1136697287241475, 91.89341636764112309 ) ) ; +#31913 = DIRECTION ( 'NONE', ( -0.0002331579778304450367, 0.000000000000000000, 0.9999999728186783621 ) ) ; +#31914 = LINE ( 'NONE', #28246, #4546 ) ; +#31915 = DIRECTION ( 'NONE', ( 0.0005559617641698784158, -0.3907311284608755431, 0.9205046855710228293 ) ) ; +#31916 = ADVANCED_FACE ( 'NONE', ( #30686 ), #31087, .T. ) ; +#31917 = VECTOR ( 'NONE', #20868, 1000.000000000000114 ) ; +#31918 = DIRECTION ( 'NONE', ( -0.0005884949961214528541, 0.2249510543439078303, -0.9743698870671260170 ) ) ; +#31919 = CARTESIAN_POINT ( 'NONE', ( -2.943769803757999792, 209.8858866696000121, 72.92663106025999298 ) ) ; +#31920 = CARTESIAN_POINT ( 'NONE', ( 38.67304637376000187, 118.3857514081000062, 89.51272550298999420 ) ) ; +#31921 = VERTEX_POINT ( 'NONE', #19595 ) ; +#31922 = DIRECTION ( 'NONE', ( 0.7075337269008550312, 8.718783055999616425E-15, 0.7066795775298634341 ) ) ; +#31923 = VECTOR ( 'NONE', #37229, 1000.000000000000114 ) ; +#31924 = CARTESIAN_POINT ( 'NONE', ( -20.01834611325332247, 210.1689860900705753, 76.07064898925692376 ) ) ; +#31925 = DIRECTION ( 'NONE', ( 0.7933533411653078682, 0.5931840316265221125, 0.1368326740407710407 ) ) ; +#31926 = AXIS2_PLACEMENT_3D ( 'NONE', #26478, #38926, #32798 ) ; +#31927 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #706, #32206, #13393, #9932 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 8.431138928378200018E-07, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31928 = CARTESIAN_POINT ( 'NONE', ( 16.99952089899044694, 136.5640433068810182, 181.4726123975704297 ) ) ; +#31929 = ORIENTED_EDGE ( 'NONE', *, *, #28339, .F. ) ; +#31930 = ORIENTED_EDGE ( 'NONE', *, *, #35081, .F. ) ; +#31931 = EDGE_LOOP ( 'NONE', ( #13423, #19522 ) ) ; +#31932 = DIRECTION ( 'NONE', ( 8.625810036883390059E-16, 0.9743700557916298299, 0.2249510932994460699 ) ) ; +#31933 = CARTESIAN_POINT ( 'NONE', ( -26.01494426630450008, 211.0902259182902014, 73.07465174665132679 ) ) ; +#31934 = ORIENTED_EDGE ( 'NONE', *, *, #36599, .T. ) ; +#31935 = CARTESIAN_POINT ( 'NONE', ( 20.23141915213000175, 210.3997737976999929, 75.79629159974001595 ) ) ; +#31936 = CARTESIAN_POINT ( 'NONE', ( -34.37617727112554178, 159.7078911223883608, 187.3767538074542358 ) ) ; +#31937 = CARTESIAN_POINT ( 'NONE', ( -38.86369648667000121, 118.8228811146000083, 89.72077586238000890 ) ) ; +#31938 = CARTESIAN_POINT ( 'NONE', ( -38.36013681963000010, 118.8201344991000070, 87.71886890835001793 ) ) ; +#31939 = DIRECTION ( 'NONE', ( 0.0005884949961257158286, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#31940 = CARTESIAN_POINT ( 'NONE', ( -14.39900080767387358, 134.4949918206585551, 152.5558619512717371 ) ) ; +#31941 = VERTEX_POINT ( 'NONE', #589 ) ; +#31942 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927769559465, -0.0005734119022075471854 ) ) ; +#31943 = ORIENTED_EDGE ( 'NONE', *, *, #33371, .T. ) ; +#31944 = EDGE_CURVE ( 'NONE', #37610, #7652, #26969, .T. ) ; +#31945 = LINE ( 'NONE', #19646, #39665 ) ; +#31946 = DIRECTION ( 'NONE', ( 0.0005884949961246697904, -0.2249510543439056376, 0.9743698870671265722 ) ) ; +#31947 = CARTESIAN_POINT ( 'NONE', ( -12.63676213157982531, 181.6119438013536183, 104.1547372293333495 ) ) ; +#31948 = EDGE_LOOP ( 'NONE', ( #11281, #12489, #19158, #15648 ) ) ; +#31949 = ORIENTED_EDGE ( 'NONE', *, *, #37832, .T. ) ; +#31950 = AXIS2_PLACEMENT_3D ( 'NONE', #1392, #26560, #26759 ) ; +#31951 = CARTESIAN_POINT ( 'NONE', ( -2.937322396554999937, 191.1124756257999877, 103.7764890163000047 ) ) ; +#31952 = FACE_OUTER_BOUND ( 'NONE', #23009, .T. ) ; +#31953 = CARTESIAN_POINT ( 'NONE', ( 2.685751687114999786, 190.9521868795999922, 106.4257393099999973 ) ) ; +#31954 = VECTOR ( 'NONE', #20726, 1000.000000000000000 ) ; +#31955 = AXIS2_PLACEMENT_3D ( 'NONE', #18609, #30720, #12911 ) ; +#31956 = ORIENTED_EDGE ( 'NONE', *, *, #15362, .F. ) ; +#31957 = CARTESIAN_POINT ( 'NONE', ( -20.02016821360482268, 211.0854730039747267, 73.07052224373646254 ) ) ; +#31958 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#31959 = ORIENTED_EDGE ( 'NONE', *, *, #38334, .F. ) ; +#31960 = CARTESIAN_POINT ( 'NONE', ( 114.5937281169188253, 50.54601443099469549, 171.8750556891886276 ) ) ; +#31961 = DIRECTION ( 'NONE', ( -0.0005884949961262653023, 0.2249510543439053600, -0.9743698870671265722 ) ) ; +#31962 = CARTESIAN_POINT ( 'NONE', ( -25.99977390623968532, 118.5811435109333303, 90.28348805114744380 ) ) ; +#31963 = ORIENTED_EDGE ( 'NONE', *, *, #13151, .T. ) ; +#31964 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10338, #7239, #20106, #1307 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#31965 = CARTESIAN_POINT ( 'NONE', ( -19.99829785685910011, 119.7153791177249502, 90.38236254249699186 ) ) ; +#31966 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; +#31967 = EDGE_CURVE ( 'NONE', #6135, #22589, #31889, .T. ) ; +#31968 = VERTEX_POINT ( 'NONE', #7326 ) ; +#31969 = CARTESIAN_POINT ( 'NONE', ( 25.66733978393000015, 120.1839125632999981, 90.12708786838000208 ) ) ; +#31970 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971593713 ) ) ; +#31971 = CARTESIAN_POINT ( 'NONE', ( -14.75545039936645253, 171.9013578063558043, 152.1279856333616465 ) ) ; +#31973 = CARTESIAN_POINT ( 'NONE', ( -11.82471700305710627, 154.1761034371582468, 95.25442204585927186 ) ) ; +#31972 = CARTESIAN_POINT ( 'NONE', ( -20.49970524097187763, 120.2776284062741325, 87.94673202274765345 ) ) ; +#31974 = ORIENTED_EDGE ( 'NONE', *, *, #25723, .T. ) ; +#31975 = CARTESIAN_POINT ( 'NONE', ( -19.99984748064912665, 127.7403057018771904, 89.15611954941233819 ) ) ; +#31976 = AXIS2_PLACEMENT_3D ( 'NONE', #39318, #1107, #13590 ) ; +#31977 = AXIS2_PLACEMENT_3D ( 'NONE', #28209, #19165, #15907 ) ; +#31978 = CARTESIAN_POINT ( 'NONE', ( 39.71644276554569331, 128.0354526761064164, 94.31825870285607039 ) ) ; +#31979 = EDGE_LOOP ( 'NONE', ( #184, #9259, #20904, #37658 ) ) ; +#31980 = ORIENTED_EDGE ( 'NONE', *, *, #18405, .T. ) ; +#31981 = CARTESIAN_POINT ( 'NONE', ( 15.50147167064367437, 126.2420947773427997, 91.35460322390918009 ) ) ; +#31982 = CARTESIAN_POINT ( 'NONE', ( -45.01686328689083894, 124.5428679525740989, 91.48657569876101547 ) ) ; +#31983 = CARTESIAN_POINT ( 'NONE', ( -2.300492201474999998, 191.0297072097000068, 106.1836901105999971 ) ) ; +#31984 = CARTESIAN_POINT ( 'NONE', ( 35.57400175955999799, 192.0876667541000131, 103.8903688872000117 ) ) ; +#31985 = ORIENTED_EDGE ( 'NONE', *, *, #9741, .F. ) ; +#31986 = ORIENTED_EDGE ( 'NONE', *, *, #22674, .F. ) ; +#31987 = CARTESIAN_POINT ( 'NONE', ( -42.85824143706140177, 121.9102241652851575, 87.85339546770353536 ) ) ; +#31989 = ADVANCED_FACE ( 'NONE', ( #790 ), #18987, .F. ) ; +#31988 = CARTESIAN_POINT ( 'NONE', ( -12.63707034089905612, 177.5566571168823486, 100.8521260122499683 ) ) ; +#31990 = CARTESIAN_POINT ( 'NONE', ( -23.36303326529986890, 134.3845102228084158, 93.64833256334264888 ) ) ; +#31991 = EDGE_CURVE ( 'NONE', #33925, #13672, #39242, .T. ) ; +#31992 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971536259 ) ) ; +#31993 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #370, #562, #6296 ), + ( #15517, #38193, #16302 ), + ( #9386, #37987, #3826 ), + ( #18755, #9990, #12640 ) ), + .UNSPECIFIED., .F., .F., .T. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), + ( 3, 3 ), + ( 0.4680274479876873617, 0.4680515558888064809 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.7506739324345677034, 1.000000000000000000), + ( 1.000000000000000000, 0.7506633861694811394, 1.000000000000000000), + ( 1.000000000000000000, 0.7506528395853189206, 1.000000000000000000), + ( 1.000000000000000000, 0.7506422926820343067, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#31994 = ORIENTED_EDGE ( 'NONE', *, *, #9270, .T. ) ; +#31995 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #8508, #29969, #26508, #14644 ), + ( #27332, #36299, #18082, #17474 ), + ( #1755, #8298, #27128, #14848 ), + ( #20761, #17877, #8719, #20346 ), + ( #39564, #23636, #38957, #20974 ), + ( #17679, #17265, #33427, #36087 ), + ( #26710, #30175, #35873, #2173 ), + ( #21176, #11574, #30586, #30373 ), + ( #2575, #39156, #36504, #2374 ), + ( #33634, #23430, #7882, #4803 ), + ( #20548, #11165, #39760, #33021 ), + ( #11779, #24263, #5012, #1966 ), + ( #26920, #3154, #22190, #6619 ), + ( #21395, #24866, #33835, #37317 ), + ( #9509, #3355, #28321, #6420 ), + ( #8921, #15043, #9310, #21992 ), + ( #31184, #30986, #37117, #12368 ), + ( #18284, #21788, #34226, #5836 ), + ( #34424, #2951, #30787, #34618 ), + ( #287, #15827, #15445, #18883 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 3, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.009978065169328498643, 2.171379472327000104E-05, 0.001571209923265000103, 0.003133759667688999859, 0.006258859156535999738, 0.01250905813423000036, 0.01875925711191999898, 0.02500945608961999828, 0.05001025200038999863, 0.1000118438218999956, 0.1500134356435000038, 0.2000150274648999915, 0.4000110835753000194, 0.6000071396855000128, 0.8000031957958999573, 0.9999996101999000242 ), + ( 0.1755988089626999982, 0.8244287575951999569 ), + .UNSPECIFIED. ) ; +#31996 = DIRECTION ( 'NONE', ( -0.7069397806464156053, 0.6508950906897285060, 0.2767159689204939932 ) ) ; +#31997 = ORIENTED_EDGE ( 'NONE', *, *, #10939, .T. ) ; +#31998 = CARTESIAN_POINT ( 'NONE', ( 35.93343626571697769, 108.4364864373064137, 169.8429943716569994 ) ) ; +#31999 = ORIENTED_EDGE ( 'NONE', *, *, #38522, .T. ) ; +#32000 = FACE_OUTER_BOUND ( 'NONE', #6409, .T. ) ; +#32001 = AXIS2_PLACEMENT_3D ( 'NONE', #21234, #3011, #24924 ) ; +#32002 = VECTOR ( 'NONE', #40354, 1000.000000000000114 ) ; +#32003 = CARTESIAN_POINT ( 'NONE', ( -0.3488545754133000054, 188.2235992194000289, 106.3567909089000096 ) ) ; +#32004 = DIRECTION ( 'NONE', ( 0.7069375452530322068, -0.1593035203500595132, 0.6891020936811141917 ) ) ; +#32005 = ORIENTED_EDGE ( 'NONE', *, *, #12694, .F. ) ; +#32006 = PLANE ( 'NONE', #30859 ) ; +#32007 = ORIENTED_EDGE ( 'NONE', *, *, #4660, .F. ) ; +#32008 = CONICAL_SURFACE ( 'NONE', #14374, 3.003158621626311309, 0.7854054549419372533 ) ; +#32009 = DIRECTION ( 'NONE', ( 0.0005884965073590145944, -0.2249510525036911290, 0.9743698874910607932 ) ) ; +#32010 = CARTESIAN_POINT ( 'NONE', ( -38.49874843363917165, 163.0800447631557688, 197.8568742794042805 ) ) ; +#32011 = CARTESIAN_POINT ( 'NONE', ( 13.50015683897842678, 123.9577177740650598, 91.11541229130565966 ) ) ; +#32012 = CARTESIAN_POINT ( 'NONE', ( -29.94810845983804271, 109.6131156702000027, 87.28587219900418859 ) ) ; +#32013 = ORIENTED_EDGE ( 'NONE', *, *, #4873, .F. ) ; +#32014 = CARTESIAN_POINT ( 'NONE', ( 20.89286828480348035, 176.3842452922319524, 100.3618186666556369 ) ) ; +#32015 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178582662422E-05, 0.0002331579774919529443 ) ) ; +#32016 = CARTESIAN_POINT ( 'NONE', ( -36.79164517774999865, 117.4412903973999960, 90.44275846995999757 ) ) ; +#32017 = ORIENTED_EDGE ( 'NONE', *, *, #32753, .T. ) ; +#32018 = DIRECTION ( 'NONE', ( 0.0001358595490717324182, 0.9743700647852328034, 0.2249510133175757765 ) ) ; +#32019 = CARTESIAN_POINT ( 'NONE', ( 38.56885418974432866, 118.4610218664272452, 89.66265752007532797 ) ) ; +#32020 = EDGE_LOOP ( 'NONE', ( #18127, #39145, #32933, #33520, #8889, #11888, #14811, #33146, #1507, #54, #12018 ) ) ; +#32021 = CARTESIAN_POINT ( 'NONE', ( 0.5456353394255060163, 210.9999999999900240, 75.55817498829998158 ) ) ; +#32022 = EDGE_CURVE ( 'NONE', #11123, #9057, #22494, .T. ) ; +#32023 = CARTESIAN_POINT ( 'NONE', ( -27.18894999058629480, 124.1015279925761661, 88.32043755942639507 ) ) ; +#32024 = CARTESIAN_POINT ( 'NONE', ( -29.96982177062705333, 161.3773976535714780, 187.2046641938986511 ) ) ; +#32025 = CARTESIAN_POINT ( 'NONE', ( -20.49970533570471787, 160.6243682191729363, 97.26151316895288801 ) ) ; +#32026 = ORIENTED_EDGE ( 'NONE', *, *, #5294, .T. ) ; +#32027 = VERTEX_POINT ( 'NONE', #32096 ) ; +#32028 = CARTESIAN_POINT ( 'NONE', ( 42.60888955940591671, 68.11159795993565069, 322.0780808329887464 ) ) ; +#32029 = ORIENTED_EDGE ( 'NONE', *, *, #38124, .F. ) ; +#32030 = ORIENTED_EDGE ( 'NONE', *, *, #32073, .F. ) ; +#32031 = ORIENTED_EDGE ( 'NONE', *, *, #1415, .F. ) ; +#32032 = CARTESIAN_POINT ( 'NONE', ( 20.50039165879256942, 118.8156470718432729, 87.75541749211321019 ) ) ; +#32034 = CIRCLE ( 'NONE', #22894, 2.499999161650496848 ) ; +#32033 = FACE_OUTER_BOUND ( 'NONE', #13305, .T. ) ; +#32035 = ADVANCED_FACE ( 'NONE', ( #19784 ), #26960, .F. ) ; +#32036 = AXIS2_PLACEMENT_3D ( 'NONE', #37358, #37163, #40415 ) ; +#32037 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#32038 = AXIS2_PLACEMENT_3D ( 'NONE', #19820, #29257, #23517 ) ; +#32039 = ORIENTED_EDGE ( 'NONE', *, *, #22520, .F. ) ; +#32040 = DIRECTION ( 'NONE', ( -0.7942820423213359238, -0.5918950211223032998, -0.1370267171630252523 ) ) ; +#32041 = VECTOR ( 'NONE', #37724, 1000.000000000000114 ) ; +#32043 = ADVANCED_FACE ( 'NONE', ( #13081 ), #31696, .F. ) ; +#32042 = CARTESIAN_POINT ( 'NONE', ( 23.36366720388904383, 174.6836436729091133, 103.0466216106880495 ) ) ; +#32044 = CARTESIAN_POINT ( 'NONE', ( 36.18873234541000272, 116.0516713650000185, 87.35401155214999847 ) ) ; +#32045 = CARTESIAN_POINT ( 'NONE', ( -38.68891799773000884, 119.1263286439999973, 90.16723566163000214 ) ) ; +#32046 = ADVANCED_FACE ( 'NONE', ( #9611 ), #19182, .T. ) ; +#32047 = CARTESIAN_POINT ( 'NONE', ( 19.99974539165517839, 193.0912053986162391, 103.5857589997535797 ) ) ; +#32048 = EDGE_CURVE ( 'NONE', #25706, #11904, #13765, .T. ) ; +#32049 = EDGE_CURVE ( 'NONE', #23147, #17425, #38410, .T. ) ; +#32050 = CARTESIAN_POINT ( 'NONE', ( 30.07038801303579234, 136.6840993378064866, 94.26968325502151913 ) ) ; +#32051 = VERTEX_POINT ( 'NONE', #10420 ) ; +#32052 = CARTESIAN_POINT ( 'NONE', ( 21.15680152563498950, 128.4898158065484779, 92.04116564476515805 ) ) ; +#32053 = CARTESIAN_POINT ( 'NONE', ( -20.51784484524898389, 207.7575274251524604, 76.50869542728868566 ) ) ; +#32054 = CARTESIAN_POINT ( 'NONE', ( -10.30841286990177430, 131.0201488766975046, 89.90757730957309946 ) ) ; +#32055 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 132.9679238121742912, 90.36185680194377312 ) ) ; +#32056 = CARTESIAN_POINT ( 'NONE', ( 3.850504590650025261, 136.1268787497847370, 91.07796198998222792 ) ) ; +#32057 = ORIENTED_EDGE ( 'NONE', *, *, #37844, .F. ) ; +#32058 = DIRECTION ( 'NONE', ( -0.6068733047655824331, -0.7745082036644093115, -0.1784428043363773808 ) ) ; +#32059 = CARTESIAN_POINT ( 'NONE', ( 0.6355662970509753373, 189.0012791104650205, 103.6864957496327264 ) ) ; +#32060 = CARTESIAN_POINT ( 'NONE', ( 20.50028285398298777, 191.4126458000098978, 104.3447517631808097 ) ) ; +#32061 = CARTESIAN_POINT ( 'NONE', ( 13.50130427969020275, 124.2930898829833524, 90.90584795771297877 ) ) ; +#32062 = CARTESIAN_POINT ( 'NONE', ( -26.12734889465999899, 191.8689129175999994, 103.7983224447000055 ) ) ; +#32063 = CARTESIAN_POINT ( 'NONE', ( -26.00138850119475364, 118.1173731751006102, 87.28355378449504087 ) ) ; +#32064 = CARTESIAN_POINT ( 'NONE', ( -3.168077445297452055, 127.9087829914206651, 92.26382811782556814 ) ) ; +#32065 = PLANE ( 'NONE', #3979 ) ; +#32066 = CARTESIAN_POINT ( 'NONE', ( -42.83272783108322557, 107.4558756614410697, 150.2543767220365680 ) ) ; +#32067 = ORIENTED_EDGE ( 'NONE', *, *, #23720, .T. ) ; +#32068 = AXIS2_PLACEMENT_3D ( 'NONE', #31428, #24911, #22235 ) ; +#32069 = FACE_OUTER_BOUND ( 'NONE', #7410, .T. ) ; +#32070 = ORIENTED_EDGE ( 'NONE', *, *, #5992, .T. ) ; +#32071 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#32072 = CARTESIAN_POINT ( 'NONE', ( -25.99161325705826897, 191.8394051827992826, 103.9324257214252754 ) ) ; +#32073 = EDGE_CURVE ( 'NONE', #10983, #26453, #32313, .T. ) ; +#32074 = DIRECTION ( 'NONE', ( 0.0004161288024568778944, 0.5299192578645700591, 0.8480479980408438534 ) ) ; +#32075 = FACE_OUTER_BOUND ( 'NONE', #18701, .T. ) ; +#32076 = CARTESIAN_POINT ( 'NONE', ( -12.64523939051215073, 134.9174765714697344, 90.80875027841997849 ) ) ; +#32077 = CARTESIAN_POINT ( 'NONE', ( 41.10429549663972892, 182.7543144023022137, 104.8991682080530126 ) ) ; +#32078 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4313, #3714, #10679, #27458 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32079 = CARTESIAN_POINT ( 'NONE', ( 35.69170447249999967, 192.9058989856999915, 106.6881889106000045 ) ) ; +#32080 = ORIENTED_EDGE ( 'NONE', *, *, #15955, .T. ) ; +#32081 = CARTESIAN_POINT ( 'NONE', ( -2.780775877414999986, 209.2815418106999914, 75.92975070871000298 ) ) ; +#32082 = ADVANCED_FACE ( 'NONE', ( #19397 ), #22693, .T. ) ; +#32083 = CARTESIAN_POINT ( 'NONE', ( 35.93828886713654924, 107.3103096182504146, 174.7145176258908350 ) ) ; +#32084 = EDGE_CURVE ( 'NONE', #21381, #7388, #4457, .T. ) ; +#32085 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10085, #9893, #19667, #31354, #465, #38086, #16203, #25836, #10293, #13348 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999963918, 0.4999999999999927836, 0.7499999999999963363, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32086 = DIRECTION ( 'NONE', ( 8.326672684845666840E-15, 0.9743700557921587402, 0.2249510932971545696 ) ) ; +#32087 = ORIENTED_EDGE ( 'NONE', *, *, #3613, .T. ) ; +#32088 = CARTESIAN_POINT ( 'NONE', ( 14.27573290317919330, 135.8449083118874228, 91.00656752237129865 ) ) ; +#32089 = ADVANCED_FACE ( 'NONE', ( #13675 ), #26762, .F. ) ; +#32090 = ORIENTED_EDGE ( 'NONE', *, *, #28165, .F. ) ; +#32091 = EDGE_CURVE ( 'NONE', #4584, #25855, #34020, .T. ) ; +#32092 = VECTOR ( 'NONE', #32202, 1000.000000000000227 ) ; +#32093 = VECTOR ( 'NONE', #1019, 1000.000000000000000 ) ; +#32094 = CARTESIAN_POINT ( 'NONE', ( 39.53379105069361543, 120.3902222971681368, 87.42331650858173475 ) ) ; +#32095 = CARTESIAN_POINT ( 'NONE', ( 25.92237104596770081, 117.3323686320814119, 87.25212782947929213 ) ) ; +#32096 = CARTESIAN_POINT ( 'NONE', ( -12.63675505126982657, 134.8421811116586753, 93.35708474409203461 ) ) ; +#32097 = CARTESIAN_POINT ( 'NONE', ( -39.33474900027509591, 175.4267096001368316, 136.0977776169101787 ) ) ; +#32098 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#32099 = LINE ( 'NONE', #31701, #2749 ) ; +#32100 = VERTEX_POINT ( 'NONE', #17527 ) ; +#32101 = CARTESIAN_POINT ( 'NONE', ( 15.94060000479266925, 152.3716036959190205, 183.5932755018154694 ) ) ; +#32102 = CARTESIAN_POINT ( 'NONE', ( 30.06998772288336141, 177.5055085816675842, 100.8631312348358193 ) ) ; +#32103 = CARTESIAN_POINT ( 'NONE', ( -15.10713178427481651, 176.3794795624077096, 100.3824614381103828 ) ) ; +#32104 = CARTESIAN_POINT ( 'NONE', ( -37.13682434169999880, 191.1674602843000059, 103.9294490895999985 ) ) ; +#32105 = ORIENTED_EDGE ( 'NONE', *, *, #32127, .T. ) ; +#32106 = FACE_OUTER_BOUND ( 'NONE', #21768, .T. ) ; +#32107 = EDGE_LOOP ( 'NONE', ( #39548, #28408, #5319, #23854 ) ) ; +#32108 = CARTESIAN_POINT ( 'NONE', ( 35.04645051037203984, 217.7719116314000303, 75.53733736051519543 ) ) ; +#32109 = PLANE ( 'NONE', #39322 ) ; +#32110 = DIRECTION ( 'NONE', ( -0.0005884949961225237206, 0.2249510543439054433, -0.9743698870671265722 ) ) ; +#32111 = CIRCLE ( 'NONE', #4015, 2.250000000000011102 ) ; +#32112 = FACE_OUTER_BOUND ( 'NONE', #7281, .T. ) ; +#32113 = VECTOR ( 'NONE', #5490, 999.9999999999998863 ) ; +#32114 = DIRECTION ( 'NONE', ( 0.0006039748319384539597, 1.295170900108887039E-14, 0.9999998176071845934 ) ) ; +#32115 = CARTESIAN_POINT ( 'NONE', ( -37.70271471075000136, 190.8147333642999968, 106.4196837288999973 ) ) ; +#32116 = ORIENTED_EDGE ( 'NONE', *, *, #22399, .F. ) ; +#32117 = EDGE_CURVE ( 'NONE', #37405, #16629, #37304, .T. ) ; +#32118 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971568733 ) ) ; +#32119 = ADVANCED_FACE ( 'NONE', ( #32288 ), #23281, .F. ) ; +#32120 = CARTESIAN_POINT ( 'NONE', ( 18.59950176164737812, 148.9135478570107409, 180.2224150185023177 ) ) ; +#32121 = LINE ( 'NONE', #38037, #26873 ) ; +#32122 = EDGE_CURVE ( 'NONE', #12519, #33382, #32174, .T. ) ; +#32123 = FACE_OUTER_BOUND ( 'NONE', #37843, .T. ) ; +#32124 = VERTEX_POINT ( 'NONE', #19989 ) ; +#32125 = ORIENTED_EDGE ( 'NONE', *, *, #14306, .F. ) ; +#32126 = CARTESIAN_POINT ( 'NONE', ( 25.83231656248760189, 118.8155665305523740, 87.41885382068512911 ) ) ; +#32127 = EDGE_CURVE ( 'NONE', #11480, #40319, #17119, .T. ) ; +#32128 = CARTESIAN_POINT ( 'NONE', ( 16.00173003433196328, 160.0551282760237086, 99.67379390875994716 ) ) ; +#32129 = VERTEX_POINT ( 'NONE', #10621 ) ; +#32130 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#32131 = EDGE_CURVE ( 'NONE', #19810, #328, #20651, .T. ) ; +#32132 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#32133 = CARTESIAN_POINT ( 'NONE', ( -20.30860343291056225, 211.0893031747332316, 75.78085498041677681 ) ) ; +#32134 = CARTESIAN_POINT ( 'NONE', ( -38.01249147463000355, 119.1964217757000029, 87.30166645433000383 ) ) ; +#32135 = CARTESIAN_POINT ( 'NONE', ( 14.30273991137152123, 209.7096250667529205, 76.04986613324078348 ) ) ; +#32136 = ORIENTED_EDGE ( 'NONE', *, *, #11121, .F. ) ; +#32137 = CARTESIAN_POINT ( 'NONE', ( 19.32231137207130800, 148.3832603922512021, 183.4602508322493009 ) ) ; +#32138 = ORIENTED_EDGE ( 'NONE', *, *, #34223, .T. ) ; +#32139 = CARTESIAN_POINT ( 'NONE', ( -26.00760980910003184, 207.8686442860052921, 77.29275028082734877 ) ) ; +#32140 = AXIS2_PLACEMENT_3D ( 'NONE', #19599, #13678, #22892 ) ; +#32141 = CARTESIAN_POINT ( 'NONE', ( 20.22266559583958667, 184.3432592364629272, 105.0517724516481906 ) ) ; +#32142 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319380481428 ) ) ; +#32143 = CARTESIAN_POINT ( 'NONE', ( -20.00017858637951207, 184.9560350789418237, 102.3655360699851400 ) ) ; +#32144 = CARTESIAN_POINT ( 'NONE', ( 40.92144267131097024, 126.9198679979903233, 91.49572650408431684 ) ) ; +#32145 = VERTEX_POINT ( 'NONE', #39007 ) ; +#32146 = VECTOR ( 'NONE', #31134, 1000.000000000000227 ) ; +#32147 = ADVANCED_FACE ( 'NONE', ( #11017 ), #719, .F. ) ; +#32148 = ORIENTED_EDGE ( 'NONE', *, *, #17500, .F. ) ; +#32149 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971526822 ) ) ; +#32150 = CIRCLE ( 'NONE', #29540, 1.999999999914603865 ) ; +#32151 = CARTESIAN_POINT ( 'NONE', ( 25.49223589608078555, 207.9233622696484360, 76.22750517669706483 ) ) ; +#32152 = CARTESIAN_POINT ( 'NONE', ( -39.76913700811847718, 110.4455167082730753, 170.2888389991151143 ) ) ; +#32153 = CARTESIAN_POINT ( 'NONE', ( 2.685592881625999961, 190.9411674561000041, 106.4227546106999966 ) ) ; +#32154 = EDGE_LOOP ( 'NONE', ( #36761, #15165, #36148, #2423 ) ) ; +#32155 = ORIENTED_EDGE ( 'NONE', *, *, #27852, .F. ) ; +#32156 = CARTESIAN_POINT ( 'NONE', ( 19.99941580399983110, 118.1025156334579265, 87.25545403306659864 ) ) ; +#32157 = CARTESIAN_POINT ( 'NONE', ( 22.50034184233011914, 153.8097659799650501, 95.66226703669086362 ) ) ; +#32158 = EDGE_LOOP ( 'NONE', ( #29072, #29140, #36465, #5110 ) ) ; +#32159 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26166, #25360, #3650, #25967 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32160 = DIRECTION ( 'NONE', ( 0.0004161288024809969475, 0.5299192578176238344, 0.8480479980701790543 ) ) ; +#32161 = VERTEX_POINT ( 'NONE', #12420 ) ; +#32162 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; +#32163 = CARTESIAN_POINT ( 'NONE', ( 28.46433317244940753, 130.4256741595737310, 90.26002097211915043 ) ) ; +#32164 = CYLINDRICAL_SURFACE ( 'NONE', #26087, 2.000000000000011546 ) ; +#32165 = ORIENTED_EDGE ( 'NONE', *, *, #5947, .T. ) ; +#32166 = CARTESIAN_POINT ( 'NONE', ( 26.00088934340000080, 120.1020457456000088, 90.44395696404001228 ) ) ; +#32167 = EDGE_CURVE ( 'NONE', #3248, #32435, #13142, .T. ) ; +#32168 = DIRECTION ( 'NONE', ( 0.9999998268370356991, 0.0001323828866989250124, -0.0005734114318351182446 ) ) ; +#32169 = EDGE_CURVE ( 'NONE', #29827, #5998, #30437, .T. ) ; +#32170 = EDGE_CURVE ( 'NONE', #34570, #27269, #16389, .T. ) ; +#32172 = CARTESIAN_POINT ( 'NONE', ( -11.42861031051659637, 154.0584472107514671, 95.22701972222303368 ) ) ; +#32171 = CARTESIAN_POINT ( 'NONE', ( 76.10601358362096391, 156.3575724116909669, 95.70494597592171715 ) ) ; +#32173 = VERTEX_POINT ( 'NONE', #18532 ) ; +#32174 = CIRCLE ( 'NONE', #3342, 1.749999999999998446 ) ; +#32175 = AXIS2_PLACEMENT_3D ( 'NONE', #6789, #16200, #31156 ) ; +#32176 = DIRECTION ( 'NONE', ( -0.7933532970003738249, -0.5930762008556724751, -0.1372995488602876402 ) ) ; +#32177 = ORIENTED_EDGE ( 'NONE', *, *, #2076, .F. ) ; +#32178 = PLANE ( 'NONE', #20590 ) ; +#32179 = EDGE_CURVE ( 'NONE', #38692, #24100, #29481, .T. ) ; +#32180 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#32181 = EDGE_LOOP ( 'NONE', ( #33346, #30363, #8675, #7963 ) ) ; +#32182 = ORIENTED_EDGE ( 'NONE', *, *, #6085, .F. ) ; +#32183 = CARTESIAN_POINT ( 'NONE', ( -25.74991476775000265, 118.4643410412000009, 90.03333709688999420 ) ) ; +#32184 = EDGE_CURVE ( 'NONE', #26074, #34987, #23546, .T. ) ; +#32185 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921596284, 0.2249510932971517940 ) ) ; +#32186 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319356122658 ) ) ; +#32187 = ORIENTED_EDGE ( 'NONE', *, *, #1074, .F. ) ; +#32188 = ORIENTED_EDGE ( 'NONE', *, *, #3259, .F. ) ; +#32189 = ORIENTED_EDGE ( 'NONE', *, *, #21973, .F. ) ; +#32190 = CARTESIAN_POINT ( 'NONE', ( -6.035103513883293580, 176.8182870450115161, 103.1499335225169887 ) ) ; +#32191 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; +#32192 = DIRECTION ( 'NONE', ( -0.0005884949961226190220, 0.2249510543439057486, -0.9743698870671265722 ) ) ; +#32193 = ADVANCED_FACE ( 'NONE', ( #33679 ), #30637, .F. ) ; +#32194 = ORIENTED_EDGE ( 'NONE', *, *, #5767, .T. ) ; +#32195 = CARTESIAN_POINT ( 'NONE', ( -3.668404236352207359, 128.0226348367964988, 91.77725148510558029 ) ) ; +#32196 = ORIENTED_EDGE ( 'NONE', *, *, #23439, .T. ) ; +#32197 = AXIS2_PLACEMENT_3D ( 'NONE', #25801, #31732, #24999 ) ; +#32198 = CARTESIAN_POINT ( 'NONE', ( -12.63072017624268106, 177.7897717398484474, 100.7065154983451407 ) ) ; +#32199 = CARTESIAN_POINT ( 'NONE', ( 22.99888613823950578, 118.1131156702000169, 87.25083745503069110 ) ) ; +#32200 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29719, #4957, #33164, #23993 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32201 = ORIENTED_EDGE ( 'NONE', *, *, #38829, .F. ) ; +#32202 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825929682393506, -0.0005734119019024616929 ) ) ; +#32203 = VECTOR ( 'NONE', #17384, 1000.000000000000114 ) ; +#32204 = CARTESIAN_POINT ( 'NONE', ( -26.00142186005520983, 120.7678123865047297, 87.55007858260474052 ) ) ; +#32205 = CARTESIAN_POINT ( 'NONE', ( 20.61396327107688364, 153.5808548369363962, 95.09740590315053055 ) ) ; +#32206 = CARTESIAN_POINT ( 'NONE', ( 21.85653426457336579, 135.3094414512686967, 93.78622837506166832 ) ) ; +#32207 = ORIENTED_EDGE ( 'NONE', *, *, #8420, .T. ) ; +#32208 = CARTESIAN_POINT ( 'NONE', ( -23.00127433124000476, 115.6131156702010401, 87.78148031792994743 ) ) ; +#32209 = CARTESIAN_POINT ( 'NONE', ( 22.13129314184573460, 118.4600442149447161, 173.2772851743895899 ) ) ; +#32210 = CARTESIAN_POINT ( 'NONE', ( 19.52627756605939169, 125.2598979802000656, 175.1265769270767976 ) ) ; +#32211 = CARTESIAN_POINT ( 'NONE', ( 45.25458193946054308, 131.0018592820668175, 90.04080149089566021 ) ) ; +#32212 = ORIENTED_EDGE ( 'NONE', *, *, #14390, .T. ) ; +#32213 = CARTESIAN_POINT ( 'NONE', ( 21.14632598203208147, 213.4889694835328271, 76.04699967246882863 ) ) ; +#32214 = CARTESIAN_POINT ( 'NONE', ( 33.58239838537006250, 82.39900825877703028, 287.2850754345870428 ) ) ; +#32215 = ADVANCED_FACE ( 'NONE', ( #5470 ), #30836, .F. ) ; +#32216 = EDGE_CURVE ( 'NONE', #20739, #8063, #30876, .T. ) ; +#32217 = CARTESIAN_POINT ( 'NONE', ( -38.47073163710999921, 118.2823429409999960, 89.55163764424000306 ) ) ; +#32218 = ORIENTED_EDGE ( 'NONE', *, *, #7043, .T. ) ; +#32219 = AXIS2_PLACEMENT_3D ( 'NONE', #1476, #29298, #13754 ) ; +#32220 = ORIENTED_EDGE ( 'NONE', *, *, #3615, .F. ) ; +#32221 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6968, #22536, #32133, #23130 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.8698163993620108281 ), + .UNSPECIFIED. ) ; +#32222 = CARTESIAN_POINT ( 'NONE', ( 35.11870792466202573, 88.60542317626236297, 280.9309724330075255 ) ) ; +#32223 = DIRECTION ( 'NONE', ( 0.6087904839324246309, -0.7729173423006461263, -0.1788097554503957631 ) ) ; +#32224 = ORIENTED_EDGE ( 'NONE', *, *, #19320, .F. ) ; +#32225 = ORIENTED_EDGE ( 'NONE', *, *, #29404, .T. ) ; +#32226 = LINE ( 'NONE', #32028, #17389 ) ; +#32227 = EDGE_LOOP ( 'NONE', ( #699, #27121, #2159, #28989 ) ) ; +#32228 = ORIENTED_EDGE ( 'NONE', *, *, #23399, .T. ) ; +#32229 = CARTESIAN_POINT ( 'NONE', ( -6.036392767846526120, 177.5104564733402697, 100.8777564939393159 ) ) ; +#32230 = CIRCLE ( 'NONE', #5450, 4.500000113611068997 ) ; +#32231 = LINE ( 'NONE', #13420, #22927 ) ; +#32232 = CARTESIAN_POINT ( 'NONE', ( 19.71701219870257304, 124.6133069866743455, 177.2811646003819135 ) ) ; +#32233 = EDGE_LOOP ( 'NONE', ( #22595, #2311, #29710, #24804 ) ) ; +#32234 = CARTESIAN_POINT ( 'NONE', ( -75.43109585698152841, 195.4393986266174750, 195.0604493769935459 ) ) ; +#32235 = CARTESIAN_POINT ( 'NONE', ( 36.19634185401000082, 113.3779856859000006, 87.88489253477000318 ) ) ; +#32236 = CARTESIAN_POINT ( 'NONE', ( 36.09356709709999933, 191.3986140952000028, 103.6885138668000081 ) ) ; +#32237 = CARTESIAN_POINT ( 'NONE', ( -45.39606049366843621, 123.6566771517818637, 91.23024032489176705 ) ) ; +#32238 = EDGE_CURVE ( 'NONE', #24392, #8481, #27390, .T. ) ; +#32239 = DIRECTION ( 'NONE', ( -0.0002267487151011638629, -0.6230052038431761474, -0.7822176580526309930 ) ) ; +#32240 = ORIENTED_EDGE ( 'NONE', *, *, #7733, .T. ) ; +#32241 = CARTESIAN_POINT ( 'NONE', ( 25.66582274369000061, 120.7019146121999995, 87.84584558110999808 ) ) ; +#32242 = DIRECTION ( 'NONE', ( -0.0004229286328628529840, 0.2247401617665200635, -0.9744186373528217482 ) ) ; +#32243 = LINE ( 'NONE', #28576, #38411 ) ; +#32244 = CARTESIAN_POINT ( 'NONE', ( 3.767825934166819213, 175.3046377764247268, 100.3625370439014830 ) ) ; +#32245 = CARTESIAN_POINT ( 'NONE', ( -18.84220113800309448, 125.7468176466592382, 175.1817517265227195 ) ) ; +#32246 = ORIENTED_EDGE ( 'NONE', *, *, #11918, .F. ) ; +#32247 = CARTESIAN_POINT ( 'NONE', ( 44.90853464007773965, 181.5172347420035237, 101.5323552624301016 ) ) ; +#32248 = CARTESIAN_POINT ( 'NONE', ( 0.8683326238474313730, 189.0234992568099983, 103.6916932741592063 ) ) ; +#32249 = AXIS2_PLACEMENT_3D ( 'NONE', #1769, #14248, #27140 ) ; +#32250 = AXIS2_PLACEMENT_3D ( 'NONE', #21862, #15129, #15319 ) ; +#32251 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709482895, 82.27946979429644614, 322.5205145037751890 ) ) ; +#32252 = ADVANCED_FACE ( 'NONE', ( #39815 ), #36756, .F. ) ; +#32253 = CARTESIAN_POINT ( 'NONE', ( 3.667815741540035646, 183.5629855103865964, 104.5953232250576406 ) ) ; +#32254 = CIRCLE ( 'NONE', #17857, 3.000000000000000888 ) ; +#32255 = CARTESIAN_POINT ( 'NONE', ( -25.87019154357000161, 191.8551652017999913, 104.0556614200000212 ) ) ; +#32256 = DIRECTION ( 'NONE', ( -1.868163743397223657E-15, 0.9743700557921585181, 0.2249510932971567623 ) ) ; +#32257 = CARTESIAN_POINT ( 'NONE', ( -3.625412116750075686, 168.4715326382302294, 98.63986567913343606 ) ) ; +#32258 = CARTESIAN_POINT ( 'NONE', ( 36.54215494650633644, 137.9975274739460644, 288.6199674919093923 ) ) ; +#32259 = CARTESIAN_POINT ( 'NONE', ( -20.24838124913999948, 167.0064264920000028, 101.0439605547000070 ) ) ; +#32260 = ORIENTED_EDGE ( 'NONE', *, *, #32486, .F. ) ; +#32261 = CARTESIAN_POINT ( 'NONE', ( -1.987599235653746188, 161.6130078871375417, 102.0969471392255770 ) ) ; +#32262 = EDGE_CURVE ( 'NONE', #12930, #12044, #17147, .T. ) ; +#32263 = EDGE_CURVE ( 'NONE', #27919, #35056, #25956, .T. ) ; +#32264 = ADVANCED_FACE ( 'NONE', ( #6275 ), #540, .T. ) ; +#32265 = FACE_OUTER_BOUND ( 'NONE', #5132, .T. ) ; +#32266 = ORIENTED_EDGE ( 'NONE', *, *, #24342, .T. ) ; +#32267 = FACE_OUTER_BOUND ( 'NONE', #9429, .T. ) ; +#32268 = CARTESIAN_POINT ( 'NONE', ( -25.99613447915552555, 191.6796580302363964, 103.9154390762144260 ) ) ; +#32269 = EDGE_CURVE ( 'NONE', #10234, #11951, #38097, .T. ) ; +#32270 = CARTESIAN_POINT ( 'NONE', ( 36.77959379203999646, 191.5319398393999961, 106.2265964018000091 ) ) ; +#32271 = CARTESIAN_POINT ( 'NONE', ( -41.34363534162371678, 121.0516446937131718, 87.79591618170475442 ) ) ; +#32272 = CARTESIAN_POINT ( 'NONE', ( 40.49581267819608854, 84.18892247206676416, 282.5307213418886931 ) ) ; +#32273 = DIRECTION ( 'NONE', ( 0.0005884949961262337520, -0.2249510543439053878, 0.9743698870671265722 ) ) ; +#32274 = VERTEX_POINT ( 'NONE', #3406 ) ; +#32275 = CARTESIAN_POINT ( 'NONE', ( -2.713411677741000450, 209.5989927075000026, 75.89345322724000198 ) ) ; +#32276 = CIRCLE ( 'NONE', #29683, 22.50000000000899902 ) ; +#32277 = CARTESIAN_POINT ( 'NONE', ( -16.28146077159970062, 122.7838420707920051, 174.3381434293534937 ) ) ; +#32278 = AXIS2_PLACEMENT_3D ( 'NONE', #9364, #37170, #39817 ) ; +#32279 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29473, #4922, #36196, #17377, #35772, #20253, #39670, #30493, #30693, #21294, #33531, #33935, #24161, #14948, #27642, #2868, #39874, #36816, #9222, #24570 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000489053, 0.1875000000000614786, 0.2187500000000586475, 0.2343750000000572042, 0.2500000000000557332, 0.5000000000000536238, 0.6250000000000585088, 0.6875000000000549560, 0.7187500000000485167, 0.7343750000000416334, 0.7500000000000347500, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32280 = CARTESIAN_POINT ( 'NONE', ( -45.68157572959258772, 116.8137947612332681, 122.5502833297559135 ) ) ; +#32281 = ORIENTED_EDGE ( 'NONE', *, *, #19430, .F. ) ; +#32282 = DIRECTION ( 'NONE', ( -0.9999998186616234630, 7.423303222494310403E-07, 0.0006022260116136528329 ) ) ; +#32283 = AXIS2_PLACEMENT_3D ( 'NONE', #6301, #34112, #27618 ) ; +#32284 = ORIENTED_EDGE ( 'NONE', *, *, #36948, .F. ) ; +#32285 = CARTESIAN_POINT ( 'NONE', ( -4.726290685248240919, 130.8407438226161048, 89.86274152813891192 ) ) ; +#32286 = CARTESIAN_POINT ( 'NONE', ( -16.15354643035712812, 122.9157560190214156, 174.2038265287079071 ) ) ; +#32287 = ORIENTED_EDGE ( 'NONE', *, *, #34642, .T. ) ; +#32288 = FACE_OUTER_BOUND ( 'NONE', #12183, .T. ) ; +#32289 = CARTESIAN_POINT ( 'NONE', ( 23.77777407637487883, 214.0117437154297590, 76.04410721373406545 ) ) ; +#32290 = CARTESIAN_POINT ( 'NONE', ( -36.45592555318621919, 191.2086150054764175, 103.8189291966230741 ) ) ; +#32291 = DIRECTION ( 'NONE', ( -0.5976534202554355524, 0.8017545692149061765, 0.000000000000000000 ) ) ; +#32292 = ORIENTED_EDGE ( 'NONE', *, *, #2893, .F. ) ; +#32293 = ORIENTED_EDGE ( 'NONE', *, *, #25588, .T. ) ; +#32294 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; +#32295 = CARTESIAN_POINT ( 'NONE', ( -5.662686464640452222, 188.3429660633563287, 103.1387990589197869 ) ) ; +#32296 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971594823 ) ) ; +#32297 = EDGE_CURVE ( 'NONE', #38998, #14154, #746, .T. ) ; +#32298 = CARTESIAN_POINT ( 'NONE', ( -22.78292978085340081, 157.6260587155269661, 99.13643849004034792 ) ) ; +#32299 = ORIENTED_EDGE ( 'NONE', *, *, #14552, .F. ) ; +#32300 = CARTESIAN_POINT ( 'NONE', ( -23.36013622322100858, 127.9076955631267509, 92.27576111913165846 ) ) ; +#32301 = CONICAL_SURFACE ( 'NONE', #27093, 2.500000000042679638, 0.7853981634197695350 ) ; +#32302 = EDGE_CURVE ( 'NONE', #17683, #10631, #13173, .T. ) ; +#32303 = AXIS2_PLACEMENT_3D ( 'NONE', #12045, #8983, #21461 ) ; +#32304 = AXIS2_PLACEMENT_3D ( 'NONE', #5020, #23849, #19943 ) ; +#32305 = CARTESIAN_POINT ( 'NONE', ( -20.39369818271929802, 136.8328687898372777, 91.25559555417643764 ) ) ; +#32306 = VECTOR ( 'NONE', #36735, 1000.000000000000000 ) ; +#32307 = ADVANCED_FACE ( 'NONE', ( #22646 ), #10120, .F. ) ; +#32308 = ADVANCED_FACE ( 'NONE', ( #20496 ), #14481, .T. ) ; +#32309 = CARTESIAN_POINT ( 'NONE', ( -38.95668886436796896, 209.7096538830999748, 73.08203294633123903 ) ) ; +#32310 = EDGE_CURVE ( 'NONE', #20231, #14032, #18091, .T. ) ; +#32311 = FACE_OUTER_BOUND ( 'NONE', #32696, .T. ) ; +#32312 = EDGE_CURVE ( 'NONE', #2464, #3137, #9262, .T. ) ; +#32313 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9814, #194, #16132, #10222, #38006, #22287, #22086, #16516, #12666, #6516, #10011, #29012 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999890088, 0.3749999999999897304, 0.4374999999999955036, 0.5000000000000013323, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32314 = CARTESIAN_POINT ( 'NONE', ( -2.713752470710999898, 209.7550057423999874, 73.18224161559000152 ) ) ; +#32315 = CARTESIAN_POINT ( 'NONE', ( -37.67176343985000386, 190.1981568370999867, 106.8040751365000034 ) ) ; +#32316 = ORIENTED_EDGE ( 'NONE', *, *, #527, .F. ) ; +#32317 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#32318 = CARTESIAN_POINT ( 'NONE', ( -36.17397473344645675, 191.8429952646565937, 106.4342576988118623 ) ) ; +#32319 = CARTESIAN_POINT ( 'NONE', ( 2.561557522426482159, 191.9759150222000130, 101.9199002238076162 ) ) ; +#32320 = CARTESIAN_POINT ( 'NONE', ( -28.16705410445850433, 186.9743050576410326, 105.9152681543748997 ) ) ; +#32321 = ORIENTED_EDGE ( 'NONE', *, *, #6623, .T. ) ; +#32322 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #7465, #9607, #7675, #10965 ), + ( #3249, #35662, #4608, #16864 ), + ( #20137, #13817, #29563, #28224 ), + ( #29368, #1540, #190, #10563 ), + ( #19935, #38359, #1338, #35458 ), + ( #13427, #32044, #14024, #26506 ), + ( #16468, #25913, #12663, #25153 ), + ( #22082, #10366, #35266, #32235 ), + ( #4195, #30063, #14731, #33310 ), + ( #23512, #23933, #24133, #30468 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.004176192228627999790, 0.000000000000000000, 7.579363622111999969E-07, 0.2500138562320999847, 0.5000092427718999533, 0.7500046293118000085, 1.000000000000000000, 1.016692674581000100 ), + ( 1.377093476695000024E-06, 1.000019867702000020 ), + .UNSPECIFIED. ) ; +#32323 = ORIENTED_EDGE ( 'NONE', *, *, #19120, .T. ) ; +#32324 = DIRECTION ( 'NONE', ( -0.6087611427424988175, -0.7731004630501198127, -0.1781166615410728349 ) ) ; +#32325 = DIRECTION ( 'NONE', ( 0.5987319967475925875, 0.8009494341533932582, 0.000000000000000000 ) ) ; +#32326 = EDGE_LOOP ( 'NONE', ( #17997, #11168, #32029, #15429 ) ) ; +#32327 = AXIS2_PLACEMENT_3D ( 'NONE', #24070, #17088, #36526 ) ; +#32328 = CARTESIAN_POINT ( 'NONE', ( 13.50147201671766695, 185.3473651114627501, 105.0013405082515163 ) ) ; +#32329 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052565999616 ) ) ; +#32330 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; +#32331 = CARTESIAN_POINT ( 'NONE', ( -38.35450013695000138, 119.2981560018999971, 87.45630205388999912 ) ) ; +#32332 = VECTOR ( 'NONE', #16836, 999.9999999999998863 ) ; +#32333 = CONICAL_SURFACE ( 'NONE', #24505, 2.500000000096461505, 0.7853981634068133433 ) ; +#32334 = FACE_OUTER_BOUND ( 'NONE', #2369, .T. ) ; +#32335 = ORIENTED_EDGE ( 'NONE', *, *, #22520, .T. ) ; +#32336 = CARTESIAN_POINT ( 'NONE', ( 0.04412548967593893368, 271.9029643396000324, 73.05847743173070796 ) ) ; +#32337 = EDGE_LOOP ( 'NONE', ( #18660, #1920, #4327, #31414 ) ) ; +#32338 = CARTESIAN_POINT ( 'NONE', ( -3.169906973560626895, 184.1222312815566795, 102.1628149875517408 ) ) ; +#32339 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23259, #20379, #23875, #35695 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32340 = CONICAL_SURFACE ( 'NONE', #31059, 2.503171115049211082, 0.7853981633607578505 ) ; +#32341 = DIRECTION ( 'NONE', ( -0.0005884949961204158147, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#32342 = LINE ( 'NONE', #32536, #34035 ) ; +#32343 = CARTESIAN_POINT ( 'NONE', ( 46.04942073387295665, 125.5491642319759791, 88.61041671179513912 ) ) ; +#32344 = VERTEX_POINT ( 'NONE', #7276 ) ; +#32345 = CARTESIAN_POINT ( 'NONE', ( -2.179982539881000214, 189.9716861103999861, 103.9665167251000071 ) ) ; +#32346 = CARTESIAN_POINT ( 'NONE', ( 25.49246811489144804, 207.5987292058227354, 76.61788227749146074 ) ) ; +#32347 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319386436951 ) ) ; +#32348 = EDGE_CURVE ( 'NONE', #37942, #23839, #16679, .T. ) ; +#32349 = ORIENTED_EDGE ( 'NONE', *, *, #25031, .T. ) ; +#32350 = CARTESIAN_POINT ( 'NONE', ( -20.33223045282921149, 118.1161730931157763, 89.94609189684267392 ) ) ; +#32351 = CARTESIAN_POINT ( 'NONE', ( -38.93661188355890346, 190.9636362828419749, 106.3296291375942388 ) ) ; +#32352 = ORIENTED_EDGE ( 'NONE', *, *, #33118, .T. ) ; +#32353 = EDGE_CURVE ( 'NONE', #11480, #6338, #28273, .T. ) ; +#32354 = EDGE_CURVE ( 'NONE', #30934, #7762, #24821, .T. ) ; +#32355 = EDGE_LOOP ( 'NONE', ( #36485, #1635, #30079, #7949 ) ) ; +#32356 = EDGE_LOOP ( 'NONE', ( #5106, #39001, #17790, #28369 ) ) ; +#32357 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971579003 ) ) ; +#32358 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -1.027544597027591327E-15, 0.0006039748319388571745 ) ) ; +#32359 = CARTESIAN_POINT ( 'NONE', ( 16.71302903106570881, 121.9752588367690436, 177.8431961985013459 ) ) ; +#32360 = EDGE_CURVE ( 'NONE', #6578, #4754, #24068, .T. ) ; +#32361 = VECTOR ( 'NONE', #32557, 1000.000000000000227 ) ; +#32362 = AXIS2_PLACEMENT_3D ( 'NONE', #15789, #37877, #10079 ) ; +#32363 = ORIENTED_EDGE ( 'NONE', *, *, #1536, .T. ) ; +#32364 = CARTESIAN_POINT ( 'NONE', ( 25.84393118718000082, 120.4857180374000052, 90.36132433278000065 ) ) ; +#32365 = FACE_OUTER_BOUND ( 'NONE', #10958, .T. ) ; +#32366 = AXIS2_PLACEMENT_3D ( 'NONE', #23845, #28815, #23432 ) ; +#32368 = LINE ( 'NONE', #16408, #37716 ) ; +#32367 = DIRECTION ( 'NONE', ( 0.0005884949961245237483, -0.2249510543439061649, 0.9743698870671263501 ) ) ; +#32369 = ORIENTED_EDGE ( 'NONE', *, *, #4118, .F. ) ; +#32370 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 67.27946979429633245, 315.0857197240632672 ) ) ; +#32371 = PLANE ( 'NONE', #2797 ) ; +#32372 = CARTESIAN_POINT ( 'NONE', ( -35.94780537797892350, 109.6131156792400105, 87.78949595639598158 ) ) ; +#32373 = VERTEX_POINT ( 'NONE', #6569 ) ; +#32374 = ORIENTED_EDGE ( 'NONE', *, *, #37517, .T. ) ; +#32375 = LINE ( 'NONE', #39504, #28320 ) ; +#32376 = CARTESIAN_POINT ( 'NONE', ( 5.669411459768906703, 187.4950212787814223, 105.7757252900559592 ) ) ; +#32377 = CARTESIAN_POINT ( 'NONE', ( -35.93807696458344481, 196.5784392977275843, 103.8968090176416297 ) ) ; +#32378 = ORIENTED_EDGE ( 'NONE', *, *, #17729, .T. ) ; +#32379 = ORIENTED_EDGE ( 'NONE', *, *, #24852, .T. ) ; +#32380 = VECTOR ( 'NONE', #33016, 1000.000000000000000 ) ; +#32381 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921579630, -0.2249510932971586774 ) ) ; +#32382 = VECTOR ( 'NONE', #30522, 1000.000000000000114 ) ; +#32383 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#32384 = AXIS2_PLACEMENT_3D ( 'NONE', #29198, #35291, #1165 ) ; +#32385 = EDGE_LOOP ( 'NONE', ( #22985, #12444, #15619, #10453 ) ) ; +#32386 = ORIENTED_EDGE ( 'NONE', *, *, #35833, .T. ) ; +#32387 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#32388 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34051, #24683, #8524, #36934 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32389 = ADVANCED_FACE ( 'NONE', ( #9663 ), #15393, .F. ) ; +#32390 = AXIS2_PLACEMENT_3D ( 'NONE', #22585, #35006, #12973 ) ; +#32391 = ADVANCED_FACE ( 'NONE', ( #5785 ), #8628, .T. ) ; +#32392 = EDGE_CURVE ( 'NONE', #13325, #39904, #27496, .T. ) ; +#32393 = AXIS2_PLACEMENT_3D ( 'NONE', #12325, #21744, #27688 ) ; +#32394 = DIRECTION ( 'NONE', ( -0.0002393071182776102175, -0.2252352986010028590, 0.9743043687658493601 ) ) ; +#32395 = EDGE_CURVE ( 'NONE', #650, #26354, #18830, .T. ) ; +#32396 = CARTESIAN_POINT ( 'NONE', ( 2.897570750862338507, 190.9033107830884148, 106.6325337691695836 ) ) ; +#32397 = ORIENTED_EDGE ( 'NONE', *, *, #36075, .T. ) ; +#32398 = CARTESIAN_POINT ( 'NONE', ( -30.07328833497793497, 135.0802858635263135, 91.08308969254834153 ) ) ; +#32399 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971575394 ) ) ; +#32400 = CARTESIAN_POINT ( 'NONE', ( 21.26219377714503622, 154.1161458975605001, 95.22059608960054788 ) ) ; +#32401 = CARTESIAN_POINT ( 'NONE', ( 44.30339254327586218, 188.9591885891941558, 103.2508314896253552 ) ) ; +#32402 = EDGE_CURVE ( 'NONE', #26493, #17270, #18598, .T. ) ; +#32403 = ORIENTED_EDGE ( 'NONE', *, *, #9836, .F. ) ; +#32404 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319385907860 ) ) ; +#32405 = CARTESIAN_POINT ( 'NONE', ( -28.94659870514799849, 110.6131156702000027, 89.78526776826356581 ) ) ; +#32406 = DIRECTION ( 'NONE', ( 0.0005884949961259294164, -0.2255194585872565272, 0.9742384859325513569 ) ) ; +#32407 = EDGE_CURVE ( 'NONE', #5335, #37130, #33400, .T. ) ; +#32408 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118781, 163.7809401697382725, 187.7700750526365425 ) ) ; +#32409 = VERTEX_POINT ( 'NONE', #31143 ) ; +#32410 = CARTESIAN_POINT ( 'NONE', ( 15.01573401434461807, 123.4937399423546509, 178.4505912408948802 ) ) ; +#32411 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35032, #3774, #35240, #32010, #37934, #19314, #9940 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 4 ), + ( 6.938893903907228378E-18, 0.001964037002783663999, 0.003942463309350621725 ), + .UNSPECIFIED. ) ; +#32412 = VECTOR ( 'NONE', #17914, 1000.000000000000114 ) ; +#32413 = AXIS2_PLACEMENT_3D ( 'NONE', #12104, #24788, #37042 ) ; +#32414 = CARTESIAN_POINT ( 'NONE', ( -35.82052824944000236, 112.9963127814999950, 89.90514415641000312 ) ) ; +#32415 = ORIENTED_EDGE ( 'NONE', *, *, #13177, .F. ) ; +#32416 = ORIENTED_EDGE ( 'NONE', *, *, #13812, .T. ) ; +#32417 = CARTESIAN_POINT ( 'NONE', ( -34.43835868710999648, 176.6247318011000402, 103.5296681725999974 ) ) ; +#32418 = DIRECTION ( 'NONE', ( 0.5988681445390194868, -0.8008476418498040594, 0.000000000000000000 ) ) ; +#32419 = CARTESIAN_POINT ( 'NONE', ( 23.69388335781209776, 131.0246890999723632, 89.88804818403849595 ) ) ; +#32420 = AXIS2_PLACEMENT_3D ( 'NONE', #34919, #11028, #13680 ) ; +#32421 = LINE ( 'NONE', #1324, #5079 ) ; +#32422 = VERTEX_POINT ( 'NONE', #15198 ) ; +#32423 = EDGE_LOOP ( 'NONE', ( #29968, #11771, #30300, #19853 ) ) ; +#32424 = FACE_BOUND ( 'NONE', #22721, .T. ) ; +#32425 = VERTEX_POINT ( 'NONE', #36865 ) ; +#32426 = VERTEX_POINT ( 'NONE', #28085 ) ; +#32427 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091564245 ) ) ; +#32428 = FACE_OUTER_BOUND ( 'NONE', #21460, .T. ) ; +#32429 = ORIENTED_EDGE ( 'NONE', *, *, #13297, .F. ) ; +#32430 = ORIENTED_EDGE ( 'NONE', *, *, #7413, .F. ) ; +#32431 = CARTESIAN_POINT ( 'NONE', ( -38.93814858684476121, 191.0388300950886560, 103.7812318162937686 ) ) ; +#32432 = CARTESIAN_POINT ( 'NONE', ( -35.68392459317214360, 192.7466937109657863, 106.6325799381910286 ) ) ; +#32433 = CARTESIAN_POINT ( 'NONE', ( -38.73646192734999971, 118.8634567458999953, 89.85986150100001169 ) ) ; +#32434 = CARTESIAN_POINT ( 'NONE', ( -19.29085203336684984, 116.9605294434551439, 189.5008840201654721 ) ) ; +#32435 = VERTEX_POINT ( 'NONE', #8870 ) ; +#32436 = FACE_BOUND ( 'NONE', #7032, .T. ) ; +#32437 = VERTEX_POINT ( 'NONE', #240 ) ; +#32438 = AXIS2_PLACEMENT_3D ( 'NONE', #25336, #32601, #14002 ) ; +#32439 = CARTESIAN_POINT ( 'NONE', ( -6.037316053083784162, 134.5233555713580813, 93.55307079258861336 ) ) ; +#32440 = CYLINDRICAL_SURFACE ( 'NONE', #31237, 1.749999999999998446 ) ; +#32441 = ADVANCED_FACE ( 'NONE', ( #21340 ), #5333, .F. ) ; +#32442 = EDGE_CURVE ( 'NONE', #30934, #1537, #2910, .T. ) ; +#32443 = VECTOR ( 'NONE', #27228, 1000.000000000000227 ) ; +#32444 = CARTESIAN_POINT ( 'NONE', ( -25.71821783760721303, 116.8420470932888406, 90.28331799833721050 ) ) ; +#32445 = CARTESIAN_POINT ( 'NONE', ( -21.57293377124131339, 182.0229620896140261, 104.5971269518084341 ) ) ; +#32446 = CIRCLE ( 'NONE', #4986, 2.000000000000000000 ) ; +#32447 = ORIENTED_EDGE ( 'NONE', *, *, #27, .F. ) ; +#32448 = DIRECTION ( 'NONE', ( 0.7871416011357068587, -0.6167723240884888103, 0.000000000000000000 ) ) ; +#32449 = CARTESIAN_POINT ( 'NONE', ( 0.6060660036824134789, 189.0004550687757501, 103.6810276021836756 ) ) ; +#32450 = CARTESIAN_POINT ( 'NONE', ( -40.80749064254892744, 126.9113585741438754, 91.54312417642556454 ) ) ; +#32451 = VECTOR ( 'NONE', #17112, 1000.000000000000114 ) ; +#32452 = CARTESIAN_POINT ( 'NONE', ( 20.48021663872660625, 209.7101073659619601, 73.54617496015868028 ) ) ; +#32453 = ORIENTED_EDGE ( 'NONE', *, *, #7178, .T. ) ; +#32454 = CARTESIAN_POINT ( 'NONE', ( -25.35579335349000019, 191.8103324465000128, 104.5670375079999985 ) ) ; +#32455 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971545696 ) ) ; +#32456 = DIRECTION ( 'NONE', ( 0.7933532970003738249, 0.5930762008556724751, 0.1372995488602876402 ) ) ; +#32457 = CARTESIAN_POINT ( 'NONE', ( -45.04728614389591002, 188.6755623356005174, 103.7177943918455156 ) ) ; +#32458 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825975761958095, 0.0005734119010998334383 ) ) ; +#32459 = ORIENTED_EDGE ( 'NONE', *, *, #32747, .T. ) ; +#32460 = DIRECTION ( 'NONE', ( -0.0004161288024550937855, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#32461 = ADVANCED_FACE ( 'NONE', ( #9063 ), #53, .F. ) ; +#32462 = ORIENTED_EDGE ( 'NONE', *, *, #32392, .F. ) ; +#32463 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#32464 = CARTESIAN_POINT ( 'NONE', ( -26.00800983458967508, 191.5260122442129216, 103.8858970416150385 ) ) ; +#32465 = VECTOR ( 'NONE', #29273, 999.9999999999998863 ) ; +#32466 = CARTESIAN_POINT ( 'NONE', ( 36.90835879720000179, 191.4328249133999975, 106.2128322142000059 ) ) ; +#32467 = FACE_OUTER_BOUND ( 'NONE', #8504, .T. ) ; +#32468 = CARTESIAN_POINT ( 'NONE', ( -40.95578253733000196, 219.5549399801000163, 74.58324062236999907 ) ) ; +#32469 = DIRECTION ( 'NONE', ( -1.725162000157249213E-15, -0.9743700557915021543, -0.2249510932999991553 ) ) ; +#32470 = VECTOR ( 'NONE', #6850, 1000.000000000000114 ) ; +#32471 = ORIENTED_EDGE ( 'NONE', *, *, #25623, .F. ) ; +#32472 = CARTESIAN_POINT ( 'NONE', ( -2.531195081725338358, 209.6169330143079321, 75.72670068308755731 ) ) ; +#32473 = CARTESIAN_POINT ( 'NONE', ( 36.22847411652472260, 116.3454942628183773, 87.24590320147396483 ) ) ; +#32474 = DIRECTION ( 'NONE', ( -0.9999998268368289756, -0.0001323825434281097023, 0.0005734118713717894101 ) ) ; +#32475 = FACE_OUTER_BOUND ( 'NONE', #17491, .T. ) ; +#32476 = ORIENTED_EDGE ( 'NONE', *, *, #19681, .T. ) ; +#32477 = CARTESIAN_POINT ( 'NONE', ( 6.035547152934244153, 177.3162026418089567, 100.9932161903808066 ) ) ; +#32478 = CARTESIAN_POINT ( 'NONE', ( -5.958856852865682896, 148.4703916786008904, 97.01252450521799631 ) ) ; +#32479 = VERTEX_POINT ( 'NONE', #21941 ) ; +#32480 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802245 ) ) ; +#32481 = CARTESIAN_POINT ( 'NONE', ( 5.659153654835778369, 124.3673852322629187, 88.36203164978959990 ) ) ; +#32482 = CARTESIAN_POINT ( 'NONE', ( 22.99909745638999681, 115.1133511170128969, 87.25389341346352978 ) ) ; +#32483 = ORIENTED_EDGE ( 'NONE', *, *, #17207, .T. ) ; +#32484 = CARTESIAN_POINT ( 'NONE', ( 36.10829853855725702, 192.3105547256718069, 106.3856345698964816 ) ) ; +#32485 = PLANE ( 'NONE', #25999 ) ; +#32486 = EDGE_CURVE ( 'NONE', #21267, #10098, #2083, .T. ) ; +#32488 = EDGE_CURVE ( 'NONE', #30360, #25128, #34383, .T. ) ; +#32487 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15001, #27506, #3123, #11941, #24424, #8879 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 4 ), + ( 6.938893903907228378E-18, 0.0005393080574366226855, 0.001078647824828534536, 0.001617990336877349073 ), + .UNSPECIFIED. ) ; +#32489 = CARTESIAN_POINT ( 'NONE', ( -12.63672208255219331, 130.6949650040740778, 90.11191724478814535 ) ) ; +#32490 = LINE ( 'NONE', #1398, #36021 ) ; +#32491 = VERTEX_POINT ( 'NONE', #6377 ) ; +#32492 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560684 ) ) ; +#32493 = CARTESIAN_POINT ( 'NONE', ( 12.31576967456374838, 135.2953866561074676, 91.39403622019926843 ) ) ; +#32494 = CARTESIAN_POINT ( 'NONE', ( -41.43719618776999880, 191.1885863319999999, 105.3567702172999958 ) ) ; +#32495 = EDGE_CURVE ( 'NONE', #17976, #36762, #9358, .T. ) ; +#32496 = AXIS2_PLACEMENT_3D ( 'NONE', #1658, #7986, #2070 ) ; +#32497 = CARTESIAN_POINT ( 'NONE', ( -76.10925030609611497, 156.2249461908330375, 96.27941314736982292 ) ) ; +#32498 = VERTEX_POINT ( 'NONE', #5982 ) ; +#32499 = CARTESIAN_POINT ( 'NONE', ( 19.99999382154498662, 120.3902235794415816, 87.43511282661482653 ) ) ; +#32500 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37819, #35330, #4465, #32103 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32501 = CARTESIAN_POINT ( 'NONE', ( 5.335329622941979544, 131.0223101498888241, 89.89858245878815524 ) ) ; +#32502 = PLANE ( 'NONE', #28022 ) ; +#32503 = CARTESIAN_POINT ( 'NONE', ( -28.53030869656295110, 124.6043131503039803, 91.51623810099293621 ) ) ; +#32504 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559574 ) ) ; +#32505 = CARTESIAN_POINT ( 'NONE', ( 39.06510290334847468, 190.7637496868926235, 106.4074214906108438 ) ) ; +#32506 = CARTESIAN_POINT ( 'NONE', ( 38.65260204170999714, 118.3717869362999977, 89.51298073911000586 ) ) ; +#32507 = ORIENTED_EDGE ( 'NONE', *, *, #26633, .F. ) ; +#32508 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2252353050503803633, -0.9743043966640312359 ) ) ; +#32509 = FACE_OUTER_BOUND ( 'NONE', #23187, .T. ) ; +#32510 = CARTESIAN_POINT ( 'NONE', ( 16.14434960479789538, 123.6872145150956754, 173.7816462225611929 ) ) ; +#32511 = CARTESIAN_POINT ( 'NONE', ( 24.86462005268904463, 181.6234868533104816, 104.6479044067819899 ) ) ; +#32512 = ORIENTED_EDGE ( 'NONE', *, *, #36361, .T. ) ; +#32513 = ORIENTED_EDGE ( 'NONE', *, *, #15059, .T. ) ; +#32514 = ORIENTED_EDGE ( 'NONE', *, *, #30225, .T. ) ; +#32515 = CARTESIAN_POINT ( 'NONE', ( -30.04055490880000079, 163.2729245447999915, 152.4718672074000381 ) ) ; +#32516 = EDGE_CURVE ( 'NONE', #2348, #18841, #23991, .T. ) ; +#32517 = VECTOR ( 'NONE', #12467, 1000.000000000000227 ) ; +#32518 = CARTESIAN_POINT ( 'NONE', ( -41.57645147788533535, 119.6918065143027405, 90.38997552799222035 ) ) ; +#32519 = DIRECTION ( 'NONE', ( 0.7856007465113979960, 0.6187337610642675845, 0.000000000000000000 ) ) ; +#32520 = VECTOR ( 'NONE', #26955, 1000.000000000000000 ) ; +#32521 = ORIENTED_EDGE ( 'NONE', *, *, #40140, .F. ) ; +#32522 = CARTESIAN_POINT ( 'NONE', ( -13.50000077688951450, 188.3420892684051751, 103.1432776901117307 ) ) ; +#32523 = ADVANCED_FACE ( 'NONE', ( #843 ), #19649, .T. ) ; +#32524 = CARTESIAN_POINT ( 'NONE', ( 16.00176583137093189, 118.9451395335793649, 90.18281804087267517 ) ) ; +#32525 = CARTESIAN_POINT ( 'NONE', ( -38.05128246918000912, 119.2386161678000036, 87.30352700896000329 ) ) ; +#32526 = CARTESIAN_POINT ( 'NONE', ( -26.01125412628304190, 210.1698902315000055, 73.07311846223655039 ) ) ; +#32527 = EDGE_LOOP ( 'NONE', ( #18395, #683 ) ) ; +#32528 = CARTESIAN_POINT ( 'NONE', ( 19.37875314990832720, 147.8161002492973353, 183.5612100039927839 ) ) ; +#32529 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1821, #4470, #7338, #10836 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32530 = ORIENTED_EDGE ( 'NONE', *, *, #29188, .F. ) ; +#32531 = PLANE ( 'NONE', #35061 ) ; +#32532 = EDGE_CURVE ( 'NONE', #11953, #15935, #4100, .T. ) ; +#32533 = EDGE_CURVE ( 'NONE', #38661, #15772, #15775, .T. ) ; +#32534 = CARTESIAN_POINT ( 'NONE', ( 5.674687014606257129, 130.3475820607916660, 92.82156578849662765 ) ) ; +#32535 = DIRECTION ( 'NONE', ( 0.0005884949961215158462, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#32536 = CARTESIAN_POINT ( 'NONE', ( 44.72966403672143798, 107.3098357594950301, 174.7165674052034774 ) ) ; +#32537 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#32538 = ADVANCED_FACE ( 'NONE', ( #13729 ), #32742, .T. ) ; +#32539 = ORIENTED_EDGE ( 'NONE', *, *, #4707, .F. ) ; +#32540 = CARTESIAN_POINT ( 'NONE', ( -0.6437799103817298807, 188.6069639608899990, 103.1926838550779877 ) ) ; +#32541 = EDGE_CURVE ( 'NONE', #34570, #13870, #9907, .T. ) ; +#32542 = DIRECTION ( 'NONE', ( -0.7716293354502457014, 0.6291556465476403348, -0.09354860282138378891 ) ) ; +#32543 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#32544 = CARTESIAN_POINT ( 'NONE', ( 2.942818760358000052, 190.8925541295000130, 106.6760814302000000 ) ) ; +#32545 = ORIENTED_EDGE ( 'NONE', *, *, #3964, .T. ) ; +#32546 = ORIENTED_EDGE ( 'NONE', *, *, #21680, .T. ) ; +#32547 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971553745 ) ) ; +#32548 = CARTESIAN_POINT ( 'NONE', ( 19.98635445618997863, 211.0854288155255460, 76.04696776081749476 ) ) ; +#32549 = ORIENTED_EDGE ( 'NONE', *, *, #16278, .F. ) ; +#32550 = AXIS2_PLACEMENT_3D ( 'NONE', #31647, #38175, #3408 ) ; +#32551 = VERTEX_POINT ( 'NONE', #38455 ) ; +#32552 = ORIENTED_EDGE ( 'NONE', *, *, #18993, .T. ) ; +#32553 = CARTESIAN_POINT ( 'NONE', ( -28.43520508893000098, 186.6528701677999891, 105.6701704825000121 ) ) ; +#32554 = FACE_OUTER_BOUND ( 'NONE', #21679, .T. ) ; +#32555 = DIRECTION ( 'NONE', ( -0.9999998176071905887, 9.946155655599188003E-12, 0.0006039748219953627959 ) ) ; +#32556 = EDGE_CURVE ( 'NONE', #32614, #19409, #1511, .T. ) ; +#32557 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557922372330, 0.2249510932968150356 ) ) ; +#32558 = EDGE_LOOP ( 'NONE', ( #21216, #36847, #5431, #271 ) ) ; +#32559 = CARTESIAN_POINT ( 'NONE', ( 25.50197546413999916, 120.3616906317000002, 89.99026255478999303 ) ) ; +#32560 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -5.029098237799274788E-18, 0.0006039748319384018096 ) ) ; +#32562 = CARTESIAN_POINT ( 'NONE', ( 20.53675418873675795, 124.4626139095243786, 152.4730720674764939 ) ) ; +#32561 = CARTESIAN_POINT ( 'NONE', ( -39.03036842918214688, 175.8132598318450448, 136.1868359453157780 ) ) ; +#32563 = VERTEX_POINT ( 'NONE', #4309 ) ; +#32564 = EDGE_CURVE ( 'NONE', #30774, #27000, #11209, .T. ) ; +#32565 = CARTESIAN_POINT ( 'NONE', ( -9.144678143162121131, 6.413363568748468246, 291.5640670916855015 ) ) ; +#32566 = CARTESIAN_POINT ( 'NONE', ( 30.06443600138266703, 134.9229365128052507, 90.78414315763292564 ) ) ; +#32567 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #39649, #14323, #14924, #4898 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 2.960051731740213743, 3.141592653589768691 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9972554596699719776, 0.9972554596699719776, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#32568 = VERTEX_POINT ( 'NONE', #20048 ) ; +#32569 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799577453, 175.3514230958872133, 100.1541516780437320 ) ) ; +#32570 = AXIS2_PLACEMENT_3D ( 'NONE', #39402, #36354, #24098 ) ; +#32571 = EDGE_CURVE ( 'NONE', #23382, #25978, #21676, .T. ) ; +#32572 = CARTESIAN_POINT ( 'NONE', ( -46.29179777306748633, 126.3974345674219677, 91.94093998034792037 ) ) ; +#32573 = CARTESIAN_POINT ( 'NONE', ( 29.38693461565323872, 112.1844516200949755, 175.8396907018270383 ) ) ; +#32574 = VERTEX_POINT ( 'NONE', #10278 ) ; +#32575 = ADVANCED_FACE ( 'NONE', ( #29277 ), #449, .T. ) ; +#32576 = ORIENTED_EDGE ( 'NONE', *, *, #36315, .T. ) ; +#32577 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17339, #19799, #11039, #23102 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32578 = CIRCLE ( 'NONE', #24103, 2.500000000000003997 ) ; +#32579 = ORIENTED_EDGE ( 'NONE', *, *, #21824, .T. ) ; +#32580 = VECTOR ( 'NONE', #470, 1000.000000000000114 ) ; +#32581 = CARTESIAN_POINT ( 'NONE', ( -23.36112322160831312, 134.5243777609601921, 93.56093267912147837 ) ) ; +#32582 = AXIS2_PLACEMENT_3D ( 'NONE', #24836, #8476, #15214 ) ; +#32583 = EDGE_CURVE ( 'NONE', #29610, #19329, #27421, .T. ) ; +#32584 = ORIENTED_EDGE ( 'NONE', *, *, #37778, .T. ) ; +#32585 = CARTESIAN_POINT ( 'NONE', ( 39.04644978079199547, 209.7096538831000032, 75.53492146109870475 ) ) ; +#32586 = ORIENTED_EDGE ( 'NONE', *, *, #126, .T. ) ; +#32587 = CARTESIAN_POINT ( 'NONE', ( -22.49783753475205472, 153.7286132221404955, 98.23646823715600362 ) ) ; +#32588 = CARTESIAN_POINT ( 'NONE', ( -30.07324787560831325, 135.0898699095424718, 91.09842734486377935 ) ) ; +#32589 = CARTESIAN_POINT ( 'NONE', ( 20.00148625195223318, 152.2913976755475858, 94.80008112724152625 ) ) ; +#32590 = CARTESIAN_POINT ( 'NONE', ( -35.96311564216326673, 218.5902260770998282, 61.08022271436995965 ) ) ; +#32591 = ORIENTED_EDGE ( 'NONE', *, *, #2541, .F. ) ; +#32592 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 3.469446951982499751E-14 ) ) ; +#32593 = FACE_OUTER_BOUND ( 'NONE', #20497, .T. ) ; +#32594 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825984634766995, 0.0005734119008966697805 ) ) ; +#32595 = CIRCLE ( 'NONE', #32570, 6.500000000035469405 ) ; +#32596 = EDGE_LOOP ( 'NONE', ( #10273, #17396, #24357, #33869 ) ) ; +#32597 = VECTOR ( 'NONE', #7896, 999.9999999999998863 ) ; +#32598 = DIRECTION ( 'NONE', ( -0.0005884949961249498398, 0.2249510543439061649, -0.9743698870671263501 ) ) ; +#32599 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13804, #20332, #7255, #35441, #32610, #14220, #1127, #4788, #3984, #35252 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999281686, 0.3749999999998922529, 0.4374999999998897549, 0.4999999999998873124, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32600 = CIRCLE ( 'NONE', #8460, 5.000000000000022204 ) ; +#32602 = CARTESIAN_POINT ( 'NONE', ( -37.14029669136999701, 117.9240011325999973, 90.44462167566000232 ) ) ; +#32601 = DIRECTION ( 'NONE', ( 0.0005884949961243941862, -0.2249510543439062205, 0.9743698870671264611 ) ) ; +#32603 = ORIENTED_EDGE ( 'NONE', *, *, #36871, .T. ) ; +#32604 = ORIENTED_EDGE ( 'NONE', *, *, #31297, .F. ) ; +#32605 = ADVANCED_FACE ( 'NONE', ( #38652 ), #22746, .F. ) ; +#32606 = DIRECTION ( 'NONE', ( 0.0006039748319392010834, 1.387181216573299978E-14, 0.9999998176071847045 ) ) ; +#32607 = EDGE_CURVE ( 'NONE', #1188, #26218, #39097, .T. ) ; +#32608 = CARTESIAN_POINT ( 'NONE', ( -12.60636661545733084, 165.2216646692707229, 152.9217693202412818 ) ) ; +#32609 = ADVANCED_FACE ( 'NONE', ( #648 ), #36678, .F. ) ; +#32610 = CARTESIAN_POINT ( 'NONE', ( -13.49992725747581979, 124.0400051682925380, 91.07724209068317123 ) ) ; +#32611 = ORIENTED_EDGE ( 'NONE', *, *, #13984, .T. ) ; +#32612 = EDGE_CURVE ( 'NONE', #30359, #10990, #33230, .T. ) ; +#32613 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #14028, #16470 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32614 = VERTEX_POINT ( 'NONE', #26820 ) ; +#32615 = CARTESIAN_POINT ( 'NONE', ( -14.29616513773771125, 176.1108002494009384, 103.0567508915260362 ) ) ; +#32616 = ORIENTED_EDGE ( 'NONE', *, *, #39344, .F. ) ; +#32617 = VERTEX_POINT ( 'NONE', #8620 ) ; +#32618 = CARTESIAN_POINT ( 'NONE', ( -15.99819964153972585, 151.3054952985143302, 97.67310904513065850 ) ) ; +#32619 = CARTESIAN_POINT ( 'NONE', ( 2.711010865941999803, 209.0456857263999950, 73.43539125376000243 ) ) ; +#32620 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6496, #12256, #37197, #18971, #9193, #4228, #4439 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 4 ), + ( 0.000000000000000000, 0.2500002580796455431, 0.5000005535300821036, 0.7500008489806186951, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32621 = EDGE_CURVE ( 'NONE', #33415, #19817, #16154, .T. ) ; +#32622 = EDGE_LOOP ( 'NONE', ( #34203, #18678, #37109, #36626 ) ) ; +#32623 = LINE ( 'NONE', #17873, #32380 ) ; +#32624 = DIRECTION ( 'NONE', ( -0.9999998268367878973, -0.0001323826274100926099, 0.0005734119238466204227 ) ) ; +#32625 = CARTESIAN_POINT ( 'NONE', ( 36.89400472785000318, 191.0540516233000119, 103.5962395498000035 ) ) ; +#32626 = CARTESIAN_POINT ( 'NONE', ( 20.00005890743648607, 191.9885872211059734, 103.9228223727556752 ) ) ; +#32627 = EDGE_CURVE ( 'NONE', #25669, #11269, #2550, .T. ) ; +#32628 = AXIS2_PLACEMENT_3D ( 'NONE', #19648, #16780, #12778 ) ; +#32629 = ORIENTED_EDGE ( 'NONE', *, *, #33352, .F. ) ; +#32630 = FACE_OUTER_BOUND ( 'NONE', #15883, .T. ) ; +#32631 = CARTESIAN_POINT ( 'NONE', ( -23.35930774392331344, 176.9677908774963271, 103.4027938875997563 ) ) ; +#32632 = AXIS2_PLACEMENT_3D ( 'NONE', #19534, #32037, #7460 ) ; +#32633 = ORIENTED_EDGE ( 'NONE', *, *, #3454, .T. ) ; +#32634 = AXIS2_PLACEMENT_3D ( 'NONE', #39633, #14106, #26580 ) ; +#32635 = CARTESIAN_POINT ( 'NONE', ( 45.51092638067240870, 130.6862150259999282, 92.36248445504377003 ) ) ; +#32636 = CIRCLE ( 'NONE', #37861, 5.499999999738644618 ) ; +#32637 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#32638 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#32639 = CIRCLE ( 'NONE', #15651, 3.499999999950280216 ) ; +#32640 = CARTESIAN_POINT ( 'NONE', ( -27.80047107912594484, 149.4166296170034514, 291.5753347231419639 ) ) ; +#32641 = ORIENTED_EDGE ( 'NONE', *, *, #8916, .T. ) ; +#32642 = FACE_OUTER_BOUND ( 'NONE', #35349, .T. ) ; +#32643 = DIRECTION ( 'NONE', ( 0.1943643238945236551, -0.07321898756438741107, 0.9781929714821462341 ) ) ; +#32644 = CARTESIAN_POINT ( 'NONE', ( 32.06958471603104499, 135.8635028755992948, 91.00011324994767392 ) ) ; +#32645 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#32646 = EDGE_LOOP ( 'NONE', ( #36512, #16531, #8297, #25718 ) ) ; +#32647 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #3902, #15578, #28076 ), + ( #9658, #22135, #25011 ), + ( #31330, #16378, #3302 ), + ( #12932, #25410, #28665 ) ), + .UNSPECIFIED., .F., .F., .T. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), + ( 3, 3 ), + ( 0.5327326735548589820, 0.5327532648617869793 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.7516706677407538617, 1.000000000000000000), + ( 1.000000000000000000, 0.7516796584409587423, 1.000000000000000000), + ( 1.000000000000000000, 0.7516886489076254341, 1.000000000000000000), + ( 1.000000000000000000, 0.7516976391407651503, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#32648 = CARTESIAN_POINT ( 'NONE', ( -25.35572225526000167, 191.8208763773999976, 104.5667680184999995 ) ) ; +#32649 = CARTESIAN_POINT ( 'NONE', ( -35.95517947438523976, 209.7096537232000344, 75.58022056590567672 ) ) ; +#32650 = CARTESIAN_POINT ( 'NONE', ( 16.56169987041441161, 121.8384666780658563, 177.5555275195565059 ) ) ; +#32651 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #23831, #23628, #1749, #39341 ), + ( #11345, #20132, #32619, #7874 ), + ( #27120, #8081, #20339, #4600 ), + ( #2365, #17059, #8290, #39555 ), + ( #14227, #4799, #39151, #11153 ), + ( #20750, #30167, #2161, #37108 ), + ( #34218, #12361, #279, #2568 ), + ( #3148, #9501, #30580, #18877 ), + ( #31374, #8911, #11972, #28121 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 3, 4 ), + ( 4, 4 ), + ( 1.441988195786000121E-07, 0.3333318610857000097, 0.6666636764651000524, 0.9999981099119999994, 1.009998089569131841 ), + ( 0.1756413813676999947, 0.8243586172615999796 ), + .UNSPECIFIED. ) ; +#32652 = CARTESIAN_POINT ( 'NONE', ( -45.55635243984895055, 188.0246239919785012, 103.5677856498340788 ) ) ; +#32653 = CARTESIAN_POINT ( 'NONE', ( -15.49852918602411300, 173.9514291674110780, 102.3878961845165776 ) ) ; +#32654 = ORIENTED_EDGE ( 'NONE', *, *, #14491, .T. ) ; +#32655 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 1.540743955509789367E-33, -0.0006039748319385908944 ) ) ; +#32656 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#32657 = VECTOR ( 'NONE', #38217, 1000.000000000000114 ) ; +#32658 = AXIS2_PLACEMENT_3D ( 'NONE', #40211, #535, #3002 ) ; +#32659 = CARTESIAN_POINT ( 'NONE', ( -1.267128270904386511, 153.7461414230707533, 99.91119810786710786 ) ) ; +#32660 = CARTESIAN_POINT ( 'NONE', ( -15.94429972368852866, 121.8869921648800698, 174.4792395813007886 ) ) ; +#32661 = AXIS2_PLACEMENT_3D ( 'NONE', #4387, #16849, #3579 ) ; +#32662 = EDGE_CURVE ( 'NONE', #10007, #24020, #38620, .T. ) ; +#32663 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1340, #38167, #26109, #26305, #3799, #29175, #25915, #25715, #28964, #13624, #4610, #7271, #16277 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 0.000000000000000000, 0.3333373294491250860, 0.6666757894374520932, 0.7500296442072931224, 0.8333834989771342627, 0.8750604263620048728, 0.9167373537469253320, 0.9584142811318459021, 0.9792527448243011357, 0.9896719766705238674, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32664 = DIRECTION ( 'NONE', ( 0.1305263947813386505, -0.9660168765824634907, -0.2231014442428547184 ) ) ; +#32665 = CARTESIAN_POINT ( 'NONE', ( -29.94780647573000110, 103.6131156702000027, 87.78587210775999949 ) ) ; +#32666 = VECTOR ( 'NONE', #39023, 1000.000000000000114 ) ; +#32667 = EDGE_CURVE ( 'NONE', #21316, #37119, #25866, .T. ) ; +#32668 = FACE_OUTER_BOUND ( 'NONE', #39619, .T. ) ; +#32669 = EDGE_CURVE ( 'NONE', #24826, #40142, #19066, .T. ) ; +#32670 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#32671 = CARTESIAN_POINT ( 'NONE', ( -38.36188292311027936, 118.8221229462069886, 87.72102071481469920 ) ) ; +#32672 = ORIENTED_EDGE ( 'NONE', *, *, #37793, .T. ) ; +#32673 = CARTESIAN_POINT ( 'NONE', ( -15.66646767741427126, 185.8311504091911388, 102.9069918773323735 ) ) ; +#32674 = CARTESIAN_POINT ( 'NONE', ( 18.98506067126258046, 148.2070439170772431, 184.7168109706149721 ) ) ; +#32675 = EDGE_CURVE ( 'NONE', #9595, #24926, #29533, .T. ) ; +#32676 = LINE ( 'NONE', #4654, #32451 ) ; +#32677 = ORIENTED_EDGE ( 'NONE', *, *, #3401, .T. ) ; +#32678 = CARTESIAN_POINT ( 'NONE', ( 15.59122080578150005, 126.7491934480292599, 179.2057717501043612 ) ) ; +#32679 = ORIENTED_EDGE ( 'NONE', *, *, #25126, .F. ) ; +#32680 = ADVANCED_FACE ( 'NONE', ( #20254 ), #4718, .F. ) ; +#32681 = CARTESIAN_POINT ( 'NONE', ( 25.49063000826092562, 211.0902260967494897, 73.54299573436949800 ) ) ; +#32682 = ORIENTED_EDGE ( 'NONE', *, *, #17380, .T. ) ; +#32683 = CARTESIAN_POINT ( 'NONE', ( 36.74499328828947142, 191.3591568088928909, 106.3388620510278457 ) ) ; +#32684 = PLANE ( 'NONE', #5496 ) ; +#32685 = CARTESIAN_POINT ( 'NONE', ( 116.6745667766377892, 205.5703614864765427, 191.2914269756732040 ) ) ; +#32686 = CARTESIAN_POINT ( 'NONE', ( 3.534343284623258974, 175.3621990150981276, 100.1363906404241675 ) ) ; +#32687 = CARTESIAN_POINT ( 'NONE', ( 6.036905256830820576, 177.7921244214965668, 100.6958231142670712 ) ) ; +#32688 = ORIENTED_EDGE ( 'NONE', *, *, #33196, .T. ) ; +#32689 = ORIENTED_EDGE ( 'NONE', *, *, #23038, .F. ) ; +#32690 = AXIS2_PLACEMENT_3D ( 'NONE', #33437, #20561, #20151 ) ; +#32691 = CARTESIAN_POINT ( 'NONE', ( 17.25792980860752124, 152.7424877160250389, 181.6016748130998906 ) ) ; +#32692 = CARTESIAN_POINT ( 'NONE', ( 12.63778118622178859, 182.0343951221179850, 102.1422187760583284 ) ) ; +#32693 = LINE ( 'NONE', #36368, #39741 ) ; +#32694 = CONICAL_SURFACE ( 'NONE', #5932, 5.003058809538631024, 0.7854316141403709928 ) ; +#32695 = CARTESIAN_POINT ( 'NONE', ( -20.49960732757744353, 118.8154816606033393, 87.78015075453545535 ) ) ; +#32696 = EDGE_LOOP ( 'NONE', ( #29157, #19789, #28851 ) ) ; +#32697 = ORIENTED_EDGE ( 'NONE', *, *, #29117, .T. ) ; +#32698 = ORIENTED_EDGE ( 'NONE', *, *, #24037, .T. ) ; +#32699 = DIRECTION ( 'NONE', ( 3.989863994746633598E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#32700 = CARTESIAN_POINT ( 'NONE', ( 36.90266447701996810, 191.1365804696341968, 103.7579919604353478 ) ) ; +#32701 = LINE ( 'NONE', #20628, #1935 ) ; +#32702 = CARTESIAN_POINT ( 'NONE', ( 37.03777023944995506, 116.4244683402141618, 89.69148395127533036 ) ) ; +#32703 = CARTESIAN_POINT ( 'NONE', ( -35.93878493987465816, 193.8169247290935004, 102.7246158654722734 ) ) ; +#32704 = DIRECTION ( 'NONE', ( 0.0005884949961235723609, -0.2249510543439049992, 0.9743698870671266832 ) ) ; +#32705 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#32706 = LINE ( 'NONE', #1215, #40249 ) ; +#32707 = PLANE ( 'NONE', #10094 ) ; +#32708 = LINE ( 'NONE', #4692, #17386 ) ; +#32709 = ORIENTED_EDGE ( 'NONE', *, *, #25160, .T. ) ; +#32710 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#32711 = CARTESIAN_POINT ( 'NONE', ( -42.56963625464027245, 120.8513313564750575, 90.65827283841386475 ) ) ; +#32712 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 1.238758140229869926E-30, -0.0006039748319385906776 ) ) ; +#32713 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#32714 = EDGE_CURVE ( 'NONE', #16908, #38246, #28240, .T. ) ; +#32715 = EDGE_CURVE ( 'NONE', #30537, #2172, #11304, .T. ) ; +#32716 = CARTESIAN_POINT ( 'NONE', ( 31.50927902874334308, 191.9221069586437807, 104.4557568079087133 ) ) ; +#32717 = ORIENTED_EDGE ( 'NONE', *, *, #17823, .F. ) ; +#32718 = VERTEX_POINT ( 'NONE', #14341 ) ; +#32719 = AXIS2_PLACEMENT_3D ( 'NONE', #16346, #37628, #38024 ) ; +#32720 = EDGE_LOOP ( 'NONE', ( #36602, #24031, #38962, #20991 ) ) ; +#32721 = FACE_OUTER_BOUND ( 'NONE', #28752, .T. ) ; +#32722 = LINE ( 'NONE', #16764, #1025 ) ; +#32723 = ORIENTED_EDGE ( 'NONE', *, *, #5428, .F. ) ; +#32724 = CIRCLE ( 'NONE', #30785, 2.499999999936769690 ) ; +#32725 = CARTESIAN_POINT ( 'NONE', ( -25.99272582769830819, 191.9759150222000130, 101.9371462954573673 ) ) ; +#32726 = ADVANCED_FACE ( 'NONE', ( #23956 ), #39266, .T. ) ; +#32727 = VERTEX_POINT ( 'NONE', #33130 ) ; +#32728 = ORIENTED_EDGE ( 'NONE', *, *, #28530, .T. ) ; +#32729 = CARTESIAN_POINT ( 'NONE', ( 37.96521291183479008, 190.3639829187772250, 106.6578906949923464 ) ) ; +#32730 = CARTESIAN_POINT ( 'NONE', ( 13.36057577586396938, 130.9455636308544229, 89.87601707795123218 ) ) ; +#32731 = CARTESIAN_POINT ( 'NONE', ( -37.84794342418000213, 119.0111939293000063, 87.26395353379000142 ) ) ; +#32732 = ORIENTED_EDGE ( 'NONE', *, *, #11733, .F. ) ; +#32733 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7151642779479941980, 0.6989564046112777262 ) ) ; +#32734 = CARTESIAN_POINT ( 'NONE', ( 17.27337838772892553, 121.3064376902564589, 177.4324028043064345 ) ) ; +#32735 = CARTESIAN_POINT ( 'NONE', ( -19.61865725212798139, 149.0880427795878518, 183.0335604834078254 ) ) ; +#32736 = ORIENTED_EDGE ( 'NONE', *, *, #8106, .F. ) ; +#32737 = EDGE_CURVE ( 'NONE', #20264, #349, #38589, .T. ) ; +#32738 = CARTESIAN_POINT ( 'NONE', ( -19.99998307616975524, 191.6734502099888005, 103.9162975344601136 ) ) ; +#32739 = DIRECTION ( 'NONE', ( 0.1695469893270774853, -1.252670582138759799E-14, -0.9855221044756549142 ) ) ; +#32740 = CARTESIAN_POINT ( 'NONE', ( 26.00233459572431371, 120.1578067510816510, 90.45674428593952143 ) ) ; +#32741 = EDGE_LOOP ( 'NONE', ( #16345, #12159, #18461, #1776, #4321 ) ) ; +#32742 = CONICAL_SURFACE ( 'NONE', #6634, 5.999999999944576778, 0.7853981633665771955 ) ; +#32743 = CARTESIAN_POINT ( 'NONE', ( 19.98324763982542862, 210.6264698755651921, 76.04472544804136191 ) ) ; +#32744 = ORIENTED_EDGE ( 'NONE', *, *, #7150, .F. ) ; +#32745 = ORIENTED_EDGE ( 'NONE', *, *, #35470, .T. ) ; +#32746 = AXIS2_PLACEMENT_3D ( 'NONE', #27085, #21136, #18442 ) ; +#32747 = EDGE_CURVE ( 'NONE', #19220, #10604, #31300, .T. ) ; +#32748 = EDGE_LOOP ( 'NONE', ( #34420, #25700, #38870, #10518 ) ) ; +#32749 = ORIENTED_EDGE ( 'NONE', *, *, #14742, .T. ) ; +#32750 = CARTESIAN_POINT ( 'NONE', ( -28.06646533513999842, 186.8817599097000084, 105.7227911433000003 ) ) ; +#32751 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927745150551, 0.0005734119022082871534 ) ) ; +#32752 = CARTESIAN_POINT ( 'NONE', ( 46.97661709579189449, 139.7843841080672007, 297.5301723299980381 ) ) ; +#32753 = EDGE_CURVE ( 'NONE', #8044, #16264, #143, .T. ) ; +#32754 = ORIENTED_EDGE ( 'NONE', *, *, #2531, .F. ) ; +#32755 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12268, #34123, #24757, #6320 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32756 = CARTESIAN_POINT ( 'NONE', ( 25.99874167938696345, 118.1131156663084738, 87.25205387058410622 ) ) ; +#32757 = EDGE_LOOP ( 'NONE', ( #4498, #29375, #14750, #24403 ) ) ; +#32758 = CARTESIAN_POINT ( 'NONE', ( 26.52219644700000245, 123.5473871732999953, 90.72568424453001512 ) ) ; +#32759 = CARTESIAN_POINT ( 'NONE', ( -24.27786784973672241, 213.2748330173207592, 75.57328985925654763 ) ) ; +#32760 = ADVANCED_FACE ( 'NONE', ( #200 ), #12284, .T. ) ; +#32761 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39892, #9031, #23976, #11700 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#32762 = EDGE_CURVE ( 'NONE', #23829, #37534, #27452, .T. ) ; +#32764 = LINE ( 'NONE', #30305, #26619 ) ; +#32763 = CARTESIAN_POINT ( 'NONE', ( 20.48145322531597756, 209.2067958958842269, 75.59590488910892248 ) ) ; +#32765 = EDGE_CURVE ( 'NONE', #10706, #1289, #19706, .T. ) ; +#32766 = ORIENTED_EDGE ( 'NONE', *, *, #17359, .T. ) ; +#32767 = VERTEX_POINT ( 'NONE', #6331 ) ; +#32768 = CARTESIAN_POINT ( 'NONE', ( 20.49882255141355714, 191.9760415900621808, 101.9090510850346192 ) ) ; +#32769 = AXIS2_PLACEMENT_3D ( 'NONE', #3857, #6523, #10424 ) ; +#32770 = ORIENTED_EDGE ( 'NONE', *, *, #31523, .F. ) ; +#32772 = AXIS2_PLACEMENT_3D ( 'NONE', #23449, #7898, #33041 ) ; +#32771 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#32773 = AXIS2_PLACEMENT_3D ( 'NONE', #613, #19209, #33957 ) ; +#32774 = DIRECTION ( 'NONE', ( 0.4303597330247870278, 0.7060138277436147636, -0.5624366410767025481 ) ) ; +#32775 = LINE ( 'NONE', #27275, #5688 ) ; +#32776 = DIRECTION ( 'NONE', ( -0.0004270746993301995954, 0.7071067811865993091, -0.7071066522152992251 ) ) ; +#32777 = EDGE_LOOP ( 'NONE', ( #36548, #10484, #9252, #15004, #1481 ) ) ; +#32778 = ORIENTED_EDGE ( 'NONE', *, *, #6849, .T. ) ; +#32779 = ORIENTED_EDGE ( 'NONE', *, *, #13886, .F. ) ; +#32780 = CARTESIAN_POINT ( 'NONE', ( -12.63696992648818451, 177.4628036669718369, 100.9107721134794105 ) ) ; +#32781 = CYLINDRICAL_SURFACE ( 'NONE', #2450, 1.999999999999996891 ) ; +#32782 = ORIENTED_EDGE ( 'NONE', *, *, #35422, .F. ) ; +#32783 = CARTESIAN_POINT ( 'NONE', ( -35.43627711642999856, 192.7868341534999956, 106.8766536760000037 ) ) ; +#32784 = CARTESIAN_POINT ( 'NONE', ( 3.064393835126558496, 190.8773406645956072, 106.7989981663780981 ) ) ; +#32785 = ORIENTED_EDGE ( 'NONE', *, *, #36972, .F. ) ; +#32786 = CARTESIAN_POINT ( 'NONE', ( 39.80107749601363309, 119.4152471894954601, 89.76382462946382645 ) ) ; +#32787 = CARTESIAN_POINT ( 'NONE', ( -20.49852834815464320, 160.1744661120611681, 99.21025293621499941 ) ) ; +#32788 = LINE ( 'NONE', #7236, #19550 ) ; +#32789 = CARTESIAN_POINT ( 'NONE', ( 20.89466079040630575, 182.4265417833274796, 104.8357029080749783 ) ) ; +#32790 = EDGE_CURVE ( 'NONE', #8044, #5645, #29339, .T. ) ; +#32791 = VERTEX_POINT ( 'NONE', #28233 ) ; +#32792 = CIRCLE ( 'NONE', #23673, 2.500000000088257401 ) ; +#32793 = CARTESIAN_POINT ( 'NONE', ( 3.882702609227124846, 148.9606115484772602, 129.9617790688552077 ) ) ; +#32794 = CARTESIAN_POINT ( 'NONE', ( -18.79252570011861678, 125.8499160133713133, 175.1155745579973484 ) ) ; +#32795 = AXIS2_PLACEMENT_3D ( 'NONE', #29061, #28662, #838 ) ; +#32796 = VECTOR ( 'NONE', #19117, 1000.000000000000114 ) ; +#32797 = ORIENTED_EDGE ( 'NONE', *, *, #37650, .T. ) ; +#32798 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557941447071, -0.2249510932885531445 ) ) ; +#32799 = EDGE_CURVE ( 'NONE', #629, #31589, #27842, .T. ) ; +#32800 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #19337, #22428, #28360, #34855 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 2.960011224583242839, 3.141237505301649247 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9972649584264866585, 0.9972649584264866585, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#32802 = CARTESIAN_POINT ( 'NONE', ( -37.90028209746999721, 118.4258653137000010, 90.15013806132000695 ) ) ; +#32801 = CARTESIAN_POINT ( 'NONE', ( -35.94659742893283294, 111.0397749124999933, 89.78949559157379667 ) ) ; +#32803 = ADVANCED_FACE ( 'NONE', ( #24369 ), #34732, .F. ) ; +#32804 = ORIENTED_EDGE ( 'NONE', *, *, #27546, .T. ) ; +#32805 = ADVANCED_FACE ( 'NONE', ( #40271 ), #9617, .F. ) ; +#32806 = ORIENTED_EDGE ( 'NONE', *, *, #10530, .F. ) ; +#32807 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319377456504 ) ) ; +#32808 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7071067167009886800, -0.7071068456721004702 ) ) ; +#32809 = LINE ( 'NONE', #35650, #2507 ) ; +#32810 = ORIENTED_EDGE ( 'NONE', *, *, #5745, .F. ) ; +#32811 = VERTEX_POINT ( 'NONE', #21694 ) ; +#32812 = CARTESIAN_POINT ( 'NONE', ( -42.56961273145186908, 120.8423396639923055, 90.69722013036826525 ) ) ; +#32813 = EDGE_LOOP ( 'NONE', ( #21397, #17016, #18232, #39613 ) ) ; +#32814 = EDGE_LOOP ( 'NONE', ( #22136, #12556, #17455, #6614 ) ) ; +#32815 = EDGE_LOOP ( 'NONE', ( #1745, #1926, #23986, #6392 ) ) ; +#32816 = CARTESIAN_POINT ( 'NONE', ( 8.710107595624538845, 190.8512735252159018, 106.7880641322737034 ) ) ; +#32817 = CARTESIAN_POINT ( 'NONE', ( 25.16034815843458361, 152.9446670041224081, 185.2614157039075167 ) ) ; +#32818 = AXIS2_PLACEMENT_3D ( 'NONE', #10118, #1097, #22594 ) ; +#32819 = EDGE_LOOP ( 'NONE', ( #9822, #35851, #4999, #1478 ) ) ; +#32820 = CYLINDRICAL_SURFACE ( 'NONE', #19321, 51.40509898897001761 ) ; +#32821 = CARTESIAN_POINT ( 'NONE', ( -36.21997592040000313, 192.0428499488999989, 104.5653900318999945 ) ) ; +#32823 = CIRCLE ( 'NONE', #12565, 2.500000000051482818 ) ; +#32822 = CARTESIAN_POINT ( 'NONE', ( 30.11497173888000134, 126.4642963853000168, 91.65365240219000498 ) ) ; +#32824 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971541810 ) ) ; +#32825 = EDGE_LOOP ( 'NONE', ( #13212, #28567, #27189, #40338 ) ) ; +#32826 = CARTESIAN_POINT ( 'NONE', ( 22.78070441975003391, 158.6816533748419147, 96.78686173997256503 ) ) ; +#32827 = CARTESIAN_POINT ( 'NONE', ( -30.07038618952948639, 174.6758729064384283, 103.0802804918280771 ) ) ; +#32828 = EDGE_LOOP ( 'NONE', ( #37051, #23266, #26444, #4529 ) ) ; +#32829 = CARTESIAN_POINT ( 'NONE', ( -20.51845187336659748, 208.8853181553784850, 75.71044176397822412 ) ) ; +#32830 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#32831 = CARTESIAN_POINT ( 'NONE', ( 20.50009675764631467, 195.3341997283218348, 104.9064908536454226 ) ) ; +#32832 = DIRECTION ( 'NONE', ( 0.9914447795421099663, -0.1270909273343945323, -0.02975139169821508847 ) ) ; +#32833 = ORIENTED_EDGE ( 'NONE', *, *, #14814, .F. ) ; +#32834 = DIRECTION ( 'NONE', ( 5.782411586589349356E-15, 0.9743700557921587402, 0.2249510932971554578 ) ) ; +#32835 = PLANE ( 'NONE', #18591 ) ; +#32836 = DIRECTION ( 'NONE', ( 0.1305263947825949788, 0.9659212016154236080, 0.2235153071601011787 ) ) ; +#32837 = EDGE_CURVE ( 'NONE', #7061, #20336, #12754, .T. ) ; +#32838 = ADVANCED_FACE ( 'NONE', ( #3060 ), #2110, .F. ) ; +#32839 = VERTEX_POINT ( 'NONE', #33532 ) ; +#32840 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566235 ) ) ; +#32841 = ORIENTED_EDGE ( 'NONE', *, *, #18390, .F. ) ; +#32842 = ADVANCED_FACE ( 'NONE', ( #39875 ), #3397, .T. ) ; +#32843 = CARTESIAN_POINT ( 'NONE', ( -25.87037428029999830, 191.8434814924999898, 104.0540975785000057 ) ) ; +#32844 = DIRECTION ( 'NONE', ( 0.7066795775021695869, -1.083657843182747848E-14, -0.7075337269285155717 ) ) ; +#32845 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825852062932896, 0.0005734119039538788888 ) ) ; +#32846 = ADVANCED_FACE ( 'NONE', ( #11886 ), #26275, .F. ) ; +#32847 = CARTESIAN_POINT ( 'NONE', ( 22.78191781013921968, 158.2317512751428126, 98.73560149028561739 ) ) ; +#32848 = ORIENTED_EDGE ( 'NONE', *, *, #4043, .T. ) ; +#32849 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#32850 = ADVANCED_FACE ( 'NONE', ( #40074 ), #15163, .F. ) ; +#32851 = CIRCLE ( 'NONE', #11296, 2.500000000039660275 ) ; +#32852 = CARTESIAN_POINT ( 'NONE', ( -35.94409206926000167, 192.9208245654000109, 106.5386867681999945 ) ) ; +#32853 = CARTESIAN_POINT ( 'NONE', ( -17.17998261867176524, 121.8556495602137488, 175.2825063656824511 ) ) ; +#32854 = CARTESIAN_POINT ( 'NONE', ( 37.05652324767000039, 190.9934127923000062, 106.4015284892000039 ) ) ; +#32855 = CARTESIAN_POINT ( 'NONE', ( 31.26527125512335559, 177.5014052372173410, 100.6134679889321575 ) ) ; +#32856 = DIRECTION ( 'NONE', ( -0.0005884928212895037744, 0.2249510522791092204, -0.9743698875451359820 ) ) ; +#32857 = LINE ( 'NONE', #1793, #14513 ) ; +#32858 = CARTESIAN_POINT ( 'NONE', ( -38.46834805455461037, 118.9254695117024028, 87.72566723886511397 ) ) ; +#32859 = ORIENTED_EDGE ( 'NONE', *, *, #18914, .T. ) ; +#32860 = ADVANCED_FACE ( 'NONE', ( #26168 ), #38218, .F. ) ; +#32861 = CARTESIAN_POINT ( 'NONE', ( -15.49970618539471268, 185.7934281236995844, 103.0692296848312282 ) ) ; +#32862 = CARTESIAN_POINT ( 'NONE', ( 16.00178153260169722, 185.2344458670014831, 105.4869183982072371 ) ) ; +#32863 = EDGE_LOOP ( 'NONE', ( #5270, #36276, #17334, #12788, #27321, #8525, #3494 ) ) ; +#32864 = CARTESIAN_POINT ( 'NONE', ( 5.665213903590472277, 181.8726204490157272, 101.8888004455338745 ) ) ; +#32865 = DIRECTION ( 'NONE', ( -0.0005884949961240561319, 0.2249510543439064147, -0.9743698870671262391 ) ) ; +#32866 = ORIENTED_EDGE ( 'NONE', *, *, #22986, .T. ) ; +#32867 = CYLINDRICAL_SURFACE ( 'NONE', #18200, 54.50273826251000742 ) ; +#32868 = VERTEX_POINT ( 'NONE', #12889 ) ; +#32869 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971545418 ) ) ; +#32870 = CIRCLE ( 'NONE', #18503, 2.000000000000000000 ) ; +#32871 = DIRECTION ( 'NONE', ( 0.0005884949961224158425, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#32872 = CARTESIAN_POINT ( 'NONE', ( -35.94780537797892350, 109.6131156792400105, 87.78949595639598158 ) ) ; +#32873 = AXIS2_PLACEMENT_3D ( 'NONE', #38255, #25605, #4089 ) ; +#32874 = DIRECTION ( 'NONE', ( -0.9999998176073598977, 1.232348283187829930E-10, 0.0006039745416129974672 ) ) ; +#32875 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#32876 = VERTEX_POINT ( 'NONE', #16334 ) ; +#32877 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; +#32878 = VECTOR ( 'NONE', #6130, 1000.000000000000114 ) ; +#32879 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673440795, 184.8538583973032701, 102.8347976078998443 ) ) ; +#32880 = CARTESIAN_POINT ( 'NONE', ( 3.534343284623258974, 175.3621990150981276, 100.1363906404241675 ) ) ; +#32881 = EDGE_CURVE ( 'NONE', #6175, #36179, #35117, .T. ) ; +#32883 = ORIENTED_EDGE ( 'NONE', *, *, #15371, .F. ) ; +#32882 = EDGE_CURVE ( 'NONE', #24370, #6504, #7296, .T. ) ; +#32884 = CARTESIAN_POINT ( 'NONE', ( -5.668553076710673544, 181.6128662711424795, 104.1507415732276769 ) ) ; +#32885 = ORIENTED_EDGE ( 'NONE', *, *, #31396, .T. ) ; +#32886 = ORIENTED_EDGE ( 'NONE', *, *, #34629, .T. ) ; +#32887 = ADVANCED_FACE ( 'NONE', ( #19401 ), #13085, .T. ) ; +#32888 = ORIENTED_EDGE ( 'NONE', *, *, #25816, .F. ) ; +#32889 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971557076 ) ) ; +#32890 = ADVANCED_FACE ( 'NONE', ( #38607 ), #18998, .F. ) ; +#32891 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; +#32892 = CARTESIAN_POINT ( 'NONE', ( 6.034581674326127576, 134.5951993983805437, 93.50225422090859695 ) ) ; +#32893 = CARTESIAN_POINT ( 'NONE', ( -30.07215349727681541, 177.7873460224360542, 100.7165300549321643 ) ) ; +#32894 = CARTESIAN_POINT ( 'NONE', ( 3.484078850188212506, 129.8174280154724158, 89.62153155823813222 ) ) ; +#32895 = CARTESIAN_POINT ( 'NONE', ( -21.69612205307337760, 152.4962460410746417, 197.7980205213018507 ) ) ; +#32896 = ADVANCED_FACE ( 'NONE', ( #10227 ), #22092, .F. ) ; +#32897 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971576505 ) ) ; +#32898 = CARTESIAN_POINT ( 'NONE', ( -42.32952069418180230, 102.4430063022160056, 173.5700923359364651 ) ) ; +#32899 = CARTESIAN_POINT ( 'NONE', ( 20.16831244149273417, 119.7528658665681576, 90.19575101107872683 ) ) ; +#32900 = EDGE_CURVE ( 'NONE', #19924, #27116, #4053, .T. ) ; +#32901 = DIRECTION ( 'NONE', ( -0.0005884949961247530571, 0.2249510543439059984, -0.9743698870671264611 ) ) ; +#32902 = CARTESIAN_POINT ( 'NONE', ( 3.251734184265008931, 183.4850195645019824, 102.0118139314580930 ) ) ; +#32903 = CIRCLE ( 'NONE', #244, 2.000000000223218333 ) ; +#32904 = VECTOR ( 'NONE', #154, 1000.000000000000114 ) ; +#32905 = ORIENTED_EDGE ( 'NONE', *, *, #20468, .T. ) ; +#32906 = CARTESIAN_POINT ( 'NONE', ( -0.4361371084449976454, 189.0000000011299619, 105.7376017226662128 ) ) ; +#32907 = CARTESIAN_POINT ( 'NONE', ( -44.23619079995874870, 188.4918799454829355, 106.1042852104303336 ) ) ; +#32908 = CARTESIAN_POINT ( 'NONE', ( -35.94945294205002995, 192.4527268789682921, 106.4191431240564469 ) ) ; +#32909 = DIRECTION ( 'NONE', ( 0.1632030864945563375, -0.3417424273710317206, 0.9255143790850607344 ) ) ; +#32910 = CIRCLE ( 'NONE', #2227, 4.499999997027624765 ) ; +#32911 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921578520, 0.2249510932971587607 ) ) ; +#32912 = VERTEX_POINT ( 'NONE', #16141 ) ; +#32913 = ORIENTED_EDGE ( 'NONE', *, *, #19773, .T. ) ; +#32914 = ORIENTED_EDGE ( 'NONE', *, *, #9742, .T. ) ; +#32915 = DIRECTION ( 'NONE', ( 0.6087614115774877543, -0.7730004600455410158, -0.1785492440296698458 ) ) ; +#32916 = CARTESIAN_POINT ( 'NONE', ( -2.853038766185818087, 209.7096500570610544, 73.06022702708840200 ) ) ; +#32917 = LINE ( 'NONE', #26804, #38328 ) ; +#32918 = EDGE_LOOP ( 'NONE', ( #17344, #21120, #4087, #33154, #8425, #14790, #32988 ) ) ; +#32919 = DIRECTION ( 'NONE', ( 0.0006039748319386652707, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#32920 = DIRECTION ( 'NONE', ( 0.0006039748319392047697, -6.984862132708257173E-19, 0.9999998176071845934 ) ) ; +#32921 = CARTESIAN_POINT ( 'NONE', ( -26.01077944034773282, 209.7097224531575534, 73.07398733611859143 ) ) ; +#32922 = ORIENTED_EDGE ( 'NONE', *, *, #17488, .T. ) ; +#32923 = FACE_OUTER_BOUND ( 'NONE', #24138, .T. ) ; +#32924 = ORIENTED_EDGE ( 'NONE', *, *, #15626, .T. ) ; +#32925 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#32926 = CARTESIAN_POINT ( 'NONE', ( -19.70055405364098533, 149.1723619494412389, 182.9474843209757751 ) ) ; +#32927 = ORIENTED_EDGE ( 'NONE', *, *, #17130, .T. ) ; +#32928 = CARTESIAN_POINT ( 'NONE', ( -2.879056355731880235, 190.4460883268289990, 103.6209980420309904 ) ) ; +#32929 = CARTESIAN_POINT ( 'NONE', ( 0.6371854363678430833, 189.0060406513339615, 103.6969466364630108 ) ) ; +#32930 = AXIS2_PLACEMENT_3D ( 'NONE', #22905, #35942, #5077 ) ; +#32931 = VECTOR ( 'NONE', #7186, 1000.000000000000000 ) ; +#32932 = DIRECTION ( 'NONE', ( -0.7933530821293339752, -0.5932640870757631690, -0.1364866662427065558 ) ) ; +#32933 = ORIENTED_EDGE ( 'NONE', *, *, #21653, .F. ) ; +#32934 = EDGE_CURVE ( 'NONE', #11929, #28306, #32099, .T. ) ; +#32935 = AXIS2_PLACEMENT_3D ( 'NONE', #31463, #30668, #8996 ) ; +#32936 = ORIENTED_EDGE ( 'NONE', *, *, #23351, .T. ) ; +#32937 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#32938 = ORIENTED_EDGE ( 'NONE', *, *, #39033, .F. ) ; +#32939 = VERTEX_POINT ( 'NONE', #22697 ) ; +#32940 = VERTEX_POINT ( 'NONE', #31486 ) ; +#32941 = CARTESIAN_POINT ( 'NONE', ( -14.78542622577100119, 175.8938623147257374, 100.7833030093998303 ) ) ; +#32942 = ORIENTED_EDGE ( 'NONE', *, *, #3256, .F. ) ; +#32943 = CARTESIAN_POINT ( 'NONE', ( 21.45428261829664862, 213.0890995499228211, 73.54560849209069318 ) ) ; +#32944 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927782063840, -0.0005734119022076108281 ) ) ; +#32945 = CARTESIAN_POINT ( 'NONE', ( 23.68596773153978319, 129.9751393256367464, 92.21150139214144303 ) ) ; +#32946 = VERTEX_POINT ( 'NONE', #25567 ) ; +#32947 = CARTESIAN_POINT ( 'NONE', ( 44.86724994974370162, 186.7825132065745777, 105.8343309753838213 ) ) ; +#32948 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988409597765, 156.3551877982712028, 95.75036263596727792 ) ) ; +#32949 = ORIENTED_EDGE ( 'NONE', *, *, #9203, .T. ) ; +#32950 = CARTESIAN_POINT ( 'NONE', ( 26.02608998670000062, 120.6389521098000159, 90.56795384212999522 ) ) ; +#32951 = CARTESIAN_POINT ( 'NONE', ( 43.11176529853025130, 93.58819903903858517, 291.5325055092823163 ) ) ; +#32953 = CARTESIAN_POINT ( 'NONE', ( -27.82759976036524918, 177.7876074752642808, 100.7152660398233479 ) ) ; +#32952 = DIRECTION ( 'NONE', ( 0.7855991485562935361, -0.6187357899682438545, 0.000000000000000000 ) ) ; +#32954 = VECTOR ( 'NONE', #20729, 999.9999999999998863 ) ; +#32955 = ORIENTED_EDGE ( 'NONE', *, *, #23802, .F. ) ; +#32956 = EDGE_CURVE ( 'NONE', #31008, #1984, #13282, .T. ) ; +#32957 = AXIS2_PLACEMENT_3D ( 'NONE', #40037, #14907, #12244 ) ; +#32958 = ORIENTED_EDGE ( 'NONE', *, *, #3613, .F. ) ; +#32959 = CIRCLE ( 'NONE', #36889, 2.000000000735676409 ) ; +#32960 = ORIENTED_EDGE ( 'NONE', *, *, #21617, .F. ) ; +#32961 = DIRECTION ( 'NONE', ( -0.0005884949961259294164, 0.2255194585872565272, -0.9742384859325513569 ) ) ; +#32962 = CARTESIAN_POINT ( 'NONE', ( -20.51880467302672173, 211.0905570380611493, 75.57084890002228406 ) ) ; +#32963 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901141, 132.2978364233219963, 93.26432363102219369 ) ) ; +#32964 = CARTESIAN_POINT ( 'NONE', ( 44.69319620505716273, 133.1441970321177166, 337.0970861341226623 ) ) ; +#32965 = ORIENTED_EDGE ( 'NONE', *, *, #20100, .T. ) ; +#32966 = ORIENTED_EDGE ( 'NONE', *, *, #13900, .T. ) ; +#32967 = EDGE_LOOP ( 'NONE', ( #16428, #38580, #10005, #35279 ) ) ; +#32968 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 82.27946979429628982, 310.0857197240630967 ) ) ; +#32969 = CARTESIAN_POINT ( 'NONE', ( 16.00004425883027537, 186.0638578529228369, 102.5994861110636265 ) ) ; +#32970 = ADVANCED_FACE ( 'NONE', ( #16733 ), #28621, .T. ) ; +#32971 = VERTEX_POINT ( 'NONE', #22499 ) ; +#32972 = CARTESIAN_POINT ( 'NONE', ( -35.64317240526990815, 191.6880555651530074, 106.9491066055539790 ) ) ; +#32973 = EDGE_CURVE ( 'NONE', #30934, #1598, #22295, .T. ) ; +#32974 = CARTESIAN_POINT ( 'NONE', ( 3.079959205947283785, 190.7372649033252969, 106.7807747737359705 ) ) ; +#32975 = EDGE_CURVE ( 'NONE', #22792, #37113, #22468, .T. ) ; +#32976 = ORIENTED_EDGE ( 'NONE', *, *, #10016, .F. ) ; +#32977 = CARTESIAN_POINT ( 'NONE', ( -30.07831637853678686, 134.9151858147922667, 90.81876078434068233 ) ) ; +#32978 = CONICAL_SURFACE ( 'NONE', #360, 7.002999999845556545, 0.7853981633426221354 ) ; +#32979 = CARTESIAN_POINT ( 'NONE', ( 23.36232515670958065, 177.1947614343970372, 101.0605990059838462 ) ) ; +#32980 = AXIS2_PLACEMENT_3D ( 'NONE', #30890, #39663, #24365 ) ; +#32981 = VECTOR ( 'NONE', #18443, 1000.000000000000114 ) ; +#32982 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927801571618, -0.0005734119022069843761 ) ) ; +#32983 = CARTESIAN_POINT ( 'NONE', ( 44.53027206012822603, 189.1225043543478250, 103.6304983192370770 ) ) ; +#32984 = AXIS2_PLACEMENT_3D ( 'NONE', #20551, #27335, #26922 ) ; +#32985 = ORIENTED_EDGE ( 'NONE', *, *, #29590, .T. ) ; +#32986 = DIRECTION ( 'NONE', ( 0.0006039748319385908944, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#32987 = CARTESIAN_POINT ( 'NONE', ( -20.00111603559079398, 118.1131148921541438, 87.27965578728156970 ) ) ; +#32988 = ORIENTED_EDGE ( 'NONE', *, *, #24852, .F. ) ; +#32989 = CARTESIAN_POINT ( 'NONE', ( 32.17532506523997426, 77.89466421350269343, 291.2180765908466356 ) ) ; +#32991 = CARTESIAN_POINT ( 'NONE', ( -44.23776012402447577, 189.0917505549361692, 103.5059606069654592 ) ) ; +#32990 = DIRECTION ( 'NONE', ( 0.0005884949961246456127, -0.2249510543439063592, 0.9743698870671262391 ) ) ; +#32992 = ORIENTED_EDGE ( 'NONE', *, *, #25896, .F. ) ; +#32993 = EDGE_CURVE ( 'NONE', #21765, #29199, #38414, .T. ) ; +#32994 = VERTEX_POINT ( 'NONE', #37814 ) ; +#32995 = CARTESIAN_POINT ( 'NONE', ( 3.072975579511000532, 209.7481171635999999, 76.19203123645000630 ) ) ; +#32996 = VECTOR ( 'NONE', #37600, 1000.000000000000227 ) ; +#32997 = DIRECTION ( 'NONE', ( -0.7933532411131104523, -0.5932638852154226150, -0.1364866195435462393 ) ) ; +#32998 = LINE ( 'NONE', #23213, #16340 ) ; +#32999 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; +#33000 = FACE_OUTER_BOUND ( 'NONE', #25298, .T. ) ; +#33001 = VERTEX_POINT ( 'NONE', #25969 ) ; +#33002 = CONICAL_SURFACE ( 'NONE', #12805, 4.502999914355317657, 0.7853981633639942617 ) ; +#33003 = ORIENTED_EDGE ( 'NONE', *, *, #12992, .T. ) ; +#33004 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561239 ) ) ; +#33005 = ORIENTED_EDGE ( 'NONE', *, *, #30842, .T. ) ; +#33006 = CONICAL_SURFACE ( 'NONE', #15403, 5.000000000026098235, 0.7853981633778843729 ) ; +#33007 = ORIENTED_EDGE ( 'NONE', *, *, #18255, .F. ) ; +#33008 = CARTESIAN_POINT ( 'NONE', ( -25.99225322733902033, 193.8169247290898625, 102.7186084094957010 ) ) ; +#33009 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560961 ) ) ; +#33010 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4464, #23096, #798, #38417, #1401, #7333, #23292, #35725, #13883, #25571 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000314193, 0.3750000000000814349, 0.4375000000000909828, 0.5000000000001004752, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33011 = CARTESIAN_POINT ( 'NONE', ( 39.80107749601363309, 119.4152471894954601, 89.76382462946382645 ) ) ; +#33012 = AXIS2_PLACEMENT_3D ( 'NONE', #10588, #19956, #32455 ) ; +#33013 = AXIS2_PLACEMENT_3D ( 'NONE', #20295, #32774, #17422 ) ; +#33014 = EDGE_CURVE ( 'NONE', #5410, #39888, #6727, .T. ) ; +#33015 = ORIENTED_EDGE ( 'NONE', *, *, #16184, .T. ) ; +#33016 = DIRECTION ( 'NONE', ( -0.0005884949961181158967, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#33017 = VECTOR ( 'NONE', #2376, 1000.000000000000114 ) ; +#33018 = CARTESIAN_POINT ( 'NONE', ( -36.09109704704999899, 192.2866562552000005, 104.5690802119000011 ) ) ; +#33019 = CARTESIAN_POINT ( 'NONE', ( 36.12644007640999888, 191.3780648084000404, 103.6831328241000136 ) ) ; +#33020 = ORIENTED_EDGE ( 'NONE', *, *, #18060, .F. ) ; +#33021 = CARTESIAN_POINT ( 'NONE', ( -26.00373979082000275, 120.9358918448999987, 87.58883631886999410 ) ) ; +#33022 = ADVANCED_FACE ( 'NONE', ( #34916 ), #36146, .F. ) ; +#33023 = VERTEX_POINT ( 'NONE', #1812 ) ; +#33024 = CARTESIAN_POINT ( 'NONE', ( -6.037737380061058090, 175.3552788058639464, 100.1374507664885414 ) ) ; +#33025 = PLANE ( 'NONE', #31298 ) ; +#33026 = ORIENTED_EDGE ( 'NONE', *, *, #32486, .T. ) ; +#33027 = CARTESIAN_POINT ( 'NONE', ( 0.6522971013523114481, 188.6126488384289530, 103.1971906374716497 ) ) ; +#33028 = LINE ( 'NONE', #1977, #2505 ) ; +#33029 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #4419, #753 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33030 = EDGE_CURVE ( 'NONE', #39550, #39205, #11416, .T. ) ; +#33031 = FACE_OUTER_BOUND ( 'NONE', #31931, .T. ) ; +#33032 = EDGE_CURVE ( 'NONE', #13011, #36039, #7735, .T. ) ; +#33033 = CARTESIAN_POINT ( 'NONE', ( 45.28002203899477962, 186.1588271223781987, 106.1973972072094341 ) ) ; +#33034 = VERTEX_POINT ( 'NONE', #10822 ) ; +#33035 = CARTESIAN_POINT ( 'NONE', ( -2.453444162457494304, 207.4083922256737651, 77.08315769752742597 ) ) ; +#33036 = EDGE_CURVE ( 'NONE', #14526, #6177, #15801, .T. ) ; +#33037 = CARTESIAN_POINT ( 'NONE', ( 2.243609847812261471, 189.9161030272695712, 103.9477651519655552 ) ) ; +#33038 = CARTESIAN_POINT ( 'NONE', ( 32.25078568539211687, 136.1275797149361892, 91.06097076243848676 ) ) ; +#33039 = AXIS2_PLACEMENT_3D ( 'NONE', #26706, #36295, #11772 ) ; +#33040 = ORIENTED_EDGE ( 'NONE', *, *, #22616, .F. ) ; +#33041 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971570121 ) ) ; +#33042 = FACE_OUTER_BOUND ( 'NONE', #11744, .T. ) ; +#33043 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; +#33044 = CARTESIAN_POINT ( 'NONE', ( 25.94088316678000083, 191.2889162021000118, 103.9146051783999951 ) ) ; +#33045 = LINE ( 'NONE', #14668, #39928 ) ; +#33046 = CARTESIAN_POINT ( 'NONE', ( -20.83442437065999542, 212.3494483913675595, 75.57101870502553709 ) ) ; +#33047 = CARTESIAN_POINT ( 'NONE', ( 6.026693642215255053, 134.9199437178238838, 90.79804054718465522 ) ) ; +#33048 = ORIENTED_EDGE ( 'NONE', *, *, #37291, .T. ) ; +#33049 = VECTOR ( 'NONE', #3917, 1000.000000000000000 ) ; +#33050 = AXIS2_PLACEMENT_3D ( 'NONE', #16031, #25873, #9721 ) ; +#33051 = CARTESIAN_POINT ( 'NONE', ( 2.729325451305233852, 196.2716069310007470, 103.7432050589404042 ) ) ; +#33052 = CARTESIAN_POINT ( 'NONE', ( -15.66510137924916712, 184.3629618927121498, 104.9627433997273869 ) ) ; +#33053 = CARTESIAN_POINT ( 'NONE', ( 25.50924745143719718, 191.9344736266071436, 104.4056993596765039 ) ) ; +#33054 = DIRECTION ( 'NONE', ( 0.0006039748319393677253, 3.488873499045632102E-19, 0.9999998176071845934 ) ) ; +#33055 = PLANE ( 'NONE', #22870 ) ; +#33056 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319383136639 ) ) ; +#33057 = LINE ( 'NONE', #26957, #37360 ) ; +#33058 = CARTESIAN_POINT ( 'NONE', ( 20.73661144324140437, 116.1345660314903938, 90.25526044551206439 ) ) ; +#33059 = ORIENTED_EDGE ( 'NONE', *, *, #38401, .T. ) ; +#33060 = CARTESIAN_POINT ( 'NONE', ( -15.99998595512920652, 185.9065961375156348, 102.5825112407314634 ) ) ; +#33061 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421903059, 127.0698778186146995, 92.06007195132379195 ) ) ; +#33062 = EDGE_CURVE ( 'NONE', #29701, #19402, #32490, .T. ) ; +#33063 = AXIS2_PLACEMENT_3D ( 'NONE', #18159, #2842, #39841 ) ; +#33064 = ORIENTED_EDGE ( 'NONE', *, *, #18752, .T. ) ; +#33065 = DIRECTION ( 'NONE', ( 0.7933532411131101192, 0.5932638852154232811, 0.1364866195435442964 ) ) ; +#33066 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498903273, 176.3880814479794878, 103.4433606027979948 ) ) ; +#33067 = CONICAL_SURFACE ( 'NONE', #8938, 2.750000000007442491, 0.7853981633308424470 ) ; +#33068 = ORIENTED_EDGE ( 'NONE', *, *, #14387, .T. ) ; +#33069 = AXIS2_PLACEMENT_3D ( 'NONE', #31870, #31252, #34302 ) ; +#33070 = EDGE_CURVE ( 'NONE', #27116, #13945, #7318, .T. ) ; +#33071 = CARTESIAN_POINT ( 'NONE', ( 20.00007076059032940, 143.0057557026720190, 92.65639515983836816 ) ) ; +#33072 = EDGE_LOOP ( 'NONE', ( #21589, #32374, #22323, #34482 ) ) ; +#33073 = CARTESIAN_POINT ( 'NONE', ( 36.27379766703212738, 191.8934879371578290, 106.3925458811340690 ) ) ; +#33074 = AXIS2_PLACEMENT_3D ( 'NONE', #458, #31958, #19659 ) ; +#33075 = EDGE_CURVE ( 'NONE', #37725, #12815, #16442, .T. ) ; +#33076 = CARTESIAN_POINT ( 'NONE', ( -14.78422084203157461, 175.4439834284964945, 102.7320481277236013 ) ) ; +#33077 = DIRECTION ( 'NONE', ( -0.6068735732728635091, -0.7743428331745977333, -0.1791581501750992289 ) ) ; +#33078 = FACE_OUTER_BOUND ( 'NONE', #1960, .T. ) ; +#33079 = CARTESIAN_POINT ( 'NONE', ( 39.79702541312468611, 141.5973318770025173, 284.1405295046018864 ) ) ; +#33080 = EDGE_CURVE ( 'NONE', #12120, #14434, #1008, .T. ) ; +#33081 = VERTEX_POINT ( 'NONE', #23288 ) ; +#33082 = FACE_OUTER_BOUND ( 'NONE', #35271, .T. ) ; +#33083 = DIRECTION ( 'NONE', ( 0.6087611427445810408, 0.7731004622513006908, 0.1781166650011639374 ) ) ; +#33084 = PLANE ( 'NONE', #26690 ) ; +#33085 = ORIENTED_EDGE ( 'NONE', *, *, #9160, .F. ) ; +#33086 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13908, #23322, #35749, #7757 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33087 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#33088 = VERTEX_POINT ( 'NONE', #26767 ) ; +#33089 = EDGE_LOOP ( 'NONE', ( #38314, #2118, #29936 ) ) ; +#33090 = CARTESIAN_POINT ( 'NONE', ( 14.16683332331358613, 129.7278030047937705, 90.10754002185558420 ) ) ; +#33091 = CARTESIAN_POINT ( 'NONE', ( 22.67317654999515852, 115.6131156702006990, 89.75429555850769248 ) ) ; +#33092 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569011 ) ) ; +#33093 = CARTESIAN_POINT ( 'NONE', ( -30.07215349727681541, 177.7873460224360542, 100.7165300549321643 ) ) ; +#33094 = CARTESIAN_POINT ( 'NONE', ( 14.84630245323845621, 136.2557976693637158, 93.83789554009061362 ) ) ; +#33095 = AXIS2_PLACEMENT_3D ( 'NONE', #6820, #32191, #16821 ) ; +#33096 = VECTOR ( 'NONE', #4243, 1000.000000000000114 ) ; +#33097 = CARTESIAN_POINT ( 'NONE', ( -26.01077944034773282, 209.7097224531575534, 73.07398733611859143 ) ) ; +#33098 = CIRCLE ( 'NONE', #15489, 1.750000000000001998 ) ; +#33099 = CARTESIAN_POINT ( 'NONE', ( 26.15694028684000472, 190.9579671749999932, 106.9451011959999960 ) ) ; +#33100 = CARTESIAN_POINT ( 'NONE', ( 4.017367618393966389, 182.2867097658143507, 101.7346998419586868 ) ) ; +#33101 = VERTEX_POINT ( 'NONE', #23695 ) ; +#33102 = CARTESIAN_POINT ( 'NONE', ( 14.75941300677970602, 124.6753782222769615, 88.42758558798597335 ) ) ; +#33103 = PLANE ( 'NONE', #31582 ) ; +#33104 = FACE_OUTER_BOUND ( 'NONE', #12323, .T. ) ; +#33105 = CARTESIAN_POINT ( 'NONE', ( -16.50035848821718076, 136.6784666199758931, 180.9776494209432656 ) ) ; +#33106 = CARTESIAN_POINT ( 'NONE', ( -20.02047174850214617, 117.7199421200607077, 87.27987615529596610 ) ) ; +#33108 = EDGE_LOOP ( 'NONE', ( #5736, #33852 ) ) ; +#33107 = CARTESIAN_POINT ( 'NONE', ( 13.47343164508975377, 158.6809479346725595, 96.79232023565108989 ) ) ; +#33109 = VERTEX_POINT ( 'NONE', #35930 ) ; +#33110 = ORIENTED_EDGE ( 'NONE', *, *, #28623, .T. ) ; +#33111 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#33112 = ORIENTED_EDGE ( 'NONE', *, *, #9203, .F. ) ; +#33113 = DIRECTION ( 'NONE', ( -6.938893903965234306E-16, 0.9743700557921580740, 0.2249510932971585664 ) ) ; +#33114 = EDGE_CURVE ( 'NONE', #12555, #35055, #26885, .T. ) ; +#33115 = EDGE_CURVE ( 'NONE', #1132, #2098, #10308, .T. ) ; +#33116 = DIRECTION ( 'NONE', ( -0.6773442687123379935, -0.7356661890032381024, 0.000000000000000000 ) ) ; +#33117 = CARTESIAN_POINT ( 'NONE', ( -20.49852834491502307, 151.4051363116404900, 97.18569326181511769 ) ) ; +#33118 = EDGE_CURVE ( 'NONE', #27521, #38809, #8345, .T. ) ; +#33119 = ORIENTED_EDGE ( 'NONE', *, *, #35820, .F. ) ; +#33120 = ORIENTED_EDGE ( 'NONE', *, *, #23817, .F. ) ; +#33121 = FACE_BOUND ( 'NONE', #18010, .T. ) ; +#33122 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921572969, -0.2249510932971618138 ) ) ; +#33123 = VERTEX_POINT ( 'NONE', #35720 ) ; +#33124 = EDGE_CURVE ( 'NONE', #6589, #23150, #29781, .T. ) ; +#33125 = CIRCLE ( 'NONE', #1787, 2.000000000223404850 ) ; +#33126 = ORIENTED_EDGE ( 'NONE', *, *, #30260, .T. ) ; +#33127 = CARTESIAN_POINT ( 'NONE', ( 3.230169986108356373, 186.5436302562499122, 102.7179630022487657 ) ) ; +#33128 = CARTESIAN_POINT ( 'NONE', ( 28.46953594426098277, 131.0252485042709338, 89.88531577736306133 ) ) ; +#33129 = VECTOR ( 'NONE', #4233, 1000.000000000000000 ) ; +#33130 = CARTESIAN_POINT ( 'NONE', ( 39.17918664236205473, 77.03152903297159071, 290.9156096052041676 ) ) ; +#33131 = ADVANCED_FACE ( 'NONE', ( #30028 ), #2025, .T. ) ; +#33132 = ORIENTED_EDGE ( 'NONE', *, *, #18292, .F. ) ; +#33133 = CARTESIAN_POINT ( 'NONE', ( -1.512059224926999956, 189.1271795652999970, 103.5915707072000203 ) ) ; +#33134 = CARTESIAN_POINT ( 'NONE', ( 0.5945664429271031448, 189.0157257392609722, 103.6937134704449903 ) ) ; +#33135 = CARTESIAN_POINT ( 'NONE', ( -36.02915914471689973, 191.1279744515711627, 106.8708103113893770 ) ) ; +#33136 = ORIENTED_EDGE ( 'NONE', *, *, #40303, .F. ) ; +#33137 = ORIENTED_EDGE ( 'NONE', *, *, #9211, .F. ) ; +#33138 = CYLINDRICAL_SURFACE ( 'NONE', #24442, 59.40509898897001051 ) ; +#33139 = EDGE_LOOP ( 'NONE', ( #23352, #14479, #17053, #17983 ) ) ; +#33140 = EDGE_CURVE ( 'NONE', #36682, #2366, #17123, .T. ) ; +#33141 = ORIENTED_EDGE ( 'NONE', *, *, #4188, .T. ) ; +#33142 = ORIENTED_EDGE ( 'NONE', *, *, #27813, .F. ) ; +#33143 = CARTESIAN_POINT ( 'NONE', ( 20.49113379396988677, 211.4170907343362558, 73.54650032140015981 ) ) ; +#33144 = CARTESIAN_POINT ( 'NONE', ( -20.01944572060296323, 207.3562132816129520, 73.63222224179746433 ) ) ; +#33145 = CARTESIAN_POINT ( 'NONE', ( 45.38216566575481892, 131.0689882075479886, 90.22727308576753558 ) ) ; +#33146 = ORIENTED_EDGE ( 'NONE', *, *, #12307, .F. ) ; +#33147 = FACE_OUTER_BOUND ( 'NONE', #22231, .T. ) ; +#33148 = EDGE_LOOP ( 'NONE', ( #35077, #17083, #22881, #9469 ) ) ; +#33149 = CARTESIAN_POINT ( 'NONE', ( 28.53280061317499872, 124.6087127242800108, 91.48628689533521197 ) ) ; +#33150 = DIRECTION ( 'NONE', ( 0.7933310414247656261, 0.5931044597393390072, 0.1373060761554398823 ) ) ; +#33151 = CIRCLE ( 'NONE', #15542, 2.000000000354214436 ) ; +#33153 = DIRECTION ( 'NONE', ( -0.0005884949961224158425, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#33152 = DIRECTION ( 'NONE', ( 0.0005884949961230158400, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33154 = ORIENTED_EDGE ( 'NONE', *, *, #30365, .F. ) ; +#33155 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6476, #38369, #25120, #37565, #16089, #545, #25726, #3810, #12837, #37972 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33156 = ORIENTED_EDGE ( 'NONE', *, *, #39856, .F. ) ; +#33157 = CARTESIAN_POINT ( 'NONE', ( 21.57626859835584909, 176.1824540492217750, 103.2226781424499649 ) ) ; +#33158 = EDGE_CURVE ( 'NONE', #12909, #8503, #13852, .T. ) ; +#33159 = EDGE_CURVE ( 'NONE', #13769, #28042, #5357, .T. ) ; +#33160 = ORIENTED_EDGE ( 'NONE', *, *, #4934, .F. ) ; +#33161 = CARTESIAN_POINT ( 'NONE', ( 39.02975055476000676, 119.0105336778999998, 89.82596006120000709 ) ) ; +#33162 = DIRECTION ( 'NONE', ( 0.7933532970003738249, 0.5930762008556724751, 0.1372995488602876402 ) ) ; +#33163 = DIRECTION ( 'NONE', ( -0.5988682214889313737, 0.8008475843072039302, -6.938893903907200768E-15 ) ) ; +#33164 = CARTESIAN_POINT ( 'NONE', ( 20.16666278967802484, 160.7088898722922465, 96.91425943719899294 ) ) ; +#33165 = CARTESIAN_POINT ( 'NONE', ( 36.22776625462999789, 191.6123771812999905, 104.0140211655999991 ) ) ; +#33166 = ORIENTED_EDGE ( 'NONE', *, *, #30939, .F. ) ; +#33167 = VERTEX_POINT ( 'NONE', #9367 ) ; +#33168 = CARTESIAN_POINT ( 'NONE', ( -19.99827944177191341, 118.8155627782461181, 90.27982142893266371 ) ) ; +#33169 = CARTESIAN_POINT ( 'NONE', ( 14.69746453343251957, 188.0513169112800824, 103.0591139980062252 ) ) ; +#33170 = ORIENTED_EDGE ( 'NONE', *, *, #28089, .T. ) ; +#33171 = CARTESIAN_POINT ( 'NONE', ( 30.06788597519531336, 135.1232275265250280, 91.10458376635099853 ) ) ; +#33172 = AXIS2_PLACEMENT_3D ( 'NONE', #9877, #24621, #25021 ) ; +#33173 = CARTESIAN_POINT ( 'NONE', ( -22.49806768458547168, 153.6037118230980241, 98.03658197602312896 ) ) ; +#33174 = CARTESIAN_POINT ( 'NONE', ( 5.674778016381245571, 131.0223034755605909, 89.89838139801142347 ) ) ; +#33175 = AXIS2_PLACEMENT_3D ( 'NONE', #18666, #22376, #682 ) ; +#33176 = EDGE_CURVE ( 'NONE', #36248, #26024, #30444, .T. ) ; +#33177 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; +#33178 = CARTESIAN_POINT ( 'NONE', ( 31.79391164649184631, 220.4002260770999726, 73.03930135617515873 ) ) ; +#33179 = CARTESIAN_POINT ( 'NONE', ( 21.00169408020338224, 182.5884499274252164, 104.7019667032076455 ) ) ; +#33180 = ORIENTED_EDGE ( 'NONE', *, *, #7141, .F. ) ; +#33181 = DIRECTION ( 'NONE', ( 0.6771712326825870543, -0.7358254695422995484, 0.000000000000000000 ) ) ; +#33182 = CARTESIAN_POINT ( 'NONE', ( 20.89285664109717189, 183.1014278315721810, 101.9125999898524242 ) ) ; +#33183 = ORIENTED_EDGE ( 'NONE', *, *, #37696, .T. ) ; +#33184 = CARTESIAN_POINT ( 'NONE', ( 36.06588537441000142, 194.9391275604999976, 107.7152975676000040 ) ) ; +#33186 = CARTESIAN_POINT ( 'NONE', ( 15.99849543194476986, 160.4080026200020086, 96.67636507677717361 ) ) ; +#33185 = CARTESIAN_POINT ( 'NONE', ( 36.05533436145224613, 118.8155677978006111, 90.24600832072150070 ) ) ; +#33187 = ORIENTED_EDGE ( 'NONE', *, *, #19411, .T. ) ; +#33188 = VECTOR ( 'NONE', #18624, 1000.000000000000227 ) ; +#33189 = VERTEX_POINT ( 'NONE', #3212 ) ; +#33190 = ORIENTED_EDGE ( 'NONE', *, *, #16309, .F. ) ; +#33191 = CARTESIAN_POINT ( 'NONE', ( 20.00000522920557700, 138.5176112521621690, 91.62015419223651236 ) ) ; +#33192 = VECTOR ( 'NONE', #6138, 999.9999999999998863 ) ; +#33193 = CARTESIAN_POINT ( 'NONE', ( 36.74499328828947142, 191.3591568088928909, 106.3388620510278457 ) ) ; +#33194 = CONICAL_SURFACE ( 'NONE', #20822, 5.000000000042579273, 0.7853981634430861059 ) ; +#33195 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#33196 = EDGE_CURVE ( 'NONE', #13844, #16326, #36740, .T. ) ; +#33197 = ORIENTED_EDGE ( 'NONE', *, *, #30521, .T. ) ; +#33198 = EDGE_CURVE ( 'NONE', #1613, #1746, #9989, .T. ) ; +#33199 = VERTEX_POINT ( 'NONE', #24319 ) ; +#33200 = DIRECTION ( 'NONE', ( 0.0002393071182782299474, 0.2252352986010034697, -0.9743043687658493601 ) ) ; +#33201 = AXIS2_PLACEMENT_3D ( 'NONE', #5177, #26884, #35430 ) ; +#33202 = ORIENTED_EDGE ( 'NONE', *, *, #1800, .F. ) ; +#33203 = ORIENTED_EDGE ( 'NONE', *, *, #4982, .F. ) ; +#33204 = CARTESIAN_POINT ( 'NONE', ( -36.46592998411147590, 191.1051656101541596, 106.5992029824818701 ) ) ; +#33205 = DIRECTION ( 'NONE', ( -0.0005884949961159196283, 0.2249510543439052768, -0.9743698870671265722 ) ) ; +#33206 = CARTESIAN_POINT ( 'NONE', ( 39.51684480652362907, 114.5628099923930847, 151.3186418573310732 ) ) ; +#33207 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; +#33208 = ORIENTED_EDGE ( 'NONE', *, *, #18747, .T. ) ; +#33209 = ORIENTED_EDGE ( 'NONE', *, *, #29131, .T. ) ; +#33210 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1187, #4045, #16322, #37598 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33211 = ORIENTED_EDGE ( 'NONE', *, *, #28159, .F. ) ; +#33212 = CARTESIAN_POINT ( 'NONE', ( -20.45366101552173532, 211.0901972962080322, 75.63591788811629613 ) ) ; +#33213 = EDGE_CURVE ( 'NONE', #1201, #1952, #25645, .T. ) ; +#33214 = CARTESIAN_POINT ( 'NONE', ( -35.31822109755999861, 192.0397647290000407, 103.8027042277000049 ) ) ; +#33215 = CARTESIAN_POINT ( 'NONE', ( 36.47870239224999978, 191.4233604986999921, 103.9343244230000067 ) ) ; +#33216 = EDGE_LOOP ( 'NONE', ( #28182, #8485, #23514, #25803 ) ) ; +#33217 = CARTESIAN_POINT ( 'NONE', ( 20.48555995111231809, 211.0898943587194481, 73.54694346759191603 ) ) ; +#33218 = ORIENTED_EDGE ( 'NONE', *, *, #32348, .F. ) ; +#33219 = EDGE_LOOP ( 'NONE', ( #8226, #25290, #24907, #24822 ) ) ; +#33220 = DIRECTION ( 'NONE', ( -0.0005865300001401835836, 0.2249510543434335152, -0.9743698882520622773 ) ) ; +#33221 = CARTESIAN_POINT ( 'NONE', ( -40.45487666593005827, 220.4002261020000049, 76.08293836150286893 ) ) ; +#33222 = ORIENTED_EDGE ( 'NONE', *, *, #11115, .F. ) ; +#33223 = CARTESIAN_POINT ( 'NONE', ( -16.89229910586540129, 151.8805145963252698, 184.0522065937344962 ) ) ; +#33224 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#33225 = DIRECTION ( 'NONE', ( -0.0005884949961239352434, 0.2249510543439079413, -0.9743698870671259060 ) ) ; +#33226 = FACE_OUTER_BOUND ( 'NONE', #20077, .T. ) ; +#33227 = ORIENTED_EDGE ( 'NONE', *, *, #8158, .F. ) ; +#33228 = CIRCLE ( 'NONE', #29338, 4.999999999999990230 ) ; +#33229 = EDGE_CURVE ( 'NONE', #282, #275, #31232, .T. ) ; +#33230 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31947, #4510, #20877, #26414, #29884, #30277, #8418, #27032, #5325, #17782, #1448, #11679, #36618, #14756 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000249800, 0.3750000000000530687, 0.5000000000000811573, 0.6250000000001093570, 0.6875000000001233458, 0.7500000000001373346, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33231 = DIRECTION ( 'NONE', ( -0.0005884949961244357111, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#33232 = CARTESIAN_POINT ( 'NONE', ( 22.11776643986201663, 129.2357545819063773, 92.04174809736024088 ) ) ; +#33233 = VECTOR ( 'NONE', #14450, 1000.000000000000114 ) ; +#33234 = ORIENTED_EDGE ( 'NONE', *, *, #27211, .T. ) ; +#33235 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33236 = EDGE_LOOP ( 'NONE', ( #11088, #10633, #21207, #25506, #18129 ) ) ; +#33237 = AXIS2_PLACEMENT_3D ( 'NONE', #12065, #14521, #24543 ) ; +#33238 = CARTESIAN_POINT ( 'NONE', ( -8.050307605157906110, 151.4365984322141117, 94.61967771673485572 ) ) ; +#33239 = LINE ( 'NONE', #8114, #4944 ) ; +#33240 = VECTOR ( 'NONE', #20891, 1000.000000000000000 ) ; +#33241 = CARTESIAN_POINT ( 'NONE', ( -23.02004673814065683, 213.5902071504527839, 73.57250091739375364 ) ) ; +#33242 = CARTESIAN_POINT ( 'NONE', ( 6.033439958583901586, 135.0872164925444281, 91.06582754317723527 ) ) ; +#33243 = ORIENTED_EDGE ( 'NONE', *, *, #15653, .F. ) ; +#33244 = EDGE_CURVE ( 'NONE', #5686, #23549, #24317, .T. ) ; +#33245 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971560684 ) ) ; +#33246 = ADVANCED_FACE ( 'NONE', ( #40425 ), #40005, .F. ) ; +#33247 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -0.000000000000000000, 0.0006039748319387908213 ) ) ; +#33248 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21379, #15762, #25200, #39957 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33249 = CARTESIAN_POINT ( 'NONE', ( -24.51675559260586468, 115.4936548059245069, 87.28259179807037071 ) ) ; +#33250 = CARTESIAN_POINT ( 'NONE', ( -2.955836285853710610, 208.9211498072354800, 73.12285454242802984 ) ) ; +#33251 = CARTESIAN_POINT ( 'NONE', ( -20.49853057565002601, 184.3993303303604705, 104.8029991440840973 ) ) ; +#33252 = LINE ( 'NONE', #32665, #30726 ) ; +#33253 = DIRECTION ( 'NONE', ( -0.0005884949961255136249, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#33254 = ADVANCED_FACE ( 'NONE', ( #36975 ), #25000, .F. ) ; +#33255 = CARTESIAN_POINT ( 'NONE', ( -17.26236276037843353, 152.4432311036538579, 182.8745738163920862 ) ) ; +#33256 = ADVANCED_FACE ( 'NONE', ( #34089 ), #19736, .F. ) ; +#33257 = CARTESIAN_POINT ( 'NONE', ( 20.54337478632077918, 116.3706092612608529, 90.25537715561074492 ) ) ; +#33258 = ORIENTED_EDGE ( 'NONE', *, *, #27298, .T. ) ; +#33259 = ADVANCED_FACE ( 'NONE', ( #33481 ), #7987, .F. ) ; +#33260 = CARTESIAN_POINT ( 'NONE', ( 14.42708641008473869, 182.0277504606679884, 104.5764898171669302 ) ) ; +#33262 = CONICAL_SURFACE ( 'NONE', #18895, 2.250000000020516921, 0.7853981633778843729 ) ; +#33261 = CARTESIAN_POINT ( 'NONE', ( 3.868711044008855460, 144.1404883528797995, 93.27114193733976322 ) ) ; +#33263 = DIRECTION ( 'NONE', ( 5.204170427930391307E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#33264 = AXIS2_PLACEMENT_3D ( 'NONE', #5500, #27214, #2051 ) ; +#33265 = ORIENTED_EDGE ( 'NONE', *, *, #22399, .T. ) ; +#33266 = DIRECTION ( 'NONE', ( -0.0005884949961258157921, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#33267 = CYLINDRICAL_SURFACE ( 'NONE', #26338, 2.500000000000000888 ) ; +#33268 = AXIS2_PLACEMENT_3D ( 'NONE', #7343, #38820, #26586 ) ; +#33269 = ORIENTED_EDGE ( 'NONE', *, *, #5508, .F. ) ; +#33270 = CARTESIAN_POINT ( 'NONE', ( -38.66421384966999852, 119.1055377026000031, 87.73960695917999431 ) ) ; +#33271 = DIRECTION ( 'NONE', ( -0.0005884949961231158034, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#33272 = ORIENTED_EDGE ( 'NONE', *, *, #331, .T. ) ; +#33273 = CARTESIAN_POINT ( 'NONE', ( 36.22531506482754793, 191.0466354042188755, 106.8125635786149701 ) ) ; +#33274 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28198, #3024, #34486, #24330, #2445, #12246, #37382, #167, #18549, #2835, #24529, #24734, #15511, #6098, #9580, #8985, #33698, #21464, #6291, #15311 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999998834821, 0.1874999999998343270, 0.2187499999998188949, 0.2343749999998115674, 0.2499999999998042122, 0.4999999999998561151, 0.6249999999998827604, 0.6874999999998961941, 0.7187499999999076294, 0.7343749999999144018, 0.7499999999999211742, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33275 = DIRECTION ( 'NONE', ( 1.734723475976797036E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#33276 = CARTESIAN_POINT ( 'NONE', ( -15.99823432472775941, 127.0706064849903782, 92.07805732825173095 ) ) ; +#33277 = CARTESIAN_POINT ( 'NONE', ( 3.534269831815406882, 173.0753051157153664, 99.60843731991197103 ) ) ; +#33278 = CARTESIAN_POINT ( 'NONE', ( 29.88752274199697823, 186.0181866662012737, 102.7516051117415401 ) ) ; +#33279 = ORIENTED_EDGE ( 'NONE', *, *, #7444, .F. ) ; +#33280 = CARTESIAN_POINT ( 'NONE', ( 38.31118519780999776, 119.2261486170999945, 87.35962453867999500 ) ) ; +#33281 = EDGE_CURVE ( 'NONE', #26352, #20529, #2824, .T. ) ; +#33282 = PLANE ( 'NONE', #8826 ) ; +#33283 = DIRECTION ( 'NONE', ( 0.6075493383219849886, -0.7739051213223927528, -0.1787586772592888451 ) ) ; +#33284 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971558186 ) ) ; +#33285 = EDGE_LOOP ( 'NONE', ( #1677, #31181 ) ) ; +#33286 = ORIENTED_EDGE ( 'NONE', *, *, #21000, .T. ) ; +#33287 = CARTESIAN_POINT ( 'NONE', ( -32.82620923289504589, 141.9145509277669532, 282.5750060058261965 ) ) ; +#33288 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33289 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 67.27946979429630403, 312.5857197240632104 ) ) ; +#33290 = CARTESIAN_POINT ( 'NONE', ( -30.06677054097168522, 177.7873425219656838, 100.7165248410704379 ) ) ; +#33291 = CARTESIAN_POINT ( 'NONE', ( -20.02005459657448583, 210.1682184491333203, 73.07059569371034513 ) ) ; +#33292 = VECTOR ( 'NONE', #30692, 1000.000000000000114 ) ; +#33293 = AXIS2_PLACEMENT_3D ( 'NONE', #21330, #12313, #8662 ) ; +#33294 = CARTESIAN_POINT ( 'NONE', ( -20.00005230623649410, 189.3360834415266538, 103.3767362770949205 ) ) ; +#33295 = EDGE_CURVE ( 'NONE', #22051, #27937, #13192, .T. ) ; +#33296 = VECTOR ( 'NONE', #8127, 1000.000000000000000 ) ; +#33297 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33298 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25653, #22576, #7009, #21970, #19482, #34411, #8238, #20078, #1695, #20702, #14373, #1482, #26855, #10508, #38683, #19873, #4340, #13758, #26445, #38895, #23377, #35807, #17210, #23566, #14184, #39092, #9251, #37055 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 1, 1, 2, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000002658984, 0.1875000000003988476, 0.2187500000004621303, 0.2343750000005202783, 0.2421875000005241918, 0.2500000000005281331, 0.3750000000000497935, 0.4374999999998557820, 0.4687499999997587485, 0.4999999999996617706, 0.6249999999996865840, 0.6874999999997115641, 0.7499999999997366551, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33299 = VECTOR ( 'NONE', #13048, 1000.000000000000114 ) ; +#33300 = CARTESIAN_POINT ( 'NONE', ( -12.63810005728112529, 128.5846432257639549, 89.34357918520186104 ) ) ; +#33301 = CARTESIAN_POINT ( 'NONE', ( 6.037333824820820816, 176.9751110601698940, 103.3914243744087713 ) ) ; +#33302 = ADVANCED_FACE ( 'NONE', ( #38177 ), #34876, .T. ) ; +#33303 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#33304 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -1.540743955509788340E-33, -0.0006039748319384538513 ) ) ; +#33305 = ORIENTED_EDGE ( 'NONE', *, *, #31405, .T. ) ; +#33306 = ADVANCED_FACE ( 'NONE', ( #28188 ), #19746, .F. ) ; +#33307 = DIRECTION ( 'NONE', ( 0.0005884949961230292841, -0.2249510543439062205, 0.9743698870671264611 ) ) ; +#33308 = LINE ( 'NONE', #30251, #274 ) ; +#33309 = CARTESIAN_POINT ( 'NONE', ( 25.49226348177107582, 205.5673819639667954, 76.28481786455526503 ) ) ; +#33310 = CARTESIAN_POINT ( 'NONE', ( 36.20140471363000501, 112.8637457762999929, 87.89413822324999614 ) ) ; +#33311 = EDGE_CURVE ( 'NONE', #35054, #16205, #31739, .T. ) ; +#33313 = ORIENTED_EDGE ( 'NONE', *, *, #23305, .T. ) ; +#33312 = CARTESIAN_POINT ( 'NONE', ( 13.47101530616665954, 158.5560635654926216, 96.59244381856061068 ) ) ; +#33314 = EDGE_LOOP ( 'NONE', ( #29422, #14222, #31364, #26281 ) ) ; +#33315 = VERTEX_POINT ( 'NONE', #10376 ) ; +#33316 = EDGE_CURVE ( 'NONE', #5373, #12599, #13438, .T. ) ; +#33317 = CARTESIAN_POINT ( 'NONE', ( -1.671695307840509237, 188.9373267610033906, 103.2735520890073815 ) ) ; +#33318 = EDGE_CURVE ( 'NONE', #6430, #31651, #6369, .T. ) ; +#33319 = EDGE_LOOP ( 'NONE', ( #9934, #34957, #30235, #9547 ) ) ; +#33320 = CARTESIAN_POINT ( 'NONE', ( -23.35774878981629854, 177.6820881319245871, 100.7790085384882559 ) ) ; +#33321 = FACE_OUTER_BOUND ( 'NONE', #10908, .T. ) ; +#33322 = ORIENTED_EDGE ( 'NONE', *, *, #35981, .F. ) ; +#33323 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251387457, 132.4055461763558128, 92.79778151956838883 ) ) ; +#33324 = VECTOR ( 'NONE', #38506, 1000.000000000000227 ) ; +#33325 = VECTOR ( 'NONE', #19639, 1000.000000000000227 ) ; +#33326 = CARTESIAN_POINT ( 'NONE', ( -2.435581690730916016, 190.9709058671855360, 106.3075837308457352 ) ) ; +#33327 = CARTESIAN_POINT ( 'NONE', ( -35.56677799604999990, 112.8225408933000011, 87.40728143148000129 ) ) ; +#33328 = EDGE_LOOP ( 'NONE', ( #463, #34231, #26842, #40281, #35327 ) ) ; +#33329 = CARTESIAN_POINT ( 'NONE', ( -16.53785153513707584, 123.0772470471530085, 172.1883206570706477 ) ) ; +#33330 = AXIS2_PLACEMENT_3D ( 'NONE', #8701, #33614, #2555 ) ; +#33331 = CIRCLE ( 'NONE', #9187, 5.500000704070026281 ) ; +#33332 = CARTESIAN_POINT ( 'NONE', ( -31.13366096836537622, 145.3289308342401114, 291.5773478863123387 ) ) ; +#33333 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971576227 ) ) ; +#33334 = DIRECTION ( 'NONE', ( 0.0004161288024366806716, 0.5299192579072459219, 0.8480479980141769625 ) ) ; +#33335 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825841446765121, 0.0005734119041989553089 ) ) ; +#33336 = ORIENTED_EDGE ( 'NONE', *, *, #18529, .F. ) ; +#33337 = CARTESIAN_POINT ( 'NONE', ( -28.38063916929000285, 186.9956065833000025, 103.2298156084000027 ) ) ; +#33338 = CARTESIAN_POINT ( 'NONE', ( 0.7116569482820880310, 189.0174315982739870, 103.6976887742920184 ) ) ; +#33339 = CARTESIAN_POINT ( 'NONE', ( -35.58150936734264036, 191.9112545771486111, 106.9427098373480192 ) ) ; +#33340 = ORIENTED_EDGE ( 'NONE', *, *, #36645, .T. ) ; +#33341 = PLANE ( 'NONE', #19808 ) ; +#33342 = VERTEX_POINT ( 'NONE', #16482 ) ; +#33343 = EDGE_CURVE ( 'NONE', #28170, #17879, #33155, .T. ) ; +#33344 = ORIENTED_EDGE ( 'NONE', *, *, #38022, .T. ) ; +#33345 = ADVANCED_FACE ( 'NONE', ( #9772 ), #11266, .F. ) ; +#33346 = ORIENTED_EDGE ( 'NONE', *, *, #19147, .F. ) ; +#33347 = CARTESIAN_POINT ( 'NONE', ( -35.93274180817000030, 192.3161995874999945, 104.1918708424999949 ) ) ; +#33348 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21046, #14300, #14505, #20416 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33349 = CARTESIAN_POINT ( 'NONE', ( -30.14946743423720221, 157.4708583386490659, 204.7746580714026834 ) ) ; +#33350 = VECTOR ( 'NONE', #15452, 1000.000000000000227 ) ; +#33351 = CARTESIAN_POINT ( 'NONE', ( 39.06896504242525481, 77.46065173580983299, 289.9734668182510404 ) ) ; +#33352 = EDGE_CURVE ( 'NONE', #367, #38321, #13688, .T. ) ; +#33353 = CONICAL_SURFACE ( 'NONE', #13775, 2.503000015120896204, 0.7853981633802915585 ) ; +#33354 = ORIENTED_EDGE ( 'NONE', *, *, #8916, .F. ) ; +#33355 = FACE_OUTER_BOUND ( 'NONE', #27261, .T. ) ; +#33356 = LINE ( 'NONE', #8440, #21283 ) ; +#33357 = ORIENTED_EDGE ( 'NONE', *, *, #18205, .F. ) ; +#33358 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38992, #20381, #19766, #22871 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999913805631791552 ), + .UNSPECIFIED. ) ; +#33359 = AXIS2_PLACEMENT_3D ( 'NONE', #25104, #18719, #34664 ) ; +#33360 = CARTESIAN_POINT ( 'NONE', ( 26.03705070847000158, 122.6857235223999965, 90.52704919891000657 ) ) ; +#33361 = AXIS2_PLACEMENT_3D ( 'NONE', #24820, #33984, #18434 ) ; +#33362 = CARTESIAN_POINT ( 'NONE', ( -26.00898928064792059, 209.7096528057114710, 76.07444037909847623 ) ) ; +#33364 = CARTESIAN_POINT ( 'NONE', ( 40.34565112152872501, 84.30714302849141006, 281.9928763557079492 ) ) ; +#33363 = DIRECTION ( 'NONE', ( 2.710505431213760483E-20, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#33365 = ORIENTED_EDGE ( 'NONE', *, *, #34200, .F. ) ; +#33366 = EDGE_CURVE ( 'NONE', #12177, #6270, #32823, .T. ) ; +#33367 = EDGE_LOOP ( 'NONE', ( #30675, #13206, #2209, #34438, #236, #39336, #28015, #28093, #13123, #34703, #29555, #27063 ) ) ; +#33368 = VERTEX_POINT ( 'NONE', #28772 ) ; +#33369 = CARTESIAN_POINT ( 'NONE', ( 38.65290384512000088, 119.3054438774999966, 90.42302427312999669 ) ) ; +#33370 = DIRECTION ( 'NONE', ( -0.0006039748319393752063, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#33371 = EDGE_CURVE ( 'NONE', #23183, #9539, #21016, .T. ) ; +#33372 = DIRECTION ( 'NONE', ( -7.677760455957277161E-18, 1.000000000000000000, -1.271205131337255403E-14 ) ) ; +#33373 = CARTESIAN_POINT ( 'NONE', ( -25.57959927007320644, 190.0284346369258230, 106.1056550784269348 ) ) ; +#33374 = EDGE_LOOP ( 'NONE', ( #8473, #19023, #11158, #31746 ) ) ; +#33375 = ORIENTED_EDGE ( 'NONE', *, *, #30051, .T. ) ; +#33376 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12128, #4961, #30324, #2321, #39921, #8667, #23789, #36244, #11720 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 1, 4 ), + ( 0.000000000000000000, 0.1666665328685613123, 0.3333330550499289946, 0.4999995772315967146, 0.6666660994132644902, 0.8333326215947320925, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33377 = FACE_OUTER_BOUND ( 'NONE', #304, .T. ) ; +#33378 = AXIS2_PLACEMENT_3D ( 'NONE', #9215, #21285, #24154 ) ; +#33379 = CARTESIAN_POINT ( 'NONE', ( 20.94827535171210897, 136.6018947531004244, 91.17730147031002730 ) ) ; +#33380 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971564847 ) ) ; +#33381 = CIRCLE ( 'NONE', #3345, 2.000000000000011546 ) ; +#33382 = VERTEX_POINT ( 'NONE', #26747 ) ; +#33383 = CARTESIAN_POINT ( 'NONE', ( -36.31434820589119283, 190.8494679263099840, 106.8166726591159943 ) ) ; +#33384 = CARTESIAN_POINT ( 'NONE', ( 1.193074764343845962, 188.4261495725348539, 106.2465465345643452 ) ) ; +#33385 = VERTEX_POINT ( 'NONE', #20390 ) ; +#33386 = CARTESIAN_POINT ( 'NONE', ( 5.667817003649492591, 130.7086471584207175, 90.09438582789336181 ) ) ; +#33387 = CARTESIAN_POINT ( 'NONE', ( 39.86705590273664512, 163.8835619643772645, 187.7938324431582089 ) ) ; +#33388 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7431, #38915, #20311, #16829, #4975, #1502, #17435, #23395, #29329, #32786 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 4 ), + ( 0.000000000000000000, 0.04166555891684221857, 0.08333241167583366193, 0.1666661171939165242, 0.2499998227117794236, 0.3333335282297422708, 0.6666667690975455196, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33389 = LINE ( 'NONE', #24425, #20213 ) ; +#33390 = DIRECTION ( 'NONE', ( -0.7933532970003733809, -0.5930762008556731413, -0.1372995488602877234 ) ) ; +#33391 = VERTEX_POINT ( 'NONE', #14884 ) ; +#33392 = ADVANCED_FACE ( 'NONE', ( #24087 ), #28261, .T. ) ; +#33393 = EDGE_CURVE ( 'NONE', #8895, #529, #21081, .T. ) ; +#33394 = CARTESIAN_POINT ( 'NONE', ( -21.44693694427656538, 176.9185168219783009, 100.5107344958116897 ) ) ; +#33395 = CARTESIAN_POINT ( 'NONE', ( 15.83996889908606853, 123.3007470976622812, 173.6922296629854259 ) ) ; +#33396 = ORIENTED_EDGE ( 'NONE', *, *, #185, .F. ) ; +#33397 = EDGE_CURVE ( 'NONE', #24029, #18457, #20179, .T. ) ; +#33398 = DIRECTION ( 'NONE', ( 0.1305262051639064502, -0.9658997602660150950, -0.2236080563923503461 ) ) ; +#33399 = VERTEX_POINT ( 'NONE', #35703 ) ; +#33400 = CIRCLE ( 'NONE', #24307, 2.999999999692155583 ) ; +#33402 = CARTESIAN_POINT ( 'NONE', ( -25.73988229027240848, 191.3495811618992661, 106.6455200333169557 ) ) ; +#33401 = FACE_OUTER_BOUND ( 'NONE', #5101, .T. ) ; +#33403 = ORIENTED_EDGE ( 'NONE', *, *, #29174, .F. ) ; +#33404 = AXIS2_PLACEMENT_3D ( 'NONE', #9778, #28585, #10385 ) ; +#33405 = EDGE_CURVE ( 'NONE', #75, #17792, #11743, .T. ) ; +#33406 = ORIENTED_EDGE ( 'NONE', *, *, #2396, .T. ) ; +#33407 = VECTOR ( 'NONE', #15363, 1000.000000000000114 ) ; +#33408 = ORIENTED_EDGE ( 'NONE', *, *, #849, .T. ) ; +#33409 = DIRECTION ( 'NONE', ( 0.0005884949961257158286, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33410 = CARTESIAN_POINT ( 'NONE', ( 36.81706287246154119, 191.3054326740181352, 106.3308896061233639 ) ) ; +#33411 = DIRECTION ( 'NONE', ( 0.0005884949961252012663, -0.2249510543439044163, 0.9743698870671267942 ) ) ; +#33412 = ORIENTED_EDGE ( 'NONE', *, *, #23404, .T. ) ; +#33413 = EDGE_LOOP ( 'NONE', ( #30317, #26910, #34613, #11442 ) ) ; +#33414 = CARTESIAN_POINT ( 'NONE', ( -14.42373141347307985, 176.1776882614505269, 103.2433209713472877 ) ) ; +#33415 = VERTEX_POINT ( 'NONE', #8133 ) ; +#33416 = ORIENTED_EDGE ( 'NONE', *, *, #13474, .F. ) ; +#33417 = EDGE_LOOP ( 'NONE', ( #29271, #18571, #38333, #23542 ) ) ; +#33418 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971554578 ) ) ; +#33419 = ADVANCED_FACE ( 'NONE', ( #11007 ), #4652, .T. ) ; +#33420 = CARTESIAN_POINT ( 'NONE', ( -19.99999816303952471, 191.5261162992163690, 103.8822987450886046 ) ) ; +#33421 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.271205595054999941E-14 ) ) ; +#33422 = ORIENTED_EDGE ( 'NONE', *, *, #12537, .T. ) ; +#33423 = ORIENTED_EDGE ( 'NONE', *, *, #28235, .T. ) ; +#33424 = ORIENTED_EDGE ( 'NONE', *, *, #13343, .F. ) ; +#33425 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319368671214 ) ) ; +#33426 = CARTESIAN_POINT ( 'NONE', ( -35.83347173055000212, 192.2043590798000139, 104.3136215505000024 ) ) ; +#33427 = CARTESIAN_POINT ( 'NONE', ( -25.83463620619999901, 120.7390220298999992, 87.71382168438999827 ) ) ; +#33428 = ORIENTED_EDGE ( 'NONE', *, *, #17363, .F. ) ; +#33429 = CARTESIAN_POINT ( 'NONE', ( -24.13060896835314395, 149.4040876299065417, 197.0825913028203900 ) ) ; +#33430 = ORIENTED_EDGE ( 'NONE', *, *, #38990, .F. ) ; +#33431 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#33432 = CARTESIAN_POINT ( 'NONE', ( 29.05533563819800236, 110.6131156702000027, 90.25023614458406485 ) ) ; +#33433 = EDGE_LOOP ( 'NONE', ( #23394, #32116, #28786, #21170 ) ) ; +#33434 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22415, #10145, #6848, #19322 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.0003352960797964262582 ), + .UNSPECIFIED. ) ; +#33435 = CARTESIAN_POINT ( 'NONE', ( 1.007187599721282245, 188.6511345722273347, 103.2058614258702107 ) ) ; +#33436 = VECTOR ( 'NONE', #26976, 1000.000000000000227 ) ; +#33437 = CARTESIAN_POINT ( 'NONE', ( -28.94810864222802849, 110.6131156702000027, 87.28526822420690223 ) ) ; +#33438 = CARTESIAN_POINT ( 'NONE', ( -3.994524027314616088, 167.9238973488463103, 101.0321959041968967 ) ) ; +#33439 = VERTEX_POINT ( 'NONE', #23467 ) ; +#33440 = AXIS2_PLACEMENT_3D ( 'NONE', #35162, #13321, #25408 ) ; +#33441 = LINE ( 'NONE', #33035, #28341 ) ; +#33442 = CARTESIAN_POINT ( 'NONE', ( 45.36643772523598983, 116.4348365831125705, 122.4283839521299768 ) ) ; +#33443 = CARTESIAN_POINT ( 'NONE', ( -14.08011580147661235, 129.1601492223334446, 176.8499123979196099 ) ) ; +#33444 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2654, #12437, #31457, #15895 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0001076180654492282703, 0.0007700079201253817729 ), + .UNSPECIFIED. ) ; +#33445 = ORIENTED_EDGE ( 'NONE', *, *, #35044, .F. ) ; +#33446 = CARTESIAN_POINT ( 'NONE', ( 22.11776643986201663, 129.2357545819063773, 92.04174809736024088 ) ) ; +#33447 = ORIENTED_EDGE ( 'NONE', *, *, #32179, .F. ) ; +#33448 = EDGE_CURVE ( 'NONE', #27242, #4779, #33668, .T. ) ; +#33449 = LINE ( 'NONE', #23861, #17271 ) ; +#33450 = FACE_OUTER_BOUND ( 'NONE', #438, .T. ) ; +#33451 = CARTESIAN_POINT ( 'NONE', ( 38.35945018049999788, 118.7771177168999941, 90.10301542510001127 ) ) ; +#33452 = CARTESIAN_POINT ( 'NONE', ( -45.78692920758950180, 187.6730625466252604, 103.4985544161652626 ) ) ; +#33453 = CARTESIAN_POINT ( 'NONE', ( -25.49980755039416280, 121.1804654486459896, 90.21079787901257419 ) ) ; +#33454 = ORIENTED_EDGE ( 'NONE', *, *, #17625, .F. ) ; +#33455 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#33456 = AXIS2_PLACEMENT_3D ( 'NONE', #39544, #20953, #15026 ) ; +#33457 = CARTESIAN_POINT ( 'NONE', ( -15.99825118274618063, 184.2885608609500423, 105.2878711035513817 ) ) ; +#33458 = DIRECTION ( 'NONE', ( -1.262878690511118089E-13, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#33459 = CARTESIAN_POINT ( 'NONE', ( 19.46094739937527152, 125.6704563215593993, 178.4613359473326568 ) ) ; +#33460 = LINE ( 'NONE', #24082, #33296 ) ; +#33461 = CARTESIAN_POINT ( 'NONE', ( 20.00176513865794448, 118.9456690639568990, 90.18052439326535819 ) ) ; +#33462 = AXIS2_PLACEMENT_3D ( 'NONE', #9976, #22448, #31650 ) ; +#33463 = CARTESIAN_POINT ( 'NONE', ( 20.22318834111896635, 116.9804196145639423, 90.25557054020046621 ) ) ; +#33464 = EDGE_LOOP ( 'NONE', ( #26489, #32782, #32403, #23471 ) ) ; +#33465 = CARTESIAN_POINT ( 'NONE', ( -15.83322916944478820, 185.8688726946225813, 102.7447540698997130 ) ) ; +#33466 = EDGE_CURVE ( 'NONE', #23376, #33023, #17108, .T. ) ; +#33467 = AXIS2_PLACEMENT_3D ( 'NONE', #30048, #32704, #8583 ) ; +#33468 = CARTESIAN_POINT ( 'NONE', ( -31.52379782310919865, 135.3548788018836433, 90.92109691820547823 ) ) ; +#33469 = ORIENTED_EDGE ( 'NONE', *, *, #38131, .T. ) ; +#33470 = DIRECTION ( 'NONE', ( 0.0005884949961176092490, -0.2249510543439112442, 0.9743698870671252399 ) ) ; +#33471 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384972194 ) ) ; +#33472 = ORIENTED_EDGE ( 'NONE', *, *, #35152, .T. ) ; +#33473 = CARTESIAN_POINT ( 'NONE', ( -38.41441041566999814, 118.8735418521000042, 87.72269134817000236 ) ) ; +#33474 = CARTESIAN_POINT ( 'NONE', ( -3.706756796165672441, 143.5747363548986755, 95.70573741494366971 ) ) ; +#33475 = EDGE_LOOP ( 'NONE', ( #22826, #12574, #5821, #34040 ) ) ; +#33476 = CARTESIAN_POINT ( 'NONE', ( 36.38135911213310436, 190.8957024088025491, 106.7816086242061289 ) ) ; +#33477 = EDGE_CURVE ( 'NONE', #2293, #31797, #37085, .T. ) ; +#33478 = FACE_OUTER_BOUND ( 'NONE', #25597, .T. ) ; +#33479 = LINE ( 'NONE', #2822, #13583 ) ; +#33480 = CARTESIAN_POINT ( 'NONE', ( -1.762796036306197633, 151.6652447677196847, 130.5904578367407396 ) ) ; +#33481 = FACE_OUTER_BOUND ( 'NONE', #196, .T. ) ; +#33482 = ORIENTED_EDGE ( 'NONE', *, *, #22210, .F. ) ; +#33483 = ORIENTED_EDGE ( 'NONE', *, *, #9045, .T. ) ; +#33484 = EDGE_CURVE ( 'NONE', #21410, #18813, #13890, .T. ) ; +#33485 = CARTESIAN_POINT ( 'NONE', ( -40.05024589846355099, 182.7376013918133140, 105.6081377280634257 ) ) ; +#33486 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; +#33487 = VECTOR ( 'NONE', #12215, 1000.000000000000114 ) ; +#33488 = FACE_OUTER_BOUND ( 'NONE', #33417, .T. ) ; +#33489 = CARTESIAN_POINT ( 'NONE', ( 38.11757776978107159, 119.1971814748143146, 87.25517274288121428 ) ) ; +#33490 = EDGE_CURVE ( 'NONE', #37955, #12152, #18519, .T. ) ; +#33491 = VERTEX_POINT ( 'NONE', #30212 ) ; +#33492 = AXIS2_PLACEMENT_3D ( 'NONE', #33621, #5619, #27929 ) ; +#33493 = CYLINDRICAL_SURFACE ( 'NONE', #35501, 4.999999999999990230 ) ; +#33494 = EDGE_CURVE ( 'NONE', #39629, #12644, #2210, .T. ) ; +#33495 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#33496 = CARTESIAN_POINT ( 'NONE', ( 6.028443089694566659, 134.2450043241766195, 93.72108952724657627 ) ) ; +#33497 = CARTESIAN_POINT ( 'NONE', ( -20.02010896950462637, 210.6268457253666782, 73.07059572655020929 ) ) ; +#33498 = AXIS2_PLACEMENT_3D ( 'NONE', #14075, #36349, #16719 ) ; +#33499 = CARTESIAN_POINT ( 'NONE', ( 19.99999382154498662, 120.3902235794415816, 87.43511282661482653 ) ) ; +#33500 = EDGE_CURVE ( 'NONE', #26219, #3788, #32792, .T. ) ; +#33501 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13036, #16087, #34873, #22648 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33502 = CARTESIAN_POINT ( 'NONE', ( -26.00666714465146612, 209.7097296363926660, 73.07769990689128292 ) ) ; +#33503 = FACE_OUTER_BOUND ( 'NONE', #7355, .T. ) ; +#33504 = CALENDAR_DATE ( 2025, 24, 6 ) ; +#33505 = CARTESIAN_POINT ( 'NONE', ( 20.79492132475692401, 105.5805168949505486, 90.25522522787177593 ) ) ; +#33506 = VERTEX_POINT ( 'NONE', #24501 ) ; +#33507 = CARTESIAN_POINT ( 'NONE', ( 44.36208288160555213, 114.2238992016985577, 129.8113731785908271 ) ) ; +#33508 = CARTESIAN_POINT ( 'NONE', ( 35.09291703229374093, 226.4002260771000010, 152.4718672074037329 ) ) ; +#33509 = CARTESIAN_POINT ( 'NONE', ( 17.97063383950254334, 126.0060190202803341, 174.3181455802166795 ) ) ; +#33510 = LINE ( 'NONE', #39846, #23500 ) ; +#33511 = CARTESIAN_POINT ( 'NONE', ( -38.23160862004999672, 118.6973730046999975, 90.09692188751000685 ) ) ; +#33512 = ORIENTED_EDGE ( 'NONE', *, *, #35815, .T. ) ; +#33513 = LINE ( 'NONE', #14928, #25176 ) ; +#33514 = ORIENTED_EDGE ( 'NONE', *, *, #7917, .T. ) ; +#33515 = CARTESIAN_POINT ( 'NONE', ( -23.35994101754937091, 177.6215018238531513, 100.8168681451780202 ) ) ; +#33516 = AXIS2_PLACEMENT_3D ( 'NONE', #265, #6006, #30960 ) ; +#33517 = CARTESIAN_POINT ( 'NONE', ( 36.06505478217123795, 192.7057421143160525, 106.3400883098223915 ) ) ; +#33518 = DIRECTION ( 'NONE', ( 0.6087613503693988237, 0.7731003926570265694, 0.1781162574555661682 ) ) ; +#33519 = AXIS2_PLACEMENT_3D ( 'NONE', #33973, #10265, #15767 ) ; +#33520 = ORIENTED_EDGE ( 'NONE', *, *, #129, .F. ) ; +#33521 = DIRECTION ( 'NONE', ( 0.7072759766253136071, 0.1592272936566845043, -0.6887723585071315879 ) ) ; +#33522 = CIRCLE ( 'NONE', #21791, 6.000000000000007994 ) ; +#33523 = CARTESIAN_POINT ( 'NONE', ( 14.03037017219619109, 130.6394716187099903, 89.80494561686856514 ) ) ; +#33524 = CARTESIAN_POINT ( 'NONE', ( -20.49970533410106910, 151.8550384231813553, 95.23695349207935124 ) ) ; +#33525 = EDGE_LOOP ( 'NONE', ( #35454, #20888, #39600, #33960 ) ) ; +#33526 = FACE_OUTER_BOUND ( 'NONE', #16982, .T. ) ; +#33527 = EDGE_CURVE ( 'NONE', #10675, #7714, #29565, .T. ) ; +#33528 = CARTESIAN_POINT ( 'NONE', ( 23.36666681450611449, 177.0338548618016432, 103.4718259550949142 ) ) ; +#33529 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250100424, 132.8554482850266538, 90.84904174538199584 ) ) ; +#33530 = DIRECTION ( 'NONE', ( -0.0005884965908176638741, 0.2249510543436329113, -0.9743698870662261813 ) ) ; +#33531 = CARTESIAN_POINT ( 'NONE', ( -4.020572368890905857, 187.7456919456083142, 102.9998601274035934 ) ) ; +#33532 = CARTESIAN_POINT ( 'NONE', ( 39.01961099979754266, 175.8196705488005023, 136.1591049921323986 ) ) ; +#33533 = ORIENTED_EDGE ( 'NONE', *, *, #33036, .F. ) ; +#33534 = EDGE_CURVE ( 'NONE', #20168, #14135, #30822, .T. ) ; +#33535 = DIRECTION ( 'NONE', ( -0.7075337269008554753, -2.191878737649064204E-15, -0.7066795775298629900 ) ) ; +#33536 = CARTESIAN_POINT ( 'NONE', ( 0.9454324690280999643, 189.0434255943999915, 103.7039833884000046 ) ) ; +#33537 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319411731388 ) ) ; +#33538 = EDGE_CURVE ( 'NONE', #20341, #901, #27580, .T. ) ; +#33539 = ORIENTED_EDGE ( 'NONE', *, *, #36289, .F. ) ; +#33540 = CARTESIAN_POINT ( 'NONE', ( -3.996912173002292068, 136.7828067576370472, 93.84025925768952447 ) ) ; +#33541 = ORIENTED_EDGE ( 'NONE', *, *, #4350, .F. ) ; +#33542 = EDGE_CURVE ( 'NONE', #37891, #34375, #18419, .T. ) ; +#33543 = EDGE_CURVE ( 'NONE', #34749, #40179, #21632, .T. ) ; +#33544 = ADVANCED_FACE ( 'NONE', ( #40012 ), #12019, .F. ) ; +#33545 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422003068, 157.6312130328778096, 99.11571341752234332 ) ) ; +#33546 = AXIS2_PLACEMENT_3D ( 'NONE', #23148, #11479, #32547 ) ; +#33547 = AXIS2_PLACEMENT_3D ( 'NONE', #3829, #32463, #3631 ) ; +#33548 = VERTEX_POINT ( 'NONE', #34073 ) ; +#33549 = ORIENTED_EDGE ( 'NONE', *, *, #5315, .T. ) ; +#33550 = VECTOR ( 'NONE', #21687, 1000.000000000000114 ) ; +#33551 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33552 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#33553 = LINE ( 'NONE', #24390, #19984 ) ; +#33554 = AXIS2_PLACEMENT_3D ( 'NONE', #22492, #34907, #16514 ) ; +#33555 = ORIENTED_EDGE ( 'NONE', *, *, #21617, .T. ) ; +#33556 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971530430 ) ) ; +#33557 = CARTESIAN_POINT ( 'NONE', ( -25.50129508846853099, 118.1132512059233335, 87.78307593003776788 ) ) ; +#33558 = VERTEX_POINT ( 'NONE', #18124 ) ; +#33559 = CARTESIAN_POINT ( 'NONE', ( 26.23959569209999998, 121.6931803613000085, 90.81114231919001156 ) ) ; +#33560 = LINE ( 'NONE', #2890, #28675 ) ; +#33562 = CARTESIAN_POINT ( 'NONE', ( 38.81159562487034265, 113.5937817496002396, 151.4290813728213152 ) ) ; +#33561 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023854076 ) ) ; +#33563 = ORIENTED_EDGE ( 'NONE', *, *, #19261, .T. ) ; +#33564 = CARTESIAN_POINT ( 'NONE', ( 39.31906229016909293, 183.3064585026729674, 101.9668787784548698 ) ) ; +#33565 = EDGE_CURVE ( 'NONE', #14526, #29201, #28300, .T. ) ; +#33566 = ORIENTED_EDGE ( 'NONE', *, *, #7319, .F. ) ; +#33567 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927790412197, 0.0005734119022076163575 ) ) ; +#33569 = ORIENTED_EDGE ( 'NONE', *, *, #2178, .F. ) ; +#33568 = AXIS2_PLACEMENT_3D ( 'NONE', #23740, #14540, #17776 ) ; +#33570 = CARTESIAN_POINT ( 'NONE', ( 38.78510361949000185, 119.3955236502000048, 90.43317343257000118 ) ) ; +#33571 = CARTESIAN_POINT ( 'NONE', ( -25.99964915362324192, 120.0929955239077032, 90.47318932755659660 ) ) ; +#33572 = CARTESIAN_POINT ( 'NONE', ( -15.99999440082457447, 126.8010213445309660, 88.93691041956509480 ) ) ; +#33573 = PLANE ( 'NONE', #30045 ) ; +#33574 = CONICAL_SURFACE ( 'NONE', #25755, 4.999999999883085522, 0.7853981633291653441 ) ; +#33575 = CARTESIAN_POINT ( 'NONE', ( -12.64523939051215073, 134.9174765714697344, 90.80875027841997849 ) ) ; +#33576 = ORIENTED_EDGE ( 'NONE', *, *, #26655, .T. ) ; +#33577 = EDGE_CURVE ( 'NONE', #9446, #11054, #30244, .T. ) ; +#33578 = ORIENTED_EDGE ( 'NONE', *, *, #33477, .T. ) ; +#33579 = FACE_OUTER_BOUND ( 'NONE', #35902, .T. ) ; +#33580 = AXIS2_PLACEMENT_3D ( 'NONE', #27426, #21863, #28208 ) ; +#33581 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35561, #29881, #30272, #8415, #26617, #23741, #14753, #33127, #11676, #36615 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.002384341708615501237, 0.2517882562814616199, 0.5011921708543077836, 0.7505960854271538363, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33582 = CARTESIAN_POINT ( 'NONE', ( 15.83316883261202612, 186.7852030470082525, 102.7661225901500330 ) ) ; +#33583 = ORIENTED_EDGE ( 'NONE', *, *, #4820, .T. ) ; +#33584 = VERTEX_POINT ( 'NONE', #37547 ) ; +#33585 = ADVANCED_FACE ( 'NONE', ( #28361 ), #34460, .T. ) ; +#33586 = CARTESIAN_POINT ( 'NONE', ( -25.49718356649553641, 191.5268115629067154, 104.3989865086577140 ) ) ; +#33587 = ADVANCED_FACE ( 'NONE', ( #11818 ), #21727, .T. ) ; +#33588 = CARTESIAN_POINT ( 'NONE', ( 2.549279137596999867, 190.7083476029000053, 106.2283635592000053 ) ) ; +#33589 = DIRECTION ( 'NONE', ( 0.6087906217132987852, -0.7729786229956010501, -0.1785441886642060716 ) ) ; +#33590 = ADVANCED_FACE ( 'NONE', ( #2806 ), #27974, .F. ) ; +#33591 = CARTESIAN_POINT ( 'NONE', ( 13.49969781725042139, 124.7119230207161991, 88.90738776642010066 ) ) ; +#33592 = CARTESIAN_POINT ( 'NONE', ( 45.36643772518247886, 116.4348365834111121, 122.4283839521990984 ) ) ; +#33593 = CARTESIAN_POINT ( 'NONE', ( 36.04737028556108669, 207.4083918097865649, 77.05990514452427931 ) ) ; +#33594 = ORIENTED_EDGE ( 'NONE', *, *, #30611, .F. ) ; +#33595 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418000665, 218.5902260770999987, 73.08022052565414128 ) ) ; +#33596 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5082, #33291, #33497, #14506 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33597 = CARTESIAN_POINT ( 'NONE', ( 15.99867818869383385, 138.1324741098936215, 91.53365305490791570 ) ) ; +#33598 = CARTESIAN_POINT ( 'NONE', ( -17.00047812746342402, 136.5658759208817230, 181.4646850263357010 ) ) ; +#33599 = LOCAL_TIME ( 14, 25, 27.00000000000000000, #21058 ) ; +#33600 = VECTOR ( 'NONE', #6635, 1000.000000000000000 ) ; +#33601 = AXIS2_PLACEMENT_3D ( 'NONE', #26943, #11592, #14665 ) ; +#33602 = VECTOR ( 'NONE', #6982, 999.9999999999998863 ) ; +#33603 = EDGE_LOOP ( 'NONE', ( #27127, #38515, #31703, #23081 ) ) ; +#33604 = CARTESIAN_POINT ( 'NONE', ( -5.667984704580542932, 187.9405149811499030, 103.3903667269636202 ) ) ; +#33605 = EDGE_LOOP ( 'NONE', ( #4700, #8244, #18122, #18370 ) ) ; +#33606 = VECTOR ( 'NONE', #38341, 1000.000000000000000 ) ; +#33608 = CARTESIAN_POINT ( 'NONE', ( -44.34948217328133069, 189.1747481438389684, 103.6962404974556335 ) ) ; +#33607 = CARTESIAN_POINT ( 'NONE', ( -13.55720661489401913, 148.0719226728492970, 93.84312808491080204 ) ) ; +#33609 = ORIENTED_EDGE ( 'NONE', *, *, #39756, .F. ) ; +#33610 = ORIENTED_EDGE ( 'NONE', *, *, #17648, .F. ) ; +#33611 = VERTEX_POINT ( 'NONE', #15286 ) ; +#33612 = FACE_OUTER_BOUND ( 'NONE', #30323, .T. ) ; +#33613 = DIRECTION ( 'NONE', ( 0.0005884949961242131244, -0.2249510543439063315, 0.9743698870671262391 ) ) ; +#33614 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#33615 = CARTESIAN_POINT ( 'NONE', ( 12.63852066807981345, 177.1933417902586427, 101.0667481637636627 ) ) ; +#33616 = ORIENTED_EDGE ( 'NONE', *, *, #37246, .T. ) ; +#33617 = ORIENTED_EDGE ( 'NONE', *, *, #26599, .T. ) ; +#33618 = CARTESIAN_POINT ( 'NONE', ( -15.30926470586320853, 122.3926578048745029, 284.1741477470645236 ) ) ; +#33619 = ORIENTED_EDGE ( 'NONE', *, *, #4586, .T. ) ; +#33620 = ORIENTED_EDGE ( 'NONE', *, *, #1317, .F. ) ; +#33621 = CARTESIAN_POINT ( 'NONE', ( -2.952854088846381231, 209.7096538831000032, 78.06028844423788371 ) ) ; +#33622 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#33623 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#33624 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#33625 = ADVANCED_FACE ( 'NONE', ( #31427 ), #24302, .T. ) ; +#33626 = ORIENTED_EDGE ( 'NONE', *, *, #33642, .T. ) ; +#33627 = EDGE_CURVE ( 'NONE', #9915, #34668, #40018, .T. ) ; +#33628 = EDGE_LOOP ( 'NONE', ( #17391, #4756, #28887, #34033 ) ) ; +#33629 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640286824, -0.2252353050503915488 ) ) ; +#33630 = ADVANCED_FACE ( 'NONE', ( #32033 ), #9753, .F. ) ; +#33631 = CARTESIAN_POINT ( 'NONE', ( -36.34349144616999894, 191.9206088457000021, 104.5561665447000195 ) ) ; +#33632 = ADVANCED_FACE ( 'NONE', ( #35258, #37956, #34856, #4187 ), #31632, .T. ) ; +#33633 = ORIENTED_EDGE ( 'NONE', *, *, #15409, .F. ) ; +#33634 = CARTESIAN_POINT ( 'NONE', ( -25.50186340329999979, 120.7653135713000125, 88.06248121368000170 ) ) ; +#33635 = AXIS2_PLACEMENT_3D ( 'NONE', #4330, #17602, #4525 ) ; +#33636 = ORIENTED_EDGE ( 'NONE', *, *, #39028, .T. ) ; +#33637 = CARTESIAN_POINT ( 'NONE', ( 42.78873758771006663, 120.8665316288775102, 92.29373204621693105 ) ) ; +#33638 = CARTESIAN_POINT ( 'NONE', ( 41.00931486137713478, 189.3830257637429781, 107.0363912322027886 ) ) ; +#33639 = ORIENTED_EDGE ( 'NONE', *, *, #1828, .T. ) ; +#33640 = CIRCLE ( 'NONE', #6198, 4.000000000000000000 ) ; +#33641 = VECTOR ( 'NONE', #6478, 1000.000000000000114 ) ; +#33642 = EDGE_CURVE ( 'NONE', #15381, #6338, #13222, .T. ) ; +#33643 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#33644 = CARTESIAN_POINT ( 'NONE', ( -14.50493307988418579, 124.5700211486796434, 88.42093691827915336 ) ) ; +#33646 = EDGE_CURVE ( 'NONE', #32344, #37440, #22429, .T. ) ; +#33645 = CARTESIAN_POINT ( 'NONE', ( 15.01700441902629990, 123.4944333684167361, 178.4524337621022880 ) ) ; +#33647 = FACE_OUTER_BOUND ( 'NONE', #772, .T. ) ; +#33648 = CARTESIAN_POINT ( 'NONE', ( 26.37129435717525183, 189.9627969739057107, 103.4933647081285670 ) ) ; +#33649 = EDGE_LOOP ( 'NONE', ( #27007, #13174, #12459, #25017 ) ) ; +#33650 = FACE_OUTER_BOUND ( 'NONE', #20542, .T. ) ; +#33651 = CARTESIAN_POINT ( 'NONE', ( -25.40050087938999823, 191.0670114341999977, 104.4191319587000066 ) ) ; +#33652 = DIRECTION ( 'NONE', ( -0.0002393071182782278061, -0.2252352986010052738, 0.9743043687658489160 ) ) ; +#33653 = CARTESIAN_POINT ( 'NONE', ( 35.42042856514999727, 112.3953715357999954, 90.38152322809999362 ) ) ; +#33654 = DIRECTION ( 'NONE', ( -0.0005884949961221202890, 0.2249510543439054433, -0.9743698870671265722 ) ) ; +#33655 = VERTEX_POINT ( 'NONE', #38353 ) ; +#33656 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15574, #31529, #24607, #28072 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33657 = VECTOR ( 'NONE', #9442, 1000.000000000000114 ) ; +#33658 = LINE ( 'NONE', #12008, #35701 ) ; +#33659 = CIRCLE ( 'NONE', #34296, 2.500000000000002220 ) ; +#33660 = EDGE_LOOP ( 'NONE', ( #16625, #1472, #15232, #35875 ) ) ; +#33661 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927694284121, 0.0005734119022093313485 ) ) ; +#33662 = CYLINDRICAL_SURFACE ( 'NONE', #38488, 5.999999999999998224 ) ; +#33663 = CARTESIAN_POINT ( 'NONE', ( 26.00894374567046441, 191.9425530329557716, 103.9054621679136261 ) ) ; +#33664 = FACE_OUTER_BOUND ( 'NONE', #32748, .T. ) ; +#33665 = DIRECTION ( 'NONE', ( -0.5988682214945756366, 0.8008475843029833063, 0.000000000000000000 ) ) ; +#33666 = ORIENTED_EDGE ( 'NONE', *, *, #10807, .T. ) ; +#33667 = CARTESIAN_POINT ( 'NONE', ( -22.50040042369792559, 158.4258594287385336, 96.41306356714065373 ) ) ; +#33668 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21015, #35916, #23680, #8344 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33669 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33670 = VERTEX_POINT ( 'NONE', #38543 ) ; +#33671 = CARTESIAN_POINT ( 'NONE', ( -20.16657097893908102, 174.4711545278903770, 100.1159964656488626 ) ) ; +#33672 = EDGE_CURVE ( 'NONE', #5169, #12942, #38048, .T. ) ; +#33673 = CARTESIAN_POINT ( 'NONE', ( -20.07611744496675144, 117.3322318276110821, 90.27991031107923448 ) ) ; +#33674 = EDGE_CURVE ( 'NONE', #13786, #1942, #6842, .T. ) ; +#33675 = ORIENTED_EDGE ( 'NONE', *, *, #16818, .F. ) ; +#33676 = CARTESIAN_POINT ( 'NONE', ( -38.67639030779000109, 119.8305709359000133, 87.36412529714000641 ) ) ; +#33677 = CARTESIAN_POINT ( 'NONE', ( -5.668152766071871795, 130.6151334557387145, 90.15838212948281694 ) ) ; +#33678 = ORIENTED_EDGE ( 'NONE', *, *, #22853, .T. ) ; +#33679 = FACE_OUTER_BOUND ( 'NONE', #20658, .T. ) ; +#33680 = PRODUCT_RELATED_PRODUCT_CATEGORY ( 'detail', '', ( #16623 ) ) ; +#33681 = LINE ( 'NONE', #36757, #2878 ) ; +#33682 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#33683 = VECTOR ( 'NONE', #18323, 1000.000000000000000 ) ; +#33684 = CARTESIAN_POINT ( 'NONE', ( -24.07944809770393846, 115.3139759671915527, 90.28232822247846912 ) ) ; +#33685 = DIRECTION ( 'NONE', ( -0.0001408422045155705395, 0.2255194951287508853, -0.9742386450353663907 ) ) ; +#33686 = ORIENTED_EDGE ( 'NONE', *, *, #23620, .T. ) ; +#33687 = CARTESIAN_POINT ( 'NONE', ( 15.50147167040156049, 184.4041534622001279, 104.7823749527994011 ) ) ; +#33688 = CARTESIAN_POINT ( 'NONE', ( 21.05032377942072230, 129.1782700951465017, 89.63443569402672040 ) ) ; +#33689 = CARTESIAN_POINT ( 'NONE', ( 36.93642613006880282, 191.5645808114473709, 104.3410322388217963 ) ) ; +#33690 = CIRCLE ( 'NONE', #29130, 1.999999999999996891 ) ; +#33691 = CARTESIAN_POINT ( 'NONE', ( 21.44870230457277316, 181.8867687911781559, 104.7107509713525388 ) ) ; +#33692 = ORIENTED_EDGE ( 'NONE', *, *, #25691, .T. ) ; +#33693 = AXIS2_PLACEMENT_3D ( 'NONE', #11312, #30127, #29728 ) ; +#33694 = ORIENTED_EDGE ( 'NONE', *, *, #6389, .T. ) ; +#33695 = CARTESIAN_POINT ( 'NONE', ( -20.51767729163077547, 205.5669979433283743, 76.31342074382325791 ) ) ; +#33696 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14058, #20376, #19760, #22864 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33697 = CARTESIAN_POINT ( 'NONE', ( -43.12194749330705434, 120.9924285383533800, 90.69118127765682402 ) ) ; +#33698 = CARTESIAN_POINT ( 'NONE', ( 24.11730455176802934, 213.8702922232344292, 73.04393783477425472 ) ) ; +#33699 = ADVANCED_FACE ( 'NONE', ( #12817 ), #21758, .T. ) ; +#33700 = CARTESIAN_POINT ( 'NONE', ( -26.01494426630450008, 211.0902259182902014, 73.07465174665132679 ) ) ; +#33701 = FACE_OUTER_BOUND ( 'NONE', #2928, .T. ) ; +#33702 = CARTESIAN_POINT ( 'NONE', ( 5.674778016381245571, 131.0223034755605909, 89.89838139801142347 ) ) ; +#33703 = CARTESIAN_POINT ( 'NONE', ( 29.40353763218626426, 109.9356066219137205, 185.6772796757410333 ) ) ; +#33704 = CARTESIAN_POINT ( 'NONE', ( -48.19679236399461786, 85.21962457735440921, 278.2468068767242357 ) ) ; +#33705 = CARTESIAN_POINT ( 'NONE', ( 38.13142613197000230, 119.0401570749999962, 87.34858926297999915 ) ) ; +#33706 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; +#33707 = CARTESIAN_POINT ( 'NONE', ( 20.25161797161999999, 144.6238388024999892, 95.85207109489999766 ) ) ; +#33708 = CARTESIAN_POINT ( 'NONE', ( 2.805728947812045071, 191.0546403038702294, 104.0235302350474882 ) ) ; +#33709 = PLANE ( 'NONE', #32283 ) ; +#33710 = AXIS2_PLACEMENT_3D ( 'NONE', #6615, #885, #13375 ) ; +#33711 = CYLINDRICAL_SURFACE ( 'NONE', #7793, 8.999999999999994671 ) ; +#33712 = FACE_OUTER_BOUND ( 'NONE', #31832, .T. ) ; +#33713 = AXIS2_PLACEMENT_3D ( 'NONE', #36694, #2561, #30573 ) ; +#33714 = LINE ( 'NONE', #1630, #4965 ) ; +#33715 = VERTEX_POINT ( 'NONE', #37746 ) ; +#33716 = ORIENTED_EDGE ( 'NONE', *, *, #26632, .F. ) ; +#33717 = ORIENTED_EDGE ( 'NONE', *, *, #25583, .F. ) ; +#33718 = CARTESIAN_POINT ( 'NONE', ( 6.035970131896343460, 174.6813497870895446, 103.0565575201574262 ) ) ; +#33719 = VERTEX_POINT ( 'NONE', #6656 ) ; +#33720 = CARTESIAN_POINT ( 'NONE', ( 20.22968469989555729, 126.8125685881874603, 91.76255132582693363 ) ) ; +#33721 = AXIS2_PLACEMENT_3D ( 'NONE', #25828, #13340, #19052 ) ; +#33722 = FACE_BOUND ( 'NONE', #31148, .T. ) ; +#33723 = LINE ( 'NONE', #5510, #32443 ) ; +#33724 = AXIS2_PLACEMENT_3D ( 'NONE', #23487, #26770, #1400 ) ; +#33725 = EDGE_CURVE ( 'NONE', #20347, #33088, #17220, .T. ) ; +#33726 = EDGE_CURVE ( 'NONE', #14638, #1910, #34592, .T. ) ; +#33727 = EDGE_LOOP ( 'NONE', ( #4831, #27318, #24065, #3843 ) ) ; +#33728 = CARTESIAN_POINT ( 'NONE', ( -39.54761222249000241, 119.6738064118000011, 90.25994719927001597 ) ) ; +#33729 = LINE ( 'NONE', #2268, #30296 ) ; +#33730 = FACE_OUTER_BOUND ( 'NONE', #26830, .T. ) ; +#33731 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319364164186 ) ) ; +#33732 = PLANE ( 'NONE', #17699 ) ; +#33733 = ORIENTED_EDGE ( 'NONE', *, *, #12148, .T. ) ; +#33734 = EDGE_CURVE ( 'NONE', #13097, #6212, #6725, .T. ) ; +#33735 = FACE_OUTER_BOUND ( 'NONE', #22003, .T. ) ; +#33736 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32548, #32743, #4519, #16793 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33737 = LINE ( 'NONE', #27027, #6100 ) ; +#33738 = CARTESIAN_POINT ( 'NONE', ( 23.36703012845244487, 177.0397020477106480, 103.4811831259390118 ) ) ; +#33739 = FACE_OUTER_BOUND ( 'NONE', #12465, .T. ) ; +#33740 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; +#33741 = DIRECTION ( 'NONE', ( -0.0006039748319377573598, -1.390293078070570268E-14, -0.9999998176071845934 ) ) ; +#33742 = ORIENTED_EDGE ( 'NONE', *, *, #33371, .F. ) ; +#33743 = CARTESIAN_POINT ( 'NONE', ( -27.42685105812000046, 188.0600985815999877, 103.2113217096000000 ) ) ; +#33744 = CARTESIAN_POINT ( 'NONE', ( 1.043337447816000019, 188.6569751936000046, 103.2066641554000057 ) ) ; +#33745 = CARTESIAN_POINT ( 'NONE', ( 35.80518341334000354, 111.0397749124999933, 89.99615936003000627 ) ) ; +#33746 = VECTOR ( 'NONE', #37915, 1000.000000000000227 ) ; +#33747 = ORIENTED_EDGE ( 'NONE', *, *, #36419, .T. ) ; +#33748 = ORIENTED_EDGE ( 'NONE', *, *, #36113, .F. ) ; +#33749 = CARTESIAN_POINT ( 'NONE', ( -3.654516724589964127, 136.7043362491127709, 94.17313141517827546 ) ) ; +#33750 = AXIS2_PLACEMENT_3D ( 'NONE', #21438, #37160, #21635 ) ; +#33751 = ORIENTED_EDGE ( 'NONE', *, *, #7123, .T. ) ; +#33752 = AXIS2_PLACEMENT_3D ( 'NONE', #34350, #34933, #815 ) ; +#33753 = AXIS2_PLACEMENT_3D ( 'NONE', #34217, #278, #9104 ) ; +#33754 = LINE ( 'NONE', #30709, #30213 ) ; +#33755 = ORIENTED_EDGE ( 'NONE', *, *, #17130, .F. ) ; +#33756 = CARTESIAN_POINT ( 'NONE', ( -35.95796026000000012, 192.1755911781000066, 104.2095329361000040 ) ) ; +#33757 = CARTESIAN_POINT ( 'NONE', ( 15.10888617544567047, 175.7086446263182609, 103.2882499569403336 ) ) ; +#33758 = PLANE ( 'NONE', #17352 ) ; +#33759 = EDGE_LOOP ( 'NONE', ( #32415, #26912, #23979, #34289 ) ) ; +#33760 = CARTESIAN_POINT ( 'NONE', ( 44.90791382799785225, 186.3646954527586388, 107.7818492509791639 ) ) ; +#33761 = FACE_OUTER_BOUND ( 'NONE', #34638, .T. ) ; +#33762 = CARTESIAN_POINT ( 'NONE', ( -45.98255491755426050, 185.1241532521533770, 105.4988869918989707 ) ) ; +#33763 = ORIENTED_EDGE ( 'NONE', *, *, #23575, .T. ) ; +#33764 = EDGE_CURVE ( 'NONE', #25255, #8977, #27118, .T. ) ; +#33765 = CARTESIAN_POINT ( 'NONE', ( -15.74838202838000178, 126.6534244744000119, 91.72501638641000454 ) ) ; +#33766 = CARTESIAN_POINT ( 'NONE', ( -35.98817295377529746, 191.5260130662397273, 103.8919236801626340 ) ) ; +#33768 = CARTESIAN_POINT ( 'NONE', ( -16.00000031268763934, 184.9628657724767606, 102.3646292465979855 ) ) ; +#33767 = LINE ( 'NONE', #1895, #12772 ) ; +#33769 = ORIENTED_EDGE ( 'NONE', *, *, #26017, .F. ) ; +#33770 = ADVANCED_FACE ( 'NONE', ( #39150 ), #11344, .T. ) ; +#33771 = CARTESIAN_POINT ( 'NONE', ( 3.793707726449507600, 143.5984041309152417, 95.61717448282179532 ) ) ; +#33772 = ORIENTED_EDGE ( 'NONE', *, *, #11255, .T. ) ; +#33773 = CIRCLE ( 'NONE', #7644, 6.000000000079828588 ) ; +#33774 = ADVANCED_FACE ( 'NONE', ( #26702 ), #18450, .F. ) ; +#33775 = EDGE_CURVE ( 'NONE', #11249, #39849, #20413, .T. ) ; +#33776 = ORIENTED_EDGE ( 'NONE', *, *, #16411, .F. ) ; +#33777 = ADVANCED_FACE ( 'NONE', ( #23830 ), #38949, .T. ) ; +#33778 = DIRECTION ( 'NONE', ( 0.1942034849621051273, -0.07301477786151058802, 0.9782401794254863558 ) ) ; +#33779 = ADVANCED_FACE ( 'NONE', ( #8289 ), #14574, .F. ) ; +#33780 = CARTESIAN_POINT ( 'NONE', ( -28.46561152641098857, 127.9070196869205063, 92.27868865996876480 ) ) ; +#33781 = CARTESIAN_POINT ( 'NONE', ( 16.00176529486913424, 184.2900636920902002, 105.2688851223920778 ) ) ; +#33782 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989941907, 0.1373964268091562579 ) ) ; +#33783 = VERTEX_POINT ( 'NONE', #29962 ) ; +#33784 = ORIENTED_EDGE ( 'NONE', *, *, #14147, .F. ) ; +#33785 = CARTESIAN_POINT ( 'NONE', ( -10.03596762622328420, 143.5365797932718976, 95.87908835225771043 ) ) ; +#33786 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#33787 = CARTESIAN_POINT ( 'NONE', ( 18.90090771971125960, 120.9219860925226300, 173.6350968582803205 ) ) ; +#33788 = EDGE_LOOP ( 'NONE', ( #11915, #14349, #28087, #10922 ) ) ; +#33789 = CARTESIAN_POINT ( 'NONE', ( -36.32064378393000226, 191.6133591983000031, 106.4203980247000061 ) ) ; +#33790 = CARTESIAN_POINT ( 'NONE', ( -12.63809837006106918, 177.7897768145701036, 100.7065200156251166 ) ) ; +#33791 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35287, #10589, #32257, #7490, #9984, #19566, #3419, #9783, #22662, #10391, #4219 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999896194, 0.3749999999999844569, 0.4374999999999824030, 0.4687499999999729661, 0.4999999999999635847, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33792 = CARTESIAN_POINT ( 'NONE', ( 1.194460023360268908, 188.4195049100522965, 106.2519222112965167 ) ) ; +#33793 = CARTESIAN_POINT ( 'NONE', ( -13.73764163818622386, 127.1905248059583045, 179.0443690650147630 ) ) ; +#33794 = ADVANCED_FACE ( 'NONE', ( #5412 ), #13811, .F. ) ; +#33795 = CARTESIAN_POINT ( 'NONE', ( 12.63493752645000434, 130.4235786269885580, 90.26909773830440997 ) ) ; +#33796 = CARTESIAN_POINT ( 'NONE', ( 34.29502520496742335, 218.5902260770999987, 74.53779102012590840 ) ) ; +#33797 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7258, #13612, #34660, #23021 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 7.755276718584622330E-08, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33798 = AXIS2_PLACEMENT_3D ( 'NONE', #28032, #6329, #9219 ) ; +#33799 = VERTEX_POINT ( 'NONE', #11561 ) ; +#33800 = DIRECTION ( 'NONE', ( -0.0005884949961258157921, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#33801 = FACE_OUTER_BOUND ( 'NONE', #39020, .T. ) ; +#33802 = VECTOR ( 'NONE', #26852, 1000.000000000000000 ) ; +#33803 = CARTESIAN_POINT ( 'NONE', ( 5.666470275070142115, 124.7419549499387159, 88.96160009709909389 ) ) ; +#33804 = VERTEX_POINT ( 'NONE', #38734 ) ; +#33805 = EDGE_CURVE ( 'NONE', #8977, #31599, #30236, .T. ) ; +#33806 = CARTESIAN_POINT ( 'NONE', ( -5.668359501568912329, 187.8404812842893534, 103.4528749086814372 ) ) ; +#33807 = ORIENTED_EDGE ( 'NONE', *, *, #12901, .F. ) ; +#33809 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250099003, 132.8554482850215663, 90.84904174538408483 ) ) ; +#33808 = CARTESIAN_POINT ( 'NONE', ( 16.56127283256421734, 122.5154997165936521, 174.6307753585464582 ) ) ; +#33810 = ORIENTED_EDGE ( 'NONE', *, *, #1032, .F. ) ; +#33812 = VERTEX_POINT ( 'NONE', #23222 ) ; +#33811 = EDGE_CURVE ( 'NONE', #15505, #30695, #20338, .T. ) ; +#33813 = ORIENTED_EDGE ( 'NONE', *, *, #36893, .F. ) ; +#33814 = CARTESIAN_POINT ( 'NONE', ( 2.660888226647000199, 209.2248638908999965, 75.71736931623000544 ) ) ; +#33815 = ADVANCED_FACE ( 'NONE', ( #35656 ), #7670, .F. ) ; +#33816 = FACE_OUTER_BOUND ( 'NONE', #33947, .T. ) ; +#33817 = LINE ( 'NONE', #5193, #39080 ) ; +#33818 = ORIENTED_EDGE ( 'NONE', *, *, #10567, .F. ) ; +#33819 = ORIENTED_EDGE ( 'NONE', *, *, #2287, .F. ) ; +#33820 = EDGE_CURVE ( 'NONE', #12963, #24174, #26986, .T. ) ; +#33821 = ORIENTED_EDGE ( 'NONE', *, *, #31617, .T. ) ; +#33822 = ORIENTED_EDGE ( 'NONE', *, *, #26599, .F. ) ; +#33823 = EDGE_CURVE ( 'NONE', #16043, #8808, #10774, .T. ) ; +#33824 = PLANE ( 'NONE', #25033 ) ; +#33825 = LINE ( 'NONE', #16418, #40226 ) ; +#33826 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 67.27946979429630403, 312.5857197240632104 ) ) ; +#33827 = CARTESIAN_POINT ( 'NONE', ( 36.04502488578000197, 218.5902260770999987, 74.53673406417000535 ) ) ; +#33828 = CARTESIAN_POINT ( 'NONE', ( 35.72421708400000284, 192.2730493352999872, 104.0441781799000012 ) ) ; +#33829 = VERTEX_POINT ( 'NONE', #32618 ) ; +#33830 = AXIS2_PLACEMENT_3D ( 'NONE', #8307, #20771, #33224 ) ; +#33831 = EDGE_LOOP ( 'NONE', ( #29129, #1121, #7606, #26427 ) ) ; +#33832 = CARTESIAN_POINT ( 'NONE', ( 25.99023297330436932, 210.6304865614666539, 73.04280663293934595 ) ) ; +#33833 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#33834 = CARTESIAN_POINT ( 'NONE', ( 20.02131841667728551, 127.7987263759923167, 89.14548939899454183 ) ) ; +#33835 = CARTESIAN_POINT ( 'NONE', ( -25.89614368559000113, 121.5587206332999983, 87.90364931204000243 ) ) ; +#33836 = AXIS2_PLACEMENT_3D ( 'NONE', #29156, #26289, #1739 ) ; +#33837 = ORIENTED_EDGE ( 'NONE', *, *, #6662, .F. ) ; +#33838 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178570922545E-05, 0.0002331579774915894113 ) ) ; +#33839 = CARTESIAN_POINT ( 'NONE', ( -20.99846996374797570, 182.5827991098829841, 104.7260292976064449 ) ) ; +#33840 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#33841 = ORIENTED_EDGE ( 'NONE', *, *, #24333, .F. ) ; +#33842 = FACE_OUTER_BOUND ( 'NONE', #5618, .T. ) ; +#33843 = PLANE ( 'NONE', #8567 ) ; +#33844 = CYLINDRICAL_SURFACE ( 'NONE', #21899, 2.000000000000011546 ) ; +#33845 = CARTESIAN_POINT ( 'NONE', ( -4.036657055717371101, 136.9419995428667391, 93.15246900959645870 ) ) ; +#33846 = ORIENTED_EDGE ( 'NONE', *, *, #29765, .T. ) ; +#33847 = DIRECTION ( 'NONE', ( -0.7069397808326125521, 0.6508952215178184231, 0.2767156607089806264 ) ) ; +#33848 = CARTESIAN_POINT ( 'NONE', ( -25.65592658278999849, 191.1787881358000050, 104.1823754182999977 ) ) ; +#33849 = PLANE ( 'NONE', #14715 ) ; +#33850 = CARTESIAN_POINT ( 'NONE', ( 38.70841243942000176, 118.4099359663000115, 89.50418070357000033 ) ) ; +#33851 = VECTOR ( 'NONE', #15533, 1000.000000000000114 ) ; +#33852 = ORIENTED_EDGE ( 'NONE', *, *, #1654, .T. ) ; +#33853 = CARTESIAN_POINT ( 'NONE', ( 16.50047814177647965, 137.4650114514834911, 177.5752783435502238 ) ) ; +#33854 = ADVANCED_FACE ( 'NONE', ( #29764 ), #40036, .T. ) ; +#33855 = VERTEX_POINT ( 'NONE', #5003 ) ; +#33856 = EDGE_CURVE ( 'NONE', #18476, #31506, #1955, .T. ) ; +#33857 = CIRCLE ( 'NONE', #9738, 1.750000000000001998 ) ; +#33858 = VECTOR ( 'NONE', #4579, 1000.000000000000114 ) ; +#33859 = EDGE_CURVE ( 'NONE', #27102, #37645, #38061, .T. ) ; +#33860 = ADVANCED_FACE ( 'NONE', ( #2763 ), #8709, .F. ) ; +#33861 = DIRECTION ( 'NONE', ( 0.0005884949961230158400, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33862 = ORIENTED_EDGE ( 'NONE', *, *, #38647, .T. ) ; +#33863 = DIRECTION ( 'NONE', ( 0.0005884949961210958263, -0.2249510543439056931, 0.9743698870671265722 ) ) ; +#33864 = EDGE_CURVE ( 'NONE', #21782, #33315, #10015, .T. ) ; +#33865 = CARTESIAN_POINT ( 'NONE', ( -32.55313974955839740, 153.0051697192221241, 291.5776016089990321 ) ) ; +#33866 = CARTESIAN_POINT ( 'NONE', ( -36.50461923224486327, 165.0077707801626445, 193.7817447150420094 ) ) ; +#33867 = LINE ( 'NONE', #14680, #1146 ) ; +#33868 = DIRECTION ( 'NONE', ( 0.7933531821952876095, 0.5932639600228909460, 0.1364866368497979210 ) ) ; +#33869 = ORIENTED_EDGE ( 'NONE', *, *, #10229, .T. ) ; +#33870 = ORIENTED_EDGE ( 'NONE', *, *, #13324, .F. ) ; +#33871 = EDGE_CURVE ( 'NONE', #1494, #20919, #34416, .T. ) ; +#33872 = CARTESIAN_POINT ( 'NONE', ( -22.50072399476195528, 158.3009599602069954, 96.21317557253242114 ) ) ; +#33873 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33874 = VERTEX_POINT ( 'NONE', #18670 ) ; +#33875 = CARTESIAN_POINT ( 'NONE', ( -14.99815819359325175, 175.6178804679130963, 103.1144260744014929 ) ) ; +#33876 = ORIENTED_EDGE ( 'NONE', *, *, #34426, .T. ) ; +#33878 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #38548, #3999, #13228, #4192 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 1.570796326794897002, 2.218608660199707927 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9653329533393121276, 0.9653329533393121276, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#33877 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33879 = EDGE_CURVE ( 'NONE', #2188, #802, #37420, .T. ) ; +#33880 = VECTOR ( 'NONE', #7073, 1000.000000000000000 ) ; +#33881 = LINE ( 'NONE', #24716, #21287 ) ; +#33882 = CYLINDRICAL_SURFACE ( 'NONE', #26079, 6.000000000000008882 ) ; +#33883 = CARTESIAN_POINT ( 'NONE', ( 39.72476719869543160, 114.7060280101011784, 151.9010437499874513 ) ) ; +#33884 = VERTEX_POINT ( 'NONE', #9499 ) ; +#33885 = CARTESIAN_POINT ( 'NONE', ( 36.14783605804498734, 191.1371402971168152, 106.8287956632172211 ) ) ; +#33886 = VECTOR ( 'NONE', #15454, 1000.000000000000000 ) ; +#33887 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927775716107, -0.0005734119022078446905 ) ) ; +#33888 = CONICAL_SURFACE ( 'NONE', #20186, 7.002999999902385753, 0.7853981633639545157 ) ; +#33889 = CARTESIAN_POINT ( 'NONE', ( -25.36342966357999984, 191.0335386934000041, 106.2013971295999966 ) ) ; +#33890 = CARTESIAN_POINT ( 'NONE', ( 13.47382858277565632, 158.5309805054267827, 97.44190014375976716 ) ) ; +#33891 = CARTESIAN_POINT ( 'NONE', ( 3.293114068703774766, 126.0351413774823612, 88.74843706248260844 ) ) ; +#33892 = ORIENTED_EDGE ( 'NONE', *, *, #4320, .T. ) ; +#33893 = ORIENTED_EDGE ( 'NONE', *, *, #26967, .T. ) ; +#33894 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989908600, -0.1373964268091706076 ) ) ; +#33895 = CARTESIAN_POINT ( 'NONE', ( -1.212289009923043892, 140.3956132826605767, 157.8536590863297135 ) ) ; +#33896 = CARTESIAN_POINT ( 'NONE', ( 36.77250560128941714, 191.6244934190380889, 104.3438750475318244 ) ) ; +#33897 = CARTESIAN_POINT ( 'NONE', ( -16.56487446111976780, 151.7625539678538189, 183.4451438748824899 ) ) ; +#33898 = ORIENTED_EDGE ( 'NONE', *, *, #16763, .T. ) ; +#33899 = DIRECTION ( 'NONE', ( 0.0005884949961228156962, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#33900 = CARTESIAN_POINT ( 'NONE', ( -41.90907465551325828, 121.4486244169956422, 92.84837845933354572 ) ) ; +#33901 = FACE_OUTER_BOUND ( 'NONE', #498, .T. ) ; +#33902 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21241, #15307, #2645, #37376 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#33903 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#33904 = DIRECTION ( 'NONE', ( -0.7069397808237261049, 0.6508952152945399749, 0.2767156753701828231 ) ) ; +#33905 = EDGE_CURVE ( 'NONE', #11816, #35125, #34024, .T. ) ; +#33906 = ADVANCED_FACE ( 'NONE', ( #12172 ), #40351, .F. ) ; +#33907 = ADVANCED_FACE ( 'NONE', ( #15434 ), #13255, .F. ) ; +#33908 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319419764241 ) ) ; +#33909 = AXIS2_PLACEMENT_3D ( 'NONE', #38859, #29275, #28134 ) ; +#33910 = CARTESIAN_POINT ( 'NONE', ( 24.53318178951551332, 104.1131156702021201, 87.25296686497607368 ) ) ; +#33911 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7071067167009886800, -0.7071068456721004702 ) ) ; +#33912 = CARTESIAN_POINT ( 'NONE', ( -23.36763934512021734, 134.2409834847225625, 93.73796057560730333 ) ) ; +#33913 = ADVANCED_FACE ( 'NONE', ( #21382 ), #2170, .F. ) ; +#33914 = CIRCLE ( 'NONE', #26750, 2.000000000067106765 ) ; +#33915 = CARTESIAN_POINT ( 'NONE', ( -20.51920610917056820, 211.0905570355220391, 74.90421428432674134 ) ) ; +#33916 = CARTESIAN_POINT ( 'NONE', ( 36.67681181270000224, 191.6471298099000080, 104.3443906285999958 ) ) ; +#33917 = CONICAL_SURFACE ( 'NONE', #13692, 2.499999999937692063, 0.7853981634347277918 ) ; +#33918 = CARTESIAN_POINT ( 'NONE', ( 36.80425445088000203, 191.5142028368000240, 106.2233959256000020 ) ) ; +#33919 = ORIENTED_EDGE ( 'NONE', *, *, #30559, .T. ) ; +#33920 = ORIENTED_EDGE ( 'NONE', *, *, #38846, .T. ) ; +#33921 = ADVANCED_FACE ( 'NONE', ( #9301 ), #33824, .T. ) ; +#33922 = DIRECTION ( 'NONE', ( -0.0005884949961181158967, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#33923 = CARTESIAN_POINT ( 'NONE', ( 20.19664001585550039, 126.8052234450460531, 91.79480940071776729 ) ) ; +#33924 = CARTESIAN_POINT ( 'NONE', ( -32.25494784536992654, 176.5816106217703805, 100.4394812517788722 ) ) ; +#33925 = VERTEX_POINT ( 'NONE', #2362 ) ; +#33926 = CARTESIAN_POINT ( 'NONE', ( -40.70653755146000208, 219.0860688542000219, 73.33308985665999558 ) ) ; +#33927 = ADVANCED_FACE ( 'NONE', ( #27323 ), #10659, .T. ) ; +#33928 = CARTESIAN_POINT ( 'NONE', ( -20.00100377755662961, 193.8169056301028945, 102.7149817412491473 ) ) ; +#33929 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921591843, -0.2249510932971530985 ) ) ; +#33930 = CARTESIAN_POINT ( 'NONE', ( -14.31528021042088916, 130.4257148122239585, 89.77271602316196208 ) ) ; +#33931 = ORIENTED_EDGE ( 'NONE', *, *, #22058, .F. ) ; +#33932 = DIRECTION ( 'NONE', ( -5.204170427942586307E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; +#33933 = FACE_OUTER_BOUND ( 'NONE', #8343, .T. ) ; +#33934 = CARTESIAN_POINT ( 'NONE', ( -26.00155756584835132, 118.8155666110999960, 87.28349583687662516 ) ) ; +#33935 = CARTESIAN_POINT ( 'NONE', ( -4.217312996133716574, 187.9026746933314200, 103.0362212834276505 ) ) ; +#33936 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319357747877 ) ) ; +#33937 = ORIENTED_EDGE ( 'NONE', *, *, #31331, .F. ) ; +#33938 = ORIENTED_EDGE ( 'NONE', *, *, #39113, .T. ) ; +#33939 = VECTOR ( 'NONE', #32098, 1000.000000000000114 ) ; +#33940 = CARTESIAN_POINT ( 'NONE', ( -28.24453843805000375, 186.7254228616999967, 103.4310317869999949 ) ) ; +#33941 = VECTOR ( 'NONE', #38691, 1000.000000000000114 ) ; +#33942 = CARTESIAN_POINT ( 'NONE', ( 30.07478355117409308, 177.7951688118731681, 100.6820556990014950 ) ) ; +#33943 = DIRECTION ( 'NONE', ( -0.1305260325596789561, -0.9660514818508212365, -0.2229517643753060330 ) ) ; +#33944 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #317, #25891, #22615, #35244 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.002384341708615501237 ), + .UNSPECIFIED. ) ; +#33945 = CIRCLE ( 'NONE', #17619, 2.499999999859688238 ) ; +#33946 = AXIS2_PLACEMENT_3D ( 'NONE', #33178, #11737, #30750 ) ; +#33947 = EDGE_LOOP ( 'NONE', ( #39944, #18675, #32688, #31930 ) ) ; +#33948 = DIRECTION ( 'NONE', ( -1.734723476026711224E-15, 0.9743700557921592953, 0.2249510932971530708 ) ) ; +#33949 = EDGE_LOOP ( 'NONE', ( #38134, #9025, #3592, #12916 ) ) ; +#33950 = CIRCLE ( 'NONE', #6501, 2.250000000000011102 ) ; +#33951 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25742, #22671, #967, #7103 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 8.293593285356573369E-05, 0.0002234385402793080384 ), + .UNSPECIFIED. ) ; +#33952 = EDGE_CURVE ( 'NONE', #18169, #18000, #18074, .T. ) ; +#33953 = EDGE_CURVE ( 'NONE', #30098, #31170, #21778, .T. ) ; +#33954 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#33955 = CARTESIAN_POINT ( 'NONE', ( -20.01803677399909986, 205.2975181657300823, 75.66848068974326225 ) ) ; +#33956 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173593504, 151.8558615133134708, 95.23291569143458446 ) ) ; +#33957 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#33958 = CARTESIAN_POINT ( 'NONE', ( -12.63726403360912443, 134.5147472857125024, 93.56168837650750447 ) ) ; +#33959 = DIRECTION ( 'NONE', ( -0.7856007465113974408, -0.6187337610642683616, 0.000000000000000000 ) ) ; +#33960 = ORIENTED_EDGE ( 'NONE', *, *, #17669, .T. ) ; +#33961 = CYLINDRICAL_SURFACE ( 'NONE', #12661, 2.000000000000001332 ) ; +#33962 = CARTESIAN_POINT ( 'NONE', ( -21.82963564516986210, 182.7566075890955517, 102.3719474125277458 ) ) ; +#33963 = CARTESIAN_POINT ( 'NONE', ( 77.66065009075275327, 193.3992594998515244, 188.4681838635439419 ) ) ; +#33965 = FACE_OUTER_BOUND ( 'NONE', #34764, .T. ) ; +#33964 = CARTESIAN_POINT ( 'NONE', ( 12.63088349563799184, 181.6904995670203391, 101.5918601121804556 ) ) ; +#33966 = ORIENTED_EDGE ( 'NONE', *, *, #38563, .F. ) ; +#33967 = ORIENTED_EDGE ( 'NONE', *, *, #16683, .T. ) ; +#33968 = CIRCLE ( 'NONE', #14393, 4.499999999867380751 ) ; +#33969 = ORIENTED_EDGE ( 'NONE', *, *, #18349, .T. ) ; +#33970 = CARTESIAN_POINT ( 'NONE', ( 20.58859091300540101, 116.2799714523409307, 87.25534929902624981 ) ) ; +#33971 = CIRCLE ( 'NONE', #15672, 2.000000000000011546 ) ; +#33972 = ORIENTED_EDGE ( 'NONE', *, *, #39756, .T. ) ; +#33973 = CARTESIAN_POINT ( 'NONE', ( -23.36013624460098725, 136.6770260652199624, 94.30032095887112575 ) ) ; +#33974 = EDGE_CURVE ( 'NONE', #29634, #9657, #26335, .T. ) ; +#33975 = DIRECTION ( 'NONE', ( 0.0005884949961213889946, -0.2249510543439060262, 0.9743698870671263501 ) ) ; +#33976 = FACE_OUTER_BOUND ( 'NONE', #10473, .T. ) ; +#33977 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#33978 = CARTESIAN_POINT ( 'NONE', ( 12.63808109716345562, 130.8952551135587328, 89.97435998385378753 ) ) ; +#33979 = CYLINDRICAL_SURFACE ( 'NONE', #39298, 7.999999999999993783 ) ; +#33980 = ORIENTED_EDGE ( 'NONE', *, *, #8428, .F. ) ; +#33981 = VERTEX_POINT ( 'NONE', #11970 ) ; +#33982 = CARTESIAN_POINT ( 'NONE', ( -20.01829689993581596, 209.7096928646539880, 76.07061354826153377 ) ) ; +#33983 = DIRECTION ( 'NONE', ( -0.6087613508527969230, -0.7731002078751149087, -0.1781170578336949695 ) ) ; +#33984 = DIRECTION ( 'NONE', ( -0.0005884949961143349584, 0.2249510543439047494, -0.9743698870671267942 ) ) ; +#33985 = DIRECTION ( 'NONE', ( 0.0005885022774582036268, -0.2255194047039537075, 0.9742384984012096849 ) ) ; +#33986 = ORIENTED_EDGE ( 'NONE', *, *, #489, .T. ) ; +#33987 = ORIENTED_EDGE ( 'NONE', *, *, #12733, .F. ) ; +#33988 = CARTESIAN_POINT ( 'NONE', ( -36.09963665326999660, 191.9454656849000003, 106.4428026597999946 ) ) ; +#33989 = CARTESIAN_POINT ( 'NONE', ( 22.49999747537572503, 127.4352350531587916, 89.05702986626522488 ) ) ; +#33990 = EDGE_CURVE ( 'NONE', #4954, #22242, #18277, .T. ) ; +#33991 = CARTESIAN_POINT ( 'NONE', ( 39.76231351996260344, 182.5576203638986215, 106.5366729533402719 ) ) ; +#33992 = CARTESIAN_POINT ( 'NONE', ( -20.51975923822563885, 209.4935045172389323, 73.57087796969078397 ) ) ; +#33993 = AXIS2_PLACEMENT_3D ( 'NONE', #16166, #15374, #25387 ) ; +#33994 = FACE_OUTER_BOUND ( 'NONE', #15759, .T. ) ; +#33995 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421901105, 184.2914807614214681, 105.2707223255345070 ) ) ; +#33996 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971558741 ) ) ; +#33997 = CIRCLE ( 'NONE', #19630, 2.000000000000011546 ) ; +#33998 = ORIENTED_EDGE ( 'NONE', *, *, #32238, .T. ) ; +#33999 = CARTESIAN_POINT ( 'NONE', ( -8.575359839930298378, 209.7096282739807975, 73.06368338489360781 ) ) ; +#34000 = AXIS2_PLACEMENT_3D ( 'NONE', #19156, #31658, #3619 ) ; +#34002 = EDGE_CURVE ( 'NONE', #19078, #32161, #13917, .T. ) ; +#34001 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12039, #3016, #33688, #18141 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34003 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; +#34004 = CYLINDRICAL_SURFACE ( 'NONE', #18236, 3.000000000000001332 ) ; +#34005 = EDGE_CURVE ( 'NONE', #37794, #35545, #52, .T. ) ; +#34006 = ORIENTED_EDGE ( 'NONE', *, *, #39770, .T. ) ; +#34007 = DIRECTION ( 'NONE', ( 0.9914447795421099663, 0.1272537940605282525, 0.02904687618140097335 ) ) ; +#34008 = ORIENTED_EDGE ( 'NONE', *, *, #257, .T. ) ; +#34009 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10481, #29077, #13539, #38461 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 2.162974296351655106E-05 ), + .UNSPECIFIED. ) ; +#34011 = DIRECTION ( 'NONE', ( -0.9914448404770122014, 0.1272256268000152013, 0.02916793062345835602 ) ) ; +#34010 = CARTESIAN_POINT ( 'NONE', ( -13.55543936442095365, 147.3963946565080505, 96.76916085575265924 ) ) ; +#34012 = VERTEX_POINT ( 'NONE', #19282 ) ; +#34013 = VERTEX_POINT ( 'NONE', #38104 ) ; +#34014 = VERTEX_POINT ( 'NONE', #3745 ) ; +#34015 = DIRECTION ( 'NONE', ( -0.6087614810001749088, 0.7729390313185979799, 0.1788147452385885350 ) ) ; +#34016 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; +#34017 = DIRECTION ( 'NONE', ( 0.7933533175743878729, 0.5930761747309519771, 0.1372995428259456974 ) ) ; +#34018 = PLANE ( 'NONE', #5793 ) ; +#34019 = EDGE_LOOP ( 'NONE', ( #24772, #742, #2436, #31872 ) ) ; +#34020 = CIRCLE ( 'NONE', #30771, 5.999999999733434564 ) ; +#34021 = ORIENTED_EDGE ( 'NONE', *, *, #5575, .F. ) ; +#34022 = ORIENTED_EDGE ( 'NONE', *, *, #24386, .T. ) ; +#34023 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; +#34025 = AXIS2_PLACEMENT_3D ( 'NONE', #19609, #22902, #801 ) ; +#34024 = LINE ( 'NONE', #8908, #38702 ) ; +#34026 = VECTOR ( 'NONE', #35899, 1000.000000000000000 ) ; +#34027 = CARTESIAN_POINT ( 'NONE', ( -28.25689436368393714, 186.9042180597057836, 103.3333805992548093 ) ) ; +#34028 = FACE_OUTER_BOUND ( 'NONE', #27714, .T. ) ; +#34029 = LINE ( 'NONE', #21169, #27456 ) ; +#34030 = ORIENTED_EDGE ( 'NONE', *, *, #37072, .F. ) ; +#34031 = ORIENTED_EDGE ( 'NONE', *, *, #4820, .F. ) ; +#34032 = AXIS2_PLACEMENT_3D ( 'NONE', #1285, #37911, #9913 ) ; +#34033 = ORIENTED_EDGE ( 'NONE', *, *, #28037, .F. ) ; +#34034 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; +#34035 = VECTOR ( 'NONE', #5114, 1000.000000000000114 ) ; +#34036 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552635 ) ) ; +#34037 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052566002458 ) ) ; +#34038 = VERTEX_POINT ( 'NONE', #6811 ) ; +#34039 = CARTESIAN_POINT ( 'NONE', ( 44.91030012776904812, 180.8423815822312974, 104.4554649243456339 ) ) ; +#34040 = ORIENTED_EDGE ( 'NONE', *, *, #12514, .T. ) ; +#34041 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971550969 ) ) ; +#34042 = DIRECTION ( 'NONE', ( -0.7072735235281812916, -0.6508952706406510025, -0.2758613955842038612 ) ) ; +#34043 = EDGE_LOOP ( 'NONE', ( #39726, #4611, #28810, #33120 ) ) ; +#34044 = ADVANCED_FACE ( 'NONE', ( #26050 ), #9701, .T. ) ; +#34045 = CARTESIAN_POINT ( 'NONE', ( -28.43676750982233870, 187.2527449520754033, 103.0718515660780810 ) ) ; +#34046 = CARTESIAN_POINT ( 'NONE', ( -15.83960171297270669, 125.9416570919932639, 88.73841019156296284 ) ) ; +#34047 = EDGE_CURVE ( 'NONE', #6484, #22954, #10512, .T. ) ; +#34048 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#34049 = DIRECTION ( 'NONE', ( 0.0005121997063476214180, 0.5299192642332222203, 0.8480479414785353498 ) ) ; +#34050 = ORIENTED_EDGE ( 'NONE', *, *, #26091, .T. ) ; +#34051 = CARTESIAN_POINT ( 'NONE', ( -25.50870663471662780, 209.7066555246269104, 75.57407794464953099 ) ) ; +#34053 = EDGE_CURVE ( 'NONE', #24276, #25396, #34609, .T. ) ; +#34052 = CARTESIAN_POINT ( 'NONE', ( -23.36825939451128775, 181.8106237295894232, 101.8123839998682598 ) ) ; +#34054 = EDGE_CURVE ( 'NONE', #16610, #32971, #31261, .T. ) ; +#34055 = CARTESIAN_POINT ( 'NONE', ( -37.62979971966999670, 118.9928318095000037, 87.16482861535000382 ) ) ; +#34056 = CARTESIAN_POINT ( 'NONE', ( 35.79488954871000317, 114.2303209881000043, 90.11900988012999392 ) ) ; +#34057 = EDGE_CURVE ( 'NONE', #23210, #25244, #4375, .T. ) ; +#34058 = EDGE_CURVE ( 'NONE', #5169, #12815, #29308, .T. ) ; +#34059 = VECTOR ( 'NONE', #34351, 1000.000000000000000 ) ; +#34060 = ORIENTED_EDGE ( 'NONE', *, *, #34722, .T. ) ; +#34061 = LINE ( 'NONE', #31009, #5653 ) ; +#34062 = ORIENTED_EDGE ( 'NONE', *, *, #40010, .T. ) ; +#34063 = DIRECTION ( 'NONE', ( -0.7066795775423879711, -2.101331897360152536E-15, 0.7075337268883457043 ) ) ; +#34064 = ORIENTED_EDGE ( 'NONE', *, *, #16406, .F. ) ; +#34065 = DIRECTION ( 'NONE', ( 0.6075492010474008442, -0.7738441339353225867, -0.1790229724939112477 ) ) ; +#34066 = CARTESIAN_POINT ( 'NONE', ( 15.50147165924775372, 160.1795853765612492, 99.18969171619460212 ) ) ; +#34067 = CARTESIAN_POINT ( 'NONE', ( -34.25071196010493679, 164.1090595955299705, 189.9791968356034317 ) ) ; +#34068 = LINE ( 'NONE', #5456, #38386 ) ; +#34069 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#34070 = CARTESIAN_POINT ( 'NONE', ( -36.60903273347671671, 116.8843463709822856, 90.28989577763331908 ) ) ; +#34071 = ORIENTED_EDGE ( 'NONE', *, *, #16268, .T. ) ; +#34072 = ORIENTED_EDGE ( 'NONE', *, *, #27155, .T. ) ; +#34073 = CARTESIAN_POINT ( 'NONE', ( -19.73823131666757291, 124.3520775053762719, 178.1518425532499919 ) ) ; +#34074 = CARTESIAN_POINT ( 'NONE', ( 15.50029467073742140, 160.6294874787857623, 97.24095194441136414 ) ) ; +#34075 = ORIENTED_EDGE ( 'NONE', *, *, #37069, .F. ) ; +#34076 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490320223031, 156.2427122711505092, 96.23754757942438687 ) ) ; +#34077 = FACE_OUTER_BOUND ( 'NONE', #13242, .T. ) ; +#34078 = ORIENTED_EDGE ( 'NONE', *, *, #16538, .T. ) ; +#34079 = PLANE ( 'NONE', #18959 ) ; +#34080 = AXIS2_PLACEMENT_3D ( 'NONE', #17045, #1734, #5189 ) ; +#34081 = CARTESIAN_POINT ( 'NONE', ( -3.655627072371400832, 143.5621891693900523, 95.75525358861933967 ) ) ; +#34082 = CARTESIAN_POINT ( 'NONE', ( -37.27014767442771870, 125.7173236923148920, 91.77847513361253107 ) ) ; +#34083 = EDGE_LOOP ( 'NONE', ( #26016, #12077, #33243, #9557 ) ) ; +#34084 = CARTESIAN_POINT ( 'NONE', ( 35.96235740873753173, 191.3941559883908781, 106.8664037029334679 ) ) ; +#34085 = EDGE_CURVE ( 'NONE', #23911, #8209, #1484, .T. ) ; +#34086 = CARTESIAN_POINT ( 'NONE', ( 15.75014751337000263, 185.3820984328999941, 102.6988165233999979 ) ) ; +#34087 = CARTESIAN_POINT ( 'NONE', ( -25.35220960110000021, 191.3102199587999905, 106.2530543496999940 ) ) ; +#34088 = CARTESIAN_POINT ( 'NONE', ( -3.537743815313965978, 139.6338291191595147, 91.89207571717663825 ) ) ; +#34089 = FACE_OUTER_BOUND ( 'NONE', #33219, .T. ) ; +#34090 = EDGE_LOOP ( 'NONE', ( #7206, #926, #3600, #502 ) ) ; +#34091 = DIRECTION ( 'NONE', ( -0.5988683521957626210, 0.8008474865655332842, 0.000000000000000000 ) ) ; +#34092 = EDGE_CURVE ( 'NONE', #31116, #21943, #28511, .T. ) ; +#34093 = CARTESIAN_POINT ( 'NONE', ( -37.25193126930087573, 101.1987487022166192, 196.4587490517199910 ) ) ; +#34094 = CARTESIAN_POINT ( 'NONE', ( 37.03385106520757120, 191.5330081719584996, 104.3393119305905827 ) ) ; +#34095 = ADVANCED_FACE ( 'NONE', ( #22977 ), #12971, .T. ) ; +#34096 = CARTESIAN_POINT ( 'NONE', ( -16.56540403922939930, 152.2173637657497522, 181.4728899840186784 ) ) ; +#34097 = ORIENTED_EDGE ( 'NONE', *, *, #29998, .F. ) ; +#34098 = CARTESIAN_POINT ( 'NONE', ( 37.26954635975619823, 164.8944657675721999, 196.8584033196613916 ) ) ; +#34099 = CARTESIAN_POINT ( 'NONE', ( 19.70892818629356569, 149.4293184409359014, 181.7720440811204412 ) ) ; +#34100 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082099409, 80.75443884356324986, 297.5876476292040707 ) ) ; +#34101 = EDGE_CURVE ( 'NONE', #5530, #30592, #6095, .T. ) ; +#34102 = CARTESIAN_POINT ( 'NONE', ( -35.90337984466000165, 191.4407742571999904, 103.7425389865999961 ) ) ; +#34103 = CARTESIAN_POINT ( 'NONE', ( -27.14078297295159814, 187.2702107481940175, 105.4646800884559923 ) ) ; +#34104 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418800025, 218.5902260770999987, 73.08022052563953253 ) ) ; +#34105 = VECTOR ( 'NONE', #18581, 1000.000000000000114 ) ; +#34106 = CARTESIAN_POINT ( 'NONE', ( -12.64072194042923769, 181.7794263596476583, 101.7540337600396754 ) ) ; +#34107 = VECTOR ( 'NONE', #31406, 1000.000000000000227 ) ; +#34108 =( NAMED_UNIT ( * ) SI_UNIT ( $, .STERADIAN. ) SOLID_ANGLE_UNIT ( ) ); +#34109 = CARTESIAN_POINT ( 'NONE', ( 28.46561332783693743, 181.0140531701010218, 104.5081722671034044 ) ) ; +#34110 = CARTESIAN_POINT ( 'NONE', ( 15.99984756993140600, 126.4799761663122126, 88.84346073563017399 ) ) ; +#34111 = CARTESIAN_POINT ( 'NONE', ( 28.45310815370287472, 181.6925917411357148, 101.5827842051393617 ) ) ; +#34112 = DIRECTION ( 'NONE', ( 0.7933533411653341805, 0.5931840316264885837, 0.1368326740407639630 ) ) ; +#34113 = CARTESIAN_POINT ( 'NONE', ( 20.00523442206463187, 127.4381545316818034, 89.06762383505567016 ) ) ; +#34114 = CARTESIAN_POINT ( 'NONE', ( 37.68824946257000619, 191.1162786932000017, 105.6221892660999941 ) ) ; +#34116 = VERTEX_POINT ( 'NONE', #277 ) ; +#34115 = CARTESIAN_POINT ( 'NONE', ( 36.35466606127999967, 191.5373058733999869, 106.4897778570999947 ) ) ; +#34117 = ORIENTED_EDGE ( 'NONE', *, *, #17562, .F. ) ; +#34118 = VERTEX_POINT ( 'NONE', #9909 ) ; +#34119 = VERTEX_POINT ( 'NONE', #29110 ) ; +#34120 = PLANE ( 'NONE', #23197 ) ; +#34121 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1962, #23427, #26503, #36081, #8083, #14428 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34122 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7154541036601358428, 0.6986597351757661833 ) ) ; +#34123 = CARTESIAN_POINT ( 'NONE', ( 25.66718964653109936, 118.1138626092876933, 89.91897397334423658 ) ) ; +#34124 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #23881, #21010 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34125 = ORIENTED_EDGE ( 'NONE', *, *, #23571, .F. ) ; +#34126 = CARTESIAN_POINT ( 'NONE', ( 39.01510164518473545, 183.0220360124133379, 104.9622384439134919 ) ) ; +#34127 = CARTESIAN_POINT ( 'NONE', ( -15.99988230060963090, 169.9304744392778161, 98.89424861963034630 ) ) ; +#34128 = CARTESIAN_POINT ( 'NONE', ( -18.67137549021800069, 125.9747537310184669, 174.9884018054523551 ) ) ; +#34129 = AXIS2_PLACEMENT_3D ( 'NONE', #9494, #21971, #3939 ) ; +#34130 = EDGE_CURVE ( 'NONE', #7629, #29487, #21787, .T. ) ; +#34131 = VERTEX_POINT ( 'NONE', #22380 ) ; +#34132 = CARTESIAN_POINT ( 'NONE', ( -18.78463277247493224, 125.8407709676298794, 175.1119453963373473 ) ) ; +#34133 = EDGE_CURVE ( 'NONE', #1239, #38935, #12628, .T. ) ; +#34134 = EDGE_CURVE ( 'NONE', #4358, #1066, #26857, .T. ) ; +#34135 = CARTESIAN_POINT ( 'NONE', ( 23.36785027129286618, 177.0533458852208071, 103.5030171923318534 ) ) ; +#34136 = AXIS2_PLACEMENT_3D ( 'NONE', #19338, #19728, #32427 ) ; +#34137 = EDGE_CURVE ( 'NONE', #8441, #29325, #38898, .T. ) ; +#34138 = CARTESIAN_POINT ( 'NONE', ( 17.27144951970729991, 122.5453306081213043, 172.0736587966182469 ) ) ; +#34139 = CARTESIAN_POINT ( 'NONE', ( -24.42776677020912146, 104.1131156706543095, 87.28253805075753746 ) ) ; +#34140 = ORIENTED_EDGE ( 'NONE', *, *, #9085, .F. ) ; +#34141 = CARTESIAN_POINT ( 'NONE', ( -25.59434203952000075, 189.9641803873000185, 104.1771573359999934 ) ) ; +#34142 = CIRCLE ( 'NONE', #10663, 6.500000133288976301 ) ; +#34143 = CARTESIAN_POINT ( 'NONE', ( 2.300571176476160495, 189.9856582103720370, 103.9795987939660051 ) ) ; +#34144 = CARTESIAN_POINT ( 'NONE', ( 16.00176583134766517, 118.9451395335793649, 90.18281804087268938 ) ) ; +#34145 = EDGE_CURVE ( 'NONE', #18594, #25314, #26654, .T. ) ; +#34146 = VERTEX_POINT ( 'NONE', #35407 ) ; +#34147 = CARTESIAN_POINT ( 'NONE', ( -37.29428432633125112, 118.1868522465356364, 122.8630558711557796 ) ) ; +#34148 = ORIENTED_EDGE ( 'NONE', *, *, #8428, .T. ) ; +#34149 = EDGE_CURVE ( 'NONE', #3193, #26291, #32375, .T. ) ; +#34150 = CARTESIAN_POINT ( 'NONE', ( -16.56455474137609585, 122.0416192665172872, 176.5739763051747957 ) ) ; +#34151 = CARTESIAN_POINT ( 'NONE', ( -30.04041123780218570, 165.2216646703757590, 152.9217693104508555 ) ) ; +#34152 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#34153 = CARTESIAN_POINT ( 'NONE', ( 23.31905259271698583, 213.5902233259226932, 75.54461392219040761 ) ) ; +#34154 = CARTESIAN_POINT ( 'NONE', ( -37.98559843192000329, 191.1060541152999974, 105.7311499935999990 ) ) ; +#34155 = LINE ( 'NONE', #9631, #18906 ) ; +#34156 = CARTESIAN_POINT ( 'NONE', ( -28.94780665481193793, 110.6131156702000027, 87.78526813307001930 ) ) ; +#34157 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; +#34158 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971572064 ) ) ; +#34159 = CARTESIAN_POINT ( 'NONE', ( -2.077548941156783791, 189.8518222458260425, 105.9844770551106024 ) ) ; +#34160 = VECTOR ( 'NONE', #5553, 1000.000000000000000 ) ; +#34161 = ORIENTED_EDGE ( 'NONE', *, *, #9363, .T. ) ; +#34162 = FACE_OUTER_BOUND ( 'NONE', #19651, .T. ) ; +#34163 = CARTESIAN_POINT ( 'NONE', ( -35.97906088785056511, 191.5313222965560840, 103.8930300040437515 ) ) ; +#34164 = CARTESIAN_POINT ( 'NONE', ( 14.78600921306619576, 183.3613208809844366, 102.4894415693095340 ) ) ; +#34165 = AXIS2_PLACEMENT_3D ( 'NONE', #27881, #40310, #2313 ) ; +#34167 = CARTESIAN_POINT ( 'NONE', ( 37.22395090682895358, 117.3071371955010846, 87.68550344713307254 ) ) ; +#34166 = CARTESIAN_POINT ( 'NONE', ( 15.83342737871519113, 185.8720056236915923, 102.7263494051578334 ) ) ; +#34168 = EDGE_LOOP ( 'NONE', ( #4145, #26049, #39291, #35101 ) ) ; +#34169 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.271205363195980628E-14, -0.9999998176071845934 ) ) ; +#34170 = ORIENTED_EDGE ( 'NONE', *, *, #24688, .T. ) ; +#34171 = CARTESIAN_POINT ( 'NONE', ( 39.92597513567999812, 119.3672243733000045, 89.61382895184999597 ) ) ; +#34172 = CARTESIAN_POINT ( 'NONE', ( -41.48561289357779458, 135.1802067451934022, 25.19087159780533725 ) ) ; +#34173 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9334763082618803276, -0.3586390691402302489 ) ) ; +#34174 = DIRECTION ( 'NONE', ( 3.469446951914370331E-15, -1.000000000000000000, 1.387778780765748132E-14 ) ) ; +#34175 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#34176 = ORIENTED_EDGE ( 'NONE', *, *, #10304, .F. ) ; +#34177 = LINE ( 'NONE', #6972, #29059 ) ; +#34178 = EDGE_LOOP ( 'NONE', ( #18683, #23442, #6382, #4750, #29727, #23216, #2875 ) ) ; +#34179 = CARTESIAN_POINT ( 'NONE', ( 3.535839194698592980, 136.6870853775678825, 94.28644726325400427 ) ) ; +#34180 = DIRECTION ( 'NONE', ( 0.0004161288024508587834, -0.8480480898039491899, 0.5299191110128907978 ) ) ; +#34181 = ORIENTED_EDGE ( 'NONE', *, *, #31574, .T. ) ; +#34182 = ORIENTED_EDGE ( 'NONE', *, *, #17830, .F. ) ; +#34183 = CARTESIAN_POINT ( 'NONE', ( -25.51533646434189961, 211.0902259025884007, 73.57326538444725372 ) ) ; +#34184 = CARTESIAN_POINT ( 'NONE', ( 2.291809631987290263, 189.2956671362705663, 103.3538876406753104 ) ) ; +#34185 = VECTOR ( 'NONE', #35381, 1000.000000000000000 ) ; +#34186 = AXIS2_PLACEMENT_3D ( 'NONE', #37587, #9586, #22066 ) ; +#34187 = DIRECTION ( 'NONE', ( 0.0005884963607281444966, -0.2249510543436698262, 0.9743698870663567435 ) ) ; +#34188 = ORIENTED_EDGE ( 'NONE', *, *, #34709, .F. ) ; +#34189 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #15111, #34096, #30650 ), + ( #27604, #40034, #8981 ), + ( #21458, #33897, #18352 ), + ( #34882, #16488, #31862 ) ), + .UNSPECIFIED., .F., .F., .T. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), + ( 3, 3 ), + ( 0.5322958190830298086, 0.5323199333288397561 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.7510980103643672967, 1.000000000000000000), + ( 1.000000000000000000, 0.7511085508386285969, 1.000000000000000000), + ( 1.000000000000000000, 0.7511190909932190518, 1.000000000000000000), + ( 1.000000000000000000, 0.7511296308280239753, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#34190 = VECTOR ( 'NONE', #18607, 1000.000000000000000 ) ; +#34191 = VERTEX_POINT ( 'NONE', #7412 ) ; +#34192 = CARTESIAN_POINT ( 'NONE', ( 0.7692663204041000347, 188.3858291373000213, 106.2236757186000062 ) ) ; +#34193 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#34194 = CARTESIAN_POINT ( 'NONE', ( 36.13896817258297034, 191.5090930219296581, 103.8444545286726566 ) ) ; +#34195 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971528487 ) ) ; +#34196 = ORIENTED_EDGE ( 'NONE', *, *, #20907, .T. ) ; +#34197 = CARTESIAN_POINT ( 'NONE', ( -13.49823352875945304, 151.2928090228515998, 97.67176352529210703 ) ) ; +#34198 = DIRECTION ( 'NONE', ( 0.1305262051636603415, -0.9658997602660466253, -0.2236080563923574516 ) ) ; +#34199 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#34200 = EDGE_CURVE ( 'NONE', #31885, #37835, #29311, .T. ) ; +#34201 = ORIENTED_EDGE ( 'NONE', *, *, #11723, .T. ) ; +#34202 = CARTESIAN_POINT ( 'NONE', ( 22.99918985293999540, 115.6131156702015801, 87.75369723384940812 ) ) ; +#34203 = ORIENTED_EDGE ( 'NONE', *, *, #3561, .F. ) ; +#34205 = CARTESIAN_POINT ( 'NONE', ( 35.57766939435025932, 192.1569325708144618, 103.8918082975675077 ) ) ; +#34204 = CARTESIAN_POINT ( 'NONE', ( -21.44693882331385026, 135.7861819143374760, 91.01458761472625270 ) ) ; +#34206 = VERTEX_POINT ( 'NONE', #14376 ) ; +#34207 = ORIENTED_EDGE ( 'NONE', *, *, #7806, .F. ) ; +#34208 = AXIS2_PLACEMENT_3D ( 'NONE', #34341, #28630, #38020 ) ; +#34209 = AXIS2_PLACEMENT_3D ( 'NONE', #7079, #38557, #13435 ) ; +#34210 = ORIENTED_EDGE ( 'NONE', *, *, #15021, .T. ) ; +#34211 = LINE ( 'NONE', #6015, #16608 ) ; +#34212 = FACE_OUTER_BOUND ( 'NONE', #15384, .T. ) ; +#34214 = ORIENTED_EDGE ( 'NONE', *, *, #19596, .F. ) ; +#34213 = VECTOR ( 'NONE', #20642, 1000.000000000000227 ) ; +#34215 = VERTEX_POINT ( 'NONE', #7821 ) ; +#34216 = CARTESIAN_POINT ( 'NONE', ( 22.50176470575405929, 151.2986482266788357, 97.64828959533576835 ) ) ; +#34217 = CARTESIAN_POINT ( 'NONE', ( -0.04020359587071823532, 99.17590004611790278, 343.2031739270701678 ) ) ; +#34218 = CARTESIAN_POINT ( 'NONE', ( 2.940600607905301089, 209.7122358168481355, 73.05672848799805763 ) ) ; +#34219 = ORIENTED_EDGE ( 'NONE', *, *, #16540, .F. ) ; +#34220 = ORIENTED_EDGE ( 'NONE', *, *, #19454, .T. ) ; +#34221 = CARTESIAN_POINT ( 'NONE', ( 25.99030105615392827, 209.7097546603872900, 73.04280869622928662 ) ) ; +#34223 = EDGE_CURVE ( 'NONE', #32718, #27269, #35443, .T. ) ; +#34222 = DIRECTION ( 'NONE', ( -0.7933535320750290110, 0.5931614265262136199, 0.1369295264925107503 ) ) ; +#34224 = CARTESIAN_POINT ( 'NONE', ( 20.94827535171210897, 136.6018947531004244, 91.17730147031002730 ) ) ; +#34225 = EDGE_CURVE ( 'NONE', #529, #844, #20293, .T. ) ; +#34226 = CARTESIAN_POINT ( 'NONE', ( -27.53589760592999980, 124.7259939882000026, 88.63586416396999823 ) ) ; +#34227 = VERTEX_POINT ( 'NONE', #11302 ) ; +#34228 = EDGE_LOOP ( 'NONE', ( #38226, #37809, #33876, #15793 ) ) ; +#34229 = CARTESIAN_POINT ( 'NONE', ( 35.83899097077466678, 166.8947553277887437, 183.3570906540052761 ) ) ; +#34230 = CARTESIAN_POINT ( 'NONE', ( 40.98057714432916754, 189.5249999328831336, 106.9586619333081217 ) ) ; +#34231 = ORIENTED_EDGE ( 'NONE', *, *, #25306, .F. ) ; +#34232 = ADVANCED_FACE ( 'NONE', ( #17624 ), #29505, .F. ) ; +#34233 = CARTESIAN_POINT ( 'NONE', ( 20.50098233080591470, 193.6977305113042007, 106.0730745358513474 ) ) ; +#34234 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; +#34235 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#34236 = VECTOR ( 'NONE', #22805, 1000.000000000000000 ) ; +#34237 = CONICAL_SURFACE ( 'NONE', #16604, 6.499999999988696153, 0.7853981634219892038 ) ; +#34238 = CARTESIAN_POINT ( 'NONE', ( 28.70699186922535873, 163.1576631238072821, 99.86925946332931403 ) ) ; +#34239 = VERTEX_POINT ( 'NONE', #1283 ) ; +#34240 = CARTESIAN_POINT ( 'NONE', ( -8.231320070466233929, 177.7901967163663528, 100.7040324006646017 ) ) ; +#34241 = ORIENTED_EDGE ( 'NONE', *, *, #25465, .T. ) ; +#34242 = VECTOR ( 'NONE', #10740, 1000.000000000000000 ) ; +#34243 = CARTESIAN_POINT ( 'NONE', ( 27.82602830715945785, 77.14301703112145958, 291.5417377113968769 ) ) ; +#34244 = DIRECTION ( 'NONE', ( 0.7933535320750287889, -0.5931614265262138419, -0.1369295264925107780 ) ) ; +#34245 = CARTESIAN_POINT ( 'NONE', ( 38.38453715826999968, 118.8006487722999935, 90.10292451339999786 ) ) ; +#34246 = EDGE_CURVE ( 'NONE', #6712, #38112, #40062, .T. ) ; +#34247 = ORIENTED_EDGE ( 'NONE', *, *, #2081, .F. ) ; +#34248 = DIRECTION ( 'NONE', ( -0.0005884949961230354640, 0.2249510543439063315, -0.9743698870671264611 ) ) ; +#34249 = VERTEX_POINT ( 'NONE', #38688 ) ; +#34250 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#34251 = CARTESIAN_POINT ( 'NONE', ( -38.19156396606999948, 118.7192053888999936, 90.14876594949001287 ) ) ; +#34252 = CARTESIAN_POINT ( 'NONE', ( 15.83500788452659869, 185.2721260511765138, 105.3246691832816566 ) ) ; +#34253 = VERTEX_POINT ( 'NONE', #10707 ) ; +#34254 = FACE_OUTER_BOUND ( 'NONE', #17860, .T. ) ; +#34255 = ADVANCED_FACE ( 'NONE', ( #39095 ), #11107, .T. ) ; +#34256 = FACE_OUTER_BOUND ( 'NONE', #21432, .T. ) ; +#34257 = DIRECTION ( 'NONE', ( -0.0005884949961216715377, 0.2249510543439054988, -0.9743698870671265722 ) ) ; +#34258 = LINE ( 'NONE', #324, #522 ) ; +#34259 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#34260 = CARTESIAN_POINT ( 'NONE', ( -37.03339179615628751, 117.5430036078971767, 90.29015207987367830 ) ) ; +#34261 = ORIENTED_EDGE ( 'NONE', *, *, #17925, .F. ) ; +#34262 = CARTESIAN_POINT ( 'NONE', ( 0.9871371177456488288, 189.0442807250963710, 105.7489971128403141 ) ) ; +#34263 = EDGE_CURVE ( 'NONE', #24174, #15694, #1700, .T. ) ; +#34264 = CIRCLE ( 'NONE', #28427, 4.999999999999990230 ) ; +#34265 = PLANE ( 'NONE', #24901 ) ; +#34266 = ORIENTED_EDGE ( 'NONE', *, *, #30926, .F. ) ; +#34267 = DIRECTION ( 'NONE', ( 0.0004161288024809103739, -0.8480480897620947811, 0.5299191110798721072 ) ) ; +#34268 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #31827, #19330 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34269 = CIRCLE ( 'NONE', #16641, 2.500000000008752998 ) ; +#34270 = EDGE_CURVE ( 'NONE', #38540, #17312, #4955, .T. ) ; +#34271 = ORIENTED_EDGE ( 'NONE', *, *, #21242, .T. ) ; +#34272 = CARTESIAN_POINT ( 'NONE', ( -16.27370299762399597, 147.0379182250262318, 180.4996822280638185 ) ) ; +#34273 = EDGE_CURVE ( 'NONE', #6720, #7841, #27810, .T. ) ; +#34274 = EDGE_CURVE ( 'NONE', #2805, #19017, #8452, .T. ) ; +#34275 = CARTESIAN_POINT ( 'NONE', ( 15.05621097240102912, 151.2968320376545819, 177.4259961740748963 ) ) ; +#34276 = CARTESIAN_POINT ( 'NONE', ( 37.69154582877660431, 190.3650434775613007, 106.6583049985661376 ) ) ; +#34277 = DIRECTION ( 'NONE', ( 0.1305260325596790116, 0.9660514818508153523, 0.2229517643753315681 ) ) ; +#34278 = ORIENTED_EDGE ( 'NONE', *, *, #22358, .F. ) ; +#34279 = CARTESIAN_POINT ( 'NONE', ( 28.25168715536999997, 125.5814672718000082, 89.14042886232999763 ) ) ; +#34280 = CARTESIAN_POINT ( 'NONE', ( 25.90751652792749482, 211.0919911608675363, 73.12569551730074124 ) ) ; +#34281 = LINE ( 'NONE', #16286, #37768 ) ; +#34282 = CARTESIAN_POINT ( 'NONE', ( 30.07150458489775957, 176.8779762188897848, 103.2171028121363463 ) ) ; +#34283 = CARTESIAN_POINT ( 'NONE', ( 36.04593084803796188, 218.5902260770999987, 76.03673379054495740 ) ) ; +#34284 = ORIENTED_EDGE ( 'NONE', *, *, #26154, .F. ) ; +#34285 = CARTESIAN_POINT ( 'NONE', ( 16.56127283256421734, 122.5154997165936521, 174.6307753585464582 ) ) ; +#34286 = CARTESIAN_POINT ( 'NONE', ( 26.00067918362605468, 118.8155664802563791, 90.25207353690788636 ) ) ; +#34287 = CARTESIAN_POINT ( 'NONE', ( -35.45366962862317450, 209.7096538831000032, 78.07991812243204777 ) ) ; +#34288 = DIRECTION ( 'NONE', ( -0.0005884949961255136249, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#34289 = ORIENTED_EDGE ( 'NONE', *, *, #32048, .T. ) ; +#34290 = ORIENTED_EDGE ( 'NONE', *, *, #38846, .F. ) ; +#34291 = CARTESIAN_POINT ( 'NONE', ( -40.70653755145999497, 217.7719116711000140, 73.33308985666000979 ) ) ; +#34292 = CARTESIAN_POINT ( 'NONE', ( -38.93778834861265636, 191.4135373867393355, 104.3808903904224508 ) ) ; +#34293 = AXIS2_PLACEMENT_3D ( 'NONE', #15602, #25035, #12337 ) ; +#34294 = FACE_BOUND ( 'NONE', #24093, .T. ) ; +#34295 = PLANE ( 'NONE', #13147 ) ; +#34296 = AXIS2_PLACEMENT_3D ( 'NONE', #5134, #17607, #2099 ) ; +#34297 = VECTOR ( 'NONE', #1922, 1000.000000000000000 ) ; +#34298 = CARTESIAN_POINT ( 'NONE', ( -36.36152854251999855, 191.9073049239999875, 104.5548041313000027 ) ) ; +#34299 = CARTESIAN_POINT ( 'NONE', ( -25.53732099362649421, 190.4811272833740077, 106.2050102730240013 ) ) ; +#34300 = AXIS2_PLACEMENT_3D ( 'NONE', #9142, #21625, #322 ) ; +#34301 = CIRCLE ( 'NONE', #10199, 6.500000000061821659 ) ; +#34302 = DIRECTION ( 'NONE', ( -1.214306433183758024E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#34303 = CARTESIAN_POINT ( 'NONE', ( 39.53555642364394629, 119.7153706430301554, 90.34642614193101906 ) ) ; +#34304 = APPROVAL_DATE_TIME ( #2247, #17932 ) ; +#34305 = FACE_OUTER_BOUND ( 'NONE', #33603, .T. ) ; +#34306 = ORIENTED_EDGE ( 'NONE', *, *, #6611, .F. ) ; +#34307 = CARTESIAN_POINT ( 'NONE', ( 29.20104124293241910, 162.9684951647539322, 100.3384403448970659 ) ) ; +#34308 = CARTESIAN_POINT ( 'NONE', ( -19.99823943612422994, 184.2798415734382900, 105.2882683904008729 ) ) ; +#34309 = EDGE_CURVE ( 'NONE', #27723, #27687, #15572, .T. ) ; +#34310 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15447, #13531, #28132, #101 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34311 = DIRECTION ( 'NONE', ( 0.1305262051639064502, -0.9658997602660150950, -0.2236080563923503461 ) ) ; +#34312 = CARTESIAN_POINT ( 'NONE', ( 36.36572176811999668, 191.7985677483000018, 105.0395229366000081 ) ) ; +#34313 = CARTESIAN_POINT ( 'NONE', ( 35.62122414768001022, 191.7289062099000319, 107.0376823697000077 ) ) ; +#34314 = ORIENTED_EDGE ( 'NONE', *, *, #4080, .F. ) ; +#34315 = ORIENTED_EDGE ( 'NONE', *, *, #9255, .F. ) ; +#34316 = CARTESIAN_POINT ( 'NONE', ( -4.153479741491477917, 135.7446565152251026, 90.99455322396016754 ) ) ; +#34317 = EDGE_CURVE ( 'NONE', #267, #29667, #5777, .T. ) ; +#34318 = DIRECTION ( 'NONE', ( 0.5605692862037902069, 0.5785653851273900861, -0.5924729280712899282 ) ) ; +#34319 = EDGE_CURVE ( 'NONE', #3379, #12706, #21929, .T. ) ; +#34320 = CIRCLE ( 'NONE', #33039, 2.249999999967385644 ) ; +#34321 = CARTESIAN_POINT ( 'NONE', ( -30.04578366432821568, 126.2160355793363067, 91.71819783549720739 ) ) ; +#34322 = AXIS2_PLACEMENT_3D ( 'NONE', #11709, #11913, #29909 ) ; +#34323 = ORIENTED_EDGE ( 'NONE', *, *, #10807, .F. ) ; +#34324 = AXIS2_PLACEMENT_3D ( 'NONE', #23057, #26533, #32458 ) ; +#34325 = FACE_OUTER_BOUND ( 'NONE', #38347, .T. ) ; +#34326 = EDGE_CURVE ( 'NONE', #9860, #36789, #5447, .T. ) ; +#34327 = CARTESIAN_POINT ( 'NONE', ( -5.668553076710002081, 181.6128662685622999, 104.1507415738063571 ) ) ; +#34328 = LINE ( 'NONE', #9409, #14549 ) ; +#34329 = VERTEX_POINT ( 'NONE', #9254 ) ; +#34330 = AXIS2_PLACEMENT_3D ( 'NONE', #2512, #20909, #30309 ) ; +#34331 = CARTESIAN_POINT ( 'NONE', ( -18.77674127522291414, 125.8316197988405065, 175.1083285267641259 ) ) ; +#34332 = CARTESIAN_POINT ( 'NONE', ( -23.36052865741024931, 181.6105241600809563, 104.1608863649894374 ) ) ; +#34333 = CONICAL_SURFACE ( 'NONE', #32393, 2.502995680536484802, 0.7853981633384532479 ) ; +#34334 = CARTESIAN_POINT ( 'NONE', ( -43.94750435760008855, 112.8136638115850872, 88.29031078334202221 ) ) ; +#34335 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#34336 = VERTEX_POINT ( 'NONE', #30531 ) ; +#34337 = CARTESIAN_POINT ( 'NONE', ( -25.84214186235915278, 209.7086532927333451, 75.90780821924042243 ) ) ; +#34338 = CARTESIAN_POINT ( 'NONE', ( 1.719903430310000036, 189.0438803499000358, 103.4359278008000018 ) ) ; +#34339 = DIRECTION ( 'NONE', ( -0.0005884949961228156962, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#34340 = VERTEX_POINT ( 'NONE', #28068 ) ; +#34341 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; +#34342 = VERTEX_POINT ( 'NONE', #24404 ) ; +#34343 = DIRECTION ( 'NONE', ( -0.9999998268365722920, -0.0001323830666111439785, 0.0005734121982944762486 ) ) ; +#34344 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#34345 = CARTESIAN_POINT ( 'NONE', ( 25.49183423580130636, 211.0903769678246817, 75.54322026927223988 ) ) ; +#34346 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22960, #464, #6591, #12954 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34347 = CONICAL_SURFACE ( 'NONE', #19323, 2.503056644700593747, 0.7853981634374213039 ) ; +#34348 = FACE_OUTER_BOUND ( 'NONE', #23043, .T. ) ; +#34349 = AXIS2_PLACEMENT_3D ( 'NONE', #21811, #6246, #18702 ) ; +#34350 = CARTESIAN_POINT ( 'NONE', ( 26.00773540302725451, 191.9759150222000130, 101.9057393198873882 ) ) ; +#34351 = DIRECTION ( 'NONE', ( -0.0005884949961178157895, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#34352 = CARTESIAN_POINT ( 'NONE', ( -5.670596477536101077, 181.8451598895398149, 101.8537560070761714 ) ) ; +#34353 = CARTESIAN_POINT ( 'NONE', ( -1.850721682729105533, 189.5858787790424458, 105.9075550088280977 ) ) ; +#34354 = ORIENTED_EDGE ( 'NONE', *, *, #34246, .F. ) ; +#34355 = EDGE_CURVE ( 'NONE', #22883, #31048, #13078, .T. ) ; +#34356 = VECTOR ( 'NONE', #38075, 1000.000000000000000 ) ; +#34357 = FACE_OUTER_BOUND ( 'NONE', #21523, .T. ) ; +#34358 = ADVANCED_FACE ( 'NONE', ( #21729 ), #37444, .F. ) ; +#34359 = CARTESIAN_POINT ( 'NONE', ( -39.71549914202294218, 121.2606343799488826, 123.5760462896040934 ) ) ; +#34360 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#34361 = EDGE_CURVE ( 'NONE', #32912, #40272, #9758, .T. ) ; +#34362 = ADVANCED_FACE ( 'NONE', ( #15188 ), #861, .T. ) ; +#34363 = CYLINDRICAL_SURFACE ( 'NONE', #31082, 4.999999999999990230 ) ; +#34364 = ORIENTED_EDGE ( 'NONE', *, *, #2240, .T. ) ; +#34365 = EDGE_LOOP ( 'NONE', ( #39735, #9866, #14380, #38944 ) ) ; +#34366 = EDGE_CURVE ( 'NONE', #22181, #906, #18422, .T. ) ; +#34367 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37442, #31924, #6357, #424 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34368 = CARTESIAN_POINT ( 'NONE', ( 21.80190282490775644, 115.3623219337571300, 87.25461648903451817 ) ) ; +#34369 = DIRECTION ( 'NONE', ( -0.0005884949961225150470, 0.2249510543439052768, -0.9743698870671265722 ) ) ; +#34370 = ORIENTED_EDGE ( 'NONE', *, *, #26400, .F. ) ; +#34371 = EDGE_CURVE ( 'NONE', #29701, #26876, #23882, .T. ) ; +#34372 = CARTESIAN_POINT ( 'NONE', ( 38.59702762342853077, 118.9500968533072580, 87.67928447194626074 ) ) ; +#34373 = CARTESIAN_POINT ( 'NONE', ( -25.49185251848652101, 194.0776887492533547, 103.3836342745381671 ) ) ; +#34374 = CARTESIAN_POINT ( 'NONE', ( -29.41585490894198784, 161.0327472628627561, 187.1177767716451399 ) ) ; +#34375 = VERTEX_POINT ( 'NONE', #18622 ) ; +#34376 = CARTESIAN_POINT ( 'NONE', ( 39.01707480719999666, 201.0803718256000252, 26.89884147244999824 ) ) ; +#34377 = ORIENTED_EDGE ( 'NONE', *, *, #8837, .T. ) ; +#34378 = AXIS2_PLACEMENT_3D ( 'NONE', #5495, #11044, #23928 ) ; +#34379 = CARTESIAN_POINT ( 'NONE', ( -20.01825848499977667, 209.3198982265599852, 76.07060713741022084 ) ) ; +#34380 = CARTESIAN_POINT ( 'NONE', ( -48.17001161002253440, 82.27946979429644614, 322.5876430693837733 ) ) ; +#34381 = CYLINDRICAL_SURFACE ( 'NONE', #21654, 2.000000000000011546 ) ; +#34382 = VECTOR ( 'NONE', #12906, 1000.000000000000000 ) ; +#34383 = LINE ( 'NONE', #3308, #16414 ) ; +#34384 = ADVANCED_FACE ( 'NONE', ( #8656 ), #13280, .F. ) ; +#34385 = EDGE_LOOP ( 'NONE', ( #5018, #13800, #30554, #22123 ) ) ; +#34386 = FACE_OUTER_BOUND ( 'NONE', #29898, .T. ) ; +#34387 = CARTESIAN_POINT ( 'NONE', ( 25.49959212878524539, 118.1133528988263919, 88.41900765034652920 ) ) ; +#34388 = VECTOR ( 'NONE', #8454, 1000.000000000000114 ) ; +#34389 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #23891, #32478 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34390 = EDGE_LOOP ( 'NONE', ( #1860, #30829, #31248, #31959, #35089 ) ) ; +#34391 = EDGE_LOOP ( 'NONE', ( #12683, #9635, #32965, #35932 ) ) ; +#34392 = CARTESIAN_POINT ( 'NONE', ( -19.46367937371129742, 126.2449231135791052, 175.9963188856066267 ) ) ; +#34393 = DIRECTION ( 'NONE', ( 0.5614015438086682463, 0.2604365532041851283, 0.7854941809869552261 ) ) ; +#34394 = CARTESIAN_POINT ( 'NONE', ( -39.61053789571219852, 75.07173372617528173, 323.7343870505221730 ) ) ; +#34395 = CARTESIAN_POINT ( 'NONE', ( -45.38555676493081137, 123.7228266434447903, 91.29725465774555460 ) ) ; +#34396 = CARTESIAN_POINT ( 'NONE', ( -25.87859003943000147, 120.0559740090000105, 90.33984099753000407 ) ) ; +#34397 = EDGE_LOOP ( 'NONE', ( #28572, #13815, #23753, #18888 ) ) ; +#34398 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#34399 = CARTESIAN_POINT ( 'NONE', ( 36.44552767798368365, 77.20147770176781421, 291.4604096236121222 ) ) ; +#34400 = ORIENTED_EDGE ( 'NONE', *, *, #8822, .T. ) ; +#34401 = FACE_OUTER_BOUND ( 'NONE', #8000, .T. ) ; +#34402 = CARTESIAN_POINT ( 'NONE', ( -43.94721011010098266, 112.7011882844193309, 88.77749572683383406 ) ) ; +#34403 = ADVANCED_FACE ( 'NONE', ( #40108 ), #10689, .F. ) ; +#34404 = EDGE_CURVE ( 'NONE', #35358, #14158, #1524, .T. ) ; +#34406 = CARTESIAN_POINT ( 'NONE', ( -15.56603823844334578, 127.7826210530077446, 174.7414047399612400 ) ) ; +#34405 = CARTESIAN_POINT ( 'NONE', ( 36.14392112904619836, 192.0943178556035775, 104.3839432946396784 ) ) ; +#34407 = ORIENTED_EDGE ( 'NONE', *, *, #23617, .T. ) ; +#34408 = EDGE_LOOP ( 'NONE', ( #33430, #6010, #36497, #33980 ) ) ; +#34409 = CARTESIAN_POINT ( 'NONE', ( -29.78271245060107830, 185.5388541528431290, 103.0190830191734648 ) ) ; +#34410 = EDGE_CURVE ( 'NONE', #37873, #9277, #25204, .T. ) ; +#34411 = CARTESIAN_POINT ( 'NONE', ( -35.98078365430546910, 192.1676821918738085, 104.4282768544623394 ) ) ; +#34412 = CARTESIAN_POINT ( 'NONE', ( 21.26009136220303120, 136.4215387128503494, 93.70123539943294588 ) ) ; +#34413 = DIRECTION ( 'NONE', ( -0.6087614883550945821, 0.7730004026499607273, 0.1785492307423600655 ) ) ; +#34414 = ORIENTED_EDGE ( 'NONE', *, *, #17510, .T. ) ; +#34415 = ORIENTED_EDGE ( 'NONE', *, *, #6118, .T. ) ; +#34416 = LINE ( 'NONE', #12552, #9345 ) ; +#34417 = ADVANCED_FACE ( 'NONE', ( #22332 ), #833, .T. ) ; +#34418 = CARTESIAN_POINT ( 'NONE', ( 21.72426698684031976, 130.1004708904147265, 89.67586055015539159 ) ) ; +#34419 = CARTESIAN_POINT ( 'NONE', ( -6.035968311314003465, 134.2396840962197189, 93.73032776046711945 ) ) ; +#34420 = ORIENTED_EDGE ( 'NONE', *, *, #32310, .F. ) ; +#34421 = EDGE_LOOP ( 'NONE', ( #39413, #20433, #30230, #4564, #2510, #37088, #1428, #9295, #21738, #19412, #805 ) ) ; +#34422 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#34423 = CARTESIAN_POINT ( 'NONE', ( 20.48136443024816344, 209.7093559074854454, 75.54613107284740181 ) ) ; +#34424 = CARTESIAN_POINT ( 'NONE', ( -27.92846131486000161, 125.3695171036000033, 89.12691434018999814 ) ) ; +#34425 = EDGE_LOOP ( 'NONE', ( #11680, #23466, #27787, #14181 ) ) ; +#34426 = EDGE_CURVE ( 'NONE', #31352, #24000, #9652, .T. ) ; +#34427 = ORIENTED_EDGE ( 'NONE', *, *, #848, .T. ) ; +#34428 = CARTESIAN_POINT ( 'NONE', ( -3.168077445297452055, 127.9087829914206651, 92.26382811782556814 ) ) ; +#34429 = LINE ( 'NONE', #16570, #7142 ) ; +#34430 = VERTEX_POINT ( 'NONE', #28659 ) ; +#34431 = CARTESIAN_POINT ( 'NONE', ( -37.67380420164612076, 117.5786341847554581, 89.72039306778212620 ) ) ; +#34432 = AXIS2_PLACEMENT_3D ( 'NONE', #5979, #12317, #36862 ) ; +#34433 = CYLINDRICAL_SURFACE ( 'NONE', #25529, 22.50000000000000000 ) ; +#34434 = CARTESIAN_POINT ( 'NONE', ( -15.99849772754149591, 160.0724928513803036, 99.69724197557108880 ) ) ; +#34435 = VECTOR ( 'NONE', #37152, 1000.000000000000000 ) ; +#34436 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921579630, -0.2249510932971593713 ) ) ; +#34437 = CARTESIAN_POINT ( 'NONE', ( 91.24491504682553966, 223.7088386879784423, 197.5310967501930577 ) ) ; +#34438 = ORIENTED_EDGE ( 'NONE', *, *, #36868, .T. ) ; +#34439 = DIRECTION ( 'NONE', ( 0.6771712326825307660, -0.7358254695423512848, 0.000000000000000000 ) ) ; +#34440 = ORIENTED_EDGE ( 'NONE', *, *, #11829, .T. ) ; +#34441 = CARTESIAN_POINT ( 'NONE', ( 38.45203725779199999, 79.83084358632200406, 285.1665681227444793 ) ) ; +#34442 = CARTESIAN_POINT ( 'NONE', ( -38.07016371915999997, 118.2980697155000058, 87.84172081773000684 ) ) ; +#34443 = LINE ( 'NONE', #38138, #21602 ) ; +#34444 = CARTESIAN_POINT ( 'NONE', ( 15.99998877809332143, 185.5947573397194219, 102.4911857378799880 ) ) ; +#34445 = ORIENTED_EDGE ( 'NONE', *, *, #27736, .F. ) ; +#34446 = CARTESIAN_POINT ( 'NONE', ( -37.83635444431042316, 190.3639788717852923, 106.7036751988638912 ) ) ; +#34447 = EDGE_LOOP ( 'NONE', ( #37318, #28317, #36628, #5940 ) ) ; +#34448 = DIRECTION ( 'NONE', ( 0.0005559617614583168633, -0.3907311284917806549, 0.9205046855579059883 ) ) ; +#34449 = EDGE_CURVE ( 'NONE', #14325, #21600, #23731, .T. ) ; +#34450 = EDGE_CURVE ( 'NONE', #9106, #36316, #17033, .T. ) ; +#34451 = ORIENTED_EDGE ( 'NONE', *, *, #33159, .F. ) ; +#34452 = CARTESIAN_POINT ( 'NONE', ( -28.46570037481023974, 129.9682353462455353, 92.24140578278095859 ) ) ; +#34453 = CYLINDRICAL_SURFACE ( 'NONE', #24841, 1.750000000000001998 ) ; +#34454 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#34455 = CARTESIAN_POINT ( 'NONE', ( -20.61404310602679502, 159.1294364323455568, 96.40329781580336999 ) ) ; +#34456 = CARTESIAN_POINT ( 'NONE', ( 45.12876369734329529, 130.2598771944438170, 92.77743955731769177 ) ) ; +#34457 = AXIS2_PLACEMENT_3D ( 'NONE', #20124, #26095, #14011 ) ; +#34458 = ORIENTED_EDGE ( 'NONE', *, *, #31297, .T. ) ; +#34459 = EDGE_LOOP ( 'NONE', ( #26428, #34284, #34755, #30120 ) ) ; +#34460 = PLANE ( 'NONE', #26956 ) ; +#34461 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971553190 ) ) ; +#34462 = VERTEX_POINT ( 'NONE', #19636 ) ; +#34463 = CARTESIAN_POINT ( 'NONE', ( -23.36361985736456148, 135.0109247816458833, 90.96681983546676520 ) ) ; +#34464 = CARTESIAN_POINT ( 'NONE', ( -28.55555411531191012, 225.5077044902969021, 75.57575137751560135 ) ) ; +#34465 = ORIENTED_EDGE ( 'NONE', *, *, #27015, .T. ) ; +#34466 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#34467 = EDGE_CURVE ( 'NONE', #14434, #21069, #14608, .T. ) ; +#34468 = CARTESIAN_POINT ( 'NONE', ( 17.18127995227040117, 121.6259304897876774, 177.7629839600756156 ) ) ; +#34469 = EDGE_LOOP ( 'NONE', ( #14886, #28489, #3742, #4469, #2260 ) ) ; +#34470 = CARTESIAN_POINT ( 'NONE', ( 28.48577721303999866, 125.2596771088999930, 88.55415022690999649 ) ) ; +#34471 = CARTESIAN_POINT ( 'NONE', ( 3.651536791988571728, 167.8514937833010379, 101.3625248932176959 ) ) ; +#34472 = CARTESIAN_POINT ( 'NONE', ( -12.63088703835403237, 131.0198726340251199, 89.90887950976862442 ) ) ; +#34473 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#34474 = CARTESIAN_POINT ( 'NONE', ( 44.00772395466434261, 121.9453774596282898, 90.79738088892072767 ) ) ; +#34475 = ORIENTED_EDGE ( 'NONE', *, *, #35357, .F. ) ; +#34476 = CARTESIAN_POINT ( 'NONE', ( 19.86084717194416172, 148.9562488000109965, 184.3380894802987484 ) ) ; +#34477 = CARTESIAN_POINT ( 'NONE', ( 25.74903847615999908, 118.4643410412000009, 87.50223256360000335 ) ) ; +#34478 = DIRECTION ( 'NONE', ( -0.0005884949954653354411, 0.2249049336873584770, -0.9743805337119194609 ) ) ; +#34479 = EDGE_CURVE ( 'NONE', #14957, #9728, #9861, .T. ) ; +#34480 = CONICAL_SURFACE ( 'NONE', #16848, 2.503022657348932700, 0.7853981633682908248 ) ; +#34481 = CARTESIAN_POINT ( 'NONE', ( -46.06386797141990996, 125.2795831766159438, 91.72091677834144718 ) ) ; +#34482 = ORIENTED_EDGE ( 'NONE', *, *, #25899, .F. ) ; +#34483 = CARTESIAN_POINT ( 'NONE', ( -26.71540925256000065, 134.5404870428999970, 93.55251239663999741 ) ) ; +#34484 = CARTESIAN_POINT ( 'NONE', ( -23.36043048140902911, 174.7899337806854589, 102.5862286567353436 ) ) ; +#34485 = VECTOR ( 'NONE', #18871, 1000.000000000000227 ) ; +#34486 = CARTESIAN_POINT ( 'NONE', ( 25.96376524127702368, 211.5623268173172278, 73.04282261878624638 ) ) ; +#34487 = EDGE_CURVE ( 'NONE', #13582, #30170, #27692, .T. ) ; +#34488 = EDGE_CURVE ( 'NONE', #4354, #4523, #12501, .T. ) ; +#34489 = EDGE_CURVE ( 'NONE', #19698, #37155, #24420, .T. ) ; +#34490 = EDGE_CURVE ( 'NONE', #36343, #31088, #15271, .T. ) ; +#34491 = CARTESIAN_POINT ( 'NONE', ( -12.64382648178746571, 181.7261798233791978, 101.6688239033984047 ) ) ; +#34492 = FACE_OUTER_BOUND ( 'NONE', #29840, .T. ) ; +#34493 = CARTESIAN_POINT ( 'NONE', ( -2.937261516931815919, 196.5784392894775010, 103.8768773714908775 ) ) ; +#34494 = CARTESIAN_POINT ( 'NONE', ( -20.25978691166676171, 184.3446264524550884, 105.0351082379391414 ) ) ; +#34495 = CARTESIAN_POINT ( 'NONE', ( -75.98947031532999574, 156.0077016488999959, 97.25549023460999365 ) ) ; +#34496 = CARTESIAN_POINT ( 'NONE', ( 37.68785012072999763, 191.2689211507999971, 104.9610270439000033 ) ) ; +#34498 = ORIENTED_EDGE ( 'NONE', *, *, #16639, .F. ) ; +#34497 = CARTESIAN_POINT ( 'NONE', ( 35.85700008397000005, 191.8443248289999872, 106.7786176113000067 ) ) ; +#34499 = ORIENTED_EDGE ( 'NONE', *, *, #26676, .F. ) ; +#34500 = ORIENTED_EDGE ( 'NONE', *, *, #31685, .T. ) ; +#34502 = AXIS2_PLACEMENT_3D ( 'NONE', #17773, #8409, #27234 ) ; +#34501 = CARTESIAN_POINT ( 'NONE', ( -3.598352747846551569, 136.7377413143313163, 91.22348967418774635 ) ) ; +#34503 = CARTESIAN_POINT ( 'NONE', ( -25.26021706816886692, 117.1739734221355889, 170.8214860574283591 ) ) ; +#34504 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27702, #6196, #31161, #37282, #20940, #24433, #27303, #9078, #2923, #15414, #24636 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000001509903, 0.3750000000001908473, 0.4375000000002049472, 0.4687500000001764144, 0.5000000000001478817, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34505 = DIRECTION ( 'NONE', ( 6.245004513562242117E-15, 0.9743700557921592953, 0.2249510932971531540 ) ) ; +#34506 = DIRECTION ( 'NONE', ( 0.0005734119072316638333, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#34507 = CONICAL_SURFACE ( 'NONE', #3181, 5.000000000151219481, 0.7853981634251813171 ) ; +#34508 = ORIENTED_EDGE ( 'NONE', *, *, #10155, .F. ) ; +#34509 = CARTESIAN_POINT ( 'NONE', ( -26.00138850119475364, 118.1173731751006102, 87.28355378449504087 ) ) ; +#34510 = CARTESIAN_POINT ( 'NONE', ( 3.667031087185668614, 126.5406573962001033, 90.06227382706777007 ) ) ; +#34511 = DIRECTION ( 'NONE', ( 0.7066903833891088338, 9.361005956520113971E-05, -0.7075229277292088836 ) ) ; +#34512 = ORIENTED_EDGE ( 'NONE', *, *, #27567, .F. ) ; +#34513 = LINE ( 'NONE', #34911, #37584 ) ; +#34514 = CARTESIAN_POINT ( 'NONE', ( -15.49823494792000034, 124.1767752774999991, 91.40966175313999997 ) ) ; +#34515 = CARTESIAN_POINT ( 'NONE', ( -25.99970180910948159, 119.7153706046974833, 90.38600776144090787 ) ) ; +#34516 = CARTESIAN_POINT ( 'NONE', ( -14.55306309020423505, 135.7870933973037211, 91.01063163966807679 ) ) ; +#34517 = DIRECTION ( 'NONE', ( 0.5988974202702760374, -0.8008257488327958917, 0.000000000000000000 ) ) ; +#34518 = VERTEX_POINT ( 'NONE', #6561 ) ; +#34519 = PLANE ( 'NONE', #37013 ) ; +#34520 = CARTESIAN_POINT ( 'NONE', ( 1.766901104769819986, 189.4078520347610208, 103.8106879554589881 ) ) ; +#34521 = DIRECTION ( 'NONE', ( -0.0005884949961205877692, 0.2249510543439036392, -0.9743698870671270162 ) ) ; +#34522 = ORIENTED_EDGE ( 'NONE', *, *, #20329, .F. ) ; +#34523 = ORIENTED_EDGE ( 'NONE', *, *, #3814, .F. ) ; +#34524 = PLANE ( 'NONE', #27744 ) ; +#34525 = ORIENTED_EDGE ( 'NONE', *, *, #5184, .T. ) ; +#34526 = CIRCLE ( 'NONE', #1904, 1.999999999847029697 ) ; +#34527 = EDGE_CURVE ( 'NONE', #802, #315, #18819, .T. ) ; +#34529 = EDGE_CURVE ( 'NONE', #35520, #37873, #30691, .T. ) ; +#34528 = CARTESIAN_POINT ( 'NONE', ( -13.55720484940903781, 164.6355387680886224, 97.67021978055177556 ) ) ; +#34530 = AXIS2_PLACEMENT_3D ( 'NONE', #34287, #39825, #40225 ) ; +#34531 = CIRCLE ( 'NONE', #14320, 4.999999999999990230 ) ; +#34532 = CARTESIAN_POINT ( 'NONE', ( 24.99091232081798708, 212.6266500085528151, 75.54358765244305118 ) ) ; +#34533 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14625, #5820, #18271, #27111, #11554, #30769, #24027, #18067, #36484, #8073, #21160, #40152, #12164, #14834, #14414, #8491, #33615 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999383271, 0.1874999999999074907, 0.2187499999999421296, 0.2343749999999594769, 0.2499999999999767963, 0.3750000000000690004, 0.4375000000001306732, 0.4687500000001615930, 0.5000000000001924017, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34534 = ADVANCED_FACE ( 'NONE', ( #19029 ), #31737, .T. ) ; +#34535 = VECTOR ( 'NONE', #12742, 1000.000000000000227 ) ; +#34536 = CARTESIAN_POINT ( 'NONE', ( -36.61650759155055113, 191.3591673295911733, 106.3831752203444267 ) ) ; +#34537 = EDGE_CURVE ( 'NONE', #28359, #4391, #7392, .T. ) ; +#34538 = CARTESIAN_POINT ( 'NONE', ( -25.50819987896827712, 205.5673820218000003, 76.31562095570974691 ) ) ; +#34539 = EDGE_CURVE ( 'NONE', #17036, #26229, #3895, .T. ) ; +#34540 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #14144, #11068, #26618, #29882, #35985, #20876, #24160, #17781, #36617, #8619, #5525, #2867, #3451, #9017, #24969, #15154, #37421, #18780, #15927 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 1, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000006939, 0.2500000000000013878, 0.3750000000000021094, 0.4375000000000024425, 0.5000000000000027756, 0.6249999999999968914, 0.6874999999999921174, 0.7187499999999890088, 0.7499999999999857891, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34541 = LINE ( 'NONE', #6543, #23223 ) ; +#34542 = PLANE ( 'NONE', #38925 ) ; +#34543 = ORIENTED_EDGE ( 'NONE', *, *, #38647, .F. ) ; +#34544 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971565402 ) ) ; +#34545 = CARTESIAN_POINT ( 'NONE', ( -51.85292886923593159, 86.58783266284258673, 291.5898618049438937 ) ) ; +#34546 = CARTESIAN_POINT ( 'NONE', ( 3.166350953592421025, 126.8041585549839709, 88.92605846951083493 ) ) ; +#34547 = DIRECTION ( 'NONE', ( 0.0005884949961208581692, -0.2249510543439069699, 0.9743698870671261281 ) ) ; +#34548 = ORIENTED_EDGE ( 'NONE', *, *, #20109, .T. ) ; +#34549 = ORIENTED_EDGE ( 'NONE', *, *, #10906, .T. ) ; +#34550 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #40422, #24722, #31230, #18534 ), + ( #27986, #18136, #12033, #36970 ), + ( #21448, #21643, #30640, #33889 ), + ( #40026, #18340, #30840, #34087 ), + ( #15298, #37172, #6083, #31040 ), + ( #12422, #37366, #9365, #21838 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 4 ), + ( 4, 4 ), + ( -0.4117284577470000095, 0.000000000000000000, 1.000000000000000000, 1.411728457748999910 ), + ( -3.970401296627000013E-07, 1.000000188336999996 ), + .UNSPECIFIED. ) ; +#34551 = VERTEX_POINT ( 'NONE', #16175 ) ; +#34552 = LINE ( 'NONE', #37647, #30752 ) ; +#34553 = CARTESIAN_POINT ( 'NONE', ( 15.99974815555098218, 138.5019114137554936, 91.61902897505088106 ) ) ; +#34554 = EDGE_LOOP ( 'NONE', ( #7601, #34628, #33180, #6182, #36620 ) ) ; +#34555 = ORIENTED_EDGE ( 'NONE', *, *, #29300, .T. ) ; +#34556 = CARTESIAN_POINT ( 'NONE', ( 15.99985850662387676, 165.3259634487874905, 97.81191083758460536 ) ) ; +#34557 = CIRCLE ( 'NONE', #16932, 6.000000000369111852 ) ; +#34558 = CYLINDRICAL_SURFACE ( 'NONE', #14634, 2.000000000000014655 ) ; +#34559 = CARTESIAN_POINT ( 'NONE', ( -20.51745969899640087, 207.4083551867479116, 77.09396086730279762 ) ) ; +#34560 = LINE ( 'NONE', #38257, #36606 ) ; +#34561 = CARTESIAN_POINT ( 'NONE', ( -62.16409435615067025, 244.6873810594820497, 206.4486349095241735 ) ) ; +#34562 = EDGE_LOOP ( 'NONE', ( #15222, #7419, #30518, #19883, #36894, #29696 ) ) ; +#34563 = CARTESIAN_POINT ( 'NONE', ( 30.06862252805091273, 137.3589525008079590, 91.34657359371807672 ) ) ; +#34564 = EDGE_LOOP ( 'NONE', ( #16674, #10962, #25468, #33807 ) ) ; +#34565 = AXIS2_PLACEMENT_3D ( 'NONE', #3236, #34311, #9997 ) ; +#34566 = CARTESIAN_POINT ( 'NONE', ( 31.91158941450065356, 174.0369345777030787, 102.3790021461855133 ) ) ; +#34567 = CONICAL_SURFACE ( 'NONE', #40450, 2.503072324631959944, 0.7853981633575404242 ) ; +#34568 = CARTESIAN_POINT ( 'NONE', ( 40.87660703992253275, 128.6351741493065219, 92.40491543180627332 ) ) ; +#34569 = ORIENTED_EDGE ( 'NONE', *, *, #21905, .T. ) ; +#34570 = VERTEX_POINT ( 'NONE', #13317 ) ; +#34571 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971577615 ) ) ; +#34572 = CARTESIAN_POINT ( 'NONE', ( 1.967363662627033216, 189.0444863294190156, 103.2960939288106488 ) ) ; +#34574 = ADVANCED_FACE ( 'NONE', ( #28856, #35158, #38640, #38845, #29664, #13919, #17367, #23523, #14332, #26004, #26610, #14136, #10865, #23331, #26806, #33121, #13714, #20036 ), #29871, .F. ) ; +#34573 = CARTESIAN_POINT ( 'NONE', ( -26.00892325947948436, 205.5538223707005727, 75.25157465572357296 ) ) ; +#34575 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#34576 = EDGE_CURVE ( 'NONE', #32435, #33874, #26345, .T. ) ; +#34577 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #4956, #17423 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 0.9999996464390269457 ), + .UNSPECIFIED. ) ; +#34578 = ORIENTED_EDGE ( 'NONE', *, *, #11909, .F. ) ; +#34579 = DIRECTION ( 'NONE', ( 0.7075337269147008445, -0.000000000000000000, 0.7066795775160008564 ) ) ; +#34580 = CARTESIAN_POINT ( 'NONE', ( 39.69446386203616584, 161.8153251821185563, 196.1471770628630793 ) ) ; +#34581 = ORIENTED_EDGE ( 'NONE', *, *, #8020, .T. ) ; +#34582 = EDGE_CURVE ( 'NONE', #26218, #3644, #32910, .T. ) ; +#34583 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624403437, 0.1792657018023851578 ) ) ; +#34584 = FACE_OUTER_BOUND ( 'NONE', #7530, .T. ) ; +#34585 = CARTESIAN_POINT ( 'NONE', ( -26.52798348243999982, 122.1192044545999948, 91.08024802501999773 ) ) ; +#34586 = EDGE_CURVE ( 'NONE', #23972, #34711, #15920, .T. ) ; +#34587 = ORIENTED_EDGE ( 'NONE', *, *, #6393, .F. ) ; +#34588 = DIRECTION ( 'NONE', ( 0.6087614115774881984, 0.7729348350621344510, 0.1788331191967955092 ) ) ; +#34589 = CARTESIAN_POINT ( 'NONE', ( -29.78153558668642376, 185.0889519685938183, 104.9678232557472199 ) ) ; +#34590 = EDGE_CURVE ( 'NONE', #12043, #75, #19937, .T. ) ; +#34591 = VECTOR ( 'NONE', #8361, 1000.000000000000227 ) ; +#34592 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3791, #16267, #30166, #2160 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34593 = EDGE_LOOP ( 'NONE', ( #11140, #21636, #18139, #11748 ) ) ; +#34594 = VECTOR ( 'NONE', #38344, 1000.000000000000227 ) ; +#34595 = VECTOR ( 'NONE', #37077, 1000.000000000000227 ) ; +#34596 = CARTESIAN_POINT ( 'NONE', ( 25.25244696082440754, 117.1946158480437248, 170.8386649222292704 ) ) ; +#34597 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989941907, 0.1373964268091566465 ) ) ; +#34599 = CARTESIAN_POINT ( 'NONE', ( -16.54773196322278750, 121.5501185848507220, 177.2466710267809447 ) ) ; +#34598 = CARTESIAN_POINT ( 'NONE', ( -36.27950425524976907, 191.8188495074159334, 104.4051415298545180 ) ) ; +#34600 = EDGE_LOOP ( 'NONE', ( #35610, #32603, #39342, #22427 ) ) ; +#34601 = EDGE_CURVE ( 'NONE', #5625, #19444, #38444, .T. ) ; +#34602 = CARTESIAN_POINT ( 'NONE', ( -42.43605116069559102, 176.1238575639636963, 166.1285832315935238 ) ) ; +#34603 = ORIENTED_EDGE ( 'NONE', *, *, #29917, .T. ) ; +#34604 = CARTESIAN_POINT ( 'NONE', ( 62.95950931629634795, 82.27946979429611929, 297.5205190635955432 ) ) ; +#34605 = CARTESIAN_POINT ( 'NONE', ( -4.036853220715999946, 174.6757490132999919, 101.5218917698000070 ) ) ; +#34606 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562904 ) ) ; +#34607 = VERTEX_POINT ( 'NONE', #10464 ) ; +#34608 = ORIENTED_EDGE ( 'NONE', *, *, #30879, .F. ) ; +#34609 = LINE ( 'NONE', #481, #22458 ) ; +#34610 = CARTESIAN_POINT ( 'NONE', ( 12.67270221306000089, 114.0103269029000188, 152.4718672074000381 ) ) ; +#34611 = CARTESIAN_POINT ( 'NONE', ( -39.77033354370986018, 109.3176668593371659, 175.1599740040520885 ) ) ; +#34612 = FACE_OUTER_BOUND ( 'NONE', #11338, .T. ) ; +#34613 = ORIENTED_EDGE ( 'NONE', *, *, #15596, .T. ) ; +#34614 = VERTEX_POINT ( 'NONE', #7769 ) ; +#34615 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 82.27946979429644614, 322.5967026918628449 ) ) ; +#34616 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39878, #2694, #11889, #27645 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.018919284545057323E-05 ), + .UNSPECIFIED. ) ; +#34617 = CARTESIAN_POINT ( 'NONE', ( 20.00057261911097228, 127.6202858744403272, 89.10430568560569498 ) ) ; +#34618 = CARTESIAN_POINT ( 'NONE', ( -28.22659469502000107, 125.0890361073000179, 88.54897414206999429 ) ) ; +#34619 = ORIENTED_EDGE ( 'NONE', *, *, #26548, .F. ) ; +#34620 = VERTEX_POINT ( 'NONE', #1645 ) ; +#34621 = CARTESIAN_POINT ( 'NONE', ( -20.83567718070347397, 212.3494766734548591, 73.57110327059724852 ) ) ; +#34622 = AXIS2_PLACEMENT_3D ( 'NONE', #13231, #1543, #22641 ) ; +#34623 = EDGE_LOOP ( 'NONE', ( #11179, #13615, #37460, #13195 ) ) ; +#34624 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26356, #33071, #4455, #5059 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34625 = VECTOR ( 'NONE', #12074, 1000.000000000000227 ) ; +#34626 = EDGE_CURVE ( 'NONE', #31583, #26486, #19823, .T. ) ; +#34627 = VECTOR ( 'NONE', #31939, 1000.000000000000000 ) ; +#34628 = ORIENTED_EDGE ( 'NONE', *, *, #11909, .T. ) ; +#34629 = EDGE_CURVE ( 'NONE', #26621, #31941, #15123, .T. ) ; +#34630 = FACE_OUTER_BOUND ( 'NONE', #40454, .T. ) ; +#34631 = CARTESIAN_POINT ( 'NONE', ( -12.63676213157982531, 181.6119438013536183, 104.1547372293333495 ) ) ; +#34632 = CARTESIAN_POINT ( 'NONE', ( -2.726782783521000120, 189.4935947808999970, 106.6363833331000137 ) ) ; +#34633 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971542643 ) ) ; +#34634 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20473, #10294, #29091, #32945 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34635 = ADVANCED_FACE ( 'NONE', ( #7978 ), #20238, .T. ) ; +#34636 = ORIENTED_EDGE ( 'NONE', *, *, #20135, .T. ) ; +#34637 = CARTESIAN_POINT ( 'NONE', ( 2.804056179529000215, 199.6921533858000259, 89.49986858798999378 ) ) ; +#34638 = EDGE_LOOP ( 'NONE', ( #1038, #19887, #23421, #17735 ) ) ; +#34639 = CARTESIAN_POINT ( 'NONE', ( 32.48195952060035552, 83.06028001681806927, 291.5538007505838323 ) ) ; +#34640 = CARTESIAN_POINT ( 'NONE', ( -31.91276639771151125, 174.2534364592530949, 101.4412295696469926 ) ) ; +#34641 = DIRECTION ( 'NONE', ( -0.0004161288024623961039, -0.5299192578740949955, -0.8480479980348919478 ) ) ; +#34642 = EDGE_CURVE ( 'NONE', #40029, #21947, #34839, .T. ) ; +#34643 = VERTEX_POINT ( 'NONE', #1437 ) ; +#34644 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; +#34645 = ORIENTED_EDGE ( 'NONE', *, *, #30662, .F. ) ; +#34646 = CARTESIAN_POINT ( 'NONE', ( 19.98880994172048275, 211.4784726885777957, 76.04928499183930057 ) ) ; +#34647 = CARTESIAN_POINT ( 'NONE', ( 22.78070441975003391, 158.6816533748419147, 96.78686173997256503 ) ) ; +#34648 = CYLINDRICAL_SURFACE ( 'NONE', #8966, 4.999999999999990230 ) ; +#34649 = ORIENTED_EDGE ( 'NONE', *, *, #27793, .F. ) ; +#34650 = CONICAL_SURFACE ( 'NONE', #9911, 2.499999999403085482, 0.7853981633778843729 ) ; +#34651 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319369828058 ) ) ; +#34652 = VERTEX_POINT ( 'NONE', #26402 ) ; +#34653 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#34654 = AXIS2_PLACEMENT_3D ( 'NONE', #19132, #1136, #23224 ) ; +#34655 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #1589, #27119 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34656 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250904288, 179.1753088542885735, 103.5954339978219281 ) ) ; +#34657 = DIRECTION ( 'NONE', ( -0.0006039748319417796414, 6.167438909946999677E-15, -0.9999998176071844824 ) ) ; +#34658 = AXIS2_PLACEMENT_3D ( 'NONE', #29070, #6977, #6771 ) ; +#34659 = CARTESIAN_POINT ( 'NONE', ( 23.36419446305882275, 177.6323096098335270, 100.7871876170524814 ) ) ; +#34660 = CARTESIAN_POINT ( 'NONE', ( -2.935406218811822399, 190.8780696450395737, 106.8012255142375864 ) ) ; +#34661 = EDGE_LOOP ( 'NONE', ( #4932, #17222, #26055, #7812 ) ) ; +#34662 = EDGE_LOOP ( 'NONE', ( #14700, #38315, #8894, #31010, #34176, #28189, #14588, #13566, #10454, #15221, #8729 ) ) ; +#34663 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178570903572E-05, -0.0002331579774915885982 ) ) ; +#34664 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564015 ) ) ; +#34665 = VERTEX_POINT ( 'NONE', #32729 ) ; +#34666 = CARTESIAN_POINT ( 'NONE', ( -15.99823277108970743, 185.2321969574450975, 105.5057198903149782 ) ) ; +#34667 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265227786, -0.1368326740407717901 ) ) ; +#34668 = VERTEX_POINT ( 'NONE', #27632 ) ; +#34669 = PLANE ( 'NONE', #22263 ) ; +#34670 = CARTESIAN_POINT ( 'NONE', ( -38.93814858684476121, 191.0388300950886560, 103.7812318162937686 ) ) ; +#34671 = ORIENTED_EDGE ( 'NONE', *, *, #27339, .F. ) ; +#34672 = CARTESIAN_POINT ( 'NONE', ( 28.34631006716999835, 125.4808168258000052, 88.95028025583000897 ) ) ; +#34673 = CARTESIAN_POINT ( 'NONE', ( 40.67213421850927801, 184.8215034846340075, 102.8109167764341407 ) ) ; +#34674 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799573900, 175.3514230958744520, 100.1541516780990406 ) ) ; +#34675 = ADVANCED_FACE ( 'NONE', ( #14745 ), #11876, .T. ) ; +#34676 = AXIS2_PLACEMENT_3D ( 'NONE', #2681, #21689, #28028 ) ; +#34677 = EDGE_CURVE ( 'NONE', #11521, #7245, #5314, .T. ) ; +#34678 = CARTESIAN_POINT ( 'NONE', ( -6.036405711824646581, 134.8430548843712131, 93.35330002513178727 ) ) ; +#34679 = CARTESIAN_POINT ( 'NONE', ( 3.613113740660051754, 136.7269897419313622, 91.21665193260847104 ) ) ; +#34680 = VERTEX_POINT ( 'NONE', #34126 ) ; +#34681 = CARTESIAN_POINT ( 'NONE', ( -13.35657892733726726, 177.7135493816460325, 100.6893958121277279 ) ) ; +#34682 = AXIS2_PLACEMENT_3D ( 'NONE', #13110, #25595, #31925 ) ; +#34683 = CARTESIAN_POINT ( 'NONE', ( 0.9866909474777101341, 189.0453558675688441, 103.6973837186184682 ) ) ; +#34684 = CARTESIAN_POINT ( 'NONE', ( 20.50029254611199292, 184.8549113859068029, 102.8308091169877798 ) ) ; +#34685 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -1.785014166949466476E-16, -0.0006039748319386109522 ) ) ; +#34686 = ORIENTED_EDGE ( 'NONE', *, *, #7123, .F. ) ; +#34687 = VERTEX_POINT ( 'NONE', #6124 ) ; +#34688 = EDGE_CURVE ( 'NONE', #38719, #28941, #2267, .T. ) ; +#34689 = CARTESIAN_POINT ( 'NONE', ( 38.22729489356998300, 118.8169745464294920, 90.24469516268244718 ) ) ; +#34690 = CARTESIAN_POINT ( 'NONE', ( -42.13796565469444744, 121.2774612726109922, 92.80900056227228845 ) ) ; +#34691 = FACE_OUTER_BOUND ( 'NONE', #38673, .T. ) ; +#34692 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#34693 = EDGE_LOOP ( 'NONE', ( #24410, #28464, #11917, #5849 ) ) ; +#34694 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15559, #5955, #20892, #33351, #2292, #27260, #21312, #24183, #18408, #8640 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.0007807016828180784107, 0.001561403365636156821, 0.003122806731272460661, 0.006245613462545087854 ), + .UNSPECIFIED. ) ; +#34695 = CARTESIAN_POINT ( 'NONE', ( -0.02805196447938418727, 127.1761617620222893, 297.5585619722723436 ) ) ; +#34696 = EDGE_CURVE ( 'NONE', #9444, #12044, #18506, .T. ) ; +#34697 = ORIENTED_EDGE ( 'NONE', *, *, #10487, .F. ) ; +#34698 = CARTESIAN_POINT ( 'NONE', ( -22.49857731217000278, 158.2257569204417393, 98.76156587226640227 ) ) ; +#34699 = CARTESIAN_POINT ( 'NONE', ( -26.00525532982161181, 191.5536840588030714, 103.8922918156798687 ) ) ; +#34700 = DIRECTION ( 'NONE', ( 0.0006039748319375912600, 1.387265140328410610E-14, 0.9999998176071847045 ) ) ; +#34701 = CARTESIAN_POINT ( 'NONE', ( 36.06507008640249268, 192.5935567513030264, 106.3654035318940032 ) ) ; +#34702 = CARTESIAN_POINT ( 'NONE', ( 13.50157275071688723, 188.0659121227523087, 103.3026035752030651 ) ) ; +#34703 = ORIENTED_EDGE ( 'NONE', *, *, #33725, .T. ) ; +#34704 = CONICAL_SURFACE ( 'NONE', #15166, 2.499999999971520115, 0.7853981633778842619 ) ; +#34705 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825837453473963, 0.0005734119042911652942 ) ) ; +#34706 = CONICAL_SURFACE ( 'NONE', #17078, 51.90509899241903469, 0.7853981633972695331 ) ; +#34707 = DIRECTION ( 'NONE', ( -0.7933533411653077572, -0.5931840316265212243, -0.1368326740407759534 ) ) ; +#34709 = EDGE_CURVE ( 'NONE', #26700, #14103, #27301, .T. ) ; +#34708 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27227, #5728, #20862, #5922, #2262, #14740, #36600, #24554, #30480, #27439 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.0004306238141922298450, 0.0008612476283844596901, 0.001291871442576689481, 0.001722495256768919380 ), + .UNSPECIFIED. ) ; +#34710 = CARTESIAN_POINT ( 'NONE', ( 22.74549108420935184, 156.0105960157455343, 185.9695902395600342 ) ) ; +#34711 = VERTEX_POINT ( 'NONE', #40064 ) ; +#34712 = ORIENTED_EDGE ( 'NONE', *, *, #6901, .F. ) ; +#34713 = EDGE_CURVE ( 'NONE', #34146, #36524, #2063, .T. ) ; +#34714 = CARTESIAN_POINT ( 'NONE', ( -22.64037623556000156, 153.5412426005999862, 97.93672204453001484 ) ) ; +#34715 = CARTESIAN_POINT ( 'NONE', ( -4.665344088811993473, 130.8156869893767578, 89.85691989110142686 ) ) ; +#34716 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#34717 = EDGE_LOOP ( 'NONE', ( #7219, #4482, #23431, #6464, #28393, #33986 ) ) ; +#34718 = CARTESIAN_POINT ( 'NONE', ( -21.82963563099358950, 129.7230376101904881, 90.12818080884812844 ) ) ; +#34719 = DIRECTION ( 'NONE', ( -0.7947985590179719173, 0.5913221741348985150, 0.1365039814779491212 ) ) ; +#34720 = CARTESIAN_POINT ( 'NONE', ( 0.05270753573806398473, 83.21792371834001756, 87.26775245801255210 ) ) ; +#34721 = EDGE_CURVE ( 'NONE', #29469, #39798, #8611, .T. ) ; +#34722 = EDGE_CURVE ( 'NONE', #24020, #5749, #8752, .T. ) ; +#34723 = DIRECTION ( 'NONE', ( 0.5987319967475925875, 0.8009494341533932582, 0.000000000000000000 ) ) ; +#34724 = CARTESIAN_POINT ( 'NONE', ( -30.06930555481828549, 176.9293638124302390, 103.3465668613376494 ) ) ; +#34725 = DIRECTION ( 'NONE', ( -0.9999998268368093246, -0.0001323825833059327241, 0.0005734118962871372982 ) ) ; +#34726 = ORIENTED_EDGE ( 'NONE', *, *, #6673, .T. ) ; +#34727 = CARTESIAN_POINT ( 'NONE', ( 20.94615154526903567, 129.3425601203839221, 89.50137061379278691 ) ) ; +#34728 = CARTESIAN_POINT ( 'NONE', ( 1.765871439063640080, 189.4088296708220014, 103.8123468599179802 ) ) ; +#34729 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971557908 ) ) ; +#34730 = CARTESIAN_POINT ( 'NONE', ( -36.31592225947999708, 191.9399448098000107, 104.5569264237000198 ) ) ; +#34731 = ORIENTED_EDGE ( 'NONE', *, *, #8399, .T. ) ; +#34732 = CONICAL_SURFACE ( 'NONE', #37993, 3.002819725383311322, 0.7853589219486486472 ) ; +#34733 = DIRECTION ( 'NONE', ( -0.0005884949961258157921, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#34734 = ORIENTED_EDGE ( 'NONE', *, *, #3890, .T. ) ; +#34735 = VECTOR ( 'NONE', #305, 1000.000000000000000 ) ; +#34736 = AXIS2_PLACEMENT_3D ( 'NONE', #10306, #3528, #8022 ) ; +#34737 = PLANE ( 'NONE', #22119 ) ; +#34738 = DIRECTION ( 'NONE', ( 0.7933535320750288999, 0.5930759023596231527, 0.1372994799130531351 ) ) ; +#34739 = CARTESIAN_POINT ( 'NONE', ( 25.99214295446221357, 205.1071317750680123, 76.08915132579089402 ) ) ; +#34740 = CARTESIAN_POINT ( 'NONE', ( -2.225641404526999878, 209.5844923308000034, 73.69572292342999731 ) ) ; +#34741 = CARTESIAN_POINT ( 'NONE', ( -37.23546393651999864, 190.2450898259000098, 106.8159057760000081 ) ) ; +#34742 = ORIENTED_EDGE ( 'NONE', *, *, #210, .T. ) ; +#34743 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971555410 ) ) ; +#34744 = CYLINDRICAL_SURFACE ( 'NONE', #7117, 2.499999999999997335 ) ; +#34745 = CARTESIAN_POINT ( 'NONE', ( 23.68617301127497043, 136.6832541776373660, 94.27334404510794741 ) ) ; +#34746 = CARTESIAN_POINT ( 'NONE', ( 13.49999901374599354, 184.9670087776437697, 102.3446895546948099 ) ) ; +#34747 = EDGE_LOOP ( 'NONE', ( #28872, #1312, #21871, #17486 ) ) ; +#34748 = ORIENTED_EDGE ( 'NONE', *, *, #36878, .F. ) ; +#34749 = VERTEX_POINT ( 'NONE', #36808 ) ; +#34750 = CARTESIAN_POINT ( 'NONE', ( 5.666344154467410910, 131.0223139869003148, 89.89838483048988849 ) ) ; +#34751 = AXIS2_PLACEMENT_3D ( 'NONE', #38940, #8072, #29954 ) ; +#34752 = EDGE_CURVE ( 'NONE', #19682, #32767, #10697, .T. ) ; +#34753 = CARTESIAN_POINT ( 'NONE', ( 28.45934412591282126, 181.0176348879864747, 104.5058915996823004 ) ) ; +#34754 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552156487, 3.781093664149108639E-12, 291.5584375788758393 ) ) ; +#34755 = ORIENTED_EDGE ( 'NONE', *, *, #32184, .F. ) ; +#34756 = CARTESIAN_POINT ( 'NONE', ( 43.76856227852993442, 122.2716156806393997, 88.00825085342030718 ) ) ; +#34757 = ADVANCED_FACE ( 'NONE', ( #2859 ), #30264, .T. ) ; +#34758 = CONICAL_SURFACE ( 'NONE', #13233, 5.999999999815448071, 0.7853981634347138030 ) ; +#34759 = DIRECTION ( 'NONE', ( 0.0006039748319379437342, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#34760 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -6.964038142101568045E-16, -0.0006039748319386693907 ) ) ; +#34761 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#34762 = VERTEX_POINT ( 'NONE', #14939 ) ; +#34763 = DIRECTION ( 'NONE', ( 0.6068735732728639531, 0.7743428331745974003, 0.1791581501750992012 ) ) ; +#34764 = EDGE_LOOP ( 'NONE', ( #17802, #934, #7011, #37954 ) ) ; +#34765 = LINE ( 'NONE', #13327, #40305 ) ; +#34766 = ADVANCED_FACE ( 'NONE', ( #39657 ), #28389, .F. ) ; +#34767 = ADVANCED_FACE ( 'NONE', ( #7071 ), #27047, .F. ) ; +#34768 = DIRECTION ( 'NONE', ( 4.270088556239930975E-15, 0.9743700557921584071, 0.2249510932971566790 ) ) ; +#34769 = ORIENTED_EDGE ( 'NONE', *, *, #29725, .F. ) ; +#34770 = ADVANCED_FACE ( 'NONE', ( #34325 ), #26108, .F. ) ; +#34771 = ORIENTED_EDGE ( 'NONE', *, *, #31890, .T. ) ; +#34772 = CARTESIAN_POINT ( 'NONE', ( -2.940303397145800357, 190.8908889203140120, 103.7236568775780086 ) ) ; +#34773 = EDGE_CURVE ( 'NONE', #36316, #12909, #25844, .T. ) ; +#34774 = CARTESIAN_POINT ( 'NONE', ( 0.9497808450137488201, 188.6415325040748598, 103.2036792856017939 ) ) ; +#34775 = CARTESIAN_POINT ( 'NONE', ( 2.428547639155000493, 191.0029869882000071, 106.1726329739999954 ) ) ; +#34776 = VERTEX_POINT ( 'NONE', #937 ) ; +#34777 = VERTEX_POINT ( 'NONE', #23230 ) ; +#34778 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564015 ) ) ; +#34779 = FACE_OUTER_BOUND ( 'NONE', #3828, .T. ) ; +#34780 = ORIENTED_EDGE ( 'NONE', *, *, #2037, .T. ) ; +#34781 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775999513 ) ) ; +#34782 = FACE_OUTER_BOUND ( 'NONE', #25854, .T. ) ; +#34783 = CARTESIAN_POINT ( 'NONE', ( -25.99976593112455348, 118.8155677978001705, 90.28348901843737906 ) ) ; +#34784 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21209, #5043, #30413, #18115, #8748, #33251 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34785 = ORIENTED_EDGE ( 'NONE', *, *, #12785, .T. ) ; +#34786 = VECTOR ( 'NONE', #18875, 1000.000000000000000 ) ; +#34787 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825838551259833, 0.0005734119042673001612 ) ) ; +#34788 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 7.822507694019387433E-18, 0.0006039748319385908944 ) ) ; +#34789 = AXIS2_PLACEMENT_3D ( 'NONE', #25713, #15674, #28566 ) ; +#34790 = ORIENTED_EDGE ( 'NONE', *, *, #8405, .F. ) ; +#34791 = CYLINDRICAL_SURFACE ( 'NONE', #8458, 2.500000000000000888 ) ; +#34792 = CARTESIAN_POINT ( 'NONE', ( -38.93661188417907937, 190.9636357529212773, 106.3296281109435171 ) ) ; +#34794 = CARTESIAN_POINT ( 'NONE', ( 21.83022404666562366, 176.4985800024501259, 100.9007981789296053 ) ) ; +#34793 = CARTESIAN_POINT ( 'NONE', ( 4.034499242067735025, 144.1016867008426061, 93.43213283160849869 ) ) ; +#34795 = CARTESIAN_POINT ( 'NONE', ( -39.67750709825072164, 110.6863703745082717, 169.3181700334782818 ) ) ; +#34796 = ORIENTED_EDGE ( 'NONE', *, *, #33820, .F. ) ; +#34797 = LINE ( 'NONE', #3740, #975 ) ; +#34798 = EDGE_CURVE ( 'NONE', #39862, #10712, #38761, .T. ) ; +#34799 = PLANE ( 'NONE', #14780 ) ; +#34800 = DIRECTION ( 'NONE', ( 0.0005884949961258157921, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#34801 = ORIENTED_EDGE ( 'NONE', *, *, #10626, .T. ) ; +#34802 = VERTEX_POINT ( 'NONE', #38742 ) ; +#34803 = CARTESIAN_POINT ( 'NONE', ( 15.66823304406520734, 126.2044585855555709, 91.51686078600738483 ) ) ; +#34804 = ADVANCED_FACE ( 'NONE', ( #10170 ), #19567, .F. ) ; +#34805 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490399612217, 161.1145625500912217, 97.36230304590552009 ) ) ; +#34806 = CARTESIAN_POINT ( 'NONE', ( 8.188077164138951147, 151.3149838351109224, 94.75284390784567279 ) ) ; +#34807 = DIRECTION ( 'NONE', ( 0.0005884949961237125483, -0.2249508317808572577, 0.9743699384498373250 ) ) ; +#34808 = VECTOR ( 'NONE', #24746, 1000.000000000000000 ) ; +#34809 = ADVANCED_FACE ( 'NONE', ( #24043 ), #20972, .T. ) ; +#34810 = EDGE_LOOP ( 'NONE', ( #18272, #29460, #27175, #2284, #27510, #24637, #35173 ) ) ; +#34811 = ORIENTED_EDGE ( 'NONE', *, *, #7470, .F. ) ; +#34812 = CARTESIAN_POINT ( 'NONE', ( -6.035112224946922233, 176.9992328849287162, 103.4395074864133051 ) ) ; +#34813 = DIRECTION ( 'NONE', ( 0.0005884949961243157984, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#34814 = PLANE ( 'NONE', #33095 ) ; +#34815 = VECTOR ( 'NONE', #3695, 1000.000000000000000 ) ; +#34816 = LINE ( 'NONE', #10116, #3320 ) ; +#34817 = ADVANCED_FACE ( 'NONE', ( #11352 ), #22193, .F. ) ; +#34818 = EDGE_LOOP ( 'NONE', ( #27251, #20917, #36873, #18199 ) ) ; +#34819 = VECTOR ( 'NONE', #34719, 1000.000000000000114 ) ; +#34820 = DIRECTION ( 'NONE', ( -0.0005884949961190681514, 0.2249510543439036114, -0.9743698870671270162 ) ) ; +#34821 = ORIENTED_EDGE ( 'NONE', *, *, #31991, .T. ) ; +#34822 = CARTESIAN_POINT ( 'NONE', ( 5.666342389698421300, 131.0259113980956727, 89.89613783104117317 ) ) ; +#34823 = ORIENTED_EDGE ( 'NONE', *, *, #2730, .T. ) ; +#34824 = LINE ( 'NONE', #11124, #10546 ) ; +#34825 = CARTESIAN_POINT ( 'NONE', ( -3.075166755969000132, 190.6381430620999993, 106.8872809968000013 ) ) ; +#34826 = PLANE ( 'NONE', #8457 ) ; +#34827 = VERTEX_POINT ( 'NONE', #18011 ) ; +#34828 = DIRECTION ( 'NONE', ( 0.0006039748319390937474, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#34829 = ORIENTED_EDGE ( 'NONE', *, *, #17460, .F. ) ; +#34830 = CARTESIAN_POINT ( 'NONE', ( -23.36498252095550043, 181.9355249988448975, 102.0122652968446744 ) ) ; +#34831 = LINE ( 'NONE', #22610, #29053 ) ; +#34832 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; +#34833 = AXIS2_PLACEMENT_3D ( 'NONE', #24271, #30595, #39982 ) ; +#34834 = AXIS2_PLACEMENT_3D ( 'NONE', #5265, #17120, #11629 ) ; +#34835 = FACE_OUTER_BOUND ( 'NONE', #32741, .T. ) ; +#34836 = ORIENTED_EDGE ( 'NONE', *, *, #191, .T. ) ; +#34837 = CARTESIAN_POINT ( 'NONE', ( 21.47967604010160869, 213.7116322668614146, 76.04653396927230347 ) ) ; +#34838 = CARTESIAN_POINT ( 'NONE', ( -0.4558744193316150994, 208.9999999999999716, 73.05877908015641253 ) ) ; +#34839 = CIRCLE ( 'NONE', #8112, 4.500000000005264233 ) ; +#34840 = DIRECTION ( 'NONE', ( 0.7072735235946167043, 0.6508952239913153859, 0.2758615054830065305 ) ) ; +#34841 = VECTOR ( 'NONE', #6983, 999.9999999999998863 ) ; +#34842 = EDGE_LOOP ( 'NONE', ( #23174, #21574, #20673, #4310 ) ) ; +#34843 = ORIENTED_EDGE ( 'NONE', *, *, #13886, .T. ) ; +#34844 = ADVANCED_FACE ( 'NONE', ( #34162 ), #33961, .F. ) ; +#34845 = CARTESIAN_POINT ( 'NONE', ( -30.05378920129078679, 185.1945982732621303, 102.9397691308601566 ) ) ; +#34846 = EDGE_CURVE ( 'NONE', #29279, #20205, #1411, .T. ) ; +#34847 = DIRECTION ( 'NONE', ( 1.040834085584171900E-14, -1.000000000000000000, 1.387778780778895919E-14 ) ) ; +#34848 = ADVANCED_FACE ( 'NONE', ( #27661 ), #35476, .F. ) ; +#34849 = DIRECTION ( 'NONE', ( 0.7933533411653341805, -0.5930537057989598848, -0.1373964268091485141 ) ) ; +#34850 = EDGE_CURVE ( 'NONE', #9812, #40162, #11336, .T. ) ; +#34851 = ORIENTED_EDGE ( 'NONE', *, *, #32354, .T. ) ; +#34852 = FACE_BOUND ( 'NONE', #3743, .T. ) ; +#34853 = ORIENTED_EDGE ( 'NONE', *, *, #30970, .T. ) ; +#34854 = ORIENTED_EDGE ( 'NONE', *, *, #29348, .T. ) ; +#34855 = CARTESIAN_POINT ( 'NONE', ( 39.71644058364383056, 182.4824187750803333, 106.8892835983133693 ) ) ; +#34856 = FACE_OUTER_BOUND ( 'NONE', #10187, .T. ) ; +#34857 = LINE ( 'NONE', #22829, #16305 ) ; +#34858 = CARTESIAN_POINT ( 'NONE', ( -39.69261857620511336, 119.4152473592345842, 89.81183687744525912 ) ) ; +#34859 = EDGE_CURVE ( 'NONE', #30603, #12211, #15952, .T. ) ; +#34860 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21062, #27213, #2461, #2666 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0001635364534413593176, 0.004146948151462667188 ), + .UNSPECIFIED. ) ; +#34861 = EDGE_LOOP ( 'NONE', ( #30812, #23655, #22270, #22574 ) ) ; +#34862 = DIRECTION ( 'NONE', ( 0.5988682214945756366, -0.8008475843029833063, 0.000000000000000000 ) ) ; +#34863 = ORIENTED_EDGE ( 'NONE', *, *, #34130, .F. ) ; +#34864 = DIRECTION ( 'NONE', ( -0.0002393071182782278061, -0.2252352986010052738, 0.9743043687658489160 ) ) ; +#34865 = ADVANCED_FACE ( 'NONE', ( #34357 ), #39410, .T. ) ; +#34866 = CARTESIAN_POINT ( 'NONE', ( -20.00083028478659486, 118.1178238269678644, 87.27986429234402976 ) ) ; +#34867 = CARTESIAN_POINT ( 'NONE', ( 3.535984824131890747, 174.6891947503640949, 103.0598728709964576 ) ) ; +#34868 = ORIENTED_EDGE ( 'NONE', *, *, #31331, .T. ) ; +#34869 = CARTESIAN_POINT ( 'NONE', ( -39.39119571213127102, 125.1643528234327789, 106.5167466242582748 ) ) ; +#34870 = CIRCLE ( 'NONE', #17237, 2.499999999928080641 ) ; +#34871 = AXIS2_PLACEMENT_3D ( 'NONE', #26419, #846, #16787 ) ; +#34872 = CARTESIAN_POINT ( 'NONE', ( 39.82850832707630673, 129.5630499648841010, 336.2667217638223178 ) ) ; +#34873 = CARTESIAN_POINT ( 'NONE', ( -20.00014137437327477, 165.3209111610133561, 97.83248740047278602 ) ) ; +#34874 = VECTOR ( 'NONE', #18562, 1000.000000000000227 ) ; +#34875 = CARTESIAN_POINT ( 'NONE', ( -25.76950758596748514, 116.9601185120032341, 90.28334897606002585 ) ) ; +#34876 = PLANE ( 'NONE', #38678 ) ; +#34877 = EDGE_LOOP ( 'NONE', ( #29584, #11795, #24284, #29721 ) ) ; +#34878 = EDGE_CURVE ( 'NONE', #468, #24898, #6355, .T. ) ; +#34879 = CARTESIAN_POINT ( 'NONE', ( 36.04411892353206781, 218.5902260770999987, 73.03673433784747715 ) ) ; +#34880 = CARTESIAN_POINT ( 'NONE', ( 0.6578553307668130179, 189.0021778648430768, 103.6874789120222715 ) ) ; +#34881 = CARTESIAN_POINT ( 'NONE', ( -30.17966072969699454, 126.7544990129442795, 88.93473033871077860 ) ) ; +#34882 = CARTESIAN_POINT ( 'NONE', ( -15.94448539992367486, 152.1420578781454651, 184.5710641058456929 ) ) ; +#34883 = EDGE_LOOP ( 'NONE', ( #23515, #4151, #33313, #38049 ) ) ; +#34884 = CARTESIAN_POINT ( 'NONE', ( -75.39299575447557800, 195.0156528577979884, 194.9624990955367423 ) ) ; +#34885 = DIRECTION ( 'NONE', ( -0.7942820423213363679, -0.5918950211223027447, -0.1370267171630251690 ) ) ; +#34886 = CYLINDRICAL_SURFACE ( 'NONE', #34000, 2.500000000000002220 ) ; +#34887 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #15995, #35737, #3125, #28286 ), + ( #18645, #34396, #31551, #31152 ), + ( #15599, #661, #22156, #3513 ), + ( #12737, #28683, #12950, #9676 ), + ( #34585, #37879, #31763, #25229 ), + ( #22361, #37678, #19057, #6787 ), + ( #16197, #34975, #6991, #28097 ), + ( #35944, #36160, #30240, #11038 ), + ( #39425, #11646, #4881, #14717 ), + ( #23496, #36575, #7952, #23707 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.01755415582484000023, 0.000000000000000000, 0.2000000583409999866, 0.4000001253193000150, 0.6000001922975000124, 0.8000002592757999853, 1.000000000000000000, 1.017829353318999930 ), + ( -6.981046197284999828E-06, 0.9999879771333000100 ), + .UNSPECIFIED. ) ; +#34888 = CARTESIAN_POINT ( 'NONE', ( -26.58131687458000414, 188.4463779415999909, 106.0831147517999966 ) ) ; +#34889 = ORIENTED_EDGE ( 'NONE', *, *, #13646, .T. ) ; +#34890 = AXIS2_PLACEMENT_3D ( 'NONE', #7647, #36050, #8475 ) ; +#34891 = FACE_OUTER_BOUND ( 'NONE', #31013, .T. ) ; +#34892 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; +#34893 = VECTOR ( 'NONE', #3820, 1000.000000000000227 ) ; +#34894 = CARTESIAN_POINT ( 'NONE', ( 20.49980344970378354, 118.1127835573565221, 87.75514417896067698 ) ) ; +#34895 = CARTESIAN_POINT ( 'NONE', ( -22.49852798327298586, 160.1744970386511113, 99.21146803022173799 ) ) ; +#34896 = CARTESIAN_POINT ( 'NONE', ( -2.935232621041004020, 190.8511156531020276, 106.7950609103722286 ) ) ; +#34897 = CARTESIAN_POINT ( 'NONE', ( 36.06384369686750802, 192.3127158670980066, 104.3348371342060119 ) ) ; +#34898 = ADVANCED_FACE ( 'NONE', ( #6154 ), #31119, .F. ) ; +#34899 = EDGE_CURVE ( 'NONE', #23158, #10328, #28057, .T. ) ; +#34900 = CARTESIAN_POINT ( 'NONE', ( 35.97497706240000070, 192.2961004130000333, 106.5149693472999957 ) ) ; +#34901 = ORIENTED_EDGE ( 'NONE', *, *, #2460, .T. ) ; +#34902 = CARTESIAN_POINT ( 'NONE', ( -2.448596876244000242, 209.1869211169000096, 75.60179039185000249 ) ) ; +#34903 = CARTESIAN_POINT ( 'NONE', ( 36.98450194789865719, 117.7737446942617652, 87.24544657960829852 ) ) ; +#34904 = ORIENTED_EDGE ( 'NONE', *, *, #39028, .F. ) ; +#34905 = DIRECTION ( 'NONE', ( 0.0006039748319381496242, 1.231904546584163304E-14, 0.9999998176071845934 ) ) ; +#34906 = EDGE_LOOP ( 'NONE', ( #11936, #11174, #24490, #19310 ) ) ; +#34907 = DIRECTION ( 'NONE', ( 0.0005884949961191896905, -0.2249510543439088017, 0.9743698870671257950 ) ) ; +#34908 = DIRECTION ( 'NONE', ( 0.0005884949961247097974, -0.2249510543025337594, 0.9743698870766778208 ) ) ; +#34909 = DIRECTION ( 'NONE', ( 0.9914448404770122014, 0.1271187482266248059, 0.02963025718429710201 ) ) ; +#34910 = DIRECTION ( 'NONE', ( 0.0001408405924830975634, -0.2249510899440180511, 0.9743700463873700146 ) ) ; +#34911 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394468890161, 87.27946979429613350, 297.5584364845175287 ) ) ; +#34912 = DIRECTION ( 'NONE', ( 0.0005884949961230356809, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#34913 = CARTESIAN_POINT ( 'NONE', ( 24.83589897093233034, 213.4888011696037893, 76.04349619863447174 ) ) ; +#34914 = CARTESIAN_POINT ( 'NONE', ( -32.82620923289504589, 141.9145509277669532, 282.5750060058261965 ) ) ; +#34915 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319383846792 ) ) ; +#34916 = FACE_OUTER_BOUND ( 'NONE', #34385, .T. ) ; +#34917 = VERTEX_POINT ( 'NONE', #30916 ) ; +#34918 = ADVANCED_FACE ( 'NONE', ( #37441 ), #10715, .F. ) ; +#34919 = CARTESIAN_POINT ( 'NONE', ( 39.06275665112901407, 183.6185768681216928, 102.5341712574336839 ) ) ; +#34920 = CARTESIAN_POINT ( 'NONE', ( -3.537744320960331645, 175.3497732290038300, 100.1377481765469355 ) ) ; +#34921 = AXIS2_PLACEMENT_3D ( 'NONE', #26408, #2684, #33932 ) ; +#34922 = VECTOR ( 'NONE', #37381, 1000.000000000000227 ) ; +#34923 = CARTESIAN_POINT ( 'NONE', ( 23.68596773153978319, 129.9751393256367464, 92.21150139214144303 ) ) ; +#34924 = VECTOR ( 'NONE', #1814, 1000.000000000000000 ) ; +#34925 = CARTESIAN_POINT ( 'NONE', ( -37.92803197069999754, 191.1273742063999919, 103.9224423712000061 ) ) ; +#34926 = CIRCLE ( 'NONE', #8200, 2.500000000143204115 ) ; +#34927 = ORIENTED_EDGE ( 'NONE', *, *, #24581, .F. ) ; +#34928 = CARTESIAN_POINT ( 'NONE', ( 30.01965015980229978, 186.1545558735057853, 102.6119579121506433 ) ) ; +#34929 = EDGE_LOOP ( 'NONE', ( #17601, #40356, #24411, #21985 ) ) ; +#34930 = FACE_OUTER_BOUND ( 'NONE', #5001, .T. ) ; +#34931 = CARTESIAN_POINT ( 'NONE', ( 24.03005510465546024, 118.3147583197998500, 189.7187950137720804 ) ) ; +#34932 = CARTESIAN_POINT ( 'NONE', ( 15.95630665993094688, 122.0088281219967712, 174.0020537915881960 ) ) ; +#34933 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#34934 = CARTESIAN_POINT ( 'NONE', ( 20.48116099893153574, 206.8503807931785730, 74.54225624234382508 ) ) ; +#34935 = CARTESIAN_POINT ( 'NONE', ( -37.90071030898999993, 191.1265196322999884, 106.2274659473000042 ) ) ; +#34936 = VERTEX_POINT ( 'NONE', #5960 ) ; +#34937 = DIRECTION ( 'NONE', ( -0.0005884949961251572477, 0.2249510543439052768, -0.9743698870671265722 ) ) ; +#34938 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30338, #5799, #30754, #5175, #30140, #40134, #24634, #24011, #8474, #8052 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#34939 = CONICAL_SURFACE ( 'NONE', #17320, 9.999999999997443823, 0.7853981633972965115 ) ; +#34940 = CARTESIAN_POINT ( 'NONE', ( -36.46828157562536177, 191.4819344684914313, 106.4006585949724695 ) ) ; +#34941 = DIRECTION ( 'NONE', ( -0.7933533411653060918, 0.5930537057989944127, 0.1373964268091604213 ) ) ; +#34942 = EDGE_CURVE ( 'NONE', #11505, #10330, #37837, .T. ) ; +#34943 = ADVANCED_FACE ( 'NONE', ( #9439 ), #31312, .T. ) ; +#34944 = VECTOR ( 'NONE', #29252, 1000.000000000000000 ) ; +#34945 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#34946 = ORIENTED_EDGE ( 'NONE', *, *, #1356, .F. ) ; +#34947 = ORIENTED_EDGE ( 'NONE', *, *, #21700, .F. ) ; +#34948 = VERTEX_POINT ( 'NONE', #40297 ) ; +#34949 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825903766432776, 0.0005734119027608631505 ) ) ; +#34950 = AXIS2_PLACEMENT_3D ( 'NONE', #40072, #12281, #33333 ) ; +#34951 = CARTESIAN_POINT ( 'NONE', ( -43.55091174306983959, 114.1088787615071283, 121.9228278241799757 ) ) ; +#34952 = VECTOR ( 'NONE', #33220, 1000.000000000000114 ) ; +#34953 = ORIENTED_EDGE ( 'NONE', *, *, #19633, .T. ) ; +#34954 = CARTESIAN_POINT ( 'NONE', ( -29.94629653533174007, 109.6131156702000027, 90.28587165238377565 ) ) ; +#34955 = CARTESIAN_POINT ( 'NONE', ( 29.09341390908912572, 130.9670914280451655, 89.87148492245351861 ) ) ; +#34956 = LINE ( 'NONE', #34561, #146 ) ; +#34957 = ORIENTED_EDGE ( 'NONE', *, *, #14295, .F. ) ; +#34958 = DIRECTION ( 'NONE', ( -0.0006039748319380209294, -1.272479560138527092E-14, -0.9999998176071845934 ) ) ; +#34959 = ORIENTED_EDGE ( 'NONE', *, *, #34410, .T. ) ; +#34960 = CARTESIAN_POINT ( 'NONE', ( -15.99999263269153182, 160.7450692216915513, 96.77351201758563093 ) ) ; +#34961 = CARTESIAN_POINT ( 'NONE', ( -21.96933725929774894, 130.6372435488027861, 89.82617414751712204 ) ) ; +#34962 = ORIENTED_EDGE ( 'NONE', *, *, #24983, .F. ) ; +#34963 = EDGE_CURVE ( 'NONE', #30170, #37342, #32254, .T. ) ; +#34964 = CARTESIAN_POINT ( 'NONE', ( 35.04675250840001155, 225.9002260768477583, 76.03733726937247184 ) ) ; +#34965 = CARTESIAN_POINT ( 'NONE', ( -1.458415330486092287, 152.0517121852905973, 130.6798743963483673 ) ) ; +#34966 = CARTESIAN_POINT ( 'NONE', ( -26.00945644612357910, 206.1769029671598332, 74.50228096851449777 ) ) ; +#34967 = CARTESIAN_POINT ( 'NONE', ( 2.428684613870999875, 191.0118196296000121, 106.1753971897999946 ) ) ; +#34968 = ORIENTED_EDGE ( 'NONE', *, *, #17460, .T. ) ; +#34969 = CARTESIAN_POINT ( 'NONE', ( -28.42925635489000413, 114.0103269030000064, 152.4718672074000381 ) ) ; +#34970 = CYLINDRICAL_SURFACE ( 'NONE', #6953, 2.000000000000014655 ) ; +#34971 = VECTOR ( 'NONE', #11814, 1000.000000000000227 ) ; +#34972 = EDGE_LOOP ( 'NONE', ( #15865, #29349, #16076, #11870, #13986, #908, #10956, #24933, #22904, #16421, #13273, #22559 ) ) ; +#34973 = CARTESIAN_POINT ( 'NONE', ( 30.77752414631618194, 157.1438219166013823, 186.2335371180630830 ) ) ; +#34974 = CARTESIAN_POINT ( 'NONE', ( 22.50029346826586973, 127.3220923531718825, 89.54710465288404464 ) ) ; +#34975 = CARTESIAN_POINT ( 'NONE', ( -27.56633822591999916, 124.0845406765999996, 91.27092842416000451 ) ) ; +#34976 = CONICAL_SURFACE ( 'NONE', #13455, 6.000000391989175341, 0.7853981633985190891 ) ; +#34977 = ADVANCED_FACE ( 'NONE', ( #15178, #218, #25190 ), #37639, .F. ) ; +#34978 = ORIENTED_EDGE ( 'NONE', *, *, #1879, .F. ) ; +#34979 = CARTESIAN_POINT ( 'NONE', ( -37.28964217851552121, 124.9030048851708870, 93.64309515347758861 ) ) ; +#34980 = CIRCLE ( 'NONE', #17364, 2.000000000000011546 ) ; +#34981 = CARTESIAN_POINT ( 'NONE', ( -17.02496641354574791, 121.6075756348253236, 176.8826037927987329 ) ) ; +#34982 = DIRECTION ( 'NONE', ( 0.0006039748319391906751, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#34983 = DIRECTION ( 'NONE', ( -0.7933535320750288999, 0.5931614265262138419, 0.1369295264925107503 ) ) ; +#34984 = LINE ( 'NONE', #18101, #12621 ) ; +#34985 = EDGE_CURVE ( 'NONE', #3624, #22354, #24328, .T. ) ; +#34986 = ORIENTED_EDGE ( 'NONE', *, *, #4639, .F. ) ; +#34987 = VERTEX_POINT ( 'NONE', #19620 ) ; +#34988 = CARTESIAN_POINT ( 'NONE', ( 26.00236367227700285, 120.1369457580689897, 90.45093567563459658 ) ) ; +#34989 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971559851 ) ) ; +#34990 = CARTESIAN_POINT ( 'NONE', ( -43.18873574177670349, 77.14301703112145958, 291.5846288494013834 ) ) ; +#34991 = EDGE_CURVE ( 'NONE', #8120, #650, #20495, .T. ) ; +#34992 = EDGE_CURVE ( 'NONE', #10351, #16108, #31627, .T. ) ; +#34994 = FACE_OUTER_BOUND ( 'NONE', #38259, .T. ) ; +#34993 = CARTESIAN_POINT ( 'NONE', ( 29.77977117171763055, 126.9465717267340352, 89.45601389182257890 ) ) ; +#34995 = ADVANCED_FACE ( 'NONE', ( #1220 ), #13980, .F. ) ; +#34996 = EDGE_CURVE ( 'NONE', #8652, #2293, #10449, .T. ) ; +#34997 = EDGE_LOOP ( 'NONE', ( #11254, #21541, #34636, #9164 ) ) ; +#34998 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#34999 = VECTOR ( 'NONE', #2046, 1000.000000000000114 ) ; +#35000 = CARTESIAN_POINT ( 'NONE', ( 22.49983404245668339, 158.4318110641182216, 96.38725090939126972 ) ) ; +#35001 = EDGE_LOOP ( 'NONE', ( #15028, #40453, #36019, #29572, #11672, #33539, #27445, #33040, #13964, #23825, #4856, #14415, #15577, #23810 ) ) ; +#35002 = CIRCLE ( 'NONE', #4985, 10.00000000000000000 ) ; +#35003 = AXIS2_PLACEMENT_3D ( 'NONE', #25377, #22107, #13103 ) ; +#35004 = ORIENTED_EDGE ( 'NONE', *, *, #39983, .T. ) ; +#35005 = DIRECTION ( 'NONE', ( -3.736326840320183149E-15, 0.9743700562689210365, 0.2249510912320714373 ) ) ; +#35006 = DIRECTION ( 'NONE', ( -0.7066903833891088338, -9.361005957775119998E-05, 0.7075229277292088836 ) ) ; +#35007 = CARTESIAN_POINT ( 'NONE', ( -45.14000178829265764, 124.4048192737162424, 91.66408474920166327 ) ) ; +#35008 = CARTESIAN_POINT ( 'NONE', ( -15.99847796691061852, 137.5244930513001975, 94.49161329741416182 ) ) ; +#35009 = CIRCLE ( 'NONE', #16727, 7.500000256701354395 ) ; +#35010 = ORIENTED_EDGE ( 'NONE', *, *, #5892, .T. ) ; +#35011 = ORIENTED_EDGE ( 'NONE', *, *, #39969, .F. ) ; +#35012 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319380485765 ) ) ; +#35013 = CIRCLE ( 'NONE', #19265, 2.499999999403085482 ) ; +#35014 = CARTESIAN_POINT ( 'NONE', ( -18.25047883326706355, 126.3894863778989333, 174.4205395528727252 ) ) ; +#35015 = FACE_OUTER_BOUND ( 'NONE', #25152, .T. ) ; +#35016 = ORIENTED_EDGE ( 'NONE', *, *, #25133, .F. ) ; +#35017 = EDGE_CURVE ( 'NONE', #3655, #4731, #7422, .T. ) ; +#35018 = CARTESIAN_POINT ( 'NONE', ( -21.76110230804757251, 213.2747375211771157, 73.57169191246816808 ) ) ; +#35019 = ORIENTED_EDGE ( 'NONE', *, *, #19852, .F. ) ; +#35020 = CARTESIAN_POINT ( 'NONE', ( -40.55663739063097495, 184.8193262793114684, 102.8594742714778363 ) ) ; +#35021 = CARTESIAN_POINT ( 'NONE', ( -13.47595942998339602, 154.4041677293344321, 95.30807215510701269 ) ) ; +#35022 = ORIENTED_EDGE ( 'NONE', *, *, #37346, .T. ) ; +#35023 = CARTESIAN_POINT ( 'NONE', ( -20.49970645903284705, 184.8492302318938698, 102.8542671896393301 ) ) ; +#35024 = CARTESIAN_POINT ( 'NONE', ( -2.556630992790999812, 191.0097281923000025, 106.4446402598999981 ) ) ; +#35025 = FACE_OUTER_BOUND ( 'NONE', #22367, .T. ) ; +#35026 = ADVANCED_FACE ( 'NONE', ( #38035 ), #22917, .T. ) ; +#35027 = VECTOR ( 'NONE', #15244, 1000.000000000000114 ) ; +#35028 = ORIENTED_EDGE ( 'NONE', *, *, #35865, .F. ) ; +#35029 = CARTESIAN_POINT ( 'NONE', ( -39.03036842895058811, 175.8132598316807105, 136.1868359458795510 ) ) ; +#35030 = CARTESIAN_POINT ( 'NONE', ( -25.00047486325557955, 116.5768236846756452, 87.78270791410004392 ) ) ; +#35031 = AXIS2_PLACEMENT_3D ( 'NONE', #983, #7116, #19590 ) ; +#35032 = CARTESIAN_POINT ( 'NONE', ( -39.69437836998564251, 161.5619712970498085, 197.5056430804474985 ) ) ; +#35033 = CIRCLE ( 'NONE', #17418, 2.500000000016445512 ) ; +#35034 = DIRECTION ( 'NONE', ( -0.0002393071182785117045, -0.2252352986010040525, 0.9743043687658490271 ) ) ; +#35035 = ADVANCED_FACE ( 'NONE', ( #9847 ), #27719, .F. ) ; +#35036 = DIRECTION ( 'NONE', ( 0.0006039748319392653766, -1.164951251755207723E-15, 0.9999998176071847045 ) ) ; +#35037 = CARTESIAN_POINT ( 'NONE', ( 22.49999922077098802, 138.5120027357782817, 91.61734752324643694 ) ) ; +#35038 = VERTEX_POINT ( 'NONE', #19213 ) ; +#35039 = EDGE_CURVE ( 'NONE', #4383, #24627, #22488, .T. ) ; +#35040 = CARTESIAN_POINT ( 'NONE', ( -19.99823943612422994, 184.2798415734382900, 105.2882683904008729 ) ) ; +#35041 = CARTESIAN_POINT ( 'NONE', ( -15.83323121387661025, 126.7633287966969391, 89.09915948006083397 ) ) ; +#35042 = ADVANCED_FACE ( 'NONE', ( #28843 ), #38630, .F. ) ; +#35043 = CARTESIAN_POINT ( 'NONE', ( -35.31151715239000310, 112.3631398901000154, 90.42436770938999757 ) ) ; +#35044 = EDGE_CURVE ( 'NONE', #30145, #7067, #40119, .T. ) ; +#35045 = ORIENTED_EDGE ( 'NONE', *, *, #16778, .F. ) ; +#35046 = LINE ( 'NONE', #4384, #3402 ) ; +#35047 = ORIENTED_EDGE ( 'NONE', *, *, #29310, .T. ) ; +#35048 = CARTESIAN_POINT ( 'NONE', ( 12.40625381042950615, 158.3833092224484744, 96.21109731316822433 ) ) ; +#35049 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#35050 = CARTESIAN_POINT ( 'NONE', ( -28.07003853489823797, 124.9673608855255793, 88.52086302510028304 ) ) ; +#35051 = CARTESIAN_POINT ( 'NONE', ( 23.36759919406680908, 177.7446085781720910, 100.7170137555415579 ) ) ; +#35052 = EDGE_LOOP ( 'NONE', ( #13316, #6517, #25711, #24802 ) ) ; +#35053 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921592953, -0.2249510932971527932 ) ) ; +#35054 = VERTEX_POINT ( 'NONE', #4280 ) ; +#35055 = VERTEX_POINT ( 'NONE', #6954 ) ; +#35056 = VERTEX_POINT ( 'NONE', #25593 ) ; +#35057 = CARTESIAN_POINT ( 'NONE', ( -19.70071604027683065, 149.4445624503525778, 181.7665744593643637 ) ) ; +#35058 = DIRECTION ( 'NONE', ( -0.0002393071182782278061, -0.2252352986010052738, 0.9743043687658489160 ) ) ; +#35059 = PLANE ( 'NONE', #35233 ) ; +#35060 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18018, #12308, #21725, #37254 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35061 = AXIS2_PLACEMENT_3D ( 'NONE', #28667, #13132, #19832 ) ; +#35062 = VERTEX_POINT ( 'NONE', #10036 ) ; +#35063 = CARTESIAN_POINT ( 'NONE', ( -44.46004285478915108, 188.8078265508242168, 105.8352584314367135 ) ) ; +#35064 = FACE_OUTER_BOUND ( 'NONE', #6818, .T. ) ; +#35065 = CARTESIAN_POINT ( 'NONE', ( 36.49023395156999783, 191.9050315565999938, 104.5102437693000041 ) ) ; +#35066 = CARTESIAN_POINT ( 'NONE', ( 19.99905349769186458, 193.8169544161346494, 102.6908434160864800 ) ) ; +#35067 = CIRCLE ( 'NONE', #18753, 2.000000000000011546 ) ; +#35068 = CARTESIAN_POINT ( 'NONE', ( 3.882702609269526928, 148.0331269928592519, 129.7473673639204605 ) ) ; +#35069 = CARTESIAN_POINT ( 'NONE', ( 6.034202883963867059, 177.7957208724328666, 100.6935805729036844 ) ) ; +#35070 = FACE_OUTER_BOUND ( 'NONE', #4054, .T. ) ; +#35071 = EDGE_LOOP ( 'NONE', ( #40133, #7138, #292, #13801 ) ) ; +#35072 = CARTESIAN_POINT ( 'NONE', ( 28.45696154535999867, 125.2413582448000113, 88.54986070440000390 ) ) ; +#35073 = CARTESIAN_POINT ( 'NONE', ( -20.51782960591933147, 207.7397650241700831, 76.53117123266314081 ) ) ; +#35074 = CARTESIAN_POINT ( 'NONE', ( -19.37162053837593945, 124.6261895189692410, 178.2150732946192306 ) ) ; +#35075 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927797511552, 0.0005734119022056451695 ) ) ; +#35076 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709481474, 92.27946979429643193, 322.5205145037750754 ) ) ; +#35077 = ORIENTED_EDGE ( 'NONE', *, *, #3350, .F. ) ; +#35078 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; +#35079 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; +#35080 = CARTESIAN_POINT ( 'NONE', ( 20.50029380412308555, 187.0408239564538917, 103.3354524056335464 ) ) ; +#35081 = EDGE_CURVE ( 'NONE', #16566, #16326, #19423, .T. ) ; +#35082 = EDGE_CURVE ( 'NONE', #32479, #31880, #10736, .T. ) ; +#35083 = FACE_OUTER_BOUND ( 'NONE', #12370, .T. ) ; +#35084 = ADVANCED_FACE ( 'NONE', ( #16755 ), #31003, .F. ) ; +#35085 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#35086 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559019 ) ) ; +#35087 = CARTESIAN_POINT ( 'NONE', ( -22.49823197369664385, 160.0613479605241878, 99.70157044293461013 ) ) ; +#35088 = CARTESIAN_POINT ( 'NONE', ( 28.26067382423566698, 125.1347711400599110, 91.09124888412546284 ) ) ; +#35089 = ORIENTED_EDGE ( 'NONE', *, *, #22807, .F. ) ; +#35090 = VECTOR ( 'NONE', #31091, 1000.000000000000000 ) ; +#35091 = AXIS2_PLACEMENT_3D ( 'NONE', #12594, #28554, #12812 ) ; +#35092 = DIRECTION ( 'NONE', ( -0.7730662169443226484, -0.5272861007345266415, -0.3526159273084134571 ) ) ; +#35093 = EDGE_CURVE ( 'NONE', #10007, #1363, #35142, .T. ) ; +#35094 = FACE_OUTER_BOUND ( 'NONE', #4726, .T. ) ; +#35095 = CARTESIAN_POINT ( 'NONE', ( -39.03036842907830106, 121.1728496032269078, 123.5553118490896907 ) ) ; +#35096 = CARTESIAN_POINT ( 'NONE', ( -21.82845856935587037, 135.5369429020799146, 93.52303473086848840 ) ) ; +#35097 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971546251 ) ) ; +#35098 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714601725811, 0.5299193037554699170 ) ) ; +#35099 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; +#35100 = CARTESIAN_POINT ( 'NONE', ( 25.99876818124551292, 118.1164810761916470, 87.25208046938912787 ) ) ; +#35101 = ORIENTED_EDGE ( 'NONE', *, *, #12138, .T. ) ; +#35102 = EDGE_CURVE ( 'NONE', #34329, #38824, #17153, .T. ) ; +#35103 = CARTESIAN_POINT ( 'NONE', ( -2.954045212696999823, 209.2037278823000293, 76.12424252725000429 ) ) ; +#35104 = DIRECTION ( 'NONE', ( -0.0002267487151011638629, -0.6230052038431761474, -0.7822176580526309930 ) ) ; +#35105 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#35106 = ORIENTED_EDGE ( 'NONE', *, *, #15195, .F. ) ; +#35107 = LINE ( 'NONE', #19981, #16119 ) ; +#35108 = EDGE_LOOP ( 'NONE', ( #32188, #6226, #14005, #25442 ) ) ; +#35109 = CARTESIAN_POINT ( 'NONE', ( -20.00062605139820704, 196.5784656963837733, 103.8871944330217048 ) ) ; +#35110 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29419, #38789, #10811, #22486 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35111 = CARTESIAN_POINT ( 'NONE', ( 20.50146814542411278, 184.4050074329408915, 104.7795556516932436 ) ) ; +#35112 = CARTESIAN_POINT ( 'NONE', ( -48.00650188892534942, 61.15928328279086656, 282.5875370178958406 ) ) ; +#35113 = CARTESIAN_POINT ( 'NONE', ( -44.59335596552107717, 185.9876800833566790, 106.7142618130726248 ) ) ; +#35114 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3911, #242, #28671, #28867 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35115 = CARTESIAN_POINT ( 'NONE', ( -12.63724133153108120, 130.4695180992949304, 90.25279237546679667 ) ) ; +#35116 = AXIS2_PLACEMENT_3D ( 'NONE', #6017, #25247, #3741 ) ; +#35117 = LINE ( 'NONE', #1200, #26929 ) ; +#35118 = VERTEX_POINT ( 'NONE', #29653 ) ; +#35119 = CARTESIAN_POINT ( 'NONE', ( 41.04644941592703589, 219.0860688542000219, 75.53371351154709146 ) ) ; +#35120 = DIRECTION ( 'NONE', ( -0.6088835995545407442, -0.7728434649458200134, -0.1788120266761852595 ) ) ; +#35121 = CARTESIAN_POINT ( 'NONE', ( -23.02004673814065683, 213.5902071504527839, 73.57250091739375364 ) ) ; +#35122 = EDGE_CURVE ( 'NONE', #14988, #1098, #25782, .T. ) ; +#35123 = CARTESIAN_POINT ( 'NONE', ( -36.43359215879000601, 191.8492174557999874, 104.5507527933000063 ) ) ; +#35124 = EDGE_CURVE ( 'NONE', #30815, #33611, #9681, .T. ) ; +#35125 = VERTEX_POINT ( 'NONE', #14921 ) ; +#35126 = FACE_OUTER_BOUND ( 'NONE', #16173, .T. ) ; +#35127 = ADVANCED_FACE ( 'NONE', ( #1627 ), #38828, .T. ) ; +#35128 = ORIENTED_EDGE ( 'NONE', *, *, #26655, .F. ) ; +#35129 = CARTESIAN_POINT ( 'NONE', ( 36.76043236804844838, 115.8485703968537592, 89.69953496976647500 ) ) ; +#35130 = FACE_OUTER_BOUND ( 'NONE', #1756, .T. ) ; +#35131 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38643, #1648, #20661, #1856 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35132 = EDGE_CURVE ( 'NONE', #33670, #13982, #39422, .T. ) ; +#35133 = DIRECTION ( 'NONE', ( 0.0005884949961252946161, -0.2249510543439068866, 0.9743698870671261281 ) ) ; +#35134 = CARTESIAN_POINT ( 'NONE', ( 25.02082990279377128, 130.0549946889516377, 92.22913080465953328 ) ) ; +#35135 = CARTESIAN_POINT ( 'NONE', ( -28.35055378863404485, 124.9527156439775979, 91.25446313298311907 ) ) ; +#35136 = CARTESIAN_POINT ( 'NONE', ( 12.64386512242256266, 130.3482773188944748, 92.81742853362089818 ) ) ; +#35137 = ADVANCED_FACE ( 'NONE', ( #10850 ), #16579, .F. ) ; +#35138 = CIRCLE ( 'NONE', #4478, 5.500000000097090336 ) ; +#35139 = FACE_OUTER_BOUND ( 'NONE', #29689, .T. ) ; +#35140 = CARTESIAN_POINT ( 'NONE', ( -37.34822902193999994, 190.8540540390999922, 106.4250283690000032 ) ) ; +#35141 = VERTEX_POINT ( 'NONE', #5300 ) ; +#35142 = LINE ( 'NONE', #35537, #22513 ) ; +#35143 = AXIS2_PLACEMENT_3D ( 'NONE', #32494, #12894, #404 ) ; +#35144 = DIRECTION ( 'NONE', ( 0.0006039748319385852566, 1.189165140469103041E-14, 0.9999998176071845934 ) ) ; +#35145 = LINE ( 'NONE', #13706, #20964 ) ; +#35146 = AXIS2_PLACEMENT_3D ( 'NONE', #17038, #32598, #20734 ) ; +#35147 = VECTOR ( 'NONE', #9629, 1000.000000000000000 ) ; +#35149 = EDGE_LOOP ( 'NONE', ( #40409, #30988, #14297, #33203 ) ) ; +#35148 = CARTESIAN_POINT ( 'NONE', ( -20.50049831744469842, 193.8789906621226180, 103.5560030610153035 ) ) ; +#35150 = ORIENTED_EDGE ( 'NONE', *, *, #6433, .F. ) ; +#35151 = EDGE_LOOP ( 'NONE', ( #1182, #17964, #21967 ) ) ; +#35152 = EDGE_CURVE ( 'NONE', #802, #32145, #14729, .T. ) ; +#35153 = ORIENTED_EDGE ( 'NONE', *, *, #36027, .T. ) ; +#35154 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#35155 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26227, #13943, #14156, #7796 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35156 = CARTESIAN_POINT ( 'NONE', ( 39.01817161878246054, 208.8753323438758684, 28.69844957298887067 ) ) ; +#35157 = ORIENTED_EDGE ( 'NONE', *, *, #38743, .F. ) ; +#35158 = FACE_BOUND ( 'NONE', #12598, .T. ) ; +#35159 = CARTESIAN_POINT ( 'NONE', ( -38.49678016213000831, 119.1204962500000022, 90.30251346168999760 ) ) ; +#35160 = CARTESIAN_POINT ( 'NONE', ( 28.46953594426098277, 131.0252485042709338, 89.88531577736306133 ) ) ; +#35161 = FACE_OUTER_BOUND ( 'NONE', #28029, .T. ) ; +#35162 = CARTESIAN_POINT ( 'NONE', ( -13.50000077916642560, 160.7384646679227558, 96.77047473222738461 ) ) ; +#35163 = ORIENTED_EDGE ( 'NONE', *, *, #27256, .T. ) ; +#35164 = DIRECTION ( 'NONE', ( 0.0001408373285424074114, -0.2255194992995608605, 0.9742386440706004569 ) ) ; +#35165 = ORIENTED_EDGE ( 'NONE', *, *, #24285, .T. ) ; +#35166 = CARTESIAN_POINT ( 'NONE', ( 41.88489195034309631, 131.9654069037970885, 291.5332465100412378 ) ) ; +#35167 = CYLINDRICAL_SURFACE ( 'NONE', #8989, 6.000000000000001776 ) ; +#35168 = CARTESIAN_POINT ( 'NONE', ( -25.98974790844193805, 191.1599268335846205, 106.8726442723167906 ) ) ; +#35169 = CARTESIAN_POINT ( 'NONE', ( -20.61078737510752035, 183.3266213687619484, 101.9896571849372435 ) ) ; +#35170 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #26582, #39026, #26377, #29846 ), + .UNSPECIFIED., .F., .F. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 2.231945410930857410, 2.405425884341014342 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9974936158455707247, 0.9974936158455707247, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#35171 = CARTESIAN_POINT ( 'NONE', ( 41.45122645698029373, 120.4517748362497116, 90.34423067234534699 ) ) ; +#35172 = ORIENTED_EDGE ( 'NONE', *, *, #5377, .T. ) ; +#35173 = ORIENTED_EDGE ( 'NONE', *, *, #15549, .F. ) ; +#35174 = VECTOR ( 'NONE', #5468, 1000.000000000000000 ) ; +#35175 = CARTESIAN_POINT ( 'NONE', ( -15.83323216943059286, 160.7053846678046511, 96.93530097182505756 ) ) ; +#35176 = CARTESIAN_POINT ( 'NONE', ( -49.68457868370908415, 77.14301703112184327, 322.0012719045439553 ) ) ; +#35177 = CARTESIAN_POINT ( 'NONE', ( -13.54340897191000082, 191.1065010711000127, 28.07991271570000080 ) ) ; +#35178 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474981076715680, 160.6646604414378317, 99.31104281998236161 ) ) ; +#35179 = CIRCLE ( 'NONE', #25475, 5.999999999874873424 ) ; +#35180 = AXIS2_PLACEMENT_3D ( 'NONE', #31313, #35144, #12699 ) ; +#35181 = ORIENTED_EDGE ( 'NONE', *, *, #36409, .F. ) ; +#35182 = ADVANCED_FACE ( 'NONE', ( #26795 ), #35747, .T. ) ; +#35183 = ORIENTED_EDGE ( 'NONE', *, *, #14868, .T. ) ; +#35184 = CARTESIAN_POINT ( 'NONE', ( -25.50801647358826330, 207.5985922142114646, 76.64904513840518518 ) ) ; +#35185 = CARTESIAN_POINT ( 'NONE', ( -20.35337581324051115, 211.0888623383745255, 73.40409155960517751 ) ) ; +#35186 = ADVANCED_FACE ( 'NONE', ( #33104 ), #7445, .T. ) ; +#35187 = EDGE_LOOP ( 'NONE', ( #3571, #19128, #4182, #32462 ) ) ; +#35188 = CIRCLE ( 'NONE', #30672, 39.99999999998085798 ) ; +#35189 = PLANE ( 'NONE', #17981 ) ; +#35190 = ORIENTED_EDGE ( 'NONE', *, *, #9053, .T. ) ; +#35191 = DIRECTION ( 'NONE', ( -0.0002393070154807157670, -0.2243321270833621428, 0.9745127189987858873 ) ) ; +#35192 = CARTESIAN_POINT ( 'NONE', ( -19.99828328446849213, 119.4206128148076971, 90.31427449916516537 ) ) ; +#35193 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#35194 = CARTESIAN_POINT ( 'NONE', ( -20.00012105759590852, 119.3449816728147113, 87.27986393354494510 ) ) ; +#35195 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #36284, #1950 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35196 = EDGE_LOOP ( 'NONE', ( #3278, #2935, #33619, #8140 ) ) ; +#35197 = CARTESIAN_POINT ( 'NONE', ( 26.00563501201460070, 120.2359422930459942, 90.47773590256639409 ) ) ; +#35198 = CARTESIAN_POINT ( 'NONE', ( -15.93427371774434498, 152.6093780528373998, 94.89519699369660088 ) ) ; +#35199 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32826, #1757, #26309, #4806 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35201 = CARTESIAN_POINT ( 'NONE', ( -8.423747253435195148, 151.9722686346081844, 94.74357249814669046 ) ) ; +#35200 = CARTESIAN_POINT ( 'NONE', ( 20.48136443024816344, 209.7093559074854454, 75.54613107284740181 ) ) ; +#35202 = AXIS2_PLACEMENT_3D ( 'NONE', #2176, #20145, #29571 ) ; +#35203 = EDGE_CURVE ( 'NONE', #10734, #8110, #27078, .T. ) ; +#35204 = FACE_OUTER_BOUND ( 'NONE', #28713, .T. ) ; +#35205 = FACE_OUTER_BOUND ( 'NONE', #34861, .T. ) ; +#35206 = EDGE_LOOP ( 'NONE', ( #9287, #33813, #29255, #4345 ) ) ; +#35207 = CARTESIAN_POINT ( 'NONE', ( 29.62444488996374403, 185.2955461510884732, 104.9796392865966652 ) ) ; +#35208 = CIRCLE ( 'NONE', #13690, 4.999999999999990230 ) ; +#35209 = CIRCLE ( 'NONE', #17592, 2.500000000003542056 ) ; +#35210 = DIRECTION ( 'NONE', ( 0.1305263947718645068, -0.9660168729586927627, -0.2231014599391233644 ) ) ; +#35211 = ORIENTED_EDGE ( 'NONE', *, *, #34846, .T. ) ; +#35212 = ORIENTED_EDGE ( 'NONE', *, *, #11536, .T. ) ; +#35213 = CARTESIAN_POINT ( 'NONE', ( 39.06348233968999750, 118.7303302136000127, 89.50758646506000105 ) ) ; +#35214 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#35215 = CARTESIAN_POINT ( 'NONE', ( 5.667983148732107956, 187.2950682004077407, 105.4557345120219480 ) ) ; +#35216 = CARTESIAN_POINT ( 'NONE', ( -2.813949932869999948, 190.8925433558999885, 106.6795638709999992 ) ) ; +#35217 = VERTEX_POINT ( 'NONE', #30061 ) ; +#35218 = EDGE_CURVE ( 'NONE', #34375, #18635, #900, .T. ) ; +#35219 = VERTEX_POINT ( 'NONE', #32711 ) ; +#35220 = CARTESIAN_POINT ( 'NONE', ( 28.45310815370287472, 181.6925917411357148, 101.5827842051393617 ) ) ; +#35221 = CARTESIAN_POINT ( 'NONE', ( -23.36442558744370857, 134.3470799714359885, 93.67172226588378692 ) ) ; +#35222 = FACE_OUTER_BOUND ( 'NONE', #15419, .T. ) ; +#35223 = EDGE_LOOP ( 'NONE', ( #26273, #27195, #18016, #1456, #20744, #39692, #1652, #29428, #22827, #32859, #2142, #32138 ) ) ; +#35224 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #28462, #29057, #6563, #10055 ), + ( #6969, #3898, #13523, #31938 ), + ( #32134, #38053, #7369, #435 ), + ( #16563, #28858, #38447, #10466 ), + ( #37656, #6765, #25407, #12711 ), + ( #28267, #35362, #9655, #28661 ), + ( #234, #12928, #19440, #22131 ), + ( #37856, #9863, #25607, #836 ), + ( #31741, #2424, #4299, #39811 ), + ( #32525, #26404, #36965, #4503 ), + ( #24309, #24511, #30632, #33473 ), + ( #23131, #17724, #14696, #10665 ), + ( #27385, #8351, #13720, #40020 ), + ( #5682, #8761, #20813, #11827 ), + ( #29464, #32331, #1237, #12025 ), + ( #36750, #21226, #19826, #33270 ), + ( #17927, #36555, #16770, #26209 ), + ( #33676, #18130, #38642, #2626 ), + ( #15092, #30218, #35554, #29268 ), + ( #7575, #20038, #38849, #5260 ), + ( #10867, #5466, #16965, #30431 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.0006433392557888000136, 0.000000000000000000, 0.001296682710712999910, 0.002598803319325999894, 0.005203044536554999634, 0.01041152697101000064, 0.01562000940545999958, 0.02082849183991999920, 0.03124545670882999948, 0.04166242157774999871, 0.06249635131556999929, 0.08333028105339999880, 0.1249981405290000042, 0.1666660000046999990, 0.2500017189559000097, 0.3333374379073000271, 0.5000030671676000127, 0.6666686964278000227, 0.9999999999941000528 ), + ( 0.1831668826576000053, 0.8168555497535000542 ), + .UNSPECIFIED. ) ; +#35225 = CARTESIAN_POINT ( 'NONE', ( -25.99151835185281456, 191.8641524188973904, 103.9340199701208292 ) ) ; +#35226 = VERTEX_POINT ( 'NONE', #21061 ) ; +#35227 = EDGE_CURVE ( 'NONE', #14541, #4671, #28475, .T. ) ; +#35228 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -9.100188726436994447E-16, -0.0006039748319385940386 ) ) ; +#35229 = EDGE_CURVE ( 'NONE', #19772, #13769, #33308, .T. ) ; +#35230 = EDGE_LOOP ( 'NONE', ( #4221, #24861, #39070, #12997, #21334 ) ) ; +#35231 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748611833, 132.4103119505575421, 92.77713868752084636 ) ) ; +#35232 = AXIS2_PLACEMENT_3D ( 'NONE', #34334, #15733, #24569 ) ; +#35233 = AXIS2_PLACEMENT_3D ( 'NONE', #4396, #16860, #29364 ) ; +#35234 = FACE_OUTER_BOUND ( 'NONE', #27018, .T. ) ; +#35235 = CARTESIAN_POINT ( 'NONE', ( -0.02657825335728297364, 128.5632152146144449, 291.5585599878308471 ) ) ; +#35236 = VERTEX_POINT ( 'NONE', #17346 ) ; +#35237 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17854, #9091, #24445, #39742 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35238 = CIRCLE ( 'NONE', #2658, 5.999999999999789502 ) ; +#35239 = CARTESIAN_POINT ( 'NONE', ( -25.50125996552617025, 117.7859951928936653, 87.78302187812163027 ) ) ; +#35240 = CARTESIAN_POINT ( 'NONE', ( -38.89729174575438009, 162.5740202740032316, 197.7397972150318424 ) ) ; +#35241 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052566002458 ) ) ; +#35242 = CARTESIAN_POINT ( 'NONE', ( -23.33162176516600184, 170.5609214779667582, 152.0219650776430740 ) ) ; +#35243 = ORIENTED_EDGE ( 'NONE', *, *, #31895, .T. ) ; +#35244 = CARTESIAN_POINT ( 'NONE', ( 5.666344154416935730, 188.3446284886178717, 103.1322861692058268 ) ) ; +#35245 = CARTESIAN_POINT ( 'NONE', ( -35.31100466289999673, 112.3975524853999985, 90.42448594319000676 ) ) ; +#35246 = ORIENTED_EDGE ( 'NONE', *, *, #35527, .T. ) ; +#35247 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29666, #38644, #14335, #5318 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.0004271504751604244632 ), + .UNSPECIFIED. ) ; +#35248 = ORIENTED_EDGE ( 'NONE', *, *, #26911, .F. ) ; +#35249 = DIRECTION ( 'NONE', ( -0.0005884949961234662175, 0.2249510543439052490, -0.9743698870671265722 ) ) ; +#35250 = CARTESIAN_POINT ( 'NONE', ( 25.70348165864240997, 190.8952330040411312, 106.4458477250591812 ) ) ; +#35251 = CARTESIAN_POINT ( 'NONE', ( -30.48419462517739831, 161.7460374893126414, 187.3626201019992550 ) ) ; +#35252 = CARTESIAN_POINT ( 'NONE', ( -13.50742204590874351, 123.6898730104831117, 91.29604175845440750 ) ) ; +#35253 = ORIENTED_EDGE ( 'NONE', *, *, #27898, .T. ) ; +#35254 = FACE_BOUND ( 'NONE', #5187, .T. ) ; +#35255 = VERTEX_POINT ( 'NONE', #2251 ) ; +#35256 = ORIENTED_EDGE ( 'NONE', *, *, #40373, .F. ) ; +#35257 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#35259 = CIRCLE ( 'NONE', #31384, 1.749999999975493381 ) ; +#35258 = FACE_BOUND ( 'NONE', #38733, .T. ) ; +#35260 = VECTOR ( 'NONE', #6667, 1000.000000000000000 ) ; +#35261 = FACE_OUTER_BOUND ( 'NONE', #13466, .T. ) ; +#35262 = EDGE_CURVE ( 'NONE', #1497, #29487, #5768, .T. ) ; +#35263 = VECTOR ( 'NONE', #35154, 1000.000000000000114 ) ; +#35264 = EDGE_LOOP ( 'NONE', ( #20737, #9229, #1546, #4123 ) ) ; +#35265 = FACE_OUTER_BOUND ( 'NONE', #29167, .T. ) ; +#35266 = CARTESIAN_POINT ( 'NONE', ( 35.93134371480000055, 113.3923198079000088, 87.62367743737000580 ) ) ; +#35267 = CARTESIAN_POINT ( 'NONE', ( 36.18548434713000006, 191.5942538933000208, 103.9704995337999947 ) ) ; +#35268 = DIRECTION ( 'NONE', ( 0.0002393071182785538528, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#35269 = ADVANCED_FACE ( 'NONE', ( #20223 ), #14317, .T. ) ; +#35270 = FACE_OUTER_BOUND ( 'NONE', #10174, .T. ) ; +#35271 = EDGE_LOOP ( 'NONE', ( #28256, #11300, #11831, #25651, #10881, #8464, #37593 ) ) ; +#35272 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559296 ) ) ; +#35273 = LINE ( 'NONE', #10572, #36171 ) ; +#35274 = CARTESIAN_POINT ( 'NONE', ( -35.93776700278350233, 192.3813625493561119, 104.4100568030667660 ) ) ; +#35275 = EDGE_CURVE ( 'NONE', #27523, #626, #23146, .T. ) ; +#35276 = FACE_OUTER_BOUND ( 'NONE', #32154, .T. ) ; +#35277 = EDGE_CURVE ( 'NONE', #32551, #38636, #10102, .T. ) ; +#35278 = CARTESIAN_POINT ( 'NONE', ( 4.773610636429394205, 135.2457129246372745, 90.87397125982342061 ) ) ; +#35279 = ORIENTED_EDGE ( 'NONE', *, *, #30331, .F. ) ; +#35280 = LINE ( 'NONE', #38179, #12206 ) ; +#35281 = ADVANCED_FACE ( 'NONE', ( #40048 ), #18162, .F. ) ; +#35282 = CARTESIAN_POINT ( 'NONE', ( 0.8177372182200383088, 189.0164223347565837, 103.6894118143446946 ) ) ; +#35283 = CARTESIAN_POINT ( 'NONE', ( -2.088166312711679407, 189.0044830006292500, 106.3682207543857601 ) ) ; +#35284 = CARTESIAN_POINT ( 'NONE', ( 12.63704587999257356, 130.1783046459918296, 92.54531033006117013 ) ) ; +#35285 = FACE_OUTER_BOUND ( 'NONE', #4559, .T. ) ; +#35286 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825933886502897, 0.0005734119020677233775 ) ) ; +#35287 = CARTESIAN_POINT ( 'NONE', ( -3.537752371395798789, 168.4800613451581910, 98.55175200207808928 ) ) ; +#35288 = AXIS2_PLACEMENT_3D ( 'NONE', #24473, #30796, #40375 ) ; +#35289 = CIRCLE ( 'NONE', #17670, 2.999999999999997335 ) ; +#35290 = CARTESIAN_POINT ( 'NONE', ( -21.21281377555379422, 136.1368903374970500, 93.66117170127317593 ) ) ; +#35291 = DIRECTION ( 'NONE', ( 0.0005884949961255130828, -0.2249510543439061094, 0.9743698870671263501 ) ) ; +#35292 = EDGE_LOOP ( 'NONE', ( #17868, #2360, #34465, #2119 ) ) ; +#35293 = CIRCLE ( 'NONE', #17673, 2.000000000000011546 ) ; +#35294 = CONICAL_SURFACE ( 'NONE', #9891, 2.503171224438736964, 0.7853981633558574371 ) ; +#35295 = CARTESIAN_POINT ( 'NONE', ( -9.584790827646999745, 124.5525812144000071, 88.67051502255999651 ) ) ; +#35296 = EDGE_LOOP ( 'NONE', ( #26838, #9699, #31514, #12365 ) ) ; +#35297 = DIRECTION ( 'NONE', ( 0.6068735732728639531, 0.7743428331745974003, 0.1791581501750992012 ) ) ; +#35298 = CARTESIAN_POINT ( 'NONE', ( 5.667234821329739880, 181.5641799568915076, 104.1756018025407826 ) ) ; +#35299 = CARTESIAN_POINT ( 'NONE', ( 37.54454435905000764, 191.1563387468999906, 106.1841328374000000 ) ) ; +#35300 = CARTESIAN_POINT ( 'NONE', ( -41.29162907220920431, 121.2433985071746605, 87.66910399198238224 ) ) ; +#35301 = CARTESIAN_POINT ( 'NONE', ( -5.659900684199740795, 130.3459505314356477, 92.82798007168634058 ) ) ; +#35302 = CARTESIAN_POINT ( 'NONE', ( -22.32836078412000091, 181.4981852331999903, 104.6474796210000022 ) ) ; +#35303 = CARTESIAN_POINT ( 'NONE', ( 13.50302196691861845, 188.2012266813463555, 103.2180489347859691 ) ) ; +#35304 = VERTEX_POINT ( 'NONE', #2665 ) ; +#35305 = CARTESIAN_POINT ( 'NONE', ( -5.669494960691238816, 181.5159006446741046, 104.2113328898530398 ) ) ; +#35306 = CARTESIAN_POINT ( 'NONE', ( -2.421663575686999970, 209.3771755197000175, 75.56751031131001639 ) ) ; +#35307 = CARTESIAN_POINT ( 'NONE', ( -77.81023841339903413, 193.0606421333745288, 189.3780882460293924 ) ) ; +#35308 = EDGE_CURVE ( 'NONE', #31880, #15231, #14664, .T. ) ; +#35309 = FACE_OUTER_BOUND ( 'NONE', #30161, .T. ) ; +#35310 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30429, #27383, #33673, #2215, #39808, #5878, #39606, #18330, #20809, #5680 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.002613673017241889291, 0.2519602547629314349, 0.5013068365086209566, 0.7506534182543105338, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35311 = ORIENTED_EDGE ( 'NONE', *, *, #23025, .F. ) ; +#35312 = CARTESIAN_POINT ( 'NONE', ( 6.035242028283734683, 177.6060540791196161, 100.8120970415375837 ) ) ; +#35313 = VECTOR ( 'NONE', #5062, 1000.000000000000000 ) ; +#35314 = ORIENTED_EDGE ( 'NONE', *, *, #9697, .T. ) ; +#35315 = AXIS2_PLACEMENT_3D ( 'NONE', #8468, #18043, #20930 ) ; +#35316 = ADVANCED_FACE ( 'NONE', ( #15130 ), #21839, .T. ) ; +#35317 = VECTOR ( 'NONE', #16211, 1000.000000000000114 ) ; +#35318 = CARTESIAN_POINT ( 'NONE', ( 20.50029381459099653, 174.4060969901985345, 100.4185135690063362 ) ) ; +#35319 = ORIENTED_EDGE ( 'NONE', *, *, #29534, .F. ) ; +#35320 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385906776 ) ) ; +#35321 = EDGE_CURVE ( 'NONE', #11123, #36191, #37400, .T. ) ; +#35322 = CARTESIAN_POINT ( 'NONE', ( -15.56569021295148225, 147.2757502908357878, 179.8547186837703293 ) ) ; +#35323 = DIRECTION ( 'NONE', ( -0.6319545750169662801, -0.7750053350989876133, 0.0003816847278651969611 ) ) ; +#35324 = CARTESIAN_POINT ( 'NONE', ( -12.63669129660635271, 130.6696852525088559, 90.12771377329683276 ) ) ; +#35325 = CARTESIAN_POINT ( 'NONE', ( -94.40216589637994105, 221.9412051121879301, 195.0241205818432491 ) ) ; +#35326 = EDGE_CURVE ( 'NONE', #14324, #23012, #11607, .T. ) ; +#35327 = ORIENTED_EDGE ( 'NONE', *, *, #24163, .T. ) ; +#35328 = FACE_OUTER_BOUND ( 'NONE', #13616, .T. ) ; +#35329 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825948087824765, 0.0005734119017360681013 ) ) ; +#35330 = CARTESIAN_POINT ( 'NONE', ( -14.89266236493446094, 176.0557335979108018, 100.6496897840496985 ) ) ; +#35331 = CARTESIAN_POINT ( 'NONE', ( -20.51841363792658157, 206.2670792612280479, 75.17265414788577971 ) ) ; +#35332 = ORIENTED_EDGE ( 'NONE', *, *, #20188, .F. ) ; +#35333 = CARTESIAN_POINT ( 'NONE', ( 30.05084665331233040, 185.2025551396690730, 102.9053044903158849 ) ) ; +#35334 = CARTESIAN_POINT ( 'NONE', ( 2.480477375138003371, 209.5058064405000096, 73.55699242858000275 ) ) ; +#35335 = DIRECTION ( 'NONE', ( 0.9999998268369701959, 0.0001323828034717448464, -0.0005734115650244319892 ) ) ; +#35336 = CIRCLE ( 'NONE', #21023, 2.500000000096262998 ) ; +#35337 = CARTESIAN_POINT ( 'NONE', ( 25.37605402239000085, 191.6202422146000401, 106.2585664214000047 ) ) ; +#35338 = AXIS2_PLACEMENT_3D ( 'NONE', #6693, #31663, #38191 ) ; +#35339 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748613609, 132.4103119505519146, 92.77713868754518955 ) ) ; +#35340 = CARTESIAN_POINT ( 'NONE', ( 20.48054274988260559, 208.2527943622279167, 73.78783556188518844 ) ) ; +#35341 = CARTESIAN_POINT ( 'NONE', ( 38.48474620529000134, 118.5518808382999936, 89.80791548221999676 ) ) ; +#35342 = VERTEX_POINT ( 'NONE', #24343 ) ; +#35343 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498906470, 179.0675991014012425, 104.0619761093222309 ) ) ; +#35344 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#35345 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#35347 = ORIENTED_EDGE ( 'NONE', *, *, #442, .T. ) ; +#35346 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971542365 ) ) ; +#35348 = VERTEX_POINT ( 'NONE', #18972 ) ; +#35349 = EDGE_LOOP ( 'NONE', ( #38723, #30346, #1461, #38704 ) ) ; +#35350 = EDGE_LOOP ( 'NONE', ( #23001, #31322, #32584, #16055 ) ) ; +#35351 = CYLINDRICAL_SURFACE ( 'NONE', #13750, 2.000000000000014655 ) ; +#35352 = EDGE_CURVE ( 'NONE', #35446, #27307, #30867, .T. ) ; +#35353 = EDGE_CURVE ( 'NONE', #11983, #12706, #12064, .T. ) ; +#35354 = CARTESIAN_POINT ( 'NONE', ( -13.66810824591000006, 129.8577187306999861, 92.72010578062001684 ) ) ; +#35355 = CARTESIAN_POINT ( 'NONE', ( 76.10630783110904929, 156.2604783516070768, 96.19568201162677212 ) ) ; +#35356 = ADVANCED_FACE ( 'NONE', ( #178 ), #33709, .T. ) ; +#35357 = EDGE_CURVE ( 'NONE', #13536, #32994, #36177, .T. ) ; +#35358 = VERTEX_POINT ( 'NONE', #33912 ) ; +#35359 = CARTESIAN_POINT ( 'NONE', ( 38.56885418974432866, 118.4610218664272452, 89.66265752007532797 ) ) ; +#35360 = FACE_OUTER_BOUND ( 'NONE', #15580, .T. ) ; +#35361 = CARTESIAN_POINT ( 'NONE', ( 6.271009700395496544, 163.8321258783347787, 97.98591366900288335 ) ) ; +#35362 = CARTESIAN_POINT ( 'NONE', ( -38.13584639906000007, 119.0796675878000030, 87.44109768843999575 ) ) ; +#35363 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319370571820 ) ) ; +#35364 = ORIENTED_EDGE ( 'NONE', *, *, #29013, .F. ) ; +#35365 = EDGE_CURVE ( 'NONE', #1422, #24833, #3234, .T. ) ; +#35366 = CYLINDRICAL_SURFACE ( 'NONE', #8854, 7.000000000000007994 ) ; +#35367 = VERTEX_POINT ( 'NONE', #21672 ) ; +#35368 = CARTESIAN_POINT ( 'NONE', ( -3.169891510579954996, 184.7168900243609926, 102.3001085725441754 ) ) ; +#35369 = CARTESIAN_POINT ( 'NONE', ( -25.99525330005595691, 191.0045489946515147, 106.8444116979025296 ) ) ; +#35370 = CARTESIAN_POINT ( 'NONE', ( -21.44693686545786449, 130.1487540525002657, 89.71308199639462089 ) ) ; +#35371 = EDGE_LOOP ( 'NONE', ( #40250, #23289, #11802, #23490 ) ) ; +#35372 = AXIS2_PLACEMENT_3D ( 'NONE', #28268, #12125, #24610 ) ; +#35373 = EDGE_CURVE ( 'NONE', #34038, #29822, #6107, .T. ) ; +#35374 = ORIENTED_EDGE ( 'NONE', *, *, #20759, .T. ) ; +#35375 = CARTESIAN_POINT ( 'NONE', ( -2.617492821688919946, 189.8265782606199821, 103.4779101626839974 ) ) ; +#35376 = CONICAL_SURFACE ( 'NONE', #34736, 2.502999999816233778, 0.7853981634033742054 ) ; +#35377 = CARTESIAN_POINT ( 'NONE', ( -8.472443769278077852, 160.9680296444896328, 99.38619809799159555 ) ) ; +#35378 = CARTESIAN_POINT ( 'NONE', ( 27.71217996750916512, 149.2638841111731267, 291.5418064729402658 ) ) ; +#35379 = ORIENTED_EDGE ( 'NONE', *, *, #33036, .T. ) ; +#35380 = EDGE_LOOP ( 'NONE', ( #26893, #4894, #18936, #3151 ) ) ; +#35381 = DIRECTION ( 'NONE', ( -0.0005884949961181158967, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#35382 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 177.2079272831676349, 102.1149241508814072 ) ) ; +#35383 = ORIENTED_EDGE ( 'NONE', *, *, #9048, .T. ) ; +#35384 = CARTESIAN_POINT ( 'NONE', ( -42.09262134878026984, 120.7842458853916270, 90.64249682962069699 ) ) ; +#35385 = ORIENTED_EDGE ( 'NONE', *, *, #14172, .F. ) ; +#35386 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#35387 = CARTESIAN_POINT ( 'NONE', ( -5.669876936568486236, 184.1246770555471244, 102.1617171593053399 ) ) ; +#35388 = DIRECTION ( 'NONE', ( -0.4292255961656983310, -0.3880767888785662256, -0.8155745174598710845 ) ) ; +#35389 = VERTEX_POINT ( 'NONE', #3038 ) ; +#35390 = CARTESIAN_POINT ( 'NONE', ( 26.00229951832000097, 120.2367750635000050, 90.47450760225000010 ) ) ; +#35391 = CARTESIAN_POINT ( 'NONE', ( -23.36030038340052428, 176.7386739072689181, 103.0361307674479150 ) ) ; +#35392 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #39630, #5701, #20834, #18146 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35393 = AXIS2_PLACEMENT_3D ( 'NONE', #9169, #11633, #18138 ) ; +#35395 = CARTESIAN_POINT ( 'NONE', ( -13.49052885539015278, 188.3420772061585353, 103.1432726234667427 ) ) ; +#35394 = LINE ( 'NONE', #32561, #857 ) ; +#35396 = CIRCLE ( 'NONE', #1480, 1.999999999958659069 ) ; +#35397 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971540422 ) ) ; +#35398 = ORIENTED_EDGE ( 'NONE', *, *, #14176, .F. ) ; +#35399 = CARTESIAN_POINT ( 'NONE', ( -16.54155363837897852, 122.5136119920553739, 174.6120670712284948 ) ) ; +#35400 = CYLINDRICAL_SURFACE ( 'NONE', #18446, 8.999999999999994671 ) ; +#35401 = CARTESIAN_POINT ( 'NONE', ( 39.01961100019079964, 121.1792603210674883, 123.5275808914922209 ) ) ; +#35402 = EDGE_CURVE ( 'NONE', #23549, #22970, #15686, .T. ) ; +#35403 = ORIENTED_EDGE ( 'NONE', *, *, #40461, .F. ) ; +#35404 = EDGE_CURVE ( 'NONE', #21943, #31524, #25141, .T. ) ; +#35405 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #7756, #19813, #4696, #17154 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 5.624397334887860644, 5.624458001010823160 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999996933017776, 0.9999999996933017776, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#35406 = ORIENTED_EDGE ( 'NONE', *, *, #17740, .T. ) ; +#35407 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 77.27946979429634666, 315.0857197240631535 ) ) ; +#35408 = CARTESIAN_POINT ( 'NONE', ( -5.668109640120363224, 183.4491314654635801, 105.0878260507181778 ) ) ; +#35409 = CARTESIAN_POINT ( 'NONE', ( -2.687146238409999999, 191.2630064568000137, 104.0676670321000046 ) ) ; +#35410 = ORIENTED_EDGE ( 'NONE', *, *, #24342, .F. ) ; +#35411 = VERTEX_POINT ( 'NONE', #3830 ) ; +#35412 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; +#35413 = CARTESIAN_POINT ( 'NONE', ( -20.01528478583289328, 211.0902260919000355, 76.07370820307239967 ) ) ; +#35414 = ORIENTED_EDGE ( 'NONE', *, *, #1041, .T. ) ; +#35415 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; +#35416 = CIRCLE ( 'NONE', #21755, 2.250000000020502711 ) ; +#35417 = CARTESIAN_POINT ( 'NONE', ( -38.46044104337040181, 118.4609804511839286, 89.70916240556151422 ) ) ; +#35418 = AXIS2_PLACEMENT_3D ( 'NONE', #26296, #36492, #20963 ) ; +#35419 = CARTESIAN_POINT ( 'NONE', ( 3.080954507411690191, 190.8735473523590258, 106.8151959787420395 ) ) ; +#35420 = ORIENTED_EDGE ( 'NONE', *, *, #23813, .T. ) ; +#35421 = CARTESIAN_POINT ( 'NONE', ( -13.49836187949100896, 187.2925309122496458, 105.4667247227192490 ) ) ; +#35422 = EDGE_CURVE ( 'NONE', #10112, #15231, #1292, .T. ) ; +#35423 = CIRCLE ( 'NONE', #23708, 2.000000000000011546 ) ; +#35424 = CARTESIAN_POINT ( 'NONE', ( -2.252216305542000363, 190.5226222670000027, 106.0270197027000165 ) ) ; +#35425 = CARTESIAN_POINT ( 'NONE', ( 20.06084863214461222, 152.5895191265099413, 94.86887204652431649 ) ) ; +#35426 = CARTESIAN_POINT ( 'NONE', ( -28.52494644200928064, 186.7521494213145559, 105.8641958179564568 ) ) ; +#35427 = EDGE_LOOP ( 'NONE', ( #9724, #201, #12933, #9000 ) ) ; +#35428 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971579558 ) ) ; +#35429 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265225566, -0.1368326740407718733 ) ) ; +#35430 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041179888821108E-05, -0.0002331579774886881676 ) ) ; +#35431 = PLANE ( 'NONE', #9569 ) ; +#35432 = ORIENTED_EDGE ( 'NONE', *, *, #30227, .F. ) ; +#35433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #4120, #13744, #26432, #1467 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35434 = CARTESIAN_POINT ( 'NONE', ( 44.05412252654215877, 112.8136638115830834, 88.23716000583523567 ) ) ; +#35435 = CARTESIAN_POINT ( 'NONE', ( -36.00659248622000064, 115.9892317533000039, 90.43727891404999752 ) ) ; +#35436 = ORIENTED_EDGE ( 'NONE', *, *, #11434, .F. ) ; +#35437 = CIRCLE ( 'NONE', #19118, 4.999999999999990230 ) ; +#35438 = ORIENTED_EDGE ( 'NONE', *, *, #25115, .T. ) ; +#35439 = FACE_OUTER_BOUND ( 'NONE', #28335, .T. ) ; +#35440 = CARTESIAN_POINT ( 'NONE', ( 25.49922775442078660, 119.7987478901816019, 87.80838759742935906 ) ) ; +#35441 = CARTESIAN_POINT ( 'NONE', ( -13.49994987718039852, 124.0778690969012956, 91.05358209079831511 ) ) ; +#35442 = EDGE_CURVE ( 'NONE', #14988, #9823, #25231, .T. ) ; +#35444 = ORIENTED_EDGE ( 'NONE', *, *, #30788, .F. ) ; +#35443 = CIRCLE ( 'NONE', #17832, 2.500000000044359627 ) ; +#35445 = EDGE_CURVE ( 'NONE', #9915, #28941, #16706, .T. ) ; +#35446 = VERTEX_POINT ( 'NONE', #35095 ) ; +#35447 = CARTESIAN_POINT ( 'NONE', ( -20.49852834234505039, 173.9502348336490059, 102.3906403256567756 ) ) ; +#35448 = ORIENTED_EDGE ( 'NONE', *, *, #25861, .F. ) ; +#35449 = ORIENTED_EDGE ( 'NONE', *, *, #27662, .T. ) ; +#35450 = ORIENTED_EDGE ( 'NONE', *, *, #39623, .F. ) ; +#35451 = CARTESIAN_POINT ( 'NONE', ( -6.036395961976134927, 177.5005587908726739, 100.8839412545769250 ) ) ; +#35452 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#35453 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 1.023300813872001534E-14, 0.7066795775160008564 ) ) ; +#35454 = ORIENTED_EDGE ( 'NONE', *, *, #19593, .T. ) ; +#35455 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32660, #11604, #36536, #1786, #38989, #39594, #17301, #17506, #32853, #35909 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 3.469446951953614189E-18, 0.0004333965559159966220, 0.0008667931118319897746, 0.001300189667747982981, 0.001733586223663976080 ), + .UNSPECIFIED. ) ; +#35456 = CARTESIAN_POINT ( 'NONE', ( -45.58331382029645340, 187.5930969719299526, 105.5207863728867892 ) ) ; +#35457 = LINE ( 'NONE', #32234, #16525 ) ; +#35458 = CARTESIAN_POINT ( 'NONE', ( 37.34957747189999822, 117.2309573341999993, 87.81489789069999574 ) ) ; +#35459 = DIRECTION ( 'NONE', ( -0.0005884949961244385300, 0.2249510543439064425, -0.9743698870671262391 ) ) ; +#35460 = CARTESIAN_POINT ( 'NONE', ( -16.89916622456234307, 146.7648798331369164, 183.8224697288354150 ) ) ; +#35461 = ORIENTED_EDGE ( 'NONE', *, *, #5580, .F. ) ; +#35462 = CARTESIAN_POINT ( 'NONE', ( -0.4015627584113334314, 211.0000000000000000, 162.9824824849015670 ) ) ; +#35463 = VERTEX_POINT ( 'NONE', #4032 ) ; +#35464 = CARTESIAN_POINT ( 'NONE', ( -20.51811334323642910, 208.1210146940394452, 76.12436689659175215 ) ) ; +#35465 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; +#35466 = CARTESIAN_POINT ( 'NONE', ( -25.78009354425976696, 116.9859542164271318, 90.28335536971354713 ) ) ; +#35467 = CARTESIAN_POINT ( 'NONE', ( 44.87323697063200001, 186.3386389082236860, 107.7764265916358113 ) ) ; +#35468 = EDGE_LOOP ( 'NONE', ( #5758, #8549, #38478, #15336 ) ) ; +#35469 = CARTESIAN_POINT ( 'NONE', ( -22.59538023922501893, 158.3009455569410022, 96.21322226912832321 ) ) ; +#35470 = EDGE_CURVE ( 'NONE', #35915, #13040, #15945, .T. ) ; +#35471 = CARTESIAN_POINT ( 'NONE', ( 0.6422618799637411779, 189.0014566651755104, 103.6871524997584686 ) ) ; +#35472 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19945, #13240, #38176, #38368 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35473 = CIRCLE ( 'NONE', #21810, 5.500000000097090336 ) ; +#35474 = CYLINDRICAL_SURFACE ( 'NONE', #21512, 2.000000000000014655 ) ; +#35475 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178582662422E-05, 0.0002331579774919529443 ) ) ; +#35476 = CONICAL_SURFACE ( 'NONE', #16550, 3.003200675574637657, 0.7854054504739538256 ) ; +#35477 = CARTESIAN_POINT ( 'NONE', ( -25.62261855603000171, 191.5186909694000121, 104.2706622284000133 ) ) ; +#35478 = CARTESIAN_POINT ( 'NONE', ( -3.893460976763133630, 148.0324882894217069, 129.7501302146819171 ) ) ; +#35479 = PLANE ( 'NONE', #1976 ) ; +#35480 = VECTOR ( 'NONE', #10009, 1000.000000000000227 ) ; +#35481 = ORIENTED_EDGE ( 'NONE', *, *, #13429, .T. ) ; +#35482 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1838, #33507, #39843, #11857 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0006366642741689145695, 0.003636664277312400863 ), + .UNSPECIFIED. ) ; +#35483 = EDGE_CURVE ( 'NONE', #81, #20733, #21197, .T. ) ; +#35484 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#35485 = EDGE_CURVE ( 'NONE', #21843, #1318, #29203, .T. ) ; +#35486 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560684 ) ) ; +#35487 = ORIENTED_EDGE ( 'NONE', *, *, #22058, .T. ) ; +#35488 = CARTESIAN_POINT ( 'NONE', ( 22.99918985293999540, 115.6131156702015801, 87.75369723384940812 ) ) ; +#35489 = DIRECTION ( 'NONE', ( 0.0002393071182785117045, 0.2252352986010040525, -0.9743043687658490271 ) ) ; +#35490 = CARTESIAN_POINT ( 'NONE', ( 38.03365593150000024, 190.8184203288000163, 106.3742049819999949 ) ) ; +#35491 = CARTESIAN_POINT ( 'NONE', ( 36.08477202003000173, 192.3114799085000186, 105.7099035117999932 ) ) ; +#35492 = FACE_OUTER_BOUND ( 'NONE', #12662, .T. ) ; +#35493 = ADVANCED_FACE ( 'NONE', ( #972, #7105 ), #16308, .T. ) ; +#35494 = EDGE_CURVE ( 'NONE', #11054, #21690, #15006, .T. ) ; +#35495 = CARTESIAN_POINT ( 'NONE', ( 35.42398992542000258, 192.6597620198000129, 106.9956823543000013 ) ) ; +#35496 = ORIENTED_EDGE ( 'NONE', *, *, #25685, .F. ) ; +#35497 = AXIS2_PLACEMENT_3D ( 'NONE', #17200, #11285, #29899 ) ; +#35498 = ADVANCED_FACE ( 'NONE', ( #374 ), #1592, .T. ) ; +#35499 = CARTESIAN_POINT ( 'NONE', ( -13.49823342806667803, 137.5174304068248432, 94.49164181115173733 ) ) ; +#35500 = EDGE_CURVE ( 'NONE', #4793, #39471, #23791, .T. ) ; +#35501 = AXIS2_PLACEMENT_3D ( 'NONE', #15114, #21658, #30853 ) ; +#35502 = CARTESIAN_POINT ( 'NONE', ( -15.66509764276284145, 127.1445024449465677, 91.75281491938407896 ) ) ; +#35503 = CONICAL_SURFACE ( 'NONE', #31645, 4.500000040450202299, 0.7854058041405644897 ) ; +#35504 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#35505 = ORIENTED_EDGE ( 'NONE', *, *, #12189, .T. ) ; +#35506 = DIRECTION ( 'NONE', ( 0.0004225984616353902282, -0.2247404086662242728, 0.9744185805510271470 ) ) ; +#35507 = VECTOR ( 'NONE', #19164, 1000.000000000000227 ) ; +#35508 = VERTEX_POINT ( 'NONE', #16115 ) ; +#35509 = LINE ( 'NONE', #26163, #13002 ) ; +#35510 = ORIENTED_EDGE ( 'NONE', *, *, #15273, .F. ) ; +#35511 = CARTESIAN_POINT ( 'NONE', ( 36.26946023011016962, 191.9013689628361874, 106.3928143862155196 ) ) ; +#35512 = DIRECTION ( 'NONE', ( -0.0005884949833308949618, 0.2255194585710127986, -0.9742384859363193428 ) ) ; +#35513 = CARTESIAN_POINT ( 'NONE', ( 21.44693881909371669, 176.9241929811547038, 100.4861407201621120 ) ) ; +#35514 = CARTESIAN_POINT ( 'NONE', ( 39.05471716683091188, 128.1851843108063917, 89.22321456362486458 ) ) ; +#35515 = ORIENTED_EDGE ( 'NONE', *, *, #7444, .T. ) ; +#35516 = CARTESIAN_POINT ( 'NONE', ( 16.56072393625937167, 151.7650864655652185, 183.4529734625197648 ) ) ; +#35517 = LINE ( 'NONE', #4056, #38816 ) ; +#35518 = CARTESIAN_POINT ( 'NONE', ( 4.773550690431221710, 177.4841922203888203, 100.6254943855425097 ) ) ; +#35519 = CARTESIAN_POINT ( 'NONE', ( -22.78255965921956161, 158.2257193261845316, 98.76172871125201880 ) ) ; +#35520 = VERTEX_POINT ( 'NONE', #22472 ) ; +#35521 = CARTESIAN_POINT ( 'NONE', ( 12.63486156935002924, 128.4748385056542190, 89.81919559417828225 ) ) ; +#35522 = CIRCLE ( 'NONE', #36882, 2.500000000030778047 ) ; +#35523 = CARTESIAN_POINT ( 'NONE', ( 36.86608789098717409, 116.0808690289381957, 89.69631361914622403 ) ) ; +#35524 = CONICAL_SURFACE ( 'NONE', #31672, 2.502986258519634966, 0.7853981633282146602 ) ; +#35525 = CONICAL_SURFACE ( 'NONE', #32304, 2.749999999872844381, 0.7853981633697728615 ) ; +#35526 = CARTESIAN_POINT ( 'NONE', ( -2.603735047448787920, 191.4510372720596081, 104.1965523528617155 ) ) ; +#35527 = EDGE_CURVE ( 'NONE', #11101, #1951, #6147, .T. ) ; +#35528 = CARTESIAN_POINT ( 'NONE', ( -37.31520213808180131, 125.3838658331930560, 91.70151751858605849 ) ) ; +#35529 = CIRCLE ( 'NONE', #26447, 8.000001494568982352 ) ; +#35530 = CARTESIAN_POINT ( 'NONE', ( 5.666342391474075590, 184.1261583153890342, 102.1553011192941653 ) ) ; +#35531 = CARTESIAN_POINT ( 'NONE', ( 25.67135618113999840, 190.7771706469999913, 106.3710741544000058 ) ) ; +#35532 = EDGE_CURVE ( 'NONE', #37162, #33439, #9143, .T. ) ; +#35533 = CARTESIAN_POINT ( 'NONE', ( 30.05533545580799881, 109.6131156702000027, 90.24963216972992086 ) ) ; +#35534 = CARTESIAN_POINT ( 'NONE', ( 38.18933094215999802, 118.9523845877999975, 90.39787065528000198 ) ) ; +#35535 = EDGE_LOOP ( 'NONE', ( #10721, #14163, #5656, #2085 ) ) ; +#35536 = EDGE_CURVE ( 'NONE', #5625, #19444, #30141, .T. ) ; +#35537 = CARTESIAN_POINT ( 'NONE', ( 12.35238742145730129, 121.2983238345577348, 152.0219650886938325 ) ) ; +#35538 = CARTESIAN_POINT ( 'NONE', ( -35.93656262315591476, 192.5778422724570191, 106.4045596097014084 ) ) ; +#35539 = FACE_OUTER_BOUND ( 'NONE', #13805, .T. ) ; +#35540 = DIRECTION ( 'NONE', ( 0.0005884949961243378077, -0.2249510543439051935, 0.9743698870671265722 ) ) ; +#35541 = ORIENTED_EDGE ( 'NONE', *, *, #10383, .T. ) ; +#35542 = ORIENTED_EDGE ( 'NONE', *, *, #33397, .T. ) ; +#35543 = EDGE_CURVE ( 'NONE', #32124, #2995, #29807, .T. ) ; +#35544 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32094, #19594, #13480, #25964 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35545 = VERTEX_POINT ( 'NONE', #39385 ) ; +#35546 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319369175368 ) ) ; +#35547 = CARTESIAN_POINT ( 'NONE', ( -21.82963565732912059, 176.4928003187452816, 100.9258332941378455 ) ) ; +#35548 = CARTESIAN_POINT ( 'NONE', ( -2.373302774618340827, 209.5677226285648942, 73.55993759090392814 ) ) ; +#35549 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; +#35550 = ORIENTED_EDGE ( 'NONE', *, *, #40363, .T. ) ; +#35551 = VERTEX_POINT ( 'NONE', #14674 ) ; +#35552 = CARTESIAN_POINT ( 'NONE', ( -15.68256000705214248, 187.1367298994813382, 102.8663136840160348 ) ) ; +#35553 = CARTESIAN_POINT ( 'NONE', ( -38.27698265560000124, 118.7379802187000024, 90.09675852578000388 ) ) ; +#35554 = CARTESIAN_POINT ( 'NONE', ( -39.19119708560000248, 119.7661023014999984, 87.67334507776000407 ) ) ; +#35555 = CONICAL_SURFACE ( 'NONE', #1649, 5.003000016051808885, 0.7853647137435869618 ) ; +#35556 = CONICAL_SURFACE ( 'NONE', #8166, 2.500000093253988087, 0.7853981634347098062 ) ; +#35557 = CARTESIAN_POINT ( 'NONE', ( -19.31068835708127907, 125.9494874673739986, 176.1026865240145867 ) ) ; +#35558 = ORIENTED_EDGE ( 'NONE', *, *, #13104, .T. ) ; +#35559 = DIRECTION ( 'NONE', ( -0.5614015438085974141, 0.5784168556941973183, -0.5918295765320973345 ) ) ; +#35560 = CARTESIAN_POINT ( 'NONE', ( 5.665321241094450677, 124.6813345406426663, 88.86458804117559396 ) ) ; +#35561 = CARTESIAN_POINT ( 'NONE', ( 5.666344154416935730, 188.3446284886178717, 103.1322861692058268 ) ) ; +#35562 = CIRCLE ( 'NONE', #19268, 2.749999999927908334 ) ; +#35563 = CARTESIAN_POINT ( 'NONE', ( -13.73940678091062750, 149.5950516795147962, 180.3890686682271394 ) ) ; +#35564 = DIRECTION ( 'NONE', ( 0.0006039748319110907569, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#35565 = EDGE_LOOP ( 'NONE', ( #36861, #18234, #23062, #12451 ) ) ; +#35566 = CARTESIAN_POINT ( 'NONE', ( -2.616039299157999931, 189.8270603464999908, 103.4795334403000027 ) ) ; +#35567 = CARTESIAN_POINT ( 'NONE', ( -8.189842672704649829, 160.7205385619579090, 99.67099101675637485 ) ) ; +#35568 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, -1.292965734478455239E-10, 0.9999998176071844824 ) ) ; +#35569 = CARTESIAN_POINT ( 'NONE', ( 2.942640810008999797, 190.8795194553999863, 106.6729299489000198 ) ) ; +#35570 = ORIENTED_EDGE ( 'NONE', *, *, #23113, .T. ) ; +#35571 = ORIENTED_EDGE ( 'NONE', *, *, #17156, .F. ) ; +#35572 = CARTESIAN_POINT ( 'NONE', ( -20.49921872406353529, 118.1134456025284152, 89.78002774633898753 ) ) ; +#35573 = CARTESIAN_POINT ( 'NONE', ( -25.41632337319661517, 212.9327801067953772, 76.07227286817062861 ) ) ; +#35574 = ORIENTED_EDGE ( 'NONE', *, *, #20236, .F. ) ; +#35575 = EDGE_CURVE ( 'NONE', #6189, #1454, #37451, .T. ) ; +#35576 = EDGE_CURVE ( 'NONE', #11256, #2373, #35455, .T. ) ; +#35577 = VERTEX_POINT ( 'NONE', #7913 ) ; +#35578 = EDGE_CURVE ( 'NONE', #39629, #24313, #18890, .T. ) ; +#35579 = ORIENTED_EDGE ( 'NONE', *, *, #37502, .T. ) ; +#35580 = EDGE_CURVE ( 'NONE', #275, #4594, #17711, .T. ) ; +#35581 = CONICAL_SURFACE ( 'NONE', #15401, 2.500000073478776841, 0.7853981633461010192 ) ; +#35582 = CARTESIAN_POINT ( 'NONE', ( 22.99060780684998662, 213.5902260770751866, 73.54442216390444287 ) ) ; +#35583 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971553467 ) ) ; +#35584 = ORIENTED_EDGE ( 'NONE', *, *, #6875, .T. ) ; +#35586 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620730239, 0.0004744508866335444284 ) ) ; +#35585 = AXIS2_PLACEMENT_3D ( 'NONE', #40095, #27864, #24592 ) ; +#35587 = CIRCLE ( 'NONE', #29095, 2.250000000000011102 ) ; +#35588 = ORIENTED_EDGE ( 'NONE', *, *, #19062, .F. ) ; +#35589 = AXIS2_PLACEMENT_3D ( 'NONE', #31418, #3382, #6648 ) ; +#35590 = EDGE_CURVE ( 'NONE', #12347, #39877, #10795, .T. ) ; +#35591 = CARTESIAN_POINT ( 'NONE', ( 26.00638047580449452, 120.1083817546529815, 90.45668068452542343 ) ) ; +#35592 = CARTESIAN_POINT ( 'NONE', ( -24.55523628323845386, 213.0895637289104059, 75.57350648182111286 ) ) ; +#35593 = VECTOR ( 'NONE', #8092, 1000.000000000000000 ) ; +#35595 = CARTESIAN_POINT ( 'NONE', ( -44.12605770667196481, 189.0087315190842503, 103.3156785504129118 ) ) ; +#35594 = CYLINDRICAL_SURFACE ( 'NONE', #14597, 10.00000000000000178 ) ; +#35596 = ORIENTED_EDGE ( 'NONE', *, *, #7042, .F. ) ; +#35597 = EDGE_CURVE ( 'NONE', #32939, #11405, #40332, .T. ) ; +#35598 = CARTESIAN_POINT ( 'NONE', ( 30.05382551872584784, 109.6131156702000027, 87.74963262556961752 ) ) ; +#35599 = ORIENTED_EDGE ( 'NONE', *, *, #21607, .F. ) ; +#35600 = CARTESIAN_POINT ( 'NONE', ( -0.7521197190870236859, 188.6099794140578183, 103.1974225847511235 ) ) ; +#35601 = CARTESIAN_POINT ( 'NONE', ( -20.78811499662441875, 115.4347536419673759, 282.5710977942478053 ) ) ; +#35602 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989940797, 0.1373964268091564245 ) ) ; +#35603 = ORIENTED_EDGE ( 'NONE', *, *, #390, .F. ) ; +#35604 = CARTESIAN_POINT ( 'NONE', ( -37.33078358961313370, 118.4311938237343469, 87.29033114988793329 ) ) ; +#35605 = EDGE_CURVE ( 'NONE', #12345, #37005, #8125, .T. ) ; +#35606 = CARTESIAN_POINT ( 'NONE', ( -45.63429964751735923, 124.0250017997251888, 91.62307165259733210 ) ) ; +#35607 = DIRECTION ( 'NONE', ( -0.9999998268367615850, -0.0001323826093066938115, 0.0005734119738014427110 ) ) ; +#35608 = CARTESIAN_POINT ( 'NONE', ( 36.22006362617999997, 191.6153237647999958, 104.0153841014000022 ) ) ; +#35609 = EDGE_LOOP ( 'NONE', ( #27762, #5343, #6581, #18948 ) ) ; +#35610 = ORIENTED_EDGE ( 'NONE', *, *, #4426, .F. ) ; +#35611 = ORIENTED_EDGE ( 'NONE', *, *, #16275, .T. ) ; +#35612 = CARTESIAN_POINT ( 'NONE', ( -23.36362643548601525, 134.3689145912054528, 93.65807808762833986 ) ) ; +#35613 = CIRCLE ( 'NONE', #16028, 2.499999999970668796 ) ; +#35614 = ORIENTED_EDGE ( 'NONE', *, *, #14956, .F. ) ; +#35615 = DIRECTION ( 'NONE', ( 0.0006039748319382907873, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#35616 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9757, #33875, #15871, #18933 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35617 = VECTOR ( 'NONE', #35706, 1000.000000000000114 ) ; +#35618 = CIRCLE ( 'NONE', #23944, 10.00000000000000355 ) ; +#35619 = LINE ( 'NONE', #35829, #7904 ) ; +#35620 = CARTESIAN_POINT ( 'NONE', ( -20.68769432855515333, 105.5805168951702342, 87.28027914095393669 ) ) ; +#35621 = VERTEX_POINT ( 'NONE', #33053 ) ; +#35622 = CARTESIAN_POINT ( 'NONE', ( -12.63650000505050741, 176.7400935530354218, 103.0299816110529747 ) ) ; +#35623 = CARTESIAN_POINT ( 'NONE', ( 18.59950176164737812, 148.9135478570107409, 180.2224150185023177 ) ) ; +#35624 = CARTESIAN_POINT ( 'NONE', ( -14.22268604928681768, 129.0012187111780406, 177.0515306709980052 ) ) ; +#35625 = CARTESIAN_POINT ( 'NONE', ( -23.36013443158915237, 134.2374061052952356, 93.74025200507369959 ) ) ; +#35626 = EDGE_CURVE ( 'NONE', #15089, #35968, #31840, .T. ) ; +#35627 = VERTEX_POINT ( 'NONE', #26540 ) ; +#35628 = EDGE_CURVE ( 'NONE', #39445, #21726, #32339, .T. ) ; +#35629 = CARTESIAN_POINT ( 'NONE', ( 23.68479074154343778, 130.4250414336578956, 90.26276162004360515 ) ) ; +#35630 = EDGE_CURVE ( 'NONE', #8808, #22688, #27518, .T. ) ; +#35631 = CARTESIAN_POINT ( 'NONE', ( -14.22274084689574636, 128.8778062397453539, 177.5848030100378026 ) ) ; +#35632 = DIRECTION ( 'NONE', ( -6.938893903689061992E-16, 0.9743700557921577410, 0.2249510932971592880 ) ) ; +#35633 = ORIENTED_EDGE ( 'NONE', *, *, #26228, .T. ) ; +#35634 = ADVANCED_FACE ( 'NONE', ( #7708 ), #39470, .F. ) ; +#35635 = AXIS2_PLACEMENT_3D ( 'NONE', #28913, #25664, #488 ) ; +#35636 = CARTESIAN_POINT ( 'NONE', ( 8.243287016505872700, 177.7923814586351909, 100.6945832946480266 ) ) ; +#35637 = CIRCLE ( 'NONE', #14798, 30.00000000000001066 ) ; +#35638 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #11622, #8557, #21022, #18332 ), + .UNSPECIFIED., .F., .F. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.841075538901985276, 4.841089743069536766 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999831867825, 0.9999999999831867825, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#35640 = CARTESIAN_POINT ( 'NONE', ( -35.65425197762999687, 113.9226696212000007, 90.16305967816001044 ) ) ; +#35639 = CARTESIAN_POINT ( 'NONE', ( 2.545697083959657991, 209.0000005535759158, 75.65980364788404700 ) ) ; +#35641 = EDGE_CURVE ( 'NONE', #34013, #5512, #22545, .T. ) ; +#35642 = ORIENTED_EDGE ( 'NONE', *, *, #7272, .F. ) ; +#35643 = CARTESIAN_POINT ( 'NONE', ( 38.57881674720375287, 118.4710469142059424, 89.66256680473345853 ) ) ; +#35644 = EDGE_LOOP ( 'NONE', ( #32246, #32886, #13295, #22526 ) ) ; +#35646 = AXIS2_PLACEMENT_3D ( 'NONE', #21385, #26351, #30366 ) ; +#35645 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#35647 = DIRECTION ( 'NONE', ( -0.7942820423213363679, -0.5918950211223027447, -0.1370267171630251690 ) ) ; +#35648 = DIRECTION ( 'NONE', ( -0.6088835995545407442, -0.7728434649458201244, -0.1788120266761852317 ) ) ; +#35649 = CIRCLE ( 'NONE', #16729, 4.750000000028161473 ) ; +#35650 = CARTESIAN_POINT ( 'NONE', ( -8.513636114222510543, 166.3610373950837413, 28.79402947992309336 ) ) ; +#35651 = ORIENTED_EDGE ( 'NONE', *, *, #5918, .T. ) ; +#35652 = ORIENTED_EDGE ( 'NONE', *, *, #6753, .T. ) ; +#35653 = CARTESIAN_POINT ( 'NONE', ( -42.59427139077273949, 120.8410302828149980, 90.84624444726389925 ) ) ; +#35654 = ORIENTED_EDGE ( 'NONE', *, *, #7547, .F. ) ; +#35655 = ORIENTED_EDGE ( 'NONE', *, *, #1147, .F. ) ; +#35656 = FACE_OUTER_BOUND ( 'NONE', #18647, .T. ) ; +#35657 = ADVANCED_FACE ( 'NONE', ( #34254 ), #5452, .T. ) ; +#35658 = CARTESIAN_POINT ( 'NONE', ( -13.83171258125842940, 124.6514559930156594, 174.6056481214619680 ) ) ; +#35659 = CARTESIAN_POINT ( 'NONE', ( -2.874686192646000116, 209.6463030548999882, 76.06021946686999513 ) ) ; +#35660 = VERTEX_POINT ( 'NONE', #37146 ) ; +#35661 = CARTESIAN_POINT ( 'NONE', ( -25.50930529680102055, 206.8620306257938637, 74.56190818570927092 ) ) ; +#35662 = CARTESIAN_POINT ( 'NONE', ( 37.88028376212000126, 118.7501674914000063, 87.34217705218000560 ) ) ; +#35663 = CARTESIAN_POINT ( 'NONE', ( -38.87745381538000089, 118.6696732969000010, 89.55817230021000341 ) ) ; +#35664 = CARTESIAN_POINT ( 'NONE', ( 20.00004282447493864, 191.5259056233101091, 103.8580927373495371 ) ) ; +#35665 = CARTESIAN_POINT ( 'NONE', ( 13.45852275855000180, 176.5968831303999877, 28.07991271570000080 ) ) ; +#35666 = CARTESIAN_POINT ( 'NONE', ( -23.35467185764349907, 177.0821513736807731, 103.5858053495271207 ) ) ; +#35667 = CARTESIAN_POINT ( 'NONE', ( -30.07183102385390328, 134.5651111927130614, 93.53877248162399383 ) ) ; +#35668 = ORIENTED_EDGE ( 'NONE', *, *, #6390, .T. ) ; +#35669 = VECTOR ( 'NONE', #4781, 1000.000000000000000 ) ; +#35670 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#35671 = CARTESIAN_POINT ( 'NONE', ( 24.53561543415755608, 116.1140095870392770, 87.75278364645060947 ) ) ; +#35672 = AXIS2_PLACEMENT_3D ( 'NONE', #5616, #227, #632 ) ; +#35673 = CARTESIAN_POINT ( 'NONE', ( 20.33352119585698503, 191.4503965976574023, 104.1825428129966298 ) ) ; +#35674 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -2.775557055476284060E-15, -0.0006039748319368685309 ) ) ; +#35675 = CONICAL_SURFACE ( 'NONE', #8940, 2.500000189908397452, 0.7853981633778498450 ) ; +#35676 = ORIENTED_EDGE ( 'NONE', *, *, #20691, .T. ) ; +#35677 = CARTESIAN_POINT ( 'NONE', ( -21.44693882331385026, 135.7861819143374760, 91.01458761472625270 ) ) ; +#35678 = CARTESIAN_POINT ( 'NONE', ( 2.150444420076068397, 189.7824041803656883, 103.9092394343438599 ) ) ; +#35679 = CARTESIAN_POINT ( 'NONE', ( 32.56862209514003581, 137.0357280551704946, 91.27044140003587813 ) ) ; +#35680 = VECTOR ( 'NONE', #33372, 1000.000000000000000 ) ; +#35681 = CARTESIAN_POINT ( 'NONE', ( 37.43408832017941990, 187.1561535229247113, 105.9176297419797095 ) ) ; +#35682 = ORIENTED_EDGE ( 'NONE', *, *, #24353, .T. ) ; +#35683 = EDGE_CURVE ( 'NONE', #33088, #29958, #21685, .T. ) ; +#35684 = CARTESIAN_POINT ( 'NONE', ( -25.35555351876000074, 191.8331706769000107, 104.5643529913999998 ) ) ; +#35685 = ADVANCED_FACE ( 'NONE', ( #128 ), #40399, .F. ) ; +#35686 = CARTESIAN_POINT ( 'NONE', ( 20.50147081230003465, 160.1804844999245176, 99.18687941561596233 ) ) ; +#35687 = CARTESIAN_POINT ( 'NONE', ( 25.36963655659999972, 191.8200828733000094, 104.5457702689000001 ) ) ; +#35688 = CARTESIAN_POINT ( 'NONE', ( -32.37225756500890839, 173.7258698620904340, 102.8591651650622936 ) ) ; +#35689 = ORIENTED_EDGE ( 'NONE', *, *, #35785, .F. ) ; +#35690 = CARTESIAN_POINT ( 'NONE', ( 25.46575390506999881, 127.1331156701999987, 32.39311599089000282 ) ) ; +#35691 = CARTESIAN_POINT ( 'NONE', ( 2.546554931011165923, 207.4083916550792424, 77.08013917139633975 ) ) ; +#35692 = CARTESIAN_POINT ( 'NONE', ( 1.447658033476510564, 152.0519508813542302, 130.6788418767396251 ) ) ; +#35693 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26902, #11147, #4593, #29358, #14014, #38945, #39147, #23622, #10955, #39337 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000002220, 0.5000000000000004441, 0.7500000000000002220, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35694 = CARTESIAN_POINT ( 'NONE', ( 37.32760420458339468, 107.6237522301635892, 168.6290816310376783 ) ) ; +#35695 = CARTESIAN_POINT ( 'NONE', ( 20.48555995111231809, 211.0898943587194481, 73.54694346759191603 ) ) ; +#35696 = CIRCLE ( 'NONE', #14205, 22.00000000001092815 ) ; +#35697 = CARTESIAN_POINT ( 'NONE', ( 37.16246192308000218, 191.2833026195000343, 106.1953380436000032 ) ) ; +#35698 = CARTESIAN_POINT ( 'NONE', ( 31.13142491820691404, 177.5650774932047113, 100.6282487300115633 ) ) ; +#35699 = CARTESIAN_POINT ( 'NONE', ( -5.666943220168050743, 130.1021739148860092, 92.43784920459198418 ) ) ; +#35700 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118071, 107.3101052615539714, 174.7154016153159830 ) ) ; +#35701 = VECTOR ( 'NONE', #33455, 1000.000000000000114 ) ; +#35702 = ORIENTED_EDGE ( 'NONE', *, *, #30441, .F. ) ; +#35703 = CARTESIAN_POINT ( 'NONE', ( -44.79177088925157335, 180.8389768040387366, 104.5088566725039527 ) ) ; +#35704 = EDGE_CURVE ( 'NONE', #25194, #31691, #19239, .T. ) ; +#35705 = PLANE ( 'NONE', #2712 ) ; +#35706 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386905326 ) ) ; +#35707 = CARTESIAN_POINT ( 'NONE', ( -39.25176738111546371, 153.0051697192221241, 291.5822510191628680 ) ) ; +#35708 = ORIENTED_EDGE ( 'NONE', *, *, #1588, .T. ) ; +#35709 = LINE ( 'NONE', #26353, #31166 ) ; +#35710 = FACE_OUTER_BOUND ( 'NONE', #23365, .T. ) ; +#35711 = ORIENTED_EDGE ( 'NONE', *, *, #13292, .F. ) ; +#35712 = LINE ( 'NONE', #17314, #29768 ) ; +#35713 = CARTESIAN_POINT ( 'NONE', ( 24.98975941420810898, 212.6265807872101163, 73.54323398625686536 ) ) ; +#35714 = ORIENTED_EDGE ( 'NONE', *, *, #38743, .T. ) ; +#35715 = CARTESIAN_POINT ( 'NONE', ( 36.17763712702846846, 192.0945858402941155, 106.3945039591156672 ) ) ; +#35716 = ADVANCED_FACE ( 'NONE', ( #6062 ), #18511, .F. ) ; +#35717 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971531818 ) ) ; +#35718 = CARTESIAN_POINT ( 'NONE', ( 2.463364856792551905, 209.5677208948551993, 75.55701285043443249 ) ) ; +#35719 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#35720 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748615030, 130.2179793250143121, 92.27099872764938482 ) ) ; +#35721 = EDGE_LOOP ( 'NONE', ( #8944, #4814, #7025, #15433 ) ) ; +#35722 = ORIENTED_EDGE ( 'NONE', *, *, #1956, .T. ) ; +#35723 = ADVANCED_FACE ( 'NONE', ( #2608 ), #12011, .F. ) ; +#35724 = CARTESIAN_POINT ( 'NONE', ( 31.79542160255000027, 226.4002260771003137, 75.53930090046030443 ) ) ; +#35725 = CARTESIAN_POINT ( 'NONE', ( -30.07108905527912768, 177.6009053965225348, 100.8330313169720540 ) ) ; +#35726 = CARTESIAN_POINT ( 'NONE', ( 3.535191698069989563, 175.6848863132240979, 100.2108397475080608 ) ) ; +#35727 = CIRCLE ( 'NONE', #7030, 1.999999999999999112 ) ; +#35728 = CARTESIAN_POINT ( 'NONE', ( -48.18983608578390232, 82.56060091850311267, 289.7643016034785433 ) ) ; +#35729 = ORIENTED_EDGE ( 'NONE', *, *, #32669, .F. ) ; +#35730 = EDGE_CURVE ( 'NONE', #13543, #33081, #30409, .T. ) ; +#35731 = ORIENTED_EDGE ( 'NONE', *, *, #17697, .F. ) ; +#35732 = CARTESIAN_POINT ( 'NONE', ( 23.36209697621471193, 182.0666116869439861, 102.1853546028109321 ) ) ; +#35733 = EDGE_CURVE ( 'NONE', #30524, #30873, #15276, .T. ) ; +#35734 = CIRCLE ( 'NONE', #18120, 16.50000000000000000 ) ; +#35736 = ADVANCED_FACE ( 'NONE', ( #12212 ), #14039, .F. ) ; +#35735 = CARTESIAN_POINT ( 'NONE', ( 6.034975439466390590, 134.4313215703540436, 93.60465627050247406 ) ) ; +#35737 = CARTESIAN_POINT ( 'NONE', ( -25.87924003072999923, 120.0237968075000197, 90.33241269644000226 ) ) ; +#35738 = CARTESIAN_POINT ( 'NONE', ( 3.166590160534637377, 128.9107321027200896, 89.41239602999318947 ) ) ; +#35739 = DIRECTION ( 'NONE', ( -0.1064928859749483120, 0.6584501104249200765, 0.7450521574481461240 ) ) ; +#35740 = CARTESIAN_POINT ( 'NONE', ( 37.79411860435257609, 218.5902260770999987, 73.03567738180409208 ) ) ; +#35741 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971549582 ) ) ; +#35742 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098504, 132.2930706491197554, 93.28496646308185802 ) ) ; +#35743 = DIRECTION ( 'NONE', ( 0.9999998268366899756, 0.0001323826366425473087, -0.0005734120921955398629 ) ) ; +#35744 = CARTESIAN_POINT ( 'NONE', ( 27.77617898001813046, 124.7465259774044881, 88.43614954403585671 ) ) ; +#35745 = EDGE_LOOP ( 'NONE', ( #19131, #17858, #30164, #38872 ) ) ; +#35746 = FACE_OUTER_BOUND ( 'NONE', #26547, .T. ) ; +#35747 = PLANE ( 'NONE', #27749 ) ; +#35748 = LINE ( 'NONE', #17348, #26728 ) ; +#35749 = CARTESIAN_POINT ( 'NONE', ( -28.46934164383677768, 181.9348616170655362, 102.0152119563739745 ) ) ; +#35751 = EDGE_LOOP ( 'NONE', ( #22500, #1558, #24023, #6049 ) ) ; +#35750 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#35752 = EDGE_LOOP ( 'NONE', ( #30765, #17898, #38041, #6736 ) ) ; +#35753 = ORIENTED_EDGE ( 'NONE', *, *, #28081, .F. ) ; +#35754 = ORIENTED_EDGE ( 'NONE', *, *, #21258, .F. ) ; +#35755 = CARTESIAN_POINT ( 'NONE', ( -13.50134333678474441, 124.5299559832934619, 88.63738261923552386 ) ) ; +#35756 = VECTOR ( 'NONE', #18942, 1000.000000000000114 ) ; +#35757 = DIRECTION ( 'NONE', ( 0.7933533411653070910, -0.5930537057989907490, -0.1373964268091706076 ) ) ; +#35758 = ORIENTED_EDGE ( 'NONE', *, *, #1641, .F. ) ; +#35759 = AXIS2_PLACEMENT_3D ( 'NONE', #2558, #33195, #11758 ) ; +#35760 = EDGE_LOOP ( 'NONE', ( #3069, #25635, #33742 ) ) ; +#35761 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001011, 118.9382625071999939, 90.21260570929000266 ) ) ; +#35762 = CARTESIAN_POINT ( 'NONE', ( -39.29309565128836113, 161.9833659626246458, 194.3051242015387743 ) ) ; +#35763 = CARTESIAN_POINT ( 'NONE', ( -13.49720193180488614, 187.3531203416616790, 105.5636871951386695 ) ) ; +#35764 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178570903572E-05, -0.0002331579774915885982 ) ) ; +#35765 = CARTESIAN_POINT ( 'NONE', ( -35.56620022681000393, 112.8577151017999967, 87.40717291247999299 ) ) ; +#35766 = VERTEX_POINT ( 'NONE', #12395 ) ; +#35767 = LINE ( 'NONE', #17372, #968 ) ; +#35768 = ORIENTED_EDGE ( 'NONE', *, *, #25160, .F. ) ; +#35769 = CARTESIAN_POINT ( 'NONE', ( -20.52021128088478008, 209.7095522429308119, 78.07090650300916934 ) ) ; +#35770 = CARTESIAN_POINT ( 'NONE', ( -3.668404236352207359, 128.0226348367964988, 91.77725148510558029 ) ) ; +#35771 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.274821093756980468E-14, 0.9999998176071847045 ) ) ; +#35772 = CARTESIAN_POINT ( 'NONE', ( -3.296644428745350464, 186.6752324597403856, 102.7522878028166247 ) ) ; +#35773 = CARTESIAN_POINT ( 'NONE', ( -19.30072366694697195, 148.2625267288300677, 183.5008936541533444 ) ) ; +#35774 = ORIENTED_EDGE ( 'NONE', *, *, #11406, .T. ) ; +#35775 = ORIENTED_EDGE ( 'NONE', *, *, #6554, .T. ) ; +#35776 = ADVANCED_FACE ( 'NONE', ( #24899 ), #15980, .F. ) ; +#35777 = CARTESIAN_POINT ( 'NONE', ( -0.4373743799229999896, 189.0000487688000135, 103.6850551722000091 ) ) ; +#35778 = CARTESIAN_POINT ( 'NONE', ( 25.49273537670449130, 207.4083917605111367, 77.06627999559472642 ) ) ; +#35779 = CARTESIAN_POINT ( 'NONE', ( 26.01884214213044189, 120.5510065312885359, 90.54751165435830274 ) ) ; +#35780 = EDGE_CURVE ( 'NONE', #21313, #18328, #27774, .T. ) ; +#35781 = ORIENTED_EDGE ( 'NONE', *, *, #2452, .T. ) ; +#35782 = CARTESIAN_POINT ( 'NONE', ( -37.26309767763914493, 111.8941053232203160, 150.0343454695379819 ) ) ; +#35783 = CARTESIAN_POINT ( 'NONE', ( 36.04411892353203228, 218.5902260770999987, 73.03673433779063373 ) ) ; +#35784 = EDGE_LOOP ( 'NONE', ( #16725, #228, #16824, #10371, #22148, #3105, #32591, #39397, #29981, #28998, #34117, #19583 ) ) ; +#35785 = EDGE_CURVE ( 'NONE', #39586, #3459, #18112, .T. ) ; +#35786 = EDGE_LOOP ( 'NONE', ( #22420, #5837, #29083, #10886 ) ) ; +#35787 = CONICAL_SURFACE ( 'NONE', #34502, 5.000000000037533532, 0.7853981633991120592 ) ; +#35788 = EDGE_CURVE ( 'NONE', #36967, #40162, #30902, .T. ) ; +#35789 = AXIS2_PLACEMENT_3D ( 'NONE', #8151, #2030, #14096 ) ; +#35790 = VERTEX_POINT ( 'NONE', #5864 ) ; +#35791 = LINE ( 'NONE', #17192, #15836 ) ; +#35792 = VECTOR ( 'NONE', #27611, 1000.000000000000000 ) ; +#35793 = VERTEX_POINT ( 'NONE', #34845 ) ; +#35794 = CARTESIAN_POINT ( 'NONE', ( -27.96587646086999968, 186.7892146652000065, 105.5303139314000020 ) ) ; +#35795 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18299, #17895, #5643, #9323 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35796 = AXIS2_PLACEMENT_3D ( 'NONE', #3339, #9698, #15814 ) ; +#35797 = PLANE ( 'NONE', #5853 ) ; +#35798 = CARTESIAN_POINT ( 'NONE', ( -20.00006126831510400, 120.3902141372887087, 87.45929000627990035 ) ) ; +#35799 = CARTESIAN_POINT ( 'NONE', ( 20.50029381459099653, 160.6303866002982375, 97.23813964974755208 ) ) ; +#35800 = ORIENTED_EDGE ( 'NONE', *, *, #23773, .F. ) ; +#35801 = CARTESIAN_POINT ( 'NONE', ( 25.83435490308000482, 120.1467052683999981, 90.28944886154999949 ) ) ; +#35802 = CARTESIAN_POINT ( 'NONE', ( -23.67312619880860680, 213.5252190068897278, 75.57282641249091171 ) ) ; +#35804 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#35803 = CARTESIAN_POINT ( 'NONE', ( 20.48210507039391359, 207.8175337693571976, 76.41195150568934480 ) ) ; +#35805 = EDGE_LOOP ( 'NONE', ( #37184, #22501, #31693, #12990 ) ) ; +#35806 = ORIENTED_EDGE ( 'NONE', *, *, #3086, .F. ) ; +#35807 = CARTESIAN_POINT ( 'NONE', ( -36.16445409389137211, 191.9130154921125779, 104.4161701276585319 ) ) ; +#35808 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#35809 = ORIENTED_EDGE ( 'NONE', *, *, #10008, .T. ) ; +#35810 = CARTESIAN_POINT ( 'NONE', ( -35.73920245160073250, 115.2227226758066081, 87.28936987476224374 ) ) ; +#35811 = CIRCLE ( 'NONE', #24780, 6.999999999999993783 ) ; +#35812 = PLANE ( 'NONE', #33013 ) ; +#35813 = CARTESIAN_POINT ( 'NONE', ( 5.669396933462909516, 187.4887502807403905, 105.7656896039401317 ) ) ; +#35814 = LINE ( 'NONE', #7824, #22866 ) ; +#35815 = EDGE_CURVE ( 'NONE', #24898, #4634, #30383, .T. ) ; +#35816 = EDGE_LOOP ( 'NONE', ( #16018, #38283, #28912, #28327 ) ) ; +#35817 = EDGE_CURVE ( 'NONE', #20812, #23133, #34268, .T. ) ; +#35818 = ORIENTED_EDGE ( 'NONE', *, *, #35972, .F. ) ; +#35819 = AXIS2_PLACEMENT_3D ( 'NONE', #33184, #30759, #37484 ) ; +#35820 = EDGE_CURVE ( 'NONE', #33506, #25208, #14304, .T. ) ; +#35821 = CARTESIAN_POINT ( 'NONE', ( 22.74078652492754316, 169.1007803562181948, 29.42961925479451324 ) ) ; +#35822 = AXIS2_PLACEMENT_3D ( 'NONE', #5801, #21560, #39728 ) ; +#35823 = ORIENTED_EDGE ( 'NONE', *, *, #807, .F. ) ; +#35824 = EDGE_CURVE ( 'NONE', #25532, #33855, #13396, .T. ) ; +#35825 = CARTESIAN_POINT ( 'NONE', ( -35.43250415655209906, 192.6083200664709807, 106.9089671552009975 ) ) ; +#35826 = CARTESIAN_POINT ( 'NONE', ( -37.85620740011129470, 117.8069959198554386, 89.71719403945294857 ) ) ; +#35827 = ADVANCED_FACE ( 'NONE', ( #25897 ), #13409, .T. ) ; +#35828 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31199, #34830, #34052, #37333 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35829 = CARTESIAN_POINT ( 'NONE', ( 42.53628601435023171, 136.4453753212296760, 337.8539966295136310 ) ) ; +#35830 = CARTESIAN_POINT ( 'NONE', ( 2.730734751406000083, 190.9310048963999975, 106.4668557451999931 ) ) ; +#35831 = ORIENTED_EDGE ( 'NONE', *, *, #22096, .F. ) ; +#35832 = PLANE ( 'NONE', #20996 ) ; +#35833 = EDGE_CURVE ( 'NONE', #11521, #2286, #12809, .T. ) ; +#35834 = DIRECTION ( 'NONE', ( 0.0002393071182782299474, 0.2252352986010034697, -0.9743043687658493601 ) ) ; +#35835 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36667, #30333, #2131, #12142, #15402, #14601, #33386, #15206, #8676, #33174 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999722444, 0.3749999999999583666, 0.4374999999999019118, 0.4999999999998454570, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35836 = DIRECTION ( 'NONE', ( -0.7069397801071900522, 0.6508947121446219120, 0.2767168607153664972 ) ) ; +#35837 = CARTESIAN_POINT ( 'NONE', ( -37.83810969319355166, 191.0388331516561777, 103.7805696149103909 ) ) ; +#35838 = EDGE_LOOP ( 'NONE', ( #5305, #39328, #28111, #38920 ) ) ; +#35839 = FACE_OUTER_BOUND ( 'NONE', #5978, .T. ) ; +#35840 = CARTESIAN_POINT ( 'NONE', ( -2.435788377003461846, 191.0000002182038941, 106.3158216037667358 ) ) ; +#35841 = EDGE_CURVE ( 'NONE', #24833, #35367, #3564, .T. ) ; +#35842 = CIRCLE ( 'NONE', #18226, 54.50273826251000742 ) ; +#35843 = ORIENTED_EDGE ( 'NONE', *, *, #22122, .F. ) ; +#35844 = AXIS2_PLACEMENT_3D ( 'NONE', #12525, #1412, #9888 ) ; +#35845 = CARTESIAN_POINT ( 'NONE', ( 32.91940139443364188, 79.66630585985183188, 290.1140374308924947 ) ) ; +#35846 = AXIS2_PLACEMENT_3D ( 'NONE', #35387, #10691, #35583 ) ; +#35848 = CARTESIAN_POINT ( 'NONE', ( -35.94308550139999880, 115.0615709833000011, 90.15961284037001633 ) ) ; +#35847 = CARTESIAN_POINT ( 'NONE', ( -15.83322826986868392, 127.7069138835006896, 89.31700631985079042 ) ) ; +#35849 = ORIENTED_EDGE ( 'NONE', *, *, #7361, .T. ) ; +#35850 = CARTESIAN_POINT ( 'NONE', ( 25.99899579567804864, 120.3902236066977025, 87.43149108636995948 ) ) ; +#35851 = ORIENTED_EDGE ( 'NONE', *, *, #15643, .T. ) ; +#35852 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -0.000000000000000000, -0.0006039748319385906776 ) ) ; +#35853 = LINE ( 'NONE', #1521, #28456 ) ; +#35854 = LINE ( 'NONE', #20742, #27509 ) ; +#35855 = CYLINDRICAL_SURFACE ( 'NONE', #33836, 16.50000000000000000 ) ; +#35856 = ORIENTED_EDGE ( 'NONE', *, *, #32993, .T. ) ; +#35857 = ORIENTED_EDGE ( 'NONE', *, *, #29310, .F. ) ; +#35858 = CARTESIAN_POINT ( 'NONE', ( 1.222756636386816309, 140.3954820326998458, 157.8542268366375652 ) ) ; +#35859 = EDGE_LOOP ( 'NONE', ( #37988, #4418, #25493, #29627 ) ) ; +#35860 = ORIENTED_EDGE ( 'NONE', *, *, #25816, .T. ) ; +#35861 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#35862 = CARTESIAN_POINT ( 'NONE', ( 47.95588533879620741, 89.40266445833195519, 291.5248371983224729 ) ) ; +#35863 = EDGE_LOOP ( 'NONE', ( #8038, #10899, #1061, #36156 ) ) ; +#35864 = EDGE_CURVE ( 'NONE', #39281, #31407, #10135, .T. ) ; +#35865 = EDGE_CURVE ( 'NONE', #19980, #23892, #16064, .T. ) ; +#35866 = ORIENTED_EDGE ( 'NONE', *, *, #37024, .F. ) ; +#35867 = CARTESIAN_POINT ( 'NONE', ( 40.92173691880906006, 126.8073924708085798, 91.98291144766025695 ) ) ; +#35868 = EDGE_CURVE ( 'NONE', #35915, #15358, #3981, .T. ) ; +#35869 = LINE ( 'NONE', #7464, #29630 ) ; +#35870 = FACE_OUTER_BOUND ( 'NONE', #896, .T. ) ; +#35871 = CARTESIAN_POINT ( 'NONE', ( 26.00189986064203040, 120.0654717175184771, 90.40948441678035863 ) ) ; +#35872 = EDGE_CURVE ( 'NONE', #81, #23946, #25043, .T. ) ; +#35873 = CARTESIAN_POINT ( 'NONE', ( -25.83465933313999940, 120.7504878537999957, 87.71733303230999468 ) ) ; +#35874 = CONICAL_SURFACE ( 'NONE', #22865, 8.499999999995104361, 0.7853981633972997312 ) ; +#35875 = ORIENTED_EDGE ( 'NONE', *, *, #1490, .F. ) ; +#35876 = LINE ( 'NONE', #25716, #37582 ) ; +#35877 = CYLINDRICAL_SURFACE ( 'NONE', #29771, 2.000000000000011546 ) ; +#35878 = CARTESIAN_POINT ( 'NONE', ( -23.35984529070648463, 176.7693366005458984, 103.0852009884378475 ) ) ; +#35879 = VECTOR ( 'NONE', #18279, 1000.000000000000000 ) ; +#35880 = EDGE_LOOP ( 'NONE', ( #685, #34377, #21366, #21749 ) ) ; +#35881 = EDGE_CURVE ( 'NONE', #10753, #11739, #514, .T. ) ; +#35882 = CARTESIAN_POINT ( 'NONE', ( 0.5670577675614898450, 188.6056077384269827, 103.1956165535758885 ) ) ; +#35883 = VECTOR ( 'NONE', #13063, 1000.000000000000227 ) ; +#35884 = CARTESIAN_POINT ( 'NONE', ( -33.95120480059922841, 108.7064547236847432, 175.0201060189330349 ) ) ; +#35885 = CARTESIAN_POINT ( 'NONE', ( 20.50004289353369202, 195.4022624757890583, 104.8282682354084585 ) ) ; +#35886 = CONICAL_SURFACE ( 'NONE', #37770, 3.005918165693955757, 0.7853589131925805544 ) ; +#35887 = PLANE ( 'NONE', #19625 ) ; +#35888 = ORIENTED_EDGE ( 'NONE', *, *, #21656, .F. ) ; +#35890 = ADVANCED_FACE ( 'NONE', ( #13013 ), #12720, .F. ) ; +#35889 = CARTESIAN_POINT ( 'NONE', ( 35.04645050415997787, 226.4002260770639907, 75.53733736050399727 ) ) ; +#35891 = CARTESIAN_POINT ( 'NONE', ( 2.243140848118248876, 189.9153760549866377, 103.9475555346419782 ) ) ; +#35892 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; +#35893 = ORIENTED_EDGE ( 'NONE', *, *, #29914, .T. ) ; +#35894 = CARTESIAN_POINT ( 'NONE', ( 35.55533445361766098, 112.4664342211686971, 90.24631030758727945 ) ) ; +#35895 = ORIENTED_EDGE ( 'NONE', *, *, #10916, .T. ) ; +#35896 = CYLINDRICAL_SURFACE ( 'NONE', #6834, 8.000000000000007105 ) ; +#35897 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 2.775557055476284060E-15, 0.0006039748319368685309 ) ) ; +#35898 = CARTESIAN_POINT ( 'NONE', ( 26.14047868689999987, 191.8757300627000006, 103.7755257792000094 ) ) ; +#35899 = DIRECTION ( 'NONE', ( 0.7075227810182288524, -0.1590644129476248281, 0.6885564805256420007 ) ) ; +#35900 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #26379, #22911, #1012, #29243 ), + ( #16941, #35531, #1419, #25984 ), + ( #1622, #10443, #14111, #33099 ), + ( #26789, #13501, #13697, #38821 ), + ( #35337, #29443, #23711, #13899 ), + ( #39032, #20019, #10843, #23312 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 4 ), + ( 4, 4 ), + ( -0.3349633148657999993, 0.000000000000000000, 1.000000000000000000, 1.334874014178000001 ), + ( 3.659027379144000085E-07, 1.000000018766999954 ), + .UNSPECIFIED. ) ; +#35901 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 130.4429303793676240, 91.29662884054138772 ) ) ; +#35902 = EDGE_LOOP ( 'NONE', ( #28167, #35689, #7973, #29578 ) ) ; +#35903 = LINE ( 'NONE', #4832, #29508 ) ; +#35904 = CARTESIAN_POINT ( 'NONE', ( 20.89285664109717189, 183.1014278315721810, 101.9125999898524242 ) ) ; +#35905 = AXIS2_PLACEMENT_3D ( 'NONE', #4154, #25469, #7031 ) ; +#35906 = CARTESIAN_POINT ( 'NONE', ( -20.49970532896238495, 138.0793279496801631, 92.05657955325195019 ) ) ; +#35907 = AXIS2_PLACEMENT_3D ( 'NONE', #31225, #30830, #27980 ) ; +#35908 = CARTESIAN_POINT ( 'NONE', ( -42.84985459259963392, 114.0190886145072113, 121.9014590159434164 ) ) ; +#35909 = CARTESIAN_POINT ( 'NONE', ( -17.26178222639411430, 121.7713432978476220, 175.3684242141576703 ) ) ; +#35910 = CONICAL_SURFACE ( 'NONE', #2657, 22.50000000000906653, 0.7853981633972855203 ) ; +#35911 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178570922545E-05, 0.0002331579774915894113 ) ) ; +#35912 = CYLINDRICAL_SURFACE ( 'NONE', #5874, 4.999999999999994671 ) ; +#35913 = DIRECTION ( 'NONE', ( -0.1305263947812629610, 0.9660168765824788117, 0.2231014442428325972 ) ) ; +#35914 = CARTESIAN_POINT ( 'NONE', ( -38.37944638082275617, 118.8393675661044000, 87.72093620509961909 ) ) ; +#35915 = VERTEX_POINT ( 'NONE', #25292 ) ; +#35916 = CARTESIAN_POINT ( 'NONE', ( 25.99209716004703097, 210.1698189683999942, 76.04278591111288677 ) ) ; +#35917 = CARTESIAN_POINT ( 'NONE', ( -20.49823408210000153, 153.4269499538000048, 98.16561777664999511 ) ) ; +#35918 = VERTEX_POINT ( 'NONE', #37735 ) ; +#35919 = CARTESIAN_POINT ( 'NONE', ( -8.472443777046803959, 150.6153475619768187, 96.99609267642283328 ) ) ; +#35920 = ADVANCED_FACE ( 'NONE', ( #25494 ), #38819, .T. ) ; +#35921 = EDGE_CURVE ( 'NONE', #28170, #1259, #26472, .T. ) ; +#35922 = ORIENTED_EDGE ( 'NONE', *, *, #4774, .F. ) ; +#35923 = CARTESIAN_POINT ( 'NONE', ( -34.30586824512814559, 218.5902260770999987, 73.07922396718730340 ) ) ; +#35924 = DIRECTION ( 'NONE', ( -0.0005884949961219279515, 0.2249510543439044163, -0.9743698870671267942 ) ) ; +#35925 = ORIENTED_EDGE ( 'NONE', *, *, #34005, .F. ) ; +#35926 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596101196, 128.5887768395678563, 89.32567453973172178 ) ) ; +#35927 = CARTESIAN_POINT ( 'NONE', ( 25.50052104635086536, 120.2145376163999941, 89.95699630689016146 ) ) ; +#35928 = CARTESIAN_POINT ( 'NONE', ( 45.65198572469971339, 124.0200644324655457, 91.33654899623203960 ) ) ; +#35929 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971559296 ) ) ; +#35930 = CARTESIAN_POINT ( 'NONE', ( 25.49919833444198858, 118.8155663768459505, 87.75236248755290092 ) ) ; +#35931 = EDGE_LOOP ( 'NONE', ( #20889, #13446, #35860, #36704 ) ) ; +#35932 = ORIENTED_EDGE ( 'NONE', *, *, #37629, .F. ) ; +#35933 = CONICAL_SURFACE ( 'NONE', #28153, 2.499999999860247790, 0.7853981633778360782 ) ; +#35934 = FACE_OUTER_BOUND ( 'NONE', #14399, .T. ) ; +#35935 = AXIS2_PLACEMENT_3D ( 'NONE', #19692, #32383, #888 ) ; +#35936 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#35937 = CARTESIAN_POINT ( 'NONE', ( 16.00178211024919861, 127.0692136201035680, 92.05841426505114100 ) ) ; +#35938 = AXIS2_PLACEMENT_3D ( 'NONE', #22226, #34657, #13215 ) ; +#35939 = VECTOR ( 'NONE', #32456, 1000.000000000000114 ) ; +#35940 = CARTESIAN_POINT ( 'NONE', ( -45.45405528451752986, 124.2940812332277289, 92.45993501987911145 ) ) ; +#35941 = VERTEX_POINT ( 'NONE', #1520 ) ; +#35942 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#35943 = CARTESIAN_POINT ( 'NONE', ( 20.00179988782546303, 151.3105026749326498, 97.65252212824069034 ) ) ; +#35944 = CARTESIAN_POINT ( 'NONE', ( -28.33045555218999922, 124.2967629910999960, 91.58406576504999919 ) ) ; +#35945 = EDGE_CURVE ( 'NONE', #27558, #33804, #3565, .T. ) ; +#35946 = CARTESIAN_POINT ( 'NONE', ( 2.544461030880475594, 209.0000001909309901, 73.61327617014224245 ) ) ; +#35947 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825906387028845, 0.0005734119026992764556 ) ) ; +#35948 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#35949 = CARTESIAN_POINT ( 'NONE', ( -2.454301921840380096, 209.0000005845445230, 75.66282330657800514 ) ) ; +#35950 = CARTESIAN_POINT ( 'NONE', ( 37.78006692254000143, 118.6320720638999973, 87.34557981016999406 ) ) ; +#35951 = DIRECTION ( 'NONE', ( 0.7066795775160008564, -0.000000000000000000, -0.7075337269147008445 ) ) ; +#35952 = CARTESIAN_POINT ( 'NONE', ( 38.42323727947000123, 119.1365327004000108, 90.40419822697000996 ) ) ; +#35953 = ORIENTED_EDGE ( 'NONE', *, *, #3726, .F. ) ; +#35954 = LINE ( 'NONE', #8176, #30943 ) ; +#35955 = DIRECTION ( 'NONE', ( 0.0005884949961190483105, -0.2249510543439053878, 0.9743698870671265722 ) ) ; +#35956 = CARTESIAN_POINT ( 'NONE', ( 44.24596348240854837, 122.9115719264381710, 88.00256960708196630 ) ) ; +#35957 = DIRECTION ( 'NONE', ( -0.0004270303127820591058, -0.7071067811865883179, -0.7071066522421171063 ) ) ; +#35958 = VECTOR ( 'NONE', #28227, 1000.000000000000114 ) ; +#35959 = DIRECTION ( 'NONE', ( -0.7731297265845318289, -0.5272054548977799238, -0.3525972691291752170 ) ) ; +#35960 = ORIENTED_EDGE ( 'NONE', *, *, #23311, .F. ) ; +#35961 = ORIENTED_EDGE ( 'NONE', *, *, #18751, .F. ) ; +#35962 = AXIS2_PLACEMENT_3D ( 'NONE', #35020, #38127, #13384 ) ; +#35963 = EDGE_CURVE ( 'NONE', #30736, #36135, #8278, .T. ) ; +#35964 = VECTOR ( 'NONE', #10492, 1000.000000000000114 ) ; +#35965 = VERTEX_POINT ( 'NONE', #33191 ) ; +#35966 = DIRECTION ( 'NONE', ( -0.7942820423213363679, -0.5918950211223027447, -0.1370267171630251690 ) ) ; +#35967 = VECTOR ( 'NONE', #1382, 1000.000000000000114 ) ; +#35968 = VERTEX_POINT ( 'NONE', #38936 ) ; +#35969 = DIRECTION ( 'NONE', ( 0.0004161288024537937186, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#35970 = AXIS2_PLACEMENT_3D ( 'NONE', #10467, #26811, #4300 ) ; +#35971 = CARTESIAN_POINT ( 'NONE', ( -43.10573975924778978, 121.2931756425902847, 90.61592751502209353 ) ) ; +#35972 = EDGE_CURVE ( 'NONE', #11781, #10321, #4000, .T. ) ; +#35973 = ORIENTED_EDGE ( 'NONE', *, *, #3853, .F. ) ; +#35974 = EDGE_CURVE ( 'NONE', #37986, #16662, #32959, .T. ) ; +#35975 = ORIENTED_EDGE ( 'NONE', *, *, #8400, .T. ) ; +#35976 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#35977 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#35978 = CARTESIAN_POINT ( 'NONE', ( -37.23494651666909050, 103.9956957637453598, 184.2025836917128174 ) ) ; +#35979 = CARTESIAN_POINT ( 'NONE', ( -26.01494426630450008, 211.0902259182902014, 73.07465174665132679 ) ) ; +#35980 = ORIENTED_EDGE ( 'NONE', *, *, #18835, .F. ) ; +#35981 = EDGE_CURVE ( 'NONE', #10675, #10713, #20119, .T. ) ; +#35982 = CARTESIAN_POINT ( 'NONE', ( 19.33632959910114124, 147.9597651028845462, 183.5586071598492026 ) ) ; +#35983 = ORIENTED_EDGE ( 'NONE', *, *, #36064, .F. ) ; +#35984 = DIRECTION ( 'NONE', ( 0.0005884950107539749361, -0.2249510543548229602, 0.9743698870645971510 ) ) ; +#35985 = CARTESIAN_POINT ( 'NONE', ( 35.67368674445789622, 113.9486398105102580, 90.24623882632185712 ) ) ; +#35986 = CARTESIAN_POINT ( 'NONE', ( -19.54703320420837898, 148.9928018343113933, 183.1147439724198591 ) ) ; +#35987 = VERTEX_POINT ( 'NONE', #7860 ) ; +#35988 = ORIENTED_EDGE ( 'NONE', *, *, #36022, .F. ) ; +#35989 = CARTESIAN_POINT ( 'NONE', ( -0.6436417827288198890, 188.6082569606599861, 103.1943079271519963 ) ) ; +#35990 = CARTESIAN_POINT ( 'NONE', ( 1.112971808851000111, 189.0817780705000075, 103.7152259047999934 ) ) ; +#35991 = CYLINDRICAL_SURFACE ( 'NONE', #30241, 2.000000000000011546 ) ; +#35992 = LINE ( 'NONE', #7996, #40391 ) ; +#35993 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2084, #4931, #23354, #4518, #17184, #11080 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 4 ), + ( 0.000000000000000000, 0.3333326433113111276, 0.6666670495315556444, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35994 = VERTEX_POINT ( 'NONE', #30156 ) ; +#35995 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22774, #19875, #7211, #32372 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#35996 = CARTESIAN_POINT ( 'NONE', ( 17.36823235821892553, 127.5715682803508173, 172.3982060061660775 ) ) ; +#35997 = ORIENTED_EDGE ( 'NONE', *, *, #7867, .F. ) ; +#35998 = ORIENTED_EDGE ( 'NONE', *, *, #4402, .T. ) ; +#35999 = CIRCLE ( 'NONE', #37308, 2.499999999972146725 ) ; +#36000 = EDGE_CURVE ( 'NONE', #26666, #7629, #35529, .T. ) ; +#36001 = CONICAL_SURFACE ( 'NONE', #9267, 6.500001283309376099, 0.7853982200479777687 ) ; +#36002 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25717, #38168, #23846, #10766 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36003 = ORIENTED_EDGE ( 'NONE', *, *, #33484, .T. ) ; +#36004 = LINE ( 'NONE', #9233, #28265 ) ; +#36005 = VERTEX_POINT ( 'NONE', #39330 ) ; +#36006 = CARTESIAN_POINT ( 'NONE', ( -45.01543256409814120, 130.9257504736116289, 89.90670049556989341 ) ) ; +#36007 = CARTESIAN_POINT ( 'NONE', ( 14.35378279688742253, 196.5784924078620293, 103.8663088710679148 ) ) ; +#36008 = PLANE ( 'NONE', #2599 ) ; +#36009 = ORIENTED_EDGE ( 'NONE', *, *, #35122, .F. ) ; +#36010 = FACE_OUTER_BOUND ( 'NONE', #32423, .T. ) ; +#36011 = ORIENTED_EDGE ( 'NONE', *, *, #3309, .T. ) ; +#36012 = EDGE_CURVE ( 'NONE', #32563, #18083, #11142, .T. ) ; +#36013 = CARTESIAN_POINT ( 'NONE', ( 28.22559710222000007, 124.4220533023000144, 91.43995667158999652 ) ) ; +#36014 = CARTESIAN_POINT ( 'NONE', ( 22.95436083522999837, 118.1131156702000169, 13.53038997162000001 ) ) ; +#36016 = CARTESIAN_POINT ( 'NONE', ( -30.18611281846582628, 185.3309324562166864, 102.8002735974070418 ) ) ; +#36015 = DIRECTION ( 'NONE', ( 0.7947975163364137119, -0.5917479692793309320, -0.1346523259333320122 ) ) ; +#36017 = ORIENTED_EDGE ( 'NONE', *, *, #32881, .T. ) ; +#36018 = ADVANCED_FACE ( 'NONE', ( #35439 ), #10549, .F. ) ; +#36019 = ORIENTED_EDGE ( 'NONE', *, *, #15045, .F. ) ; +#36020 = ADVANCED_FACE ( 'NONE', ( #36278 ), #23014, .T. ) ; +#36021 = VECTOR ( 'NONE', #36364, 1000.000000000000114 ) ; +#36022 = EDGE_CURVE ( 'NONE', #29762, #1613, #1736, .T. ) ; +#36023 = ORIENTED_EDGE ( 'NONE', *, *, #10984, .T. ) ; +#36025 = EDGE_CURVE ( 'NONE', #24812, #25693, #15355, .T. ) ; +#36024 = CARTESIAN_POINT ( 'NONE', ( 39.59230100324000290, 119.1504122669000196, 89.56670257055999684 ) ) ; +#36026 = CARTESIAN_POINT ( 'NONE', ( -42.83272783108322557, 107.4558756614410697, 150.2543767220365680 ) ) ; +#36027 = EDGE_CURVE ( 'NONE', #32971, #23892, #25814, .T. ) ; +#36028 = AXIS2_PLACEMENT_3D ( 'NONE', #23675, #5251, #7921 ) ; +#36029 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501094951, 179.0628333272064197, 104.0826189413997440 ) ) ; +#36030 = CARTESIAN_POINT ( 'NONE', ( -26.81689520618117939, 187.6029399509571078, 105.5464327012842318 ) ) ; +#36031 = CARTESIAN_POINT ( 'NONE', ( 36.42232590615000021, 191.8149838951999868, 104.3700011025999999 ) ) ; +#36032 = VERTEX_POINT ( 'NONE', #29352 ) ; +#36033 = ORIENTED_EDGE ( 'NONE', *, *, #22160, .F. ) ; +#36034 = CARTESIAN_POINT ( 'NONE', ( 20.00182604067493131, 190.8514159882993511, 106.7812686061269716 ) ) ; +#36035 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3153, #37506, #28520, #15633 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36036 = CARTESIAN_POINT ( 'NONE', ( 25.49847230246999885, 121.0495832369999931, 88.09734716337999316 ) ) ; +#36037 = ORIENTED_EDGE ( 'NONE', *, *, #31344, .T. ) ; +#36038 = CARTESIAN_POINT ( 'NONE', ( -1.212288473603901240, 143.4871526178525869, 158.5698567282870499 ) ) ; +#36039 = VERTEX_POINT ( 'NONE', #1322 ) ; +#36040 = ORIENTED_EDGE ( 'NONE', *, *, #14913, .T. ) ; +#36041 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; +#36042 = ORIENTED_EDGE ( 'NONE', *, *, #31857, .T. ) ; +#36043 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#36044 = EDGE_CURVE ( 'NONE', #31750, #36248, #26287, .T. ) ; +#36045 = CARTESIAN_POINT ( 'NONE', ( -2.691512666988662872, 209.6623512938134013, 75.89346368600931214 ) ) ; +#36046 = CARTESIAN_POINT ( 'NONE', ( -5.668107805537519361, 126.1261160540004767, 91.85696217430825072 ) ) ; +#36047 = DIRECTION ( 'NONE', ( 0.0004161288024437542234, -0.8480480898092626063, 0.5299191110043877107 ) ) ; +#36048 = VERTEX_POINT ( 'NONE', #26689 ) ; +#36049 = AXIS2_PLACEMENT_3D ( 'NONE', #5049, #38999, #39800 ) ; +#36050 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36051 = CARTESIAN_POINT ( 'NONE', ( -2.436614782451819838, 191.0000000999000065, 104.9475220120663579 ) ) ; +#36052 = AXIS2_PLACEMENT_3D ( 'NONE', #8730, #21194, #18301 ) ; +#36053 = CIRCLE ( 'NONE', #29569, 1.750000000000001998 ) ; +#36054 = ORIENTED_EDGE ( 'NONE', *, *, #3637, .T. ) ; +#36055 = ADVANCED_FACE ( 'NONE', ( #39142 ), #38188, .F. ) ; +#36056 = FACE_OUTER_BOUND ( 'NONE', #27216, .T. ) ; +#36058 = CARTESIAN_POINT ( 'NONE', ( 15.67412488234288759, 159.4968216871810398, 96.46619825634390111 ) ) ; +#36057 = FACE_OUTER_BOUND ( 'NONE', #5930, .T. ) ; +#36060 = ORIENTED_EDGE ( 'NONE', *, *, #34985, .T. ) ; +#36059 = EDGE_CURVE ( 'NONE', #10082, #20853, #30353, .T. ) ; +#36061 = LINE ( 'NONE', #23208, #24338 ) ; +#36062 = ORIENTED_EDGE ( 'NONE', *, *, #7089, .F. ) ; +#36063 = DIRECTION ( 'NONE', ( 0.5988681445390194868, -0.8008476418498040594, 0.000000000000000000 ) ) ; +#36064 = EDGE_CURVE ( 'NONE', #10990, #34119, #34211, .T. ) ; +#36065 = CARTESIAN_POINT ( 'NONE', ( 77.66065009075275327, 193.3992594998515244, 188.4681838635439419 ) ) ; +#36066 = CARTESIAN_POINT ( 'NONE', ( 15.50147165590422205, 151.4095604219332643, 97.16497155034561217 ) ) ; +#36067 = LINE ( 'NONE', #39952, #17475 ) ; +#36068 = EDGE_LOOP ( 'NONE', ( #6164, #26886, #10211, #14614 ) ) ; +#36069 = ORIENTED_EDGE ( 'NONE', *, *, #1202, .T. ) ; +#36070 = CARTESIAN_POINT ( 'NONE', ( -42.61860293796636512, 120.8482216545914270, 90.95641729975723422 ) ) ; +#36071 = ORIENTED_EDGE ( 'NONE', *, *, #35872, .T. ) ; +#36072 = ORIENTED_EDGE ( 'NONE', *, *, #39856, .T. ) ; +#36073 = ORIENTED_EDGE ( 'NONE', *, *, #37407, .F. ) ; +#36075 = EDGE_CURVE ( 'NONE', #5203, #10712, #4207, .T. ) ; +#36074 = CARTESIAN_POINT ( 'NONE', ( -22.78292978085340081, 157.6260587155269661, 99.13643849004034792 ) ) ; +#36076 = DIRECTION ( 'NONE', ( 0.1695469893270775408, -1.252670582138759641E-14, -0.9855221044756549142 ) ) ; +#36077 = CARTESIAN_POINT ( 'NONE', ( 23.08502856561264593, 148.5869484094654354, 197.0326829874275347 ) ) ; +#36078 = CARTESIAN_POINT ( 'NONE', ( 29.38693461565323872, 112.1844516200949755, 175.8396907018270383 ) ) ; +#36079 = VECTOR ( 'NONE', #1696, 1000.000000000000227 ) ; +#36080 = ORIENTED_EDGE ( 'NONE', *, *, #31396, .F. ) ; +#36081 = CARTESIAN_POINT ( 'NONE', ( 13.36382089992252453, 177.7154036444319729, 100.6736854505625018 ) ) ; +#36082 = FACE_OUTER_BOUND ( 'NONE', #29388, .T. ) ; +#36083 = CARTESIAN_POINT ( 'NONE', ( -35.81398623132000125, 192.3507530278000388, 104.2979901971000061 ) ) ; +#36084 = CARTESIAN_POINT ( 'NONE', ( 37.76913763144000313, 191.3232487601999878, 104.1935076314999975 ) ) ; +#36085 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2998, #18327, #6266, #24709 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36086 = ORIENTED_EDGE ( 'NONE', *, *, #30297, .F. ) ; +#36087 = CARTESIAN_POINT ( 'NONE', ( -26.00144291263000085, 120.7763519191999961, 87.55119131511999342 ) ) ; +#36088 = CARTESIAN_POINT ( 'NONE', ( 41.04644941596783525, 217.7719116456999870, 75.53371351155776381 ) ) ; +#36089 = VECTOR ( 'NONE', #9651, 1000.000000000000227 ) ; +#36090 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 135.6522072397361853, 90.95982947643901184 ) ) ; +#36091 = CARTESIAN_POINT ( 'NONE', ( 28.46561152637903547, 127.9145563911127113, 92.24604361343246239 ) ) ; +#36092 = ORIENTED_EDGE ( 'NONE', *, *, #10429, .F. ) ; +#36093 = CARTESIAN_POINT ( 'NONE', ( -6.037313578920448620, 134.5364664150864087, 93.54487822610151682 ) ) ; +#36094 = CARTESIAN_POINT ( 'NONE', ( -22.78373664921000241, 158.6756214347751097, 96.81298893714118492 ) ) ; +#36095 = LINE ( 'NONE', #8309, #37917 ) ; +#36096 = PLANE ( 'NONE', #61 ) ; +#36097 = EDGE_LOOP ( 'NONE', ( #7657, #37034, #33821, #36935 ) ) ; +#36098 = DIRECTION ( 'NONE', ( 0.1632030863883330296, -0.3417424275059343097, 0.9255143790539797077 ) ) ; +#36099 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#36100 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; +#36101 = ORIENTED_EDGE ( 'NONE', *, *, #21049, .F. ) ; +#36102 = CARTESIAN_POINT ( 'NONE', ( -42.87041437821633139, 121.8978841230586170, 87.86525719409469559 ) ) ; +#36103 = CARTESIAN_POINT ( 'NONE', ( -25.35601378779999848, 191.7662701877000018, 104.5630184056000047 ) ) ; +#36104 = DIRECTION ( 'NONE', ( -0.0004161288024511093967, -0.5299192578742120130, -0.8480479980348188951 ) ) ; +#36105 = CARTESIAN_POINT ( 'NONE', ( 25.68657024044000181, 191.1729245184999968, 104.1504610859000053 ) ) ; +#36106 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364818587623, 136.5649596138779884, 181.4686487119677167 ) ) ; +#36107 = CARTESIAN_POINT ( 'NONE', ( -21.75981387337644080, 213.2747155673518193, 75.57157761709684962 ) ) ; +#36108 = CARTESIAN_POINT ( 'NONE', ( 16.54117632239534430, 152.4851539532401148, 181.7923885842497214 ) ) ; +#36109 = AXIS2_PLACEMENT_3D ( 'NONE', #28493, #31007, #19259 ) ; +#36110 = LINE ( 'NONE', #8119, #10190 ) ; +#36111 = EDGE_CURVE ( 'NONE', #13982, #37303, #2283, .T. ) ; +#36112 = ORIENTED_EDGE ( 'NONE', *, *, #18908, .T. ) ; +#36113 = EDGE_CURVE ( 'NONE', #30592, #14524, #17175, .T. ) ; +#36114 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #18227, #30532, #24606, #30930, #17818, #28071 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36115 = ADVANCED_FACE ( 'NONE', ( #33612 ), #37492, .F. ) ; +#36116 = AXIS2_PLACEMENT_3D ( 'NONE', #37454, #25403, #37852 ) ; +#36117 = CARTESIAN_POINT ( 'NONE', ( 39.85586901997003650, 129.5283103249424244, 336.2586849593528768 ) ) ; +#36118 = AXIS2_PLACEMENT_3D ( 'NONE', #4194, #16863, #9109 ) ; +#36119 = CARTESIAN_POINT ( 'NONE', ( -24.84081799597801421, 115.7102179961852357, 87.28278752364165882 ) ) ; +#36120 = CARTESIAN_POINT ( 'NONE', ( -3.537750984983824232, 137.3463269818849426, 91.36396247942009552 ) ) ; +#36121 = ADVANCED_FACE ( 'NONE', ( #6803 ), #32178, .T. ) ; +#36122 = CARTESIAN_POINT ( 'NONE', ( -40.77069120851000861, 112.8448473173999957, 152.4718672074000381 ) ) ; +#36123 = CARTESIAN_POINT ( 'NONE', ( 32.08164567794030830, 176.8424030107383089, 100.4608322395127260 ) ) ; +#36124 = CARTESIAN_POINT ( 'NONE', ( -25.49003114136341352, 191.3825488810288107, 106.3975518461934371 ) ) ; +#36125 = CARTESIAN_POINT ( 'NONE', ( 29.19927575800447173, 163.6433483284885426, 97.41533068389654204 ) ) ; +#36126 = CARTESIAN_POINT ( 'NONE', ( 22.78196627740044278, 153.3599009982148118, 97.61084599868732425 ) ) ; +#36127 = CARTESIAN_POINT ( 'NONE', ( 20.25403320342156377, 116.9073549109220806, 90.25555191067651606 ) ) ; +#36128 = ORIENTED_EDGE ( 'NONE', *, *, #4043, .F. ) ; +#36129 = EDGE_CURVE ( 'NONE', #38943, #4584, #7918, .T. ) ; +#36130 = CARTESIAN_POINT ( 'NONE', ( -19.99970941558080284, 118.1131156714892114, 90.27986793006986943 ) ) ; +#36131 = DIRECTION ( 'NONE', ( 7.677760455958669993E-18, -1.000000000000000000, 1.271205131337281593E-14 ) ) ; +#36132 = ORIENTED_EDGE ( 'NONE', *, *, #35921, .F. ) ; +#36133 = CARTESIAN_POINT ( 'NONE', ( 37.78025130169015711, 80.42490204549953603, 284.8841145757368167 ) ) ; +#36134 = CARTESIAN_POINT ( 'NONE', ( 3.769207233074749031, 136.7343769535524984, 94.05766322553326120 ) ) ; +#36135 = VERTEX_POINT ( 'NONE', #34604 ) ; +#36136 = ADVANCED_FACE ( 'NONE', ( #31780 ), #16014, .T. ) ; +#36137 = CARTESIAN_POINT ( 'NONE', ( 25.42551241295287667, 211.7445882540852438, 73.54297905658798129 ) ) ; +#36138 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; +#36139 = ORIENTED_EDGE ( 'NONE', *, *, #39310, .F. ) ; +#36140 = DIRECTION ( 'NONE', ( 0.7933310414247656261, 0.5931044597393390072, 0.1373060761554398823 ) ) ; +#36141 = VECTOR ( 'NONE', #17152, 1000.000000000000114 ) ; +#36142 = CARTESIAN_POINT ( 'NONE', ( -22.78364630492483656, 153.8037711675519859, 95.68823341888959533 ) ) ; +#36143 = CARTESIAN_POINT ( 'NONE', ( -40.95517856241297494, 219.0860688542000219, 75.58324044005291853 ) ) ; +#36144 = AXIS2_PLACEMENT_3D ( 'NONE', #14534, #18380, #27019 ) ; +#36145 = CARTESIAN_POINT ( 'NONE', ( 31.79391164804998127, 225.9002260768332633, 73.03930135632873544 ) ) ; +#36146 = PLANE ( 'NONE', #10601 ) ; +#36147 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #10828, #31705, #28626, #998 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( -9.769962616701377556E-15, 0.1815409218495399601 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9972554596699720886, 0.9972554596699720886, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#36148 = ORIENTED_EDGE ( 'NONE', *, *, #25861, .T. ) ; +#36149 = CARTESIAN_POINT ( 'NONE', ( 39.68496035423999757, 120.3220653550000065, 87.52937166904000321 ) ) ; +#36150 = AXIS2_PLACEMENT_3D ( 'NONE', #1539, #7267, #20136 ) ; +#36151 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21684, #34321, #6120, #18982 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36152 = CARTESIAN_POINT ( 'NONE', ( -20.16659611466318580, 120.3526820203828436, 87.62178027201382235 ) ) ; +#36153 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501097082, 176.3833156737244110, 103.4640034347852975 ) ) ; +#36154 = CARTESIAN_POINT ( 'NONE', ( -20.35076456421905888, 207.5617848265386840, 77.15901428017532737 ) ) ; +#36155 = ORIENTED_EDGE ( 'NONE', *, *, #12836, .F. ) ; +#36156 = ORIENTED_EDGE ( 'NONE', *, *, #27956, .F. ) ; +#36157 = CARTESIAN_POINT ( 'NONE', ( -0.001765484987732086333, 156.3551877983824170, 95.75036263592863861 ) ) ; +#36158 = CARTESIAN_POINT ( 'NONE', ( -42.80211665092759432, 120.8344283343924701, 92.46298830314225370 ) ) ; +#36159 = FACE_OUTER_BOUND ( 'NONE', #38507, .T. ) ; +#36160 = CARTESIAN_POINT ( 'NONE', ( -28.17883134163000491, 124.5573437160000054, 91.38045355701001426 ) ) ; +#36161 = CARTESIAN_POINT ( 'NONE', ( -25.51533646434189961, 211.0902259025884007, 73.57326538444725372 ) ) ; +#36162 = LINE ( 'NONE', #14912, #24786 ) ; +#36163 = EDGE_CURVE ( 'NONE', #31227, #2967, #39126, .T. ) ; +#36164 = EDGE_CURVE ( 'NONE', #11951, #33925, #4131, .T. ) ; +#36165 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3838, #13074, #7516, #38784 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36166 = DIRECTION ( 'NONE', ( -0.0005884949961189345777, 0.2249510543439073862, -0.9743698870671260170 ) ) ; +#36167 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36168 = CARTESIAN_POINT ( 'NONE', ( 20.48035933545727261, 208.8549887208692155, 73.60699811742749432 ) ) ; +#36169 = CARTESIAN_POINT ( 'NONE', ( 38.80823801556999797, 118.5174377607999929, 89.51271477801999765 ) ) ; +#36170 = CIRCLE ( 'NONE', #8103, 4.999999999999990230 ) ; +#36171 = VECTOR ( 'NONE', #32242, 1000.000000000000114 ) ; +#36172 = ORIENTED_EDGE ( 'NONE', *, *, #21942, .T. ) ; +#36173 = LINE ( 'NONE', #27001, #36802 ) ; +#36174 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36175 = CARTESIAN_POINT ( 'NONE', ( -21.21399079302519652, 183.3565551017309190, 102.5100844002234197 ) ) ; +#36176 = CARTESIAN_POINT ( 'NONE', ( -22.22019231403135819, 115.1898461495169812, 87.28120473139716751 ) ) ; +#36177 = CIRCLE ( 'NONE', #2909, 59.40509898897001051 ) ; +#36178 = CARTESIAN_POINT ( 'NONE', ( -20.49975839845215830, 192.0926363215378387, 104.4339699173596756 ) ) ; +#36179 = VERTEX_POINT ( 'NONE', #12964 ) ; +#36180 = ORIENTED_EDGE ( 'NONE', *, *, #27987, .F. ) ; +#36181 = ORIENTED_EDGE ( 'NONE', *, *, #2769, .F. ) ; +#36182 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 2.523234147032834427E-15, 0.0006039748319402993802 ) ) ; +#36183 = DIRECTION ( 'NONE', ( -0.0001408404346092576671, 0.2255194953558363191, -0.9742386449830560124 ) ) ; +#36184 = VERTEX_POINT ( 'NONE', #31975 ) ; +#36185 = CARTESIAN_POINT ( 'NONE', ( -15.93637865429753120, 186.5404220567731954, 102.7287984460090655 ) ) ; +#36186 = EDGE_CURVE ( 'NONE', #16595, #22787, #9904, .T. ) ; +#36187 = CARTESIAN_POINT ( 'NONE', ( -39.69476436410172226, 161.7095167889038692, 196.8665534586947672 ) ) ; +#36188 = FACE_OUTER_BOUND ( 'NONE', #4998, .T. ) ; +#36189 = CARTESIAN_POINT ( 'NONE', ( 14.54953207236175139, 130.1535194663153447, 89.69244121379192336 ) ) ; +#36190 = CARTESIAN_POINT ( 'NONE', ( -36.08997809811999957, 113.3914357756000015, 87.92830918980999400 ) ) ; +#36191 = VERTEX_POINT ( 'NONE', #28697 ) ; +#36192 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#36193 = CARTESIAN_POINT ( 'NONE', ( -15.60630250089785065, 175.8727404917108856, 100.2657702926515242 ) ) ; +#36194 = FACE_OUTER_BOUND ( 'NONE', #6924, .T. ) ; +#36195 = DIRECTION ( 'NONE', ( 0.5986917825334768795, 0.8009794122048727871, -0.0003615948347012565940 ) ) ; +#36196 = CARTESIAN_POINT ( 'NONE', ( -3.191551117751024957, 186.2886659142941710, 102.6629783937155764 ) ) ; +#36197 = CARTESIAN_POINT ( 'NONE', ( -19.99825438583805237, 190.8509747501094580, 106.8052823956111013 ) ) ; +#36198 = AXIS2_PLACEMENT_3D ( 'NONE', #35533, #4691, #4892 ) ; +#36199 = CONICAL_SURFACE ( 'NONE', #8131, 2.503115359310264409, 0.7853981634098280429 ) ; +#36200 = ORIENTED_EDGE ( 'NONE', *, *, #17510, .F. ) ; +#36201 = CARTESIAN_POINT ( 'NONE', ( -1.594832852936999945, 189.0177083714000048, 103.4292051506999996 ) ) ; +#36202 = CARTESIAN_POINT ( 'NONE', ( 0.5623168218902999671, 188.6118872737999936, 103.1964808549000026 ) ) ; +#36203 = AXIS2_PLACEMENT_3D ( 'NONE', #759, #37379, #3417 ) ; +#36204 = AXIS2_PLACEMENT_3D ( 'NONE', #26117, #13034, #25516 ) ; +#36205 = PLANE ( 'NONE', #21761 ) ; +#36206 = CARTESIAN_POINT ( 'NONE', ( -35.64858212982840513, 191.7420658667043654, 106.9375512398736561 ) ) ; +#36207 = ORIENTED_EDGE ( 'NONE', *, *, #21375, .F. ) ; +#36208 = VECTOR ( 'NONE', #13848, 999.9999999999998863 ) ; +#36209 = ORIENTED_EDGE ( 'NONE', *, *, #17365, .T. ) ; +#36210 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282901917, 154.4034317163438175, 95.31352405029051056 ) ) ; +#36211 = VERTEX_POINT ( 'NONE', #31569 ) ; +#36212 = VERTEX_POINT ( 'NONE', #6406 ) ; +#36213 = ORIENTED_EDGE ( 'NONE', *, *, #763, .F. ) ; +#36214 = VERTEX_POINT ( 'NONE', #3938 ) ; +#36215 = EDGE_CURVE ( 'NONE', #21825, #1116, #22375, .T. ) ; +#36216 = ADVANCED_FACE ( 'NONE', ( #7008 ), #38291, .T. ) ; +#36217 = CARTESIAN_POINT ( 'NONE', ( 22.50147045824883918, 160.1804542550550536, 99.18566449512113081 ) ) ; +#36218 = CARTESIAN_POINT ( 'NONE', ( -22.64037623556000156, 157.9259078517000319, 98.94900196435999362 ) ) ; +#36219 = CARTESIAN_POINT ( 'NONE', ( -6.679083190205946056E-14, 150.3212993284946606, 97.43624128390267458 ) ) ; +#36220 = ORIENTED_EDGE ( 'NONE', *, *, #27396, .T. ) ; +#36221 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825875308198743, 0.0005734119034175035826 ) ) ; +#36222 = VERTEX_POINT ( 'NONE', #25446 ) ; +#36223 = CARTESIAN_POINT ( 'NONE', ( 26.24438363001889840, 121.6906080158060206, 90.81567923076639204 ) ) ; +#36224 = CARTESIAN_POINT ( 'NONE', ( -24.42595481105102451, 104.1131156702295186, 90.28253750387099785 ) ) ; +#36226 = CARTESIAN_POINT ( 'NONE', ( -27.18778663116000160, 103.8631156702000027, 87.53420507948000306 ) ) ; +#36225 = DIRECTION ( 'NONE', ( -0.0006039748319384231684, -2.335630580398557718E-15, -0.9999998176071847045 ) ) ; +#36227 = CONICAL_SURFACE ( 'NONE', #20549, 22.50000000000906653, 0.7853981633972855203 ) ; +#36228 = ORIENTED_EDGE ( 'NONE', *, *, #27067, .F. ) ; +#36229 = AXIS2_PLACEMENT_3D ( 'NONE', #32336, #7372, #20041 ) ; +#36230 = AXIS2_PLACEMENT_3D ( 'NONE', #8260, #20723, #8047 ) ; +#36231 = VERTEX_POINT ( 'NONE', #25652 ) ; +#36232 = CARTESIAN_POINT ( 'NONE', ( 21.44870233977301410, 176.2493420812517968, 103.4092482268179936 ) ) ; +#36233 = AXIS2_PLACEMENT_3D ( 'NONE', #7658, #10950, #20530 ) ; +#36234 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #37580, #6490 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36235 = EDGE_LOOP ( 'NONE', ( #30376, #17373, #3196, #16828, #16993 ) ) ; +#36236 = DIRECTION ( 'NONE', ( 4.163336342270463358E-15, 0.9743700557921590732, 0.2249510932971540977 ) ) ; +#36237 = EDGE_CURVE ( 'NONE', #19028, #15849, #7208, .T. ) ; +#36238 = DIRECTION ( 'NONE', ( 0.7933532411131102302, 0.5932638852154232811, 0.1364866195435443241 ) ) ; +#36239 = DIRECTION ( 'NONE', ( -0.9999998268367782384, -0.0001323826467776493491, 0.0005734119359534853039 ) ) ; +#36240 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048996748, 134.2394347309033833, 93.74516030699037117 ) ) ; +#36241 = CARTESIAN_POINT ( 'NONE', ( 36.12836467949000507, 191.5083383925000078, 103.8363012094000055 ) ) ; +#36242 = EDGE_LOOP ( 'NONE', ( #23232, #28023, #7184, #16588 ) ) ; +#36243 = ORIENTED_EDGE ( 'NONE', *, *, #4453, .T. ) ; +#36244 = CARTESIAN_POINT ( 'NONE', ( -0.6019324427172583203, 188.9986941098608781, 103.6847164217354589 ) ) ; +#36245 = DIRECTION ( 'NONE', ( 0.0005884949961215159547, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36246 = CARTESIAN_POINT ( 'NONE', ( 27.15577148128999951, 124.2993249153000050, 88.50433870978000073 ) ) ; +#36247 = ORIENTED_EDGE ( 'NONE', *, *, #623, .T. ) ; +#36248 = VERTEX_POINT ( 'NONE', #82 ) ; +#36249 = FACE_OUTER_BOUND ( 'NONE', #37858, .T. ) ; +#36251 = EDGE_CURVE ( 'NONE', #1155, #8681, #28354, .T. ) ; +#36250 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12736, #19252, #34395, #22557 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 1.757266515702729398E-05, 0.0001596853054049402290 ), + .UNSPECIFIED. ) ; +#36252 = CARTESIAN_POINT ( 'NONE', ( 3.064242084557000201, 190.8511711511999920, 106.7914576077999982 ) ) ; +#36253 = ORIENTED_EDGE ( 'NONE', *, *, #7268, .F. ) ; +#36254 = CARTESIAN_POINT ( 'NONE', ( -20.51878087562336006, 206.7719441278318584, 74.64876841760110437 ) ) ; +#36255 = AXIS2_PLACEMENT_3D ( 'NONE', #38474, #16400, #32357 ) ; +#36256 = ADVANCED_FACE ( 'NONE', ( #12757 ), #37901, .T. ) ; +#36257 = CARTESIAN_POINT ( 'NONE', ( -28.94780665481193793, 110.6131156702000027, 87.78526813307001930 ) ) ; +#36258 = AXIS2_PLACEMENT_3D ( 'NONE', #19443, #34958, #16180 ) ; +#36259 = VECTOR ( 'NONE', #34583, 999.9999999999998863 ) ; +#36260 = DIRECTION ( 'NONE', ( -0.0005884949961257158286, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#36261 = DIRECTION ( 'NONE', ( 0.0005884949961234139590, -0.2249510543439055266, 0.9743698870671265722 ) ) ; +#36262 = ORIENTED_EDGE ( 'NONE', *, *, #33405, .F. ) ; +#36263 = VECTOR ( 'NONE', #872, 1000.000000000000227 ) ; +#36264 = EDGE_CURVE ( 'NONE', #1023, #3379, #9696, .T. ) ; +#36265 = EDGE_CURVE ( 'NONE', #3470, #26904, #34797, .T. ) ; +#36266 = CARTESIAN_POINT ( 'NONE', ( -21.68252898277260954, 177.1920069373947513, 100.5740168946693842 ) ) ; +#36267 = DIRECTION ( 'NONE', ( -0.0005884949961245158337, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#36268 = EDGE_CURVE ( 'NONE', #19698, #10706, #36396, .T. ) ; +#36269 = EDGE_CURVE ( 'NONE', #23150, #38536, #6202, .T. ) ; +#36270 = ORIENTED_EDGE ( 'NONE', *, *, #29590, .F. ) ; +#36271 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7177, #8816, #36193, #29880, #1861, #11264 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36272 = CARTESIAN_POINT ( 'NONE', ( 15.49823494792000034, 187.1838939932000017, 105.9372828411000000 ) ) ; +#36274 = DIRECTION ( 'NONE', ( 0.0002083475567178606162, -0.2252353001617939665, 0.9743043755173853571 ) ) ; +#36273 = CARTESIAN_POINT ( 'NONE', ( 22.50029346827000509, 158.6816162531925158, 96.78702253073828388 ) ) ; +#36275 = EDGE_LOOP ( 'NONE', ( #7066, #22547, #24086, #34671, #13722, #18311 ) ) ; +#36276 = ORIENTED_EDGE ( 'NONE', *, *, #39860, .F. ) ; +#36277 = ORIENTED_EDGE ( 'NONE', *, *, #16896, .T. ) ; +#36278 = FACE_OUTER_BOUND ( 'NONE', #20571, .T. ) ; +#36279 = DIRECTION ( 'NONE', ( -0.6087611434178656911, -0.7731004625493616000, -0.1781166614063267317 ) ) ; +#36280 = CARTESIAN_POINT ( 'NONE', ( 18.90090771971125960, 120.9219860925226300, 173.6350968582803205 ) ) ; +#36281 = ORIENTED_EDGE ( 'NONE', *, *, #21573, .F. ) ; +#36282 = AXIS2_PLACEMENT_3D ( 'NONE', #19815, #35750, #13310 ) ; +#36283 = ORIENTED_EDGE ( 'NONE', *, *, #31431, .F. ) ; +#36284 = CARTESIAN_POINT ( 'NONE', ( 14.27573290317919330, 135.8449083118874228, 91.00656752237129865 ) ) ; +#36285 = ORIENTED_EDGE ( 'NONE', *, *, #11765, .F. ) ; +#36286 = EDGE_LOOP ( 'NONE', ( #26, #12225, #33357 ) ) ; +#36287 = VERTEX_POINT ( 'NONE', #38486 ) ; +#36288 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36289 = EDGE_CURVE ( 'NONE', #2373, #20941, #31321, .T. ) ; +#36290 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; +#36291 = PLANE ( 'NONE', #30755 ) ; +#36292 = CIRCLE ( 'NONE', #25253, 6.499999999993911537 ) ; +#36293 = ORIENTED_EDGE ( 'NONE', *, *, #23080, .F. ) ; +#36294 = ORIENTED_EDGE ( 'NONE', *, *, #16487, .F. ) ; +#36295 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36296 = CARTESIAN_POINT ( 'NONE', ( -35.54466115731000286, 191.7015624462000005, 103.7905865506999987 ) ) ; +#36297 = CARTESIAN_POINT ( 'NONE', ( 36.30644545348000207, 191.5168451883999978, 103.9534424241000181 ) ) ; +#36298 = ORIENTED_EDGE ( 'NONE', *, *, #10172, .T. ) ; +#36299 = CARTESIAN_POINT ( 'NONE', ( -25.66845890388309570, 120.6532999635128931, 87.85646371106152230 ) ) ; +#36300 = DIRECTION ( 'NONE', ( 0.0005734119072324020665, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#36301 = ORIENTED_EDGE ( 'NONE', *, *, #13292, .T. ) ; +#36302 = CARTESIAN_POINT ( 'NONE', ( -3.501646886743174480, 126.2017715745908646, 91.52781443613361034 ) ) ; +#36303 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000092726, 179.7424522644023739, 101.1388664480621884 ) ) ; +#36304 = ORIENTED_EDGE ( 'NONE', *, *, #19046, .T. ) ; +#36305 = EDGE_CURVE ( 'NONE', #21583, #28118, #22060, .T. ) ; +#36306 = CARTESIAN_POINT ( 'NONE', ( -20.51842225234980432, 208.7972206383130356, 75.74176032200549002 ) ) ; +#36307 = FACE_OUTER_BOUND ( 'NONE', #8277, .T. ) ; +#36308 = CARTESIAN_POINT ( 'NONE', ( 37.78115515336936880, 118.8155650090541968, 87.24496173037786662 ) ) ; +#36309 = DIRECTION ( 'NONE', ( 0.0005884949961246861618, -0.2249510543439068866, 0.9743698870671261281 ) ) ; +#36310 = ORIENTED_EDGE ( 'NONE', *, *, #37246, .F. ) ; +#36311 = FACE_OUTER_BOUND ( 'NONE', #16656, .T. ) ; +#36312 = EDGE_CURVE ( 'NONE', #18309, #17075, #11513, .T. ) ; +#36313 = CARTESIAN_POINT ( 'NONE', ( 2.555968269339144339, 190.8015354413785190, 104.2031804828878165 ) ) ; +#36314 = LINE ( 'NONE', #27142, #32597 ) ; +#36315 = EDGE_CURVE ( 'NONE', #11409, #19175, #39652, .T. ) ; +#36316 = VERTEX_POINT ( 'NONE', #27009 ) ; +#36317 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; +#36318 = ORIENTED_EDGE ( 'NONE', *, *, #2688, .T. ) ; +#36319 = EDGE_LOOP ( 'NONE', ( #18736, #22121, #20781, #29987 ) ) ; +#36320 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422003068, 160.0671381723056754, 99.67809115075311865 ) ) ; +#36321 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35582, #8435, #26839, #5128, #32943, #11489, #23764, #14359, #33143, #29291 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36322 = EDGE_CURVE ( 'NONE', #9576, #11668, #11662, .T. ) ; +#36323 = CARTESIAN_POINT ( 'NONE', ( -15.87151776090180100, 147.4423043082527158, 177.3699030816898699 ) ) ; +#36324 = LINE ( 'NONE', #36528, #13752 ) ; +#36325 = CARTESIAN_POINT ( 'NONE', ( -20.00100377755662961, 193.8169056301028945, 102.7149817412491473 ) ) ; +#36326 = EDGE_CURVE ( 'NONE', #9147, #23621, #30476, .T. ) ; +#36327 = EDGE_CURVE ( 'NONE', #14862, #28384, #26473, .T. ) ; +#36328 = CARTESIAN_POINT ( 'NONE', ( -25.50127375672713725, 118.8155664721400058, 87.78318651355773738 ) ) ; +#36329 = CARTESIAN_POINT ( 'NONE', ( 6.033400168022899912, 135.0731597114094598, 91.04333201587085966 ) ) ; +#36330 = ORIENTED_EDGE ( 'NONE', *, *, #18579, .T. ) ; +#36331 = AXIS2_PLACEMENT_3D ( 'NONE', #33826, #36493, #2764 ) ; +#36332 = DESIGN_CONTEXT ( 'detailed design', #6482, 'design' ) ; +#36333 = PLANE ( 'NONE', #23609 ) ; +#36334 = CIRCLE ( 'NONE', #38279, 3.000000000018959945 ) ; +#36335 = CARTESIAN_POINT ( 'NONE', ( -13.50000253664885719, 154.4078437129245458, 95.30587049155346335 ) ) ; +#36336 = CARTESIAN_POINT ( 'NONE', ( 41.04584544117999911, 219.5549399801000163, 74.53371369385999401 ) ) ; +#36337 = DIRECTION ( 'NONE', ( 0.7855473026356902810, 0.6188014303620728018, -0.0004744508866335557583 ) ) ; +#36338 = CARTESIAN_POINT ( 'NONE', ( 5.666613786283987153, 181.3391778151182336, 104.3161990643648380 ) ) ; +#36339 = CARTESIAN_POINT ( 'NONE', ( 19.01936855422726680, 125.6545233337280223, 175.1462352020453181 ) ) ; +#36340 = CARTESIAN_POINT ( 'NONE', ( -22.78246931443000278, 153.3538690590805516, 97.63697319283785703 ) ) ; +#36341 = CARTESIAN_POINT ( 'NONE', ( -37.29638110713771226, 178.8156383198445667, 136.8789424484697008 ) ) ; +#36342 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971571509 ) ) ; +#36343 = VERTEX_POINT ( 'NONE', #16606 ) ; +#36344 = CARTESIAN_POINT ( 'NONE', ( 3.768101781280366769, 144.1625501041019959, 93.17310105376213869 ) ) ; +#36345 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.271205131337281593E-14, -1.000000000000000000 ) ) ; +#36346 = AXIS2_PLACEMENT_3D ( 'NONE', #37705, #9711, #37914 ) ; +#36347 = ORIENTED_EDGE ( 'NONE', *, *, #33642, .F. ) ; +#36348 = DIRECTION ( 'NONE', ( 5.782411586632444827E-15, -1.000000000000000000, 1.387778780791786695E-14 ) ) ; +#36349 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36350 = AXIS2_PLACEMENT_3D ( 'NONE', #24147, #27630, #7976 ) ; +#36351 = ORIENTED_EDGE ( 'NONE', *, *, #10344, .T. ) ; +#36352 = AXIS2_PLACEMENT_3D ( 'NONE', #966, #26537, #38987 ) ; +#36353 = FACE_OUTER_BOUND ( 'NONE', #24384, .T. ) ; +#36354 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -7.515125404477462028E-16, 0.0006039748319388944710 ) ) ; +#36355 = ORIENTED_EDGE ( 'NONE', *, *, #15186, .F. ) ; +#36356 = CARTESIAN_POINT ( 'NONE', ( 77.76878474137986075, 193.3567070688226863, 189.4847442820362176 ) ) ; +#36357 = EDGE_CURVE ( 'NONE', #17219, #37891, #34269, .T. ) ; +#36358 = AXIS2_PLACEMENT_3D ( 'NONE', #22184, #28512, #37309 ) ; +#36359 = EDGE_CURVE ( 'NONE', #26352, #17327, #33513, .T. ) ; +#36360 = FACE_BOUND ( 'NONE', #30349, .T. ) ; +#36361 = EDGE_CURVE ( 'NONE', #4072, #20299, #10507, .T. ) ; +#36362 = FACE_OUTER_BOUND ( 'NONE', #29118, .T. ) ; +#36363 = LINE ( 'NONE', #20614, #24193 ) ; +#36364 = DIRECTION ( 'NONE', ( 0.6087595268730622289, -0.7729404925979503904, -0.1788150814213479156 ) ) ; +#36365 = ORIENTED_EDGE ( 'NONE', *, *, #9697, .F. ) ; +#36366 = CARTESIAN_POINT ( 'NONE', ( -42.55448647980254151, 182.5615766734265719, 104.9051989971102188 ) ) ; +#36367 = FACE_OUTER_BOUND ( 'NONE', #10857, .T. ) ; +#36368 = CARTESIAN_POINT ( 'NONE', ( -36.55077531636867150, 265.2798088768021785, 205.0571533001752584 ) ) ; +#36369 = ADVANCED_FACE ( 'NONE', ( #9806 ), #12073, .F. ) ; +#36370 = ORIENTED_EDGE ( 'NONE', *, *, #7914, .F. ) ; +#36371 = LINE ( 'NONE', #29839, #29506 ) ; +#36372 = ORIENTED_EDGE ( 'NONE', *, *, #17890, .F. ) ; +#36373 = ORIENTED_EDGE ( 'NONE', *, *, #23667, .T. ) ; +#36374 = DIRECTION ( 'NONE', ( 5.204170427930391307E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#36375 = CARTESIAN_POINT ( 'NONE', ( -43.84807852419523755, 120.4163362487306728, 90.70932080257742314 ) ) ; +#36376 = CARTESIAN_POINT ( 'NONE', ( 6.034614391124412336, 134.5699086312019404, 93.51805763178980158 ) ) ; +#36377 = CARTESIAN_POINT ( 'NONE', ( 16.16677578416577532, 152.0066282699150975, 180.9398513676660798 ) ) ; +#36378 = CARTESIAN_POINT ( 'NONE', ( 15.95546908501697558, 121.2205045768968432, 177.4121190822531560 ) ) ; +#36379 = ADVANCED_FACE ( 'NONE', ( #9598 ), #34120, .T. ) ; +#36380 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1405, #17540, #26773, #17332 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36381 = CARTESIAN_POINT ( 'NONE', ( -44.89460993704069836, 182.0197134189947974, 126.4837022849172286 ) ) ; +#36382 = CIRCLE ( 'NONE', #2418, 1.999999999221514280 ) ; +#36383 = LINE ( 'NONE', #11853, #24175 ) ; +#36384 = CONICAL_SURFACE ( 'NONE', #24641, 5.000000000038869352, 0.7853981634009125079 ) ; +#36385 = CARTESIAN_POINT ( 'NONE', ( 8.471855203514563115, 150.6175905705881064, 96.98637658383512417 ) ) ; +#36386 = EDGE_CURVE ( 'NONE', #844, #11929, #18572, .T. ) ; +#36387 = CARTESIAN_POINT ( 'NONE', ( 3.166350703034567449, 184.1264558197564156, 102.1599558388959537 ) ) ; +#36388 = ORIENTED_EDGE ( 'NONE', *, *, #36186, .F. ) ; +#36389 = DIRECTION ( 'NONE', ( 0.6772239534962611884, -0.7357769477300126759, 0.000000000000000000 ) ) ; +#36390 = CARTESIAN_POINT ( 'NONE', ( -14.99833315951566526, 128.8479746833272372, 92.31674066310137050 ) ) ; +#36391 = CARTESIAN_POINT ( 'NONE', ( 28.46284161542680025, 187.5721379928345129, 102.9401731420402939 ) ) ; +#36392 = CARTESIAN_POINT ( 'NONE', ( -29.94629656998989020, 104.1131156706185266, 90.28587165236147882 ) ) ; +#36393 = CARTESIAN_POINT ( 'NONE', ( -15.49852918184222439, 151.4059875814179463, 97.18286991562941068 ) ) ; +#36394 = ORIENTED_EDGE ( 'NONE', *, *, #1246, .F. ) ; +#36395 = ORIENTED_EDGE ( 'NONE', *, *, #26126, .F. ) ; +#36396 = LINE ( 'NONE', #32370, #23851 ) ; +#36397 = ORIENTED_EDGE ( 'NONE', *, *, #768, .T. ) ; +#36398 = FACE_OUTER_BOUND ( 'NONE', #28607, .T. ) ; +#36399 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364886960122, 136.5649596138813706, 181.4686487119530511 ) ) ; +#36400 = ORIENTED_EDGE ( 'NONE', *, *, #19243, .F. ) ; +#36401 = CARTESIAN_POINT ( 'NONE', ( 14.14672431444568090, 135.3083264832294219, 93.79062778484147600 ) ) ; +#36402 = FACE_OUTER_BOUND ( 'NONE', #34469, .T. ) ; +#36403 = DIRECTION ( 'NONE', ( -3.092411411307044243E-16, 0.9743043966640313469, 0.2252353050503803911 ) ) ; +#36404 = CARTESIAN_POINT ( 'NONE', ( -35.66227043188001034, 114.5285734117000089, 87.40209258470000009 ) ) ; +#36405 = EDGE_LOOP ( 'NONE', ( #3185, #36422, #38294, #12237 ) ) ; +#36406 = DIRECTION ( 'NONE', ( 0.7069397808803130623, -0.6508952550417252958, -0.2767155817316080957 ) ) ; +#36407 = EDGE_CURVE ( 'NONE', #24000, #32912, #25843, .T. ) ; +#36408 = AXIS2_PLACEMENT_3D ( 'NONE', #16380, #7580, #28863 ) ; +#36409 = EDGE_CURVE ( 'NONE', #37986, #38350, #3046, .T. ) ; +#36410 = FACE_OUTER_BOUND ( 'NONE', #28350, .T. ) ; +#36411 = ADVANCED_FACE ( 'NONE', ( #21681 ), #37552, .F. ) ; +#36412 = CARTESIAN_POINT ( 'NONE', ( 20.42079989777838733, 184.3877318267062719, 104.8584542328953972 ) ) ; +#36413 = LINE ( 'NONE', #26819, #605 ) ; +#36414 = CIRCLE ( 'NONE', #2482, 5.500000000011062262 ) ; +#36415 = VERTEX_POINT ( 'NONE', #37008 ) ; +#36416 = CARTESIAN_POINT ( 'NONE', ( -26.16810394635999870, 191.1947376692999967, 103.6705749359999942 ) ) ; +#36417 = CARTESIAN_POINT ( 'NONE', ( 0.5945927211446001559, 189.0144201489000011, 103.6920760076999954 ) ) ; +#36418 = CARTESIAN_POINT ( 'NONE', ( 26.45619759317463604, 122.2824172884349707, 90.94697524513031794 ) ) ; +#36419 = EDGE_CURVE ( 'NONE', #21265, #19089, #34926, .T. ) ; +#36420 = ORIENTED_EDGE ( 'NONE', *, *, #21926, .F. ) ; +#36421 = CARTESIAN_POINT ( 'NONE', ( -3.737793663313441428, 136.7241453543145155, 94.09233777841696167 ) ) ; +#36422 = ORIENTED_EDGE ( 'NONE', *, *, #37225, .T. ) ; +#36423 = ADVANCED_FACE ( 'NONE', ( #28016 ), #30384, .F. ) ; +#36424 = VERTEX_POINT ( 'NONE', #6113 ) ; +#36425 = CARTESIAN_POINT ( 'NONE', ( -28.26185612672702518, 125.5768230428473373, 89.17483656727264929 ) ) ; +#36426 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37143, #34252, #9138, #21620 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36427 = ORIENTED_EDGE ( 'NONE', *, *, #9135, .F. ) ; +#36428 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, -1.387778780781445676E-14, 0.9999998176071847045 ) ) ; +#36429 = CARTESIAN_POINT ( 'NONE', ( -15.91639284609066429, 127.7608495146273242, 175.0400872585933882 ) ) ; +#36430 = DIRECTION ( 'NONE', ( 0.9914447795421228449, -0.1270909273342987478, -0.02975139169819295340 ) ) ; +#36431 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#36432 = ADVANCED_FACE ( 'NONE', ( #5919 ), #15136, .T. ) ; +#36433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #56, #26019, #20257, #10480 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.8322599924996976206, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36434 = ORIENTED_EDGE ( 'NONE', *, *, #28664, .F. ) ; +#36435 = CARTESIAN_POINT ( 'NONE', ( -20.49846059232846684, 118.8155328640159070, 89.78014971369738362 ) ) ; +#36436 = ORIENTED_EDGE ( 'NONE', *, *, #7705, .F. ) ; +#36437 = CARTESIAN_POINT ( 'NONE', ( 28.22857880600450287, 124.4169991004199858, 91.44392169599001363 ) ) ; +#36438 = CARTESIAN_POINT ( 'NONE', ( 37.71311666782268190, 212.3970731212147598, 75.53572676091057758 ) ) ; +#36439 = AXIS2_PLACEMENT_3D ( 'NONE', #36691, #15227, #36898 ) ; +#36441 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36440 = CYLINDRICAL_SURFACE ( 'NONE', #2195, 5.249999999999986677 ) ; +#36442 = ORIENTED_EDGE ( 'NONE', *, *, #40182, .F. ) ; +#36443 = ORIENTED_EDGE ( 'NONE', *, *, #507, .F. ) ; +#36444 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825852987664379, 0.0005734119039362157175 ) ) ; +#36445 = EDGE_LOOP ( 'NONE', ( #6313, #27480, #1512, #39986 ) ) ; +#36446 = CARTESIAN_POINT ( 'NONE', ( 39.08375857165000156, 119.3276005580000003, 90.14496493189000148 ) ) ; +#36447 = CARTESIAN_POINT ( 'NONE', ( -11.79199677540114166, 125.9046187772866716, 176.3423774950339862 ) ) ; +#36448 = CARTESIAN_POINT ( 'NONE', ( -31.50053089286999963, 120.4304220373000049, 89.01495634284999880 ) ) ; +#36449 = CARTESIAN_POINT ( 'NONE', ( 41.37348633212936022, 109.4896380203848025, 169.0614224528716818 ) ) ; +#36450 = ORIENTED_EDGE ( 'NONE', *, *, #33366, .T. ) ; +#36451 = ORIENTED_EDGE ( 'NONE', *, *, #24983, .T. ) ; +#36452 = ADVANCED_FACE ( 'NONE', ( #22076 ), #12870, .T. ) ; +#36453 = LINE ( 'NONE', #39510, #5707 ) ; +#36454 = EDGE_CURVE ( 'NONE', #39268, #32939, #12783, .T. ) ; +#36455 = CARTESIAN_POINT ( 'NONE', ( 13.82478458197983073, 188.3446481305931854, 103.1273619351846236 ) ) ; +#36456 = EDGE_LOOP ( 'NONE', ( #3662, #30624 ) ) ; +#36457 = CARTESIAN_POINT ( 'NONE', ( -25.50922756583905837, 191.3757872987501969, 104.3640622938216183 ) ) ; +#36458 = AXIS2_PLACEMENT_3D ( 'NONE', #4616, #1762, #11362 ) ; +#36459 = CARTESIAN_POINT ( 'NONE', ( 2.730805129813000054, 189.5827490002000104, 106.4989638482000061 ) ) ; +#36460 = ORIENTED_EDGE ( 'NONE', *, *, #20419, .F. ) ; +#36461 = FACE_OUTER_BOUND ( 'NONE', #32757, .T. ) ; +#36462 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#36463 = CARTESIAN_POINT ( 'NONE', ( -35.77460950380404370, 171.1392276904801690, 164.9967004675545468 ) ) ; +#36464 = CARTESIAN_POINT ( 'NONE', ( 5.102670828619777055, 148.3404187508898815, 93.89692411454258547 ) ) ; +#36465 = ORIENTED_EDGE ( 'NONE', *, *, #262, .F. ) ; +#36466 = PLANE ( 'NONE', #4879 ) ; +#36467 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452350121, 0.1781166614240801416 ) ) ; +#36468 = ADVANCED_FACE ( 'NONE', ( #19975 ), #9785, .F. ) ; +#36469 = ORIENTED_EDGE ( 'NONE', *, *, #9741, .T. ) ; +#36470 = DIRECTION ( 'NONE', ( 0.0006039748319385826545, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#36471 = ORIENTED_EDGE ( 'NONE', *, *, #12307, .T. ) ; +#36473 = DIRECTION ( 'NONE', ( 0.0005884949961242349169, -0.2249510543439066645, 0.9743698870671261281 ) ) ; +#36472 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825945075553885, 0.0005734119018091926590 ) ) ; +#36474 = ORIENTED_EDGE ( 'NONE', *, *, #16983, .T. ) ; +#36475 = CONICAL_SURFACE ( 'NONE', #12972, 6.499999999895978320, 0.7853981634792253086 ) ; +#36476 = ORIENTED_EDGE ( 'NONE', *, *, #411, .T. ) ; +#36477 = CARTESIAN_POINT ( 'NONE', ( 38.83480492447714738, 118.7067936530172148, 89.66619639117793383 ) ) ; +#36478 = ORIENTED_EDGE ( 'NONE', *, *, #40184, .T. ) ; +#36479 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927771257326, -0.0005734119022076843370 ) ) ; +#36480 = EDGE_CURVE ( 'NONE', #20316, #36559, #13467, .T. ) ; +#36481 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #23499, #23303, #14303, #29642 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36482 = LINE ( 'NONE', #36065, #22266 ) ; +#36483 = CIRCLE ( 'NONE', #39076, 2.500000000015078605 ) ; +#36484 = CARTESIAN_POINT ( 'NONE', ( 12.64002961981943152, 177.6262665254823787, 100.7962259977304882 ) ) ; +#36485 = ORIENTED_EDGE ( 'NONE', *, *, #25823, .T. ) ; +#36486 = ORIENTED_EDGE ( 'NONE', *, *, #12498, .T. ) ; +#36487 = CARTESIAN_POINT ( 'NONE', ( -42.84327062420202026, 120.8099927651375936, 92.42850709477329474 ) ) ; +#36488 = VECTOR ( 'NONE', #2838, 999.9999999999998863 ) ; +#36489 = ORIENTED_EDGE ( 'NONE', *, *, #21607, .T. ) ; +#36490 = ORIENTED_EDGE ( 'NONE', *, *, #18024, .T. ) ; +#36491 = FACE_OUTER_BOUND ( 'NONE', #4449, .T. ) ; +#36492 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178618805657E-05, -0.0002331579774917534240 ) ) ; +#36493 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#36494 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319372081030 ) ) ; +#36495 = ORIENTED_EDGE ( 'NONE', *, *, #30724, .F. ) ; +#36496 = ORIENTED_EDGE ( 'NONE', *, *, #4361, .T. ) ; +#36497 = ORIENTED_EDGE ( 'NONE', *, *, #7470, .T. ) ; +#36498 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091565633 ) ) ; +#36499 = EDGE_CURVE ( 'NONE', #6360, #3422, #15383, .T. ) ; +#36500 = CARTESIAN_POINT ( 'NONE', ( -35.57584641406000259, 192.1220619043999989, 104.0581628891000179 ) ) ; +#36501 = CARTESIAN_POINT ( 'NONE', ( 38.03274256459000213, 191.3252113595999901, 104.1926970713000031 ) ) ; +#36502 = ADVANCED_FACE ( 'NONE', ( #26155 ), #32340, .F. ) ; +#36503 = ORIENTED_EDGE ( 'NONE', *, *, #36000, .F. ) ; +#36504 = CARTESIAN_POINT ( 'NONE', ( -25.83496534220000385, 120.7995788526999945, 87.72842892038001139 ) ) ; +#36505 = EDGE_CURVE ( 'NONE', #29827, #40452, #4447, .T. ) ; +#36506 = EDGE_LOOP ( 'NONE', ( #25548, #6422, #10310, #15863 ) ) ; +#36507 = CARTESIAN_POINT ( 'NONE', ( 1.226688065900417790, 139.2477323444667263, 176.9572749009046220 ) ) ; +#36508 = VERTEX_POINT ( 'NONE', #3638 ) ; +#36509 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684792472, 220.4002260771000294, 75.57961659108507035 ) ) ; +#36510 = FACE_OUTER_BOUND ( 'NONE', #24452, .T. ) ; +#36511 = CARTESIAN_POINT ( 'NONE', ( 40.99498287648146544, 188.9713399934180700, 107.2849007588038575 ) ) ; +#36512 = ORIENTED_EDGE ( 'NONE', *, *, #36407, .T. ) ; +#36513 = CARTESIAN_POINT ( 'NONE', ( 2.467489647358048543, 189.4902148207883954, 103.3986964145526031 ) ) ; +#36514 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#36515 = CARTESIAN_POINT ( 'NONE', ( -14.69744887555976476, 124.6590508092838263, 88.44160731344477711 ) ) ; +#36516 = VERTEX_POINT ( 'NONE', #10606 ) ; +#36517 = CARTESIAN_POINT ( 'NONE', ( -3.336448265352841780, 128.5467635469353525, 89.50334990597771423 ) ) ; +#36518 = CONICAL_SURFACE ( 'NONE', #38483, 2.750000000041938453, 0.7853981633679587571 ) ; +#36519 = CARTESIAN_POINT ( 'NONE', ( 2.413008494521430514, 190.2283635238533748, 104.0378223175451353 ) ) ; +#36520 = CARTESIAN_POINT ( 'NONE', ( 19.71701219870257304, 124.6133069866743455, 177.2811646003819135 ) ) ; +#36521 = AXIS2_PLACEMENT_3D ( 'NONE', #18093, #34049, #9122 ) ; +#36522 = ORIENTED_EDGE ( 'NONE', *, *, #575, .F. ) ; +#36523 = CARTESIAN_POINT ( 'NONE', ( -12.63072017624268106, 177.7897717398484474, 100.7065154983451407 ) ) ; +#36524 = VERTEX_POINT ( 'NONE', #7515 ) ; +#36525 = DIRECTION ( 'NONE', ( 0.0005884949961239145351, -0.2249510543439067201, 0.9743698870671262391 ) ) ; +#36526 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971557076 ) ) ; +#36527 = VECTOR ( 'NONE', #8639, 1000.000000000000227 ) ; +#36528 = CARTESIAN_POINT ( 'NONE', ( -2.935421600793285624, 191.9759150222000130, 106.9232211732562661 ) ) ; +#36529 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21500, #9418, #27641, #21891 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36530 = CARTESIAN_POINT ( 'NONE', ( 6.031586751427973070, 135.0121291300918358, 90.94566406577418149 ) ) ; +#36531 = ORIENTED_EDGE ( 'NONE', *, *, #22527, .T. ) ; +#36532 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11926, #2517, #31133, #33781 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36533 = DIRECTION ( 'NONE', ( -0.7856007465113992172, -0.6187337610642661412, 0.000000000000000000 ) ) ; +#36534 = CARTESIAN_POINT ( 'NONE', ( -37.40113477844868584, 212.8449769292228950, 73.08109343054711360 ) ) ; +#36535 = LINE ( 'NONE', #8538, #21835 ) ; +#36536 = CARTESIAN_POINT ( 'NONE', ( -16.17152365748802723, 122.0555626504313977, 174.5538714920280086 ) ) ; +#36537 = ADVANCED_FACE ( 'NONE', ( #16122 ), #782, .T. ) ; +#36538 = CARTESIAN_POINT ( 'NONE', ( 19.71670472023113518, 125.1331318090227427, 175.0259593520766543 ) ) ; +#36539 = CARTESIAN_POINT ( 'NONE', ( 31.52026657978606394, 177.3554970526973875, 100.5796284133711254 ) ) ; +#36540 = LINE ( 'NONE', #2802, #14235 ) ; +#36541 = CARTESIAN_POINT ( 'NONE', ( -35.93776700278350233, 192.3813625493561119, 104.4100568030667660 ) ) ; +#36542 = VERTEX_POINT ( 'NONE', #16318 ) ; +#36544 = AXIS2_PLACEMENT_3D ( 'NONE', #10276, #32535, #38453 ) ; +#36543 = DIRECTION ( 'NONE', ( 0.0005884949961265558685, -0.2249510543439056931, 0.9743698870671265722 ) ) ; +#36545 = EDGE_CURVE ( 'NONE', #30572, #38012, #573, .T. ) ; +#36546 = CARTESIAN_POINT ( 'NONE', ( 28.46414028889677894, 184.0160272192176762, 102.6323312183167218 ) ) ; +#36547 = CONICAL_SURFACE ( 'NONE', #3870, 2.502986836105446145, 0.7853981633574639298 ) ; +#36548 = ORIENTED_EDGE ( 'NONE', *, *, #20396, .F. ) ; +#36549 = CARTESIAN_POINT ( 'NONE', ( 5.664905786808743571, 181.8314082943285257, 101.8228474347524468 ) ) ; +#36550 = AXIS2_PLACEMENT_3D ( 'NONE', #11606, #11390, #39791 ) ; +#36551 = EDGE_CURVE ( 'NONE', #81, #12152, #31710, .T. ) ; +#36552 = EDGE_CURVE ( 'NONE', #16199, #40349, #22495, .T. ) ; +#36553 = AXIS2_PLACEMENT_3D ( 'NONE', #35530, #32110, #4273 ) ; +#36554 = ORIENTED_EDGE ( 'NONE', *, *, #12689, .T. ) ; +#36555 = CARTESIAN_POINT ( 'NONE', ( -38.59077273876000191, 119.5166102805000037, 87.47846885030999431 ) ) ; +#36556 = ADVANCED_FACE ( 'NONE', ( #393 ), #12886, .T. ) ; +#36557 = DIRECTION ( 'NONE', ( 0.6087616187692346248, -0.7730003051580284223, -0.1785492081725819080 ) ) ; +#36558 = CARTESIAN_POINT ( 'NONE', ( -15.94449010895081642, 152.1461032928982036, 184.5535245782780294 ) ) ; +#36559 = VERTEX_POINT ( 'NONE', #16134 ) ; +#36560 = DIRECTION ( 'NONE', ( 0.0005884949961248230966, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36561 = CARTESIAN_POINT ( 'NONE', ( 46.07705293508445266, 185.2595815743947014, 105.4745506663921475 ) ) ; +#36562 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#36563 = DIRECTION ( 'NONE', ( -0.7856246811335054758, -0.6187033702784218159, 0.000000000000000000 ) ) ; +#36564 = DIRECTION ( 'NONE', ( 0.0005884949961236854432, -0.2249510543439065813, 0.9743698870671262391 ) ) ; +#36565 = ORIENTED_EDGE ( 'NONE', *, *, #38519, .F. ) ; +#36566 = EDGE_LOOP ( 'NONE', ( #11958, #17024, #20229, #33007 ) ) ; +#36567 = DIRECTION ( 'NONE', ( 0.0005884949961259295249, -0.2249510543438812127, 0.9743698870671321233 ) ) ; +#36568 = CARTESIAN_POINT ( 'NONE', ( 12.63704991662151045, 181.8864431108920883, 101.9054465714154958 ) ) ; +#36569 = CARTESIAN_POINT ( 'NONE', ( 28.43929951858842387, 125.3863007536369025, 88.75451113365119227 ) ) ; +#36570 = DIRECTION ( 'NONE', ( -1.868163743362870737E-15, 0.9743700557921586292, 0.2249510932971558463 ) ) ; +#36571 = ORIENTED_EDGE ( 'NONE', *, *, #17512, .T. ) ; +#36572 = LINE ( 'NONE', #40231, #4846 ) ; +#36573 = CARTESIAN_POINT ( 'NONE', ( -43.12191331984786302, 120.9793691103432707, 90.74774789418816567 ) ) ; +#36574 = DIRECTION ( 'NONE', ( -9.300526774670117413E-14, -0.9743700557566449261, -0.2249510934509825477 ) ) ; +#36575 = CARTESIAN_POINT ( 'NONE', ( -28.54869306411000096, 124.7825067222999991, 91.43265992974001222 ) ) ; +#36576 = DIRECTION ( 'NONE', ( -0.0005884949961181158967, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#36577 = AXIS2_PLACEMENT_3D ( 'NONE', #4052, #13281, #22498 ) ; +#36578 = EDGE_CURVE ( 'NONE', #24326, #15091, #35562, .T. ) ; +#36579 = AXIS2_PLACEMENT_3D ( 'NONE', #8455, #29511, #30315 ) ; +#36580 = CARTESIAN_POINT ( 'NONE', ( -22.49852798326972092, 153.3539066485355988, 97.63681037851679889 ) ) ; +#36581 = CONICAL_SURFACE ( 'NONE', #26147, 2.503060577177303347, 0.7853981633905392501 ) ; +#36582 = CARTESIAN_POINT ( 'NONE', ( -25.53470936712000139, 115.6131156702000027, 32.42391899273999911 ) ) ; +#36583 = CARTESIAN_POINT ( 'NONE', ( -30.44899543503618489, 184.9287465216532098, 105.4443919424699487 ) ) ; +#36584 = CARTESIAN_POINT ( 'NONE', ( 33.79411933400908197, 218.5902260770999987, 73.03809328121927535 ) ) ; +#36585 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; +#36586 = CARTESIAN_POINT ( 'NONE', ( 39.03228382966999988, 118.7193833912999992, 89.52168887524000240 ) ) ; +#36587 = CARTESIAN_POINT ( 'NONE', ( 20.49930103516235746, 196.1188360154283430, 103.6658478038365558 ) ) ; +#36588 = CARTESIAN_POINT ( 'NONE', ( -21.82845864282945669, 129.2731355035732292, 92.07692058346603403 ) ) ; +#36589 = ADVANCED_FACE ( 'NONE', ( #9613 ), #3649, .T. ) ; +#36590 = DIRECTION ( 'NONE', ( 0.0005884949961279900511, -0.2249510543439064425, 0.9743698870671262391 ) ) ; +#36591 = CARTESIAN_POINT ( 'NONE', ( -6.035968311314003465, 136.6786235697017844, 94.29340140767534706 ) ) ; +#36592 = EDGE_LOOP ( 'NONE', ( #18001, #31749, #25373, #23909, #24814 ) ) ; +#36593 = VERTEX_POINT ( 'NONE', #10012 ) ; +#36594 = DIRECTION ( 'NONE', ( 3.053113317708491105E-14, 0.9743700557921588512, 0.2249510932971550137 ) ) ; +#36595 = ADVANCED_FACE ( 'NONE', ( #28229 ), #40174, .F. ) ; +#36596 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19394, #4047, #32477, #23274, #25961, #29217, #20185, #35312, #31886, #10006 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000001313394, 0.3750000000001315614, 0.4375000000001161848, 0.5000000000001008083, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36597 = ORIENTED_EDGE ( 'NONE', *, *, #25261, .T. ) ; +#36598 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971594268 ) ) ; +#36599 = EDGE_CURVE ( 'NONE', #16409, #36222, #24536, .T. ) ; +#36600 = CARTESIAN_POINT ( 'NONE', ( 16.41891712931544589, 151.9118064129741583, 184.3536622585150155 ) ) ; +#36601 = LINE ( 'NONE', #20863, #23967 ) ; +#36602 = ORIENTED_EDGE ( 'NONE', *, *, #32269, .T. ) ; +#36603 = CARTESIAN_POINT ( 'NONE', ( 75.24409552970899995, 195.1322945201532377, 195.0264630372666659 ) ) ; +#36604 = EDGE_CURVE ( 'NONE', #27328, #35918, #21290, .T. ) ; +#36605 = VECTOR ( 'NONE', #36927, 1000.000000000000227 ) ; +#36606 = VECTOR ( 'NONE', #7170, 1000.000000000000000 ) ; +#36607 = CARTESIAN_POINT ( 'NONE', ( -38.24468933979500207, 118.9460514581792268, 87.58040766581414971 ) ) ; +#36608 = CARTESIAN_POINT ( 'NONE', ( 17.97063383949850746, 149.1908938068432917, 179.6779205776419701 ) ) ; +#36609 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418000665, 218.5902260770999987, 73.08022052565414128 ) ) ; +#36610 = FACE_OUTER_BOUND ( 'NONE', #34397, .T. ) ; +#36611 = ORIENTED_EDGE ( 'NONE', *, *, #21841, .F. ) ; +#36612 = CARTESIAN_POINT ( 'NONE', ( -42.22995687933095610, 121.2138566085621392, 92.77075882374926152 ) ) ; +#36613 = AXIS2_PLACEMENT_3D ( 'NONE', #5726, #29867, #36598 ) ; +#36614 = VECTOR ( 'NONE', #35034, 1000.000000000000114 ) ; +#36615 = CARTESIAN_POINT ( 'NONE', ( 3.166376970775131028, 185.9099593149100542, 102.5717182116986521 ) ) ; +#36616 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27582, #21823, #12818, #31221 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36617 = CARTESIAN_POINT ( 'NONE', ( 36.14478326529238927, 115.6623972573988226, 90.24595429582799966 ) ) ; +#36618 = CARTESIAN_POINT ( 'NONE', ( -12.64205312145055160, 181.0622675508112422, 104.4982157022507323 ) ) ; +#36619 = ORIENTED_EDGE ( 'NONE', *, *, #24148, .F. ) ; +#36620 = ORIENTED_EDGE ( 'NONE', *, *, #2853, .T. ) ; +#36621 = CARTESIAN_POINT ( 'NONE', ( -28.27513567697000241, 186.7072156929999949, 103.4268468101000025 ) ) ; +#36622 = CARTESIAN_POINT ( 'NONE', ( 0.5732572692252020374, 188.9953112992759827, 103.7015405370500076 ) ) ; +#36623 = CARTESIAN_POINT ( 'NONE', ( -35.60480366327174551, 191.8468578592914184, 106.9415995840391531 ) ) ; +#36624 = ORIENTED_EDGE ( 'NONE', *, *, #1638, .T. ) ; +#36625 = CARTESIAN_POINT ( 'NONE', ( -3.791406087537913194, 136.7360785785722896, 94.04013485213239676 ) ) ; +#36626 = ORIENTED_EDGE ( 'NONE', *, *, #21748, .F. ) ; +#36627 = ORIENTED_EDGE ( 'NONE', *, *, #1126, .T. ) ; +#36628 = ORIENTED_EDGE ( 'NONE', *, *, #34709, .T. ) ; +#36629 = ORIENTED_EDGE ( 'NONE', *, *, #30745, .F. ) ; +#36630 = CARTESIAN_POINT ( 'NONE', ( -37.60556535410999857, 191.2771512838999968, 104.9429279799000199 ) ) ; +#36631 = DIRECTION ( 'NONE', ( -0.9914446600486547245, 0.1270322995875323713, 0.03000468167654852733 ) ) ; +#36632 = VECTOR ( 'NONE', #37124, 1000.000000000000000 ) ; +#36633 = CARTESIAN_POINT ( 'NONE', ( 20.50160081845057292, 118.3470577740523453, 89.75560736965167052 ) ) ; +#36634 = EDGE_LOOP ( 'NONE', ( #14815, #27583, #27247, #35444, #14068, #14835, #7983, #8251, #28544, #3583, #10067, #832, #16317, #6654, #37967, #31345, #11999, #12572, #8856 ) ) ; +#36635 = DIRECTION ( 'NONE', ( 0.0005884950004019305191, -0.2249510543438543730, 0.9743698870671356760 ) ) ; +#36636 = ORIENTED_EDGE ( 'NONE', *, *, #37267, .F. ) ; +#36637 = EDGE_CURVE ( 'NONE', #7200, #18386, #34513, .T. ) ; +#36638 = CIRCLE ( 'NONE', #23588, 2.500000000021942448 ) ; +#36639 = CARTESIAN_POINT ( 'NONE', ( 25.52787147563000048, 120.8002881346999970, 90.09213692394999384 ) ) ; +#36640 = EDGE_CURVE ( 'NONE', #35054, #7159, #3484, .T. ) ; +#36641 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #18076, #20183 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36642 = CIRCLE ( 'NONE', #31420, 1.999999999975517140 ) ; +#36643 = CARTESIAN_POINT ( 'NONE', ( 37.49119510912425568, 212.8449757119041408, 76.03586094040831256 ) ) ; +#36644 = EDGE_CURVE ( 'NONE', #12760, #33382, #31891, .T. ) ; +#36645 = EDGE_CURVE ( 'NONE', #20406, #3835, #9521, .T. ) ; +#36647 = CARTESIAN_POINT ( 'NONE', ( 40.13009284222664519, 84.66001446739429070, 280.9279456820921723 ) ) ; +#36646 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; +#36648 = ORIENTED_EDGE ( 'NONE', *, *, #7893, .F. ) ; +#36649 = ORIENTED_EDGE ( 'NONE', *, *, #7867, .T. ) ; +#36650 = EDGE_CURVE ( 'NONE', #24453, #31462, #40265, .T. ) ; +#36651 = ORIENTED_EDGE ( 'NONE', *, *, #13073, .F. ) ; +#36652 = CARTESIAN_POINT ( 'NONE', ( 39.18856086534000838, 118.8423561804000173, 89.52524955641000304 ) ) ; +#36653 = CARTESIAN_POINT ( 'NONE', ( 25.75482679541795150, 122.6126732673081108, 88.45788671451953178 ) ) ; +#36654 = EDGE_CURVE ( 'NONE', #25158, #21126, #30417, .T. ) ; +#36655 = DIRECTION ( 'NONE', ( -0.0005559617641560631865, 0.3907311285147092583, -0.9205046855481717749 ) ) ; +#36656 = CARTESIAN_POINT ( 'NONE', ( -13.49823529424112145, 160.0636115298041204, 99.69358428540749628 ) ) ; +#36657 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422822324, 151.2971058965562747, 97.65336929384294251 ) ) ; +#36658 = ORIENTED_EDGE ( 'NONE', *, *, #27345, .F. ) ; +#36659 = ORIENTED_EDGE ( 'NONE', *, *, #29537, .F. ) ; +#36660 = AXIS2_PLACEMENT_3D ( 'NONE', #37609, #34511, #1808 ) ; +#36661 = CARTESIAN_POINT ( 'NONE', ( 26.94931025350999931, 123.8033451839999941, 88.21882234612999696 ) ) ; +#36662 = ORIENTED_EDGE ( 'NONE', *, *, #37011, .F. ) ; +#36663 = CARTESIAN_POINT ( 'NONE', ( 35.80362116183528087, 209.7096537765151822, 75.77985605454678364 ) ) ; +#36664 = VECTOR ( 'NONE', #38982, 1000.000000000000000 ) ; +#36665 = CARTESIAN_POINT ( 'NONE', ( 28.90951000791340064, 225.0820812894944822, 76.04104400993735169 ) ) ; +#36666 = CARTESIAN_POINT ( 'NONE', ( 2.896678850647000036, 190.7891276940999887, 106.6032229042999973 ) ) ; +#36667 = CARTESIAN_POINT ( 'NONE', ( 5.666787591738080110, 130.4226561615404023, 90.27309335817682268 ) ) ; +#36668 = FACE_OUTER_BOUND ( 'NONE', #39177, .T. ) ; +#36669 = CARTESIAN_POINT ( 'NONE', ( 20.00153077817512326, 137.8436319123526914, 94.54354600521399732 ) ) ; +#36670 = DIRECTION ( 'NONE', ( 0.0005884949961258187194, -0.2249510543439062760, 0.9743698870671264611 ) ) ; +#36671 = ORIENTED_EDGE ( 'NONE', *, *, #29394, .T. ) ; +#36672 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971577615 ) ) ; +#36673 = DIRECTION ( 'NONE', ( 0.0002393071041605206672, 0.2255699564796173062, -0.9742269435125952004 ) ) ; +#36674 = ORIENTED_EDGE ( 'NONE', *, *, #12053, .F. ) ; +#36675 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36676 = ORIENTED_EDGE ( 'NONE', *, *, #40132, .T. ) ; +#36677 = EDGE_CURVE ( 'NONE', #645, #31462, #22600, .T. ) ; +#36678 = CONICAL_SURFACE ( 'NONE', #19040, 5.499999999948422591, 0.7853981634197699790 ) ; +#36679 = EDGE_CURVE ( 'NONE', #39966, #29610, #38125, .T. ) ; +#36681 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36680 = CARTESIAN_POINT ( 'NONE', ( 12.63633457232399593, 127.9117860165607823, 92.25804342146548720 ) ) ; +#36682 = VERTEX_POINT ( 'NONE', #6327 ) ; +#36683 = CIRCLE ( 'NONE', #3372, 17.00000000000409273 ) ; +#36684 = VERTEX_POINT ( 'NONE', #197 ) ; +#36685 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#36686 = CIRCLE ( 'NONE', #30153, 5.500000000011062262 ) ; +#36687 = ORIENTED_EDGE ( 'NONE', *, *, #10406, .F. ) ; +#36688 = CARTESIAN_POINT ( 'NONE', ( 2.333980040545999834, 209.5255334567000034, 75.42062080793000689 ) ) ; +#36689 = CC_DESIGN_DATE_AND_TIME_ASSIGNMENT ( #8587, #24340, ( #26440 ) ) ; +#36690 = CARTESIAN_POINT ( 'NONE', ( 23.68152057461877291, 135.0471255678871216, 90.98781015170069963 ) ) ; +#36691 = CARTESIAN_POINT ( 'NONE', ( -38.94691154124904386, 128.1851843107897650, 89.27032559287691527 ) ) ; +#36692 = ORIENTED_EDGE ( 'NONE', *, *, #17669, .F. ) ; +#36693 = ORIENTED_EDGE ( 'NONE', *, *, #7047, .F. ) ; +#36694 = CARTESIAN_POINT ( 'NONE', ( -34.95668959393805864, 220.4002260770999726, 73.07961704685790494 ) ) ; +#36695 = ORIENTED_EDGE ( 'NONE', *, *, #4858, .F. ) ; +#36696 = VERTEX_POINT ( 'NONE', #15925 ) ; +#36697 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000094857, 179.7424522644951139, 101.1388664480936512 ) ) ; +#36698 = CARTESIAN_POINT ( 'NONE', ( 23.39351881373000097, 163.2729245447999915, 152.4718672074000381 ) ) ; +#36699 = FACE_OUTER_BOUND ( 'NONE', #24500, .T. ) ; +#36700 = ORIENTED_EDGE ( 'NONE', *, *, #32049, .T. ) ; +#36701 = ORIENTED_EDGE ( 'NONE', *, *, #1026, .T. ) ; +#36702 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567068 ) ) ; +#36703 = CARTESIAN_POINT ( 'NONE', ( -36.02597112483999808, 191.6140443079000022, 104.0170653400000020 ) ) ; +#36704 = ORIENTED_EDGE ( 'NONE', *, *, #38840, .F. ) ; +#36705 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099476, 179.7424522643767375, 101.1388664481733173 ) ) ; +#36706 = ADVANCED_FACE ( 'NONE', ( #28419 ), #37810, .T. ) ; +#36707 = ORIENTED_EDGE ( 'NONE', *, *, #22858, .F. ) ; +#36708 = FACE_OUTER_BOUND ( 'NONE', #29554, .T. ) ; +#36709 = CARTESIAN_POINT ( 'NONE', ( 30.07023774425934803, 176.7457471811506764, 103.0054930552473564 ) ) ; +#36710 = ORIENTED_EDGE ( 'NONE', *, *, #9413, .F. ) ; +#36711 = CARTESIAN_POINT ( 'NONE', ( 0.7489280117216963184, 188.6199951984629593, 103.1988283159848976 ) ) ; +#36712 = AXIS2_PLACEMENT_3D ( 'NONE', #29474, #7783, #26620 ) ; +#36713 = DIRECTION ( 'NONE', ( -0.0002393071182786170347, -0.2252352986010032754, 0.9743043687658493601 ) ) ; +#36714 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971561517 ) ) ; +#36715 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; +#36716 = CIRCLE ( 'NONE', #16446, 4.999999999999994671 ) ; +#36717 = CARTESIAN_POINT ( 'NONE', ( -39.40714599703678545, 119.2344330321841710, 89.77271684653095463 ) ) ; +#36718 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9380918495502710286, 0.3463866074307025977 ) ) ; +#36719 = VERTEX_POINT ( 'NONE', #19184 ) ; +#36720 = CARTESIAN_POINT ( 'NONE', ( -6.031620047117566052, 177.7903949882438042, 100.7027583919079063 ) ) ; +#36721 = ORIENTED_EDGE ( 'NONE', *, *, #39386, .F. ) ; +#36722 = ORIENTED_EDGE ( 'NONE', *, *, #9927, .T. ) ; +#36723 = CARTESIAN_POINT ( 'NONE', ( 4.034499242442382894, 168.3851528797071921, 99.03841376523669737 ) ) ; +#36724 = CARTESIAN_POINT ( 'NONE', ( -2.391432910531668288, 209.5064440074542063, 73.55993817204769414 ) ) ; +#36725 = CARTESIAN_POINT ( 'NONE', ( 36.31854185129000001, 115.9249462840000007, 90.11330909800000200 ) ) ; +#36726 = CARTESIAN_POINT ( 'NONE', ( -22.36444088267160879, 213.5251368776724235, 75.57194279665978343 ) ) ; +#36727 = CARTESIAN_POINT ( 'NONE', ( 6.033427729241307880, 135.1029758574788104, 91.09104781574347953 ) ) ; +#36728 = EDGE_LOOP ( 'NONE', ( #8237, #28536, #40068, #15996 ) ) ; +#36729 = EDGE_CURVE ( 'NONE', #11222, #22073, #18649, .T. ) ; +#36730 = ADVANCED_FACE ( 'NONE', ( #791 ), #35877, .F. ) ; +#36731 = CARTESIAN_POINT ( 'NONE', ( 18.08289561727003658, 152.6324032069051384, 184.7487331658680887 ) ) ; +#36732 = DIRECTION ( 'NONE', ( -0.7066775280921691049, -9.360549773399602300E-05, 0.7075357676665912088 ) ) ; +#36733 = VECTOR ( 'NONE', #26711, 1000.000000000000227 ) ; +#36734 = ORIENTED_EDGE ( 'NONE', *, *, #12514, .F. ) ; +#36735 = DIRECTION ( 'NONE', ( 0.0005884949961259295249, -0.2249510543438812127, 0.9743698870671321233 ) ) ; +#36736 = EDGE_CURVE ( 'NONE', #14670, #6456, #26509, .T. ) ; +#36737 = FACE_OUTER_BOUND ( 'NONE', #6238, .T. ) ; +#36738 = CARTESIAN_POINT ( 'NONE', ( -77.55907816203951199, 192.6399520080828438, 194.4127632364133547 ) ) ; +#36739 = CARTESIAN_POINT ( 'NONE', ( -0.001471237489670575160, 156.2427122712107348, 96.23754757946103666 ) ) ; +#36740 = CIRCLE ( 'NONE', #19100, 2.249999999963666397 ) ; +#36741 = CARTESIAN_POINT ( 'NONE', ( -37.62060996692224535, 118.3102565143506126, 90.29050674493437612 ) ) ; +#36742 = ORIENTED_EDGE ( 'NONE', *, *, #31578, .F. ) ; +#36743 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#36744 = VECTOR ( 'NONE', #21513, 1000.000000000000227 ) ; +#36745 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; +#36746 = ORIENTED_EDGE ( 'NONE', *, *, #8930, .T. ) ; +#36747 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971564015 ) ) ; +#36748 = DIRECTION ( 'NONE', ( 0.0006039748319391170578, 1.156482106403593688E-14, 0.9999998176071845934 ) ) ; +#36749 = EDGE_LOOP ( 'NONE', ( #2511, #28494, #31848, #24689 ) ) ; +#36751 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #7254, #29154, #26094, #32222 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.533316785306447549, 4.712388980384685233 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973295471489362907, 0.9973295471489362907, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#36750 = CARTESIAN_POINT ( 'NONE', ( -38.33420530578000296, 119.5218683286999948, 87.32636249672000872 ) ) ; +#36752 = ADVANCED_FACE ( 'NONE', ( #39159 ), #24050, .F. ) ; +#36753 = CARTESIAN_POINT ( 'NONE', ( -2.373302774618340827, 209.5677226285648942, 73.55993759090392814 ) ) ; +#36754 = CARTESIAN_POINT ( 'NONE', ( -5.668429626480980588, 130.7562800546890855, 90.07018407237876545 ) ) ; +#36755 = ORIENTED_EDGE ( 'NONE', *, *, #6618, .F. ) ; +#36756 = PLANE ( 'NONE', #87 ) ; +#36757 = CARTESIAN_POINT ( 'NONE', ( -4.036264726510437661, 174.7924093550697080, 102.5751288755980255 ) ) ; +#36758 = CYLINDRICAL_SURFACE ( 'NONE', #28617, 2.000000000000001332 ) ; +#36759 = CARTESIAN_POINT ( 'NONE', ( -22.99922046160000022, 115.1130721137993191, 90.28167579205376114 ) ) ; +#36760 = DIRECTION ( 'NONE', ( -0.0002393071182782277790, -0.2252352986010052460, 0.9743043687658488050 ) ) ; +#36761 = ORIENTED_EDGE ( 'NONE', *, *, #35881, .F. ) ; +#36762 = VERTEX_POINT ( 'NONE', #26923 ) ; +#36763 = CARTESIAN_POINT ( 'NONE', ( 39.51726248239999961, 120.5822590371000018, 87.31942780059999620 ) ) ; +#36764 = FACE_OUTER_BOUND ( 'NONE', #39680, .T. ) ; +#36765 = CIRCLE ( 'NONE', #33516, 7.500000216081117443 ) ; +#36766 = CARTESIAN_POINT ( 'NONE', ( -17.15357717400076965, 121.6231103600700294, 177.7751830457494577 ) ) ; +#36767 = EDGE_CURVE ( 'NONE', #33034, #21775, #7885, .T. ) ; +#36768 = CARTESIAN_POINT ( 'NONE', ( -15.81543425957540983, 151.8937953670794343, 180.3140900142980456 ) ) ; +#36769 = ORIENTED_EDGE ( 'NONE', *, *, #13054, .T. ) ; +#36770 = AXIS2_PLACEMENT_3D ( 'NONE', #34216, #6215, #1082 ) ; +#36771 = CARTESIAN_POINT ( 'NONE', ( 1.222756100067673435, 140.3958132876599620, 157.8527939211185753 ) ) ; +#36772 = CARTESIAN_POINT ( 'NONE', ( -41.97653375836684830, 120.7581393263851623, 90.63639953958796980 ) ) ; +#36773 = CYLINDRICAL_SURFACE ( 'NONE', #3904, 3.000000000000000888 ) ; +#36774 = EDGE_CURVE ( 'NONE', #11241, #26453, #14033, .T. ) ; +#36775 = CONICAL_SURFACE ( 'NONE', #6730, 5.999999999897309699, 0.7853981634347277918 ) ; +#36776 = CARTESIAN_POINT ( 'NONE', ( 8.621115833165445608, 209.7097103552968633, 73.05329714473079150 ) ) ; +#36777 = CARTESIAN_POINT ( 'NONE', ( -36.21030856760999939, 191.7503831536999996, 104.2843867992999947 ) ) ; +#36778 = CARTESIAN_POINT ( 'NONE', ( 16.00173003433196328, 160.0551282760237086, 99.67379390875994716 ) ) ; +#36779 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#36780 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25794, #25993, #38242, #20028, #19623, #32320, #22524 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 4 ), + ( 0.000000000000000000, 0.001269605364445955441, 0.002539209452862989467, 0.003808813541279514568, 0.005078416946097733670 ), + .UNSPECIFIED. ) ; +#36781 = EDGE_CURVE ( 'NONE', #8209, #1388, #35199, .T. ) ; +#36782 = ADVANCED_FACE ( 'NONE', ( #32630 ), #23913, .T. ) ; +#36783 = CARTESIAN_POINT ( 'NONE', ( 0.05270753573806398473, 83.21792371834001756, 87.26775245801255210 ) ) ; +#36784 = EDGE_CURVE ( 'NONE', #14180, #27040, #12784, .T. ) ; +#36785 = CARTESIAN_POINT ( 'NONE', ( -6.000971308231505930, 121.2983238328714606, 152.0219651029707677 ) ) ; +#36786 = EDGE_CURVE ( 'NONE', #30287, #31566, #2990, .T. ) ; +#36787 =( NAMED_UNIT ( * ) PLANE_ANGLE_UNIT ( ) SI_UNIT ( $, .RADIAN. ) ); +#36788 = FACE_OUTER_BOUND ( 'NONE', #15809, .T. ) ; +#36789 = VERTEX_POINT ( 'NONE', #38960 ) ; +#36790 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748612543, 132.4103119505556663, 92.77713868752903181 ) ) ; +#36791 = LINE ( 'NONE', #23930, #26360 ) ; +#36792 = CARTESIAN_POINT ( 'NONE', ( -35.96311564216326673, 218.5902260770998282, 61.08022271437000938 ) ) ; +#36793 = CARTESIAN_POINT ( 'NONE', ( -24.42776678989819672, 109.6131156702000027, 87.28253805071517490 ) ) ; +#36794 = CARTESIAN_POINT ( 'NONE', ( 43.53522437658520516, 122.0089638388456592, 87.79461534120677868 ) ) ; +#36795 = ORIENTED_EDGE ( 'NONE', *, *, #36012, .T. ) ; +#36796 = CARTESIAN_POINT ( 'NONE', ( -20.49986301875108907, 192.5783218835306911, 104.3636470540474619 ) ) ; +#36797 = ORIENTED_EDGE ( 'NONE', *, *, #20236, .T. ) ; +#36798 = ORIENTED_EDGE ( 'NONE', *, *, #38018, .T. ) ; +#36799 = CARTESIAN_POINT ( 'NONE', ( -2.214589778089559591, 189.3541584552398263, 103.3701131804680671 ) ) ; +#36800 = ORIENTED_EDGE ( 'NONE', *, *, #1083, .T. ) ; +#36801 = CARTESIAN_POINT ( 'NONE', ( 20.27377773143900086, 126.8226760903316546, 91.71957867363825301 ) ) ; +#36802 = VECTOR ( 'NONE', #39435, 1000.000000000000114 ) ; +#36803 = CARTESIAN_POINT ( 'NONE', ( -1.458415330454428505, 152.0517121853154379, 130.6798743964100993 ) ) ; +#36804 = CARTESIAN_POINT ( 'NONE', ( 18.74192140635615544, 125.0674350211571380, 178.6426924340655091 ) ) ; +#36805 = CYLINDRICAL_SURFACE ( 'NONE', #36350, 6.000000000000001776 ) ; +#36806 = AXIS2_PLACEMENT_3D ( 'NONE', #5565, #12122, #21536 ) ; +#36807 = ORIENTED_EDGE ( 'NONE', *, *, #6753, .F. ) ; +#36808 = CARTESIAN_POINT ( 'NONE', ( 30.05503346856145086, 103.6131156702632410, 89.74963226087875512 ) ) ; +#36809 = AXIS2_PLACEMENT_3D ( 'NONE', #26505, #38954, #10964 ) ; +#36810 = CARTESIAN_POINT ( 'NONE', ( -20.00016507732883753, 192.7547116735289308, 103.8164558568720821 ) ) ; +#36811 = CARTESIAN_POINT ( 'NONE', ( 17.33193682145239478, 121.2642060194173155, 177.4241976613194822 ) ) ; +#36812 = ORIENTED_EDGE ( 'NONE', *, *, #34054, .F. ) ; +#36813 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#36814 = CARTESIAN_POINT ( 'NONE', ( -29.30090432678149170, 112.1830789903917349, 175.8249585680744644 ) ) ; +#36815 = DIRECTION ( 'NONE', ( 0.0005884949961212385073, -0.2249510543439022514, 0.9743698870671273493 ) ) ; +#36816 = CARTESIAN_POINT ( 'NONE', ( -5.038866276848922965, 188.2844575509515721, 103.1248590148407089 ) ) ; +#36817 = CARTESIAN_POINT ( 'NONE', ( 23.00070175390608895, 118.1131156702000169, 90.25694839687047022 ) ) ; +#36818 = ORIENTED_EDGE ( 'NONE', *, *, #29260, .F. ) ; +#36819 = CARTESIAN_POINT ( 'NONE', ( -19.70055405364098533, 149.1723619494412389, 182.9474843209757751 ) ) ; +#36820 = CARTESIAN_POINT ( 'NONE', ( 0.8184195450825001439, 189.0214314598999863, 103.6983566510999992 ) ) ; +#36821 = CARTESIAN_POINT ( 'NONE', ( -42.86870032173014522, 121.2410338499262537, 90.70283413665809746 ) ) ; +#36822 = EDGE_CURVE ( 'NONE', #9665, #1393, #17268, .T. ) ; +#36823 = ORIENTED_EDGE ( 'NONE', *, *, #19418, .T. ) ; +#36824 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, -1.387778780753556918E-14 ) ) ; +#36825 = ORIENTED_EDGE ( 'NONE', *, *, #10304, .T. ) ; +#36826 = ADVANCED_FACE ( 'NONE', ( #1548 ), #2175, .F. ) ; +#36827 = CARTESIAN_POINT ( 'NONE', ( 25.49062502244311190, 209.7098837966309475, 73.54308088453358039 ) ) ; +#36828 = AXIS2_PLACEMENT_3D ( 'NONE', #2225, #26362, #39615 ) ; +#36829 = ADVANCED_FACE ( 'NONE', ( #36510 ), #10834, .T. ) ; +#36830 = ORIENTED_EDGE ( 'NONE', *, *, #4429, .F. ) ; +#36831 = CARTESIAN_POINT ( 'NONE', ( -38.86369644165072401, 118.8228811219059793, 89.72077589445396484 ) ) ; +#36832 = VERTEX_POINT ( 'NONE', #36090 ) ; +#36833 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #11673, #14944, #39869, #18186 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.583415276538783445, 4.583429485978318674 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999831743480, 0.9999999999831743480, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#36834 = CARTESIAN_POINT ( 'NONE', ( 76.10777906860903386, 155.6827192487132834, 98.62805563713989443 ) ) ; +#36835 = CARTESIAN_POINT ( 'NONE', ( -36.06229575586999658, 192.0270778780000001, 105.8316978152000019 ) ) ; +#36836 = CARTESIAN_POINT ( 'NONE', ( -20.01777344647963730, 205.1071326358727163, 76.11698016271346035 ) ) ; +#36837 = CARTESIAN_POINT ( 'NONE', ( -37.24386107733144513, 191.0482304107956963, 106.3386760581659303 ) ) ; +#36838 = AXIS2_PLACEMENT_3D ( 'NONE', #18381, #17772, #8810 ) ; +#36839 = ORIENTED_EDGE ( 'NONE', *, *, #20380, .T. ) ; +#36840 = CARTESIAN_POINT ( 'NONE', ( 28.45671713553771909, 181.8174855791934874, 101.7826687346213532 ) ) ; +#36841 = CARTESIAN_POINT ( 'NONE', ( -12.63747358844825541, 134.5694263371505315, 93.52752121235565141 ) ) ; +#36842 = EDGE_LOOP ( 'NONE', ( #7256, #19712, #35379, #37064 ) ) ; +#36843 = CARTESIAN_POINT ( 'NONE', ( 26.94028454027959896, 123.1544169881439927, 91.15149743865801213 ) ) ; +#36844 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#36846 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250095806, 181.8175435884122919, 102.1528341835786193 ) ) ; +#36845 = LINE ( 'NONE', #18013, #4284 ) ; +#36847 = ORIENTED_EDGE ( 'NONE', *, *, #10888, .F. ) ; +#36848 = EDGE_LOOP ( 'NONE', ( #18379, #4412, #15740 ) ) ; +#36849 = ORIENTED_EDGE ( 'NONE', *, *, #28383, .F. ) ; +#36851 = VERTEX_POINT ( 'NONE', #29782 ) ; +#36850 = VECTOR ( 'NONE', #30299, 1000.000000000000227 ) ; +#36852 = CARTESIAN_POINT ( 'NONE', ( 38.97395985376000027, 118.9659225868000192, 89.82047495415000071 ) ) ; +#36853 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971537369 ) ) ; +#36854 = LINE ( 'NONE', #30117, #16754 ) ; +#36855 = CARTESIAN_POINT ( 'NONE', ( 30.87813405534166478, 129.2310469067220708, 89.46960946475260812 ) ) ; +#36856 = CIRCLE ( 'NONE', #38171, 2.000000000000011546 ) ; +#36857 = AXIS2_PLACEMENT_3D ( 'NONE', #23236, #4414, #29377 ) ; +#36858 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452352341, 0.1781166614240801416 ) ) ; +#36859 = ORIENTED_EDGE ( 'NONE', *, *, #21577, .F. ) ; +#36860 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17091, #11598, #27360, #26532, #36108, #17705, #8118, #11380, #5035, #2194 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 3.469446951953614189E-18, 0.0004333472065303912014, 0.0008666944130607789334, 0.001300041619591166611, 0.001733388826121554397 ), + .UNSPECIFIED. ) ; +#36861 = ORIENTED_EDGE ( 'NONE', *, *, #1941, .T. ) ; +#36862 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7071067167008887600, 0.7071068456722005013 ) ) ; +#36863 = AXIS2_PLACEMENT_3D ( 'NONE', #3428, #8795, #9391 ) ; +#36864 = LINE ( 'NONE', #12320, #9218 ) ; +#36865 = CARTESIAN_POINT ( 'NONE', ( -44.76913686494872735, 106.7077356584182866, 169.4235275077028291 ) ) ; +#36866 = ORIENTED_EDGE ( 'NONE', *, *, #39344, .T. ) ; +#36867 = CARTESIAN_POINT ( 'NONE', ( -36.40301216257000760, 191.2749683209000295, 106.5434778884000053 ) ) ; +#36868 = EDGE_CURVE ( 'NONE', #28821, #11816, #20144, .T. ) ; +#36869 = ADVANCED_FACE ( 'NONE', ( #20552 ), #369, .F. ) ; +#36870 = EDGE_CURVE ( 'NONE', #4731, #17805, #37616, .T. ) ; +#36871 = EDGE_CURVE ( 'NONE', #29005, #17707, #14438, .T. ) ; +#36872 = CARTESIAN_POINT ( 'NONE', ( 2.474132579723000269, 190.3636575362999963, 106.1296058884999951 ) ) ; +#36873 = ORIENTED_EDGE ( 'NONE', *, *, #23637, .T. ) ; +#36874 = CARTESIAN_POINT ( 'NONE', ( 6.034498894405830427, 137.2432952343929173, 91.84754016128890441 ) ) ; +#36875 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319350647437 ) ) ; +#36876 = DIRECTION ( 'NONE', ( 0.0005884949961228995051, -0.2249510543439057486, 0.9743698870671265722 ) ) ; +#36877 = PLANE ( 'NONE', #7817 ) ; +#36878 = EDGE_CURVE ( 'NONE', #38501, #23382, #21994, .T. ) ; +#36879 = ORIENTED_EDGE ( 'NONE', *, *, #26355, .T. ) ; +#36880 = CARTESIAN_POINT ( 'NONE', ( -20.49823408210000153, 174.8433562657000095, 103.1099856640999946 ) ) ; +#36881 = CARTESIAN_POINT ( 'NONE', ( 0.05451946023390214641, 83.21792371834001756, 90.26775191081762273 ) ) ; +#36882 = AXIS2_PLACEMENT_3D ( 'NONE', #14666, #35897, #7902 ) ; +#36883 = EDGE_CURVE ( 'NONE', #29484, #32574, #30026, .T. ) ; +#36884 = CONICAL_SURFACE ( 'NONE', #1618, 2.503002883974063231, 0.7853981633885572800 ) ; +#36885 = CIRCLE ( 'NONE', #6801, 2.000000000000011546 ) ; +#36886 = ORIENTED_EDGE ( 'NONE', *, *, #36305, .F. ) ; +#36887 = CARTESIAN_POINT ( 'NONE', ( 15.94114414956070114, 127.7634661670421821, 175.0287683583358671 ) ) ; +#36888 = VERTEX_POINT ( 'NONE', #27738 ) ; +#36889 = AXIS2_PLACEMENT_3D ( 'NONE', #11333, #17049, #29750 ) ; +#36891 = DIRECTION ( 'NONE', ( 0.9914447795421228449, 0.1272537940604324957, 0.02904687618137882441 ) ) ; +#36890 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; +#36892 = ORIENTED_EDGE ( 'NONE', *, *, #7399, .T. ) ; +#36893 = EDGE_CURVE ( 'NONE', #6123, #33385, #39975, .T. ) ; +#36894 = ORIENTED_EDGE ( 'NONE', *, *, #32402, .F. ) ; +#36895 = ORIENTED_EDGE ( 'NONE', *, *, #5092, .F. ) ; +#36896 = CARTESIAN_POINT ( 'NONE', ( 2.367289706466999988, 209.3890111512000090, 75.42794202579000284 ) ) ; +#36897 = CARTESIAN_POINT ( 'NONE', ( 19.99579756797234253, 191.9758059840616227, 101.9094256439181407 ) ) ; +#36898 = DIRECTION ( 'NONE', ( -7.401486830846876174E-15, -0.9743700557921587402, -0.2249510932971549027 ) ) ; +#36899 = ORIENTED_EDGE ( 'NONE', *, *, #35039, .T. ) ; +#36900 = VERTEX_POINT ( 'NONE', #12371 ) ; +#36901 = DIRECTION ( 'NONE', ( 0.0005884949961233809992, -0.2249510543439078580, 0.9743698870671259060 ) ) ; +#36902 = VERTEX_POINT ( 'NONE', #31186 ) ; +#36903 = ORIENTED_EDGE ( 'NONE', *, *, #13297, .T. ) ; +#36904 = DIRECTION ( 'NONE', ( -0.0005559617641685796500, 0.3907311284661838524, -0.9205046855687695206 ) ) ; +#36905 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.274821093756980468E-14, 0.9999998176071847045 ) ) ; +#36906 = CARTESIAN_POINT ( 'NONE', ( -11.79198343374907054, 125.9681876107315333, 176.0676422622361770 ) ) ; +#36907 = DIRECTION ( 'NONE', ( 0.0005884949961258157921, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#36908 = CARTESIAN_POINT ( 'NONE', ( 35.72711796422999697, 192.3360894857999881, 104.0326477243000198 ) ) ; +#36909 = ORIENTED_EDGE ( 'NONE', *, *, #35815, .F. ) ; +#36910 = ORIENTED_EDGE ( 'NONE', *, *, #24781, .T. ) ; +#36911 = CARTESIAN_POINT ( 'NONE', ( -5.669685120243074472, 123.9705640544748064, 91.11679149625278740 ) ) ; +#36912 = DIRECTION ( 'NONE', ( -0.0005884949961224448991, 0.2249510543439060262, -0.9743698870671263501 ) ) ; +#36913 = CARTESIAN_POINT ( 'NONE', ( -36.17494636288999743, 191.7742163892000065, 104.2876465562000021 ) ) ; +#36914 = VERTEX_POINT ( 'NONE', #34229 ) ; +#36915 = CARTESIAN_POINT ( 'NONE', ( 15.60948512045867531, 183.6109006041976102, 102.0334120927841468 ) ) ; +#36916 = CIRCLE ( 'NONE', #10790, 2.000000000183533633 ) ; +#36917 = ORIENTED_EDGE ( 'NONE', *, *, #36027, .F. ) ; +#36918 = CARTESIAN_POINT ( 'NONE', ( -40.45668859034989140, 206.4002260771000010, 73.08293890854348263 ) ) ; +#36919 = CARTESIAN_POINT ( 'NONE', ( 40.49834802958050517, 188.0236428059193656, 107.9681252167849692 ) ) ; +#36920 = ORIENTED_EDGE ( 'NONE', *, *, #34467, .T. ) ; +#36921 = CONICAL_SURFACE ( 'NONE', #4226, 2.503079361258633284, 0.7853981634253369704 ) ; +#36922 = AXIS2_PLACEMENT_3D ( 'NONE', #22450, #40427, #15500 ) ; +#36923 = EDGE_CURVE ( 'NONE', #40324, #18764, #34301, .T. ) ; +#36924 = ADVANCED_FACE ( 'NONE', ( #36708 ), #14754, .T. ) ; +#36925 = VECTOR ( 'NONE', #28112, 1000.000000000000227 ) ; +#36926 = ADVANCED_FACE ( 'NONE', ( #6227 ), #3627, .F. ) ; +#36927 = DIRECTION ( 'NONE', ( -0.7933533175743878729, 0.5931616988744193852, 0.1369295895054284395 ) ) ; +#36928 = LINE ( 'NONE', #37326, #26198 ) ; +#36929 = DIRECTION ( 'NONE', ( 0.0005884949961249387809, -0.2249510543439043608, 0.9743698870671267942 ) ) ; +#36930 = CARTESIAN_POINT ( 'NONE', ( 47.95567328239271632, 139.9374889060051146, 291.1737358715798791 ) ) ; +#36931 = DIRECTION ( 'NONE', ( 3.053113317719186166E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#36932 = EDGE_CURVE ( 'NONE', #8063, #18309, #9513, .T. ) ; +#36933 = ORIENTED_EDGE ( 'NONE', *, *, #7089, .T. ) ; +#36934 = CARTESIAN_POINT ( 'NONE', ( -25.51388077191477066, 211.0902258580313742, 75.57405363378009611 ) ) ; +#36935 = ORIENTED_EDGE ( 'NONE', *, *, #7968, .F. ) ; +#36936 = CARTESIAN_POINT ( 'NONE', ( -15.99825118274618063, 184.2885608609500423, 105.2878711035513817 ) ) ; +#36937 = CARTESIAN_POINT ( 'NONE', ( -37.47670858587999732, 118.7990821089999969, 87.16573600921000775 ) ) ; +#36938 = CARTESIAN_POINT ( 'NONE', ( 35.54174622234999958, 114.2816361784999941, 90.38793632835000835 ) ) ; +#36939 = EDGE_CURVE ( 'NONE', #25492, #12177, #21597, .T. ) ; +#36940 = ORIENTED_EDGE ( 'NONE', *, *, #6519, .T. ) ; +#36941 = CARTESIAN_POINT ( 'NONE', ( 22.78190537993189224, 157.8319756168561980, 98.98540907879944939 ) ) ; +#36942 = ORIENTED_EDGE ( 'NONE', *, *, #20665, .F. ) ; +#36943 = CONICAL_SURFACE ( 'NONE', #25864, 17.00000000000406430, 0.7853981633972577647 ) ; +#36944 = CARTESIAN_POINT ( 'NONE', ( -19.31458322240165870, 148.9716893160552331, 180.9720018909554540 ) ) ; +#36945 = CONICAL_SURFACE ( 'NONE', #39547, 2.499999999942582818, 0.7853981634397246836 ) ; +#36946 = AXIS2_PLACEMENT_3D ( 'NONE', #24073, #14259, #8740 ) ; +#36947 = CARTESIAN_POINT ( 'NONE', ( -6.038610453718359139, 135.2156387069402683, 91.28082590629979620 ) ) ; +#36948 = EDGE_CURVE ( 'NONE', #33855, #38290, #25390, .T. ) ; +#36949 = CARTESIAN_POINT ( 'NONE', ( 15.83342845893534090, 151.9301612465557980, 94.89025465113299163 ) ) ; +#36950 = VECTOR ( 'NONE', #7193, 1000.000000000000114 ) ; +#36951 = VERTEX_POINT ( 'NONE', #33637 ) ; +#36953 = VECTOR ( 'NONE', #8302, 1000.000000000000000 ) ; +#36952 = DIRECTION ( 'NONE', ( -0.0005884949961206199700, 0.2249510543439050825, -0.9743698870671266832 ) ) ; +#36954 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#36955 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971569011 ) ) ; +#36956 = CARTESIAN_POINT ( 'NONE', ( -35.88612293872638759, 115.2662337474595375, 90.28945915823193502 ) ) ; +#36957 = ORIENTED_EDGE ( 'NONE', *, *, #34539, .T. ) ; +#36958 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#36959 = DIRECTION ( 'NONE', ( -0.6086215548477215131, -0.7730393818215735013, -0.1788572534946828996 ) ) ; +#36960 = ORIENTED_EDGE ( 'NONE', *, *, #17182, .F. ) ; +#36961 = CARTESIAN_POINT ( 'NONE', ( 30.06880003763514964, 134.6508487161554797, 93.45568730988300388 ) ) ; +#36962 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31957, #6782, #3916, #13541, #6579, #28677, #26022, #19051, #3508, #656 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36963 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11323, #29938, #7650, #4776 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#36964 = VERTEX_POINT ( 'NONE', #12185 ) ; +#36965 = CARTESIAN_POINT ( 'NONE', ( -38.28238216209000200, 118.9845237992000051, 87.58241103861999477 ) ) ; +#36966 = CARTESIAN_POINT ( 'NONE', ( 35.89625689025860567, 194.1237596711137314, 102.8114730549799134 ) ) ; +#36967 = VERTEX_POINT ( 'NONE', #27550 ) ; +#36968 = CARTESIAN_POINT ( 'NONE', ( -76.10954455358901782, 156.3374217179836023, 95.79222820379374070 ) ) ; +#36969 = CYLINDRICAL_SURFACE ( 'NONE', #29650, 1.999999999999989564 ) ; +#36970 = CARTESIAN_POINT ( 'NONE', ( -25.38428316918999883, 190.8232025961000033, 106.1489432646000068 ) ) ; +#36971 = ADVANCED_FACE ( 'NONE', ( #24671 ), #25876, .F. ) ; +#36972 = EDGE_CURVE ( 'NONE', #3655, #40149, #5635, .T. ) ; +#36973 = VECTOR ( 'NONE', #23935, 1000.000000000000227 ) ; +#36974 = CARTESIAN_POINT ( 'NONE', ( -3.537750984983824232, 137.3463269818849426, 91.36396247942009552 ) ) ; +#36975 = FACE_OUTER_BOUND ( 'NONE', #7858, .T. ) ; +#36976 = CIRCLE ( 'NONE', #12169, 1.749999999999998446 ) ; +#36977 = ORIENTED_EDGE ( 'NONE', *, *, #23025, .T. ) ; +#36978 = CARTESIAN_POINT ( 'NONE', ( 38.79215607118000264, 119.3019797381000018, 87.60142219187000023 ) ) ; +#36979 = DIRECTION ( 'NONE', ( 0.0002083475567178144834, -0.2252353001617939388, 0.9743043755173853571 ) ) ; +#36980 = CARTESIAN_POINT ( 'NONE', ( 36.51445440182627777, 191.7487767046791021, 104.3532581982114493 ) ) ; +#36981 = VECTOR ( 'NONE', #31127, 1000.000000000000114 ) ; +#36982 = CARTESIAN_POINT ( 'NONE', ( -16.53154831419982074, 121.8638204742738367, 177.6006876565568575 ) ) ; +#36983 = EDGE_LOOP ( 'NONE', ( #19624, #17293, #38209, #21870 ) ) ; +#36984 = EDGE_CURVE ( 'NONE', #21279, #28866, #21927, .T. ) ; +#36985 = EDGE_LOOP ( 'NONE', ( #34241, #13771, #2529, #25135, #36554, #6952 ) ) ; +#36986 = CARTESIAN_POINT ( 'NONE', ( -31.73518137046647780, 115.2741031936126177, 176.5389297272637634 ) ) ; +#36987 = CARTESIAN_POINT ( 'NONE', ( -24.38839408367715222, 103.6131156702000027, 152.4718672074091330 ) ) ; +#36988 = CARTESIAN_POINT ( 'NONE', ( -19.44498994767157996, 147.7083494500389236, 183.5267648320292437 ) ) ; +#36989 = CARTESIAN_POINT ( 'NONE', ( 12.63245678305150044, 181.0156363297572000, 104.5149566212380989 ) ) ; +#36990 = CARTESIAN_POINT ( 'NONE', ( 25.49929013439215808, 120.2777482667009536, 87.91897806052588749 ) ) ; +#36991 = CARTESIAN_POINT ( 'NONE', ( -25.75631448573786031, 212.3218413124795916, 73.07406025094472568 ) ) ; +#36992 = CARTESIAN_POINT ( 'NONE', ( 20.45461275351677699, 105.2139170029073085, 89.75543067447466683 ) ) ; +#36993 = CARTESIAN_POINT ( 'NONE', ( 19.31133681887892095, 126.0954225582447634, 175.4729931450506513 ) ) ; +#36994 = EDGE_CURVE ( 'NONE', #7260, #12828, #26504, .T. ) ; +#36995 = CARTESIAN_POINT ( 'NONE', ( 5.035983838893847597, 181.7480468442998074, 101.6097244662869912 ) ) ; +#36996 = CARTESIAN_POINT ( 'NONE', ( 13.55367211394599458, 164.6398026302437927, 97.65175096769451102 ) ) ; +#36997 = CARTESIAN_POINT ( 'NONE', ( -20.45744622554683545, 184.3896479590997899, 104.8428823281020925 ) ) ; +#36998 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#36999 = CARTESIAN_POINT ( 'NONE', ( 37.96379516814999988, 191.4215591583999867, 104.2996976466999968 ) ) ; +#37000 = ORIENTED_EDGE ( 'NONE', *, *, #6808, .F. ) ; +#37001 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1040, #10274, #16183, #25612, #38060, #22743, #38648, #15979, #19238, #10062 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37002 = CARTESIAN_POINT ( 'NONE', ( 36.46784510777001032, 191.0154516242999989, 106.6747793348999949 ) ) ; +#37003 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #35057, #9349, #31025, #15479 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.585050951137079167, 4.585089182115460460 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999998781993193, 0.9999999998781993193, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#37004 = CONICAL_SURFACE ( 'NONE', #23310, 5.250000000007735146, 0.7853981634220036367 ) ; +#37005 = VERTEX_POINT ( 'NONE', #24869 ) ; +#37006 = ORIENTED_EDGE ( 'NONE', *, *, #19502, .T. ) ; +#37007 = ORIENTED_EDGE ( 'NONE', *, *, #23313, .F. ) ; +#37008 = CARTESIAN_POINT ( 'NONE', ( 17.36823235821892553, 127.5715682803508173, 172.3982060061660775 ) ) ; +#37009 = CARTESIAN_POINT ( 'NONE', ( 20.25014673412999855, 167.5741656236999972, 98.58481265140000005 ) ) ; +#37010 = AXIS2_PLACEMENT_3D ( 'NONE', #4241, #981, #10214 ) ; +#37011 = EDGE_CURVE ( 'NONE', #26453, #2464, #27336, .T. ) ; +#37012 = CARTESIAN_POINT ( 'NONE', ( 31.81422328508812924, 154.4985510624152312, 201.1972672685601538 ) ) ; +#37013 = AXIS2_PLACEMENT_3D ( 'NONE', #19192, #37424, #18784 ) ; +#37014 = EDGE_LOOP ( 'NONE', ( #18538, #16717, #7529, #21534, #32833 ) ) ; +#37015 = CARTESIAN_POINT ( 'NONE', ( -39.68267445646999647, 119.5205277319000032, 89.96097260070999369 ) ) ; +#37016 = EDGE_CURVE ( 'NONE', #34239, #26640, #5896, .T. ) ; +#37017 = CARTESIAN_POINT ( 'NONE', ( -38.36106832263448752, 118.8212171802660606, 87.72011982685570786 ) ) ; +#37018 = CARTESIAN_POINT ( 'NONE', ( -42.45956536336885989, 185.1121152691760301, 127.1961689306145900 ) ) ; +#37019 = CARTESIAN_POINT ( 'NONE', ( 2.562971096584431230, 190.9999997793927093, 104.2603522665603890 ) ) ; +#37020 = EDGE_LOOP ( 'NONE', ( #1611, #13701, #24387, #33898 ) ) ; +#37021 = CARTESIAN_POINT ( 'NONE', ( 3.168112933839599688, 185.2356858264948301, 105.4949491227606870 ) ) ; +#37022 = CARTESIAN_POINT ( 'NONE', ( 25.39110728864075028, 212.9334982812408725, 76.04317957727111832 ) ) ; +#37023 = EDGE_CURVE ( 'NONE', #8699, #1973, #15637, .T. ) ; +#37024 = EDGE_CURVE ( 'NONE', #17741, #21690, #31, .T. ) ; +#37025 = CARTESIAN_POINT ( 'NONE', ( -22.54148966027999990, 176.5965135413000269, 28.07991271570000080 ) ) ; +#37026 = DIRECTION ( 'NONE', ( 0.7075059952394668894, 1.630340059807711576E-15, 0.7067073416204273650 ) ) ; +#37027 = EDGE_CURVE ( 'NONE', #14988, #18841, #25201, .T. ) ; +#37028 = ORIENTED_EDGE ( 'NONE', *, *, #1041, .F. ) ; +#37029 = CARTESIAN_POINT ( 'NONE', ( 22.78222448925487953, 157.6320878318682901, 99.11031268573603370 ) ) ; +#37030 = CARTESIAN_POINT ( 'NONE', ( 3.063416923924000113, 191.1126416495999933, 103.7721432255000025 ) ) ; +#37031 = CARTESIAN_POINT ( 'NONE', ( 16.00176583131026575, 118.9451395335793649, 90.18281804087270359 ) ) ; +#37032 = VERTEX_POINT ( 'NONE', #7026 ) ; +#37033 = CARTESIAN_POINT ( 'NONE', ( -3.805127989129743593, 136.7391389931145511, 94.02677512615100852 ) ) ; +#37034 = ORIENTED_EDGE ( 'NONE', *, *, #3853, .T. ) ; +#37035 = AXIS2_PLACEMENT_3D ( 'NONE', #20169, #32656, #17907 ) ; +#37036 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #37439, #37044, #31115, #9437, #9634, #31310, #34159, #215, #31505, #15176, #21913, #34353, #18410, #21315, #12908, #12696, #18212, #37240, #3277, #30913, #19016, #3088, #9034, #25380 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 1, 2, 2, 2, 2, 2, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000219824, 0.3125000000000324185, 0.3750000000000428546, 0.4375000000000532907, 0.4687500000000501266, 0.5000000000000468514, 0.6250000000000341949, 0.6875000000000338618, 0.7187500000000390799, 0.7343750000000408562, 0.7500000000000425215, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37037 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22252, #12840, #37975, #27992 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37038 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; +#37039 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24600, #3094, #30921, #2895, #15376, #15568, #27875 ), + .UNSPECIFIED., .F., .F., + ( 4, 3, 4 ), + ( 2.775557561562891351E-17, 0.002000000000002750446, 0.002556132323769710283 ), + .UNSPECIFIED. ) ; +#37040 = LINE ( 'NONE', #24181, #9432 ) ; +#37041 = FACE_OUTER_BOUND ( 'NONE', #39565, .T. ) ; +#37042 = DIRECTION ( 'NONE', ( 0.7933533411653073131, 0.5931840316265175606, 0.1368326740407942721 ) ) ; +#37043 = CARTESIAN_POINT ( 'NONE', ( 30.06443600138266703, 134.9229365128052507, 90.78414315763292564 ) ) ; +#37044 = CARTESIAN_POINT ( 'NONE', ( -2.431666151064473258, 190.6984111013711640, 106.2266867397790406 ) ) ; +#37045 = ORIENTED_EDGE ( 'NONE', *, *, #18573, .T. ) ; +#37046 = CARTESIAN_POINT ( 'NONE', ( -10.32191354246705117, 181.6874635934578919, 101.6050416412066113 ) ) ; +#37047 = CARTESIAN_POINT ( 'NONE', ( 20.00182604067493131, 190.8514159882993511, 106.7812686061269716 ) ) ; +#37048 = CARTESIAN_POINT ( 'NONE', ( -31.70535868461000462, 226.4002260771000010, 73.57765341571000306 ) ) ; +#37050 = CARTESIAN_POINT ( 'NONE', ( 24.81837490432999971, 199.3006038172999865, 28.07991271570000080 ) ) ; +#37049 = CARTESIAN_POINT ( 'NONE', ( 22.78075325035302257, 164.5278737158889726, 98.13656827166707330 ) ) ; +#37051 = ORIENTED_EDGE ( 'NONE', *, *, #28438, .T. ) ; +#37052 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22511, #20210, #31912, #23302 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37053 = ADVANCED_FACE ( 'NONE', ( #6621 ), #38316, .F. ) ; +#37054 = CIRCLE ( 'NONE', #22059, 2.749999999947594809 ) ; +#37055 = CARTESIAN_POINT ( 'NONE', ( -36.27950425524976907, 191.8188495074159334, 104.4051415298545180 ) ) ; +#37056 = CARTESIAN_POINT ( 'NONE', ( 15.94060032687233353, 152.3729576450454317, 183.5874236705277838 ) ) ; +#37057 = CONICAL_SURFACE ( 'NONE', #8341, 4.999999999857982935, 0.7853981633778843729 ) ; +#37058 = ORIENTED_EDGE ( 'NONE', *, *, #16534, .T. ) ; +#37059 = CARTESIAN_POINT ( 'NONE', ( -28.22497418263295899, 124.4143361401367116, 91.47219364137306741 ) ) ; +#37060 = EDGE_CURVE ( 'NONE', #10259, #25706, #18040, .T. ) ; +#37061 = FACE_OUTER_BOUND ( 'NONE', #34972, .T. ) ; +#37062 = FACE_OUTER_BOUND ( 'NONE', #4899, .T. ) ; +#37063 = CARTESIAN_POINT ( 'NONE', ( 40.79509051822999766, 220.4002260892000038, 73.28386491556000237 ) ) ; +#37064 = ORIENTED_EDGE ( 'NONE', *, *, #29532, .F. ) ; +#37065 = EDGE_LOOP ( 'NONE', ( #11132, #37469, #31630 ) ) ; +#37066 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; +#37067 = ADVANCED_FACE ( 'NONE', ( #16624 ), #6903, .F. ) ; +#37068 = CARTESIAN_POINT ( 'NONE', ( 13.50176809758824703, 123.6896930292991783, 91.28289196659790150 ) ) ; +#37069 = EDGE_CURVE ( 'NONE', #27116, #5506, #25467, .T. ) ; +#37070 = ORIENTED_EDGE ( 'NONE', *, *, #20320, .T. ) ; +#37071 = CARTESIAN_POINT ( 'NONE', ( -39.80682244857173657, 74.92336540073860363, 323.7074831990058215 ) ) ; +#37072 = EDGE_CURVE ( 'NONE', #16013, #43, #16235, .T. ) ; +#37073 = CARTESIAN_POINT ( 'NONE', ( -3.537752371395798789, 168.4800613451581910, 98.55175200207808928 ) ) ; +#37074 = CARTESIAN_POINT ( 'NONE', ( 3.062273563952057298, 190.5167726273855635, 106.7325697143036365 ) ) ; +#37075 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; +#37076 = CARTESIAN_POINT ( 'NONE', ( -2.531803760470723308, 209.6150367273567383, 75.72670025133220406 ) ) ; +#37077 = DIRECTION ( 'NONE', ( -0.0005884949961246178571, 0.2249510543523500772, -0.9743698870651767985 ) ) ; +#37078 = CARTESIAN_POINT ( 'NONE', ( 3.588014096441977330, 145.1508611148875048, 93.16147139303190272 ) ) ; +#37079 = AXIS2_PLACEMENT_3D ( 'NONE', #7731, #4863, #20195 ) ; +#37080 = EDGE_LOOP ( 'NONE', ( #40369, #11558, #13254, #15689, #19288 ) ) ; +#37081 = CARTESIAN_POINT ( 'NONE', ( 45.29398665750001385, 181.0941504656715608, 101.9475978871965651 ) ) ; +#37082 = FACE_OUTER_BOUND ( 'NONE', #35296, .T. ) ; +#37083 = AXIS2_PLACEMENT_3D ( 'NONE', #30005, #30622, #2004 ) ; +#37084 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 77.27946979429611929, 297.5967072516833127 ) ) ; +#37085 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5461, #30423, #1584, #14070 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.005622273453351230368, 0.006578684328568076833 ), + .UNSPECIFIED. ) ; +#37086 = ORIENTED_EDGE ( 'NONE', *, *, #8263, .T. ) ; +#37087 = FACE_OUTER_BOUND ( 'NONE', #29283, .T. ) ; +#37088 = ORIENTED_EDGE ( 'NONE', *, *, #17090, .F. ) ; +#37090 = CARTESIAN_POINT ( 'NONE', ( 35.57142872079925411, 192.1870033824226596, 103.8888500649391204 ) ) ; +#37089 = CARTESIAN_POINT ( 'NONE', ( -15.83166473606552671, 185.2693417633693684, 105.3431436966540389 ) ) ; +#37091 = VERTEX_POINT ( 'NONE', #29128 ) ; +#37092 = ORIENTED_EDGE ( 'NONE', *, *, #29239, .T. ) ; +#37093 = ORIENTED_EDGE ( 'NONE', *, *, #29825, .T. ) ; +#37094 = EDGE_CURVE ( 'NONE', #14154, #32568, #21449, .T. ) ; +#37095 = CARTESIAN_POINT ( 'NONE', ( 2.411605089786999834, 208.9943232422999984, 75.51511931384000320 ) ) ; +#37096 = EDGE_CURVE ( 'NONE', #36039, #6809, #35618, .T. ) ; +#37097 = CARTESIAN_POINT ( 'NONE', ( 42.89072085005058454, 184.8658444924963078, 107.3903155990774536 ) ) ; +#37098 = EDGE_CURVE ( 'NONE', #1259, #31494, #20501, .T. ) ; +#37099 = DIRECTION ( 'NONE', ( 1.328421402153733269E-20, -0.9743043966640312359, -0.2252353050503803356 ) ) ; +#37100 = ORIENTED_EDGE ( 'NONE', *, *, #20329, .T. ) ; +#37101 = ORIENTED_EDGE ( 'NONE', *, *, #37488, .F. ) ; +#37102 = ORIENTED_EDGE ( 'NONE', *, *, #11674, .T. ) ; +#37103 = ORIENTED_EDGE ( 'NONE', *, *, #1878, .F. ) ; +#37104 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#37105 = EDGE_CURVE ( 'NONE', #27040, #18169, #697, .T. ) ; +#37106 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21223, #36133, #39807, #39002, #29819, #18128, #39204, #8349 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 4 ), + ( 1.962615573354718958E-17, 0.003451407961357079099, 0.005177111942035635128, 0.006902815922714191157 ), + .UNSPECIFIED. ) ; +#37107 = CARTESIAN_POINT ( 'NONE', ( -19.46394794124172023, 125.6806896231740751, 178.4345049239138064 ) ) ; +#37108 = CARTESIAN_POINT ( 'NONE', ( 2.462157157005000041, 209.5677245651999954, 73.55701709327000515 ) ) ; +#37109 = ORIENTED_EDGE ( 'NONE', *, *, #31076, .T. ) ; +#37110 = ADVANCED_FACE ( 'NONE', ( #290 ), #21320, .F. ) ; +#37111 = ORIENTED_EDGE ( 'NONE', *, *, #20389, .F. ) ; +#37112 = CONICAL_SURFACE ( 'NONE', #1196, 2.499999999987588595, 0.7853981634197695350 ) ; +#37113 = VERTEX_POINT ( 'NONE', #15829 ) ; +#37114 = DIRECTION ( 'NONE', ( -0.000000000000000000, -1.000000000000000000, -0.000000000000000000 ) ) ; +#37115 = CARTESIAN_POINT ( 'NONE', ( 20.00016034875645943, 127.4394136103090887, 89.06260552501319694 ) ) ; +#37116 = ORIENTED_EDGE ( 'NONE', *, *, #23617, .F. ) ; +#37117 = CARTESIAN_POINT ( 'NONE', ( -26.79953445320000327, 123.8790405098999940, 88.43988500796000096 ) ) ; +#37118 = EDGE_CURVE ( 'NONE', #2594, #17666, #5379, .T. ) ; +#37119 = VERTEX_POINT ( 'NONE', #10327 ) ; +#37120 = DIRECTION ( 'NONE', ( -7.677760455957277161E-18, 1.000000000000000000, -1.271205131337255403E-14 ) ) ; +#37121 = CARTESIAN_POINT ( 'NONE', ( -40.89369055242008244, 189.6827382460760418, 106.9036850101785205 ) ) ; +#37122 = ORIENTED_EDGE ( 'NONE', *, *, #38510, .T. ) ; +#37123 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; +#37124 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; +#37125 = DIRECTION ( 'NONE', ( 0.0005884949961241580469, -0.2249510543439066090, 0.9743698870671262391 ) ) ; +#37126 = CARTESIAN_POINT ( 'NONE', ( -4.036264725700203115, 136.7920597759830628, 93.80205530682346193 ) ) ; +#37127 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28747, #13216, #20532, #20331 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37128 = ORIENTED_EDGE ( 'NONE', *, *, #18800, .F. ) ; +#37129 = CARTESIAN_POINT ( 'NONE', ( 21.85661045747963271, 129.3623300076286284, 92.41322950560527261 ) ) ; +#37130 = VERTEX_POINT ( 'NONE', #28325 ) ; +#37131 = ORIENTED_EDGE ( 'NONE', *, *, #35229, .F. ) ; +#37132 = CARTESIAN_POINT ( 'NONE', ( 39.70946675458673525, 77.58522061945927817, 290.6159063730808612 ) ) ; +#37133 = CARTESIAN_POINT ( 'NONE', ( -38.18996268803999783, 119.2077463964999993, 87.40560705097000493 ) ) ; +#37134 = CARTESIAN_POINT ( 'NONE', ( 38.33443754462000186, 118.7533610134000099, 90.10310419729999865 ) ) ; +#37135 = CIRCLE ( 'NONE', #25378, 2.500000000028141489 ) ; +#37136 = ORIENTED_EDGE ( 'NONE', *, *, #4304, .T. ) ; +#37137 = DIRECTION ( 'NONE', ( -0.0002393071182785117045, -0.2252352986010040525, 0.9743043687658490271 ) ) ; +#37138 = VERTEX_POINT ( 'NONE', #28918 ) ; +#37139 = AXIS2_PLACEMENT_3D ( 'NONE', #21089, #32932, #23541 ) ; +#37140 = VECTOR ( 'NONE', #13352, 999.9999999999998863 ) ; +#37141 = CONICAL_SURFACE ( 'NONE', #33175, 2.503197955275930031, 0.7853981634052017435 ) ; +#37142 = CARTESIAN_POINT ( 'NONE', ( -38.55162595008999915, 118.3743277683000059, 89.56038587743999813 ) ) ; +#37143 = CARTESIAN_POINT ( 'NONE', ( 16.00178153260169722, 185.2344458670014831, 105.4869183982072371 ) ) ; +#37144 = ORIENTED_EDGE ( 'NONE', *, *, #39911, .F. ) ; +#37145 = EDGE_CURVE ( 'NONE', #27723, #372, #6287, .T. ) ; +#37146 = CARTESIAN_POINT ( 'NONE', ( -43.18873574177671770, 147.7379676372972881, 291.5846288494005876 ) ) ; +#37147 = ADVANCED_FACE ( 'NONE', ( #13983 ), #23185, .F. ) ; +#37148 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #9883, #6987, #25628, #32157 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37149 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927200853413, 0.0005734119022208531650 ) ) ; +#37150 = CARTESIAN_POINT ( 'NONE', ( 46.04942073387295665, 125.5491642319759791, 88.61041671179513912 ) ) ; +#37151 = ADVANCED_FACE ( 'NONE', ( #27082 ), #10927, .F. ) ; +#37152 = DIRECTION ( 'NONE', ( -0.0005884949961181158967, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#37153 = EDGE_CURVE ( 'NONE', #27146, #5373, #1495, .T. ) ; +#37154 = CARTESIAN_POINT ( 'NONE', ( -39.69379533597580689, 119.8651493286000687, 87.86309706269757669 ) ) ; +#37155 = VERTEX_POINT ( 'NONE', #17017 ) ; +#37156 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501096017, 132.2930706492104207, 93.28496646311234031 ) ) ; +#37157 = CARTESIAN_POINT ( 'NONE', ( -26.85975184320017561, 120.0694837154507439, 171.4904642190294055 ) ) ; +#37158 = EDGE_CURVE ( 'NONE', #38882, #6653, #24463, .T. ) ; +#37159 = ORIENTED_EDGE ( 'NONE', *, *, #29674, .T. ) ; +#37160 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 2.710505431213761687E-20, -0.0006039748319392908554 ) ) ; +#37161 = CARTESIAN_POINT ( 'NONE', ( 15.99988529162822992, 142.9897646997318930, 92.65516457330386402 ) ) ; +#37162 = VERTEX_POINT ( 'NONE', #20304 ) ; +#37163 = DIRECTION ( 'NONE', ( -0.7763856147932157725, 0.5343480027610243432, 0.3342118924985533757 ) ) ; +#37164 = EDGE_CURVE ( 'NONE', #33382, #12519, #19964, .T. ) ; +#37165 = DIRECTION ( 'NONE', ( 0.0005884949961259295249, -0.2249510543438812127, 0.9743698870671321233 ) ) ; +#37166 = CYLINDRICAL_SURFACE ( 'NONE', #25416, 10.00000000000000355 ) ; +#37167 = VERTEX_POINT ( 'NONE', #1714 ) ; +#37168 = CARTESIAN_POINT ( 'NONE', ( -21.21281377555379422, 136.1368903374970500, 93.66117170127317593 ) ) ; +#37169 = VECTOR ( 'NONE', #24681, 1000.000000000000000 ) ; +#37170 = DIRECTION ( 'NONE', ( 0.0005884949961263758909, -0.2249510543439055821, 0.9743698870671265722 ) ) ; +#37171 = VECTOR ( 'NONE', #19621, 1000.000000000000000 ) ; +#37172 = CARTESIAN_POINT ( 'NONE', ( -25.86921758744999877, 191.4610772821999944, 106.7890348773999989 ) ) ; +#37173 = CARTESIAN_POINT ( 'NONE', ( 18.73223105748837725, 125.8794445655114203, 175.0685815650430470 ) ) ; +#37174 = VECTOR ( 'NONE', #34343, 1000.000000000000000 ) ; +#37175 = DIRECTION ( 'NONE', ( -0.0006039748319378811757, -1.385389704782810608E-14, -0.9999998176071845934 ) ) ; +#37176 = ORIENTED_EDGE ( 'NONE', *, *, #27403, .T. ) ; +#37177 = ORIENTED_EDGE ( 'NONE', *, *, #31574, .F. ) ; +#37178 = EDGE_CURVE ( 'NONE', #22040, #34652, #11526, .T. ) ; +#37179 = CARTESIAN_POINT ( 'NONE', ( -19.99823416866533776, 118.9403737594142996, 90.20346087292678305 ) ) ; +#37180 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; +#37181 = CARTESIAN_POINT ( 'NONE', ( -29.41449785468654810, 161.0344709224577571, 187.1181755728296423 ) ) ; +#37182 = CARTESIAN_POINT ( 'NONE', ( -45.98416322616978391, 186.8584405881918542, 105.3861271832789583 ) ) ; +#37183 = ORIENTED_EDGE ( 'NONE', *, *, #8815, .F. ) ; +#37184 = ORIENTED_EDGE ( 'NONE', *, *, #3663, .T. ) ; +#37185 = CARTESIAN_POINT ( 'NONE', ( 38.60351697648751212, 119.1187903609922785, 90.25579952397890793 ) ) ; +#37186 = LINE ( 'NONE', #12046, #34922 ) ; +#37187 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#37188 = CARTESIAN_POINT ( 'NONE', ( -20.50011546390365780, 195.6232239793727672, 104.6210501281420591 ) ) ; +#37189 = LINE ( 'NONE', #21662, #10272 ) ; +#37190 = ORIENTED_EDGE ( 'NONE', *, *, #14019, .T. ) ; +#37191 = CARTESIAN_POINT ( 'NONE', ( -25.50306166618090131, 190.9267346374540182, 106.3078661562249891 ) ) ; +#37192 = DIRECTION ( 'NONE', ( 0.0002393071182785538528, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#37193 = CIRCLE ( 'NONE', #28069, 4.999999999999994671 ) ; +#37194 = APPROVAL_ROLE ( '' ) ; +#37195 = FACE_OUTER_BOUND ( 'NONE', #20489, .T. ) ; +#37196 = CARTESIAN_POINT ( 'NONE', ( -22.46513725335000089, 138.6416257239000061, 152.4718672074000381 ) ) ; +#37197 = CARTESIAN_POINT ( 'NONE', ( -36.03995056947305642, 114.4593242826029211, 87.76863778157522233 ) ) ; +#37198 = CARTESIAN_POINT ( 'NONE', ( -20.39533962340643214, 184.3752265020850700, 104.9032181557475809 ) ) ; +#37199 = AXIS2_PLACEMENT_3D ( 'NONE', #15003, #11533, #24008 ) ; +#37200 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930882020 ) ) ; +#37201 = CARTESIAN_POINT ( 'NONE', ( 36.36654887128020164, 191.7212231514119765, 106.4089556652880049 ) ) ; +#37202 = AXIS2_PLACEMENT_3D ( 'NONE', #1923, #1300, #4977 ) ; +#37203 = EDGE_CURVE ( 'NONE', #18856, #11663, #36334, .T. ) ; +#37204 = ADVANCED_FACE ( 'NONE', ( #39312 ), #13380, .F. ) ; +#37206 = ORIENTED_EDGE ( 'NONE', *, *, #10254, .T. ) ; +#37205 = CARTESIAN_POINT ( 'NONE', ( 36.81547264312000323, 191.5047199901999875, 106.2223202966000031 ) ) ; +#37207 = ORIENTED_EDGE ( 'NONE', *, *, #38424, .F. ) ; +#37208 = VERTEX_POINT ( 'NONE', #11729 ) ; +#37209 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 103.5647597712388261, 168.7177032462348620 ) ) ; +#37210 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319053226929 ) ) ; +#37211 = DIRECTION ( 'NONE', ( -0.0006039748319382907873, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#37212 = ORIENTED_EDGE ( 'NONE', *, *, #32262, .T. ) ; +#37213 = CARTESIAN_POINT ( 'NONE', ( -39.05736483137000192, 119.1152016881000009, 89.88366530550999300 ) ) ; +#37214 = DIRECTION ( 'NONE', ( -0.9999998268368058829, -0.0001323825923297300314, 0.0005734119002798992570 ) ) ; +#37215 = CARTESIAN_POINT ( 'NONE', ( 26.01073959733328067, 191.4239670711786516, 106.8751801458234496 ) ) ; +#37216 = CARTESIAN_POINT ( 'NONE', ( -38.23431137947999758, 118.4009997958000042, 87.63106613149000168 ) ) ; +#37217 = VERTEX_POINT ( 'NONE', #5579 ) ; +#37218 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672195685, 160.1796136994820188, 99.19090620720055540 ) ) ; +#37219 = CARTESIAN_POINT ( 'NONE', ( 35.11870792466202573, 88.60542317626236297, 280.9309724330075255 ) ) ; +#37220 = DIRECTION ( 'NONE', ( 0.0005884949961172263088, -0.2249510543439070254, 0.9743698870671261281 ) ) ; +#37221 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; +#37222 = ORIENTED_EDGE ( 'NONE', *, *, #12056, .F. ) ; +#37223 = ORIENTED_EDGE ( 'NONE', *, *, #33405, .T. ) ; +#37224 = AXIS2_PLACEMENT_3D ( 'NONE', #3808, #6882, #22249 ) ; +#37225 = EDGE_CURVE ( 'NONE', #19053, #3089, #39927, .T. ) ; +#37226 = CARTESIAN_POINT ( 'NONE', ( -26.40530067702999872, 188.8820921157000043, 103.6641521443000187 ) ) ; +#37227 = CIRCLE ( 'NONE', #24838, 5.500000000023937297 ) ; +#37228 = CARTESIAN_POINT ( 'NONE', ( 2.452308076451000129, 189.9363398959999927, 103.8103614717999932 ) ) ; +#37229 = DIRECTION ( 'NONE', ( -0.9914446424033068750, -0.1273124132179996593, -0.02879358418794632571 ) ) ; +#37230 = AXIS2_PLACEMENT_3D ( 'NONE', #5455, #38993, #2002 ) ; +#37231 = AXIS2_PLACEMENT_3D ( 'NONE', #30335, #21352, #18045 ) ; +#37232 = ORIENTED_EDGE ( 'NONE', *, *, #38604, .T. ) ; +#37233 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; +#37234 = ORIENTED_EDGE ( 'NONE', *, *, #7098, .T. ) ; +#37235 = CARTESIAN_POINT ( 'NONE', ( -36.06327032790999709, 192.0058469960000025, 104.2181114514999933 ) ) ; +#37236 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082099409, 82.27946979429611929, 297.5876476292040707 ) ) ; +#37237 = CARTESIAN_POINT ( 'NONE', ( 20.50156975035513440, 118.5813318771761828, 89.75551271367082506 ) ) ; +#37238 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; +#37239 = CARTESIAN_POINT ( 'NONE', ( 27.93628726423925812, 134.9227324293656238, 90.78539832649367725 ) ) ; +#37240 = CARTESIAN_POINT ( 'NONE', ( -1.288178592179473281, 189.1901137174187113, 105.7932474174069029 ) ) ; +#37241 = ORIENTED_EDGE ( 'NONE', *, *, #39029, .F. ) ; +#37242 = CARTESIAN_POINT ( 'NONE', ( 5.667964583422318015, 129.9727540549875187, 92.22183312941298539 ) ) ; +#37243 = CARTESIAN_POINT ( 'NONE', ( -16.55812367624396586, 121.7577634206059827, 178.0415208806314240 ) ) ; +#37244 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#37245 = ADVANCED_FACE ( 'NONE', ( #5374 ), #34333, .F. ) ; +#37246 = EDGE_CURVE ( 'NONE', #27090, #24177, #8465, .T. ) ; +#37248 = FACE_OUTER_BOUND ( 'NONE', #16392, .T. ) ; +#37247 = CARTESIAN_POINT ( 'NONE', ( -2.955836285853710610, 208.9211498072354800, 73.12285454242802984 ) ) ; +#37249 = ORIENTED_EDGE ( 'NONE', *, *, #24892, .T. ) ; +#37250 = AXIS2_PLACEMENT_3D ( 'NONE', #6828, #25679, #899 ) ; +#37251 = AXIS2_PLACEMENT_3D ( 'NONE', #15874, #22243, #2815 ) ; +#37252 = ORIENTED_EDGE ( 'NONE', *, *, #1368, .T. ) ; +#37253 = VECTOR ( 'NONE', #25397, 1000.000000000000000 ) ; +#37254 = CARTESIAN_POINT ( 'NONE', ( -3.537744320960331645, 175.3497732290038300, 100.1377481765469355 ) ) ; +#37255 = AXIS2_PLACEMENT_3D ( 'NONE', #738, #35453, #13225 ) ; +#37256 = ORIENTED_EDGE ( 'NONE', *, *, #15230, .F. ) ; +#37257 = CARTESIAN_POINT ( 'NONE', ( -25.99908199189640357, 120.4516993851283786, 90.55600231170684822 ) ) ; +#37258 = CARTESIAN_POINT ( 'NONE', ( -37.61311534121512068, 218.5902260770998282, 61.08121927284271635 ) ) ; +#37259 = CARTESIAN_POINT ( 'NONE', ( -5.631746571662000100, 114.0103269030000064, 152.4718672074000381 ) ) ; +#37260 = FACE_OUTER_BOUND ( 'NONE', #3477, .T. ) ; +#37261 = CARTESIAN_POINT ( 'NONE', ( -12.63881147185363929, 135.0944381253359268, 91.09204730616018253 ) ) ; +#37262 = ORIENTED_EDGE ( 'NONE', *, *, #32662, .T. ) ; +#37263 = ORIENTED_EDGE ( 'NONE', *, *, #24946, .F. ) ; +#37264 = CARTESIAN_POINT ( 'NONE', ( 16.16729401867695515, 152.0078996042194603, 180.9416867539977716 ) ) ; +#37265 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540931788, 138.0805224084985809, 92.05383544148618569 ) ) ; +#37266 = VERTEX_POINT ( 'NONE', #34183 ) ; +#37267 = EDGE_CURVE ( 'NONE', #1726, #11222, #23943, .T. ) ; +#37268 = CARTESIAN_POINT ( 'NONE', ( -36.41573719211999816, 191.0204961844000024, 106.6712136290999950 ) ) ; +#37269 = CARTESIAN_POINT ( 'NONE', ( 2.942908067099000213, 190.9184233608000056, 106.6821566891999993 ) ) ; +#37270 = ORIENTED_EDGE ( 'NONE', *, *, #31375, .T. ) ; +#37271 = CARTESIAN_POINT ( 'NONE', ( 2.714797524005000184, 190.6465356628000052, 106.3910463972000002 ) ) ; +#37272 = VECTOR ( 'NONE', #22523, 1000.000000000000000 ) ; +#37273 = CARTESIAN_POINT ( 'NONE', ( -2.372094777808882782, 209.5677220771418376, 75.55993702015497604 ) ) ; +#37274 = CARTESIAN_POINT ( 'NONE', ( 38.15045221970718359, 118.4868570840783377, 87.66883015867043127 ) ) ; +#37275 = DIRECTION ( 'NONE', ( -0.0005884949961269095352, 0.2249510543439041110, -0.9743698870671267942 ) ) ; +#37276 = EDGE_CURVE ( 'NONE', #11663, #4266, #27871, .T. ) ; +#37277 = VECTOR ( 'NONE', #10560, 1000.000000000000000 ) ; +#37278 = EDGE_LOOP ( 'NONE', ( #2148, #36476, #20129, #8203 ) ) ; +#37279 = AXIS2_PLACEMENT_3D ( 'NONE', #31742, #3699, #19640 ) ; +#37280 = DIRECTION ( 'NONE', ( -0.0002393071182776102175, -0.2252352986010028590, 0.9743043687658493601 ) ) ; +#37281 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; +#37282 = CARTESIAN_POINT ( 'NONE', ( -20.18700074617595064, 127.1092214739749977, 91.89588428313297186 ) ) ; +#37283 = EDGE_CURVE ( 'NONE', #34249, #12120, #31145, .T. ) ; +#37284 = ORIENTED_EDGE ( 'NONE', *, *, #23772, .T. ) ; +#37285 = CARTESIAN_POINT ( 'NONE', ( -5.666853951127361455, 188.1985683830214384, 103.2291164934064795 ) ) ; +#37286 = VERTEX_POINT ( 'NONE', #2913 ) ; +#37287 = EDGE_CURVE ( 'NONE', #37554, #17741, #7836, .T. ) ; +#37288 = EDGE_CURVE ( 'NONE', #24000, #16151, #14671, .T. ) ; +#37290 = CARTESIAN_POINT ( 'NONE', ( 0.5624172216153647819, 188.7416494960859552, 103.3595988756643322 ) ) ; +#37289 = CARTESIAN_POINT ( 'NONE', ( 36.33811150393685097, 191.8669705167701522, 104.3681120017585187 ) ) ; +#37291 = EDGE_CURVE ( 'NONE', #8802, #6135, #16589, .T. ) ; +#37292 = ORIENTED_EDGE ( 'NONE', *, *, #21723, .F. ) ; +#37293 = ORIENTED_EDGE ( 'NONE', *, *, #35044, .T. ) ; +#37294 = CARTESIAN_POINT ( 'NONE', ( 25.49179459016677995, 205.9694998783333233, 75.50271276408311394 ) ) ; +#37295 = EDGE_CURVE ( 'NONE', #19918, #27876, #35114, .T. ) ; +#37296 = CARTESIAN_POINT ( 'NONE', ( -13.78555796877717121, 149.9402637631540074, 180.4518122125792274 ) ) ; +#37297 = ORIENTED_EDGE ( 'NONE', *, *, #16321, .T. ) ; +#37298 = CARTESIAN_POINT ( 'NONE', ( 2.917186392815999785, 209.2977915612000004, 75.96992808251999918 ) ) ; +#37299 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251387102, 132.4055461763545907, 92.79778151957364685 ) ) ; +#37300 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #3295, #21535, #6167, #37453 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37301 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971545141 ) ) ; +#37302 = CARTESIAN_POINT ( 'NONE', ( 3.166376970775131028, 185.9099593149100542, 102.5717182116986521 ) ) ; +#37303 = VERTEX_POINT ( 'NONE', #21127 ) ; +#37304 = CIRCLE ( 'NONE', #2140, 2.000000000000011546 ) ; +#37305 = ORIENTED_EDGE ( 'NONE', *, *, #39368, .F. ) ; +#37306 = CARTESIAN_POINT ( 'NONE', ( 15.50176591790000025, 188.7039117600999987, 106.2882045247999940 ) ) ; +#37308 = AXIS2_PLACEMENT_3D ( 'NONE', #11735, #24422, #39720 ) ; +#37307 = DIRECTION ( 'NONE', ( -0.0006039748319382906789, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#37309 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971556243 ) ) ; +#37310 = CYLINDRICAL_SURFACE ( 'NONE', #19573, 1.750000000000001998 ) ; +#37311 = CARTESIAN_POINT ( 'NONE', ( 35.55404263687999844, 192.3143419058999939, 103.8603455618000027 ) ) ; +#37312 = ORIENTED_EDGE ( 'NONE', *, *, #32715, .T. ) ; +#37313 = ORIENTED_EDGE ( 'NONE', *, *, #36357, .T. ) ; +#37314 = ORIENTED_EDGE ( 'NONE', *, *, #34263, .T. ) ; +#37315 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749905971, 132.8602140592046794, 90.82839891342722183 ) ) ; +#37316 = DIRECTION ( 'NONE', ( 0.0005884949961243997156, -0.2249510543439061094, 0.9743698870671263501 ) ) ; +#37317 = CARTESIAN_POINT ( 'NONE', ( -26.06116861371999960, 121.5718545594999966, 87.73565837146999513 ) ) ; +#37318 = ORIENTED_EDGE ( 'NONE', *, *, #27811, .T. ) ; +#37319 = ORIENTED_EDGE ( 'NONE', *, *, #20420, .F. ) ; +#37320 = DIRECTION ( 'NONE', ( -0.9999998176017698137, -2.069755753680284935E-09, 0.0006039837970576557649 ) ) ; +#37321 = CARTESIAN_POINT ( 'NONE', ( 40.37954014455926455, 190.1842379730972254, 106.6726557211464694 ) ) ; +#37322 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32977, #19699, #10531, #22799, #32398, #32588, #4365, #14201, #38705, #26464, #16632 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999998852029, 0.3749999999998278044, 0.4374999999997640221, 0.4687499999997247202, 0.4999999999996853628, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37323 = ORIENTED_EDGE ( 'NONE', *, *, #39333, .T. ) ; +#37324 = CARTESIAN_POINT ( 'NONE', ( -31.49061741747999932, 191.6070539478000114, 105.4286762605999996 ) ) ; +#37325 = DIRECTION ( 'NONE', ( 0.7857167656192538541, -0.6185862421878155493, -0.0004745532380132038808 ) ) ; +#37326 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118781, 165.7683690613958731, 188.2295199183388377 ) ) ; +#37327 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 183.4515543678114966, 105.0773313099631139 ) ) ; +#37328 = LINE ( 'NONE', #28141, #33886 ) ; +#37329 = EDGE_CURVE ( 'NONE', #12388, #12363, #3311, .T. ) ; +#37330 = ORIENTED_EDGE ( 'NONE', *, *, #3305, .T. ) ; +#37331 = CARTESIAN_POINT ( 'NONE', ( -35.43878503103840671, 193.8169247151014645, 102.7243139109006194 ) ) ; +#37332 = ORIENTED_EDGE ( 'NONE', *, *, #37601, .T. ) ; +#37333 = CARTESIAN_POINT ( 'NONE', ( -23.37153626856268218, 181.6857280266875421, 101.6124992246220842 ) ) ; +#37334 = AXIS2_PLACEMENT_3D ( 'NONE', #37462, #12321, #30938 ) ; +#37335 = DIRECTION ( 'NONE', ( -0.0005884949961241158715, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#37336 = CARTESIAN_POINT ( 'NONE', ( 38.18496905104999684, 118.9607085922999943, 90.40243278587001896 ) ) ; +#37337 = AXIS2_PLACEMENT_3D ( 'NONE', #27144, #13837, #26940 ) ; +#37338 = ADVANCED_FACE ( 'NONE', ( #34386 ), #30451, .T. ) ; +#37339 = AXIS2_PLACEMENT_3D ( 'NONE', #35134, #28833, #38233 ) ; +#37340 = ORIENTED_EDGE ( 'NONE', *, *, #28750, .F. ) ; +#37341 = CARTESIAN_POINT ( 'NONE', ( 20.45461275351677699, 105.2139170029073085, 89.75543067447466683 ) ) ; +#37342 = VERTEX_POINT ( 'NONE', #845 ) ; +#37343 = EDGE_CURVE ( 'NONE', #32145, #645, #1995, .T. ) ; +#37344 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27607, #40233, #9178, #12432 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37345 = CARTESIAN_POINT ( 'NONE', ( 21.83022412997393502, 182.7623874074516266, 102.3469123272103189 ) ) ; +#37346 = EDGE_CURVE ( 'NONE', #27991, #25669, #25903, .T. ) ; +#37347 = ORIENTED_EDGE ( 'NONE', *, *, #17597, .F. ) ; +#37348 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825928029561446, -0.0005734119023360420564 ) ) ; +#37349 = CARTESIAN_POINT ( 'NONE', ( -35.95496198192999771, 218.5902260770999987, 74.58022025207000638 ) ) ; +#37350 = CARTESIAN_POINT ( 'NONE', ( 23.36310281678468925, 177.4440130396671691, 100.9048489206809904 ) ) ; +#37351 = FACE_OUTER_BOUND ( 'NONE', #11211, .T. ) ; +#37352 = VERTEX_POINT ( 'NONE', #9666 ) ; +#37353 = CARTESIAN_POINT ( 'NONE', ( -29.33473203001190655, 191.5260128509293338, 103.8879052539893024 ) ) ; +#37354 = CARTESIAN_POINT ( 'NONE', ( -39.74907094618137648, 128.0257196899142116, 94.36551623669089395 ) ) ; +#37355 = ORIENTED_EDGE ( 'NONE', *, *, #25673, .F. ) ; +#37356 = LINE ( 'NONE', #9354, #9535 ) ; +#37357 = EDGE_LOOP ( 'NONE', ( #13709, #11395, #30541, #9361 ) ) ; +#37358 = CARTESIAN_POINT ( 'NONE', ( 14.24259403095196319, 124.1280741090887574, 175.6403682132716426 ) ) ; +#37359 = AXIS2_PLACEMENT_3D ( 'NONE', #29270, #16376, #10269 ) ; +#37360 = VECTOR ( 'NONE', #11393, 1000.000000000000114 ) ; +#37361 = DIRECTION ( 'NONE', ( 0.0002393070154807156044, 0.2243321270822452584, -0.9745127189990429040 ) ) ; +#37362 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999894129, 182.4172041432880462, 101.7781247867910395 ) ) ; +#37363 = ORIENTED_EDGE ( 'NONE', *, *, #17746, .F. ) ; +#37364 = CARTESIAN_POINT ( 'NONE', ( 36.44436247437651133, 190.8511614233640330, 106.7712946021073606 ) ) ; +#37365 = CARTESIAN_POINT ( 'NONE', ( 4.035676232561270282, 167.9352507711567171, 100.9871535387873962 ) ) ; +#37366 = CARTESIAN_POINT ( 'NONE', ( -25.87112522472000009, 191.5254626433000169, 106.7952437010000040 ) ) ; +#37367 = CARTESIAN_POINT ( 'NONE', ( -1.217044208918286685, 139.0119017283902565, 177.9285297249669782 ) ) ; +#37368 = CARTESIAN_POINT ( 'NONE', ( 4.213781954923014439, 124.8077010108359701, 88.46450401330118041 ) ) ; +#37369 = ORIENTED_EDGE ( 'NONE', *, *, #23858, .T. ) ; +#37370 = FACE_OUTER_BOUND ( 'NONE', #35931, .T. ) ; +#37371 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37372 = CARTESIAN_POINT ( 'NONE', ( 36.83544183102883807, 191.6000745761645305, 104.3427389016375031 ) ) ; +#37373 = ADVANCED_FACE ( 'NONE', ( #15780 ), #14783, .F. ) ; +#37374 = EDGE_CURVE ( 'NONE', #27950, #23218, #19449, .T. ) ; +#37375 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20178, #24707, #33260, #2413 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37376 = CARTESIAN_POINT ( 'NONE', ( -45.92783482638418491, 124.8424006619797098, 91.58171271578800088 ) ) ; +#37377 = EDGE_CURVE ( 'NONE', #29960, #27558, #22142, .T. ) ; +#37378 = EDGE_LOOP ( 'NONE', ( #31274, #27043, #26099, #14129 ) ) ; +#37379 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#37380 = EDGE_CURVE ( 'NONE', #26486, #14356, #3651, .T. ) ; +#37381 = DIRECTION ( 'NONE', ( 0.0005884949961246126529, -0.2249510515334658955, 0.9743698877159676641 ) ) ; +#37382 = CARTESIAN_POINT ( 'NONE', ( 25.79670600115087709, 212.1502502800587706, 73.04292351838113007 ) ) ; +#37383 = CARTESIAN_POINT ( 'NONE', ( 12.63859106734261140, 181.5182822141926806, 104.2008611223816956 ) ) ; +#37384 = DIRECTION ( 'NONE', ( -0.0004161288024545937514, 0.8480480897973873278, -0.5299191110233921753 ) ) ; +#37385 = ORIENTED_EDGE ( 'NONE', *, *, #14212, .F. ) ; +#37386 = CARTESIAN_POINT ( 'NONE', ( -25.50364383179312711, 190.9618642916203157, 106.3193978424590114 ) ) ; +#37387 = ADVANCED_FACE ( 'NONE', ( #22748 ), #12938, .T. ) ; +#37388 = CARTESIAN_POINT ( 'NONE', ( -30.94549661354466963, 183.7382141536517963, 102.0909227894106124 ) ) ; +#37389 = VECTOR ( 'NONE', #33685, 1000.000000000000114 ) ; +#37390 = AXIS2_PLACEMENT_3D ( 'NONE', #35926, #20400, #32869 ) ; +#37391 = CARTESIAN_POINT ( 'NONE', ( -12.64112683475350352, 181.7729531356305870, 101.7436747511642636 ) ) ; +#37392 = ADVANCED_FACE ( 'NONE', ( #31751 ), #37845, .F. ) ; +#37393 = CIRCLE ( 'NONE', #19739, 5.249999999999986677 ) ; +#37394 = DIRECTION ( 'NONE', ( 0.1632030863883311977, -0.3417424275059330885, 0.9255143790539803739 ) ) ; +#37395 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5221, #24876, #15056, #30994 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37396 = APPLICATION_PROTOCOL_DEFINITION ( 'international standard', 'config_control_design', 1994, #6482 ) ; +#37397 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#37398 = EDGE_LOOP ( 'NONE', ( #5207, #29359, #12393, #30257 ) ) ; +#37399 = CARTESIAN_POINT ( 'NONE', ( 23.35635955975471134, 181.6919812636757285, 101.5857449861623110 ) ) ; +#37400 = LINE ( 'NONE', #24542, #20524 ) ; +#37401 = CARTESIAN_POINT ( 'NONE', ( -13.50000254341547468, 185.9068427740967593, 102.5779769526163960 ) ) ; +#37402 = CARTESIAN_POINT ( 'NONE', ( 37.96419449340999819, 191.2689178647999881, 104.9608596072000068 ) ) ; +#37403 = ORIENTED_EDGE ( 'NONE', *, *, #20008, .T. ) ; +#37404 = LINE ( 'NONE', #40052, #21976 ) ; +#37405 = VERTEX_POINT ( 'NONE', #29280 ) ; +#37406 = ORIENTED_EDGE ( 'NONE', *, *, #21614, .T. ) ; +#37407 = EDGE_CURVE ( 'NONE', #30211, #23690, #38534, .T. ) ; +#37408 = DIRECTION ( 'NONE', ( 0.0005884949961205877692, -0.2249510543439036392, 0.9743698870671270162 ) ) ; +#37409 = DIRECTION ( 'NONE', ( -0.0005884949961229519804, 0.2249510543439058041, -0.9743698870671265722 ) ) ; +#37410 = CARTESIAN_POINT ( 'NONE', ( 45.26975122592565270, 124.1481352483489360, 92.21575753250833429 ) ) ; +#37411 = EDGE_LOOP ( 'NONE', ( #12839, #27952, #36101, #12478 ) ) ; +#37412 = CARTESIAN_POINT ( 'NONE', ( 36.21512884357999695, 191.5734286125999972, 103.9649898384000153 ) ) ; +#37413 = DIRECTION ( 'NONE', ( -0.0005884932957440756505, 0.2249510543440633170, -0.9743698870681170021 ) ) ; +#37414 = LINE ( 'NONE', #31277, #17022 ) ; +#37415 = CARTESIAN_POINT ( 'NONE', ( -18.73195124491515884, 125.9123345718518578, 175.0519872679635114 ) ) ; +#37416 = VECTOR ( 'NONE', #31518, 999.9999999999998863 ) ; +#37417 = ORIENTED_EDGE ( 'NONE', *, *, #3209, .T. ) ; +#37418 = DIRECTION ( 'NONE', ( 0.7069397808361403968, -0.6508952239913371463, -0.2767156548817158446 ) ) ; +#37419 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; +#37420 = CIRCLE ( 'NONE', #15861, 6.000000000000001776 ) ; +#37421 = CARTESIAN_POINT ( 'NONE', ( 37.43779685826063286, 117.9749952902482448, 90.24517334801807067 ) ) ; +#37422 = CARTESIAN_POINT ( 'NONE', ( -14.29749313982478931, 129.8659757931446279, 89.98558075341080098 ) ) ; +#37423 = ORIENTED_EDGE ( 'NONE', *, *, #6758, .F. ) ; +#37424 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; +#37425 = AXIS2_PLACEMENT_3D ( 'NONE', #37699, #9300, #21777 ) ; +#37426 = CARTESIAN_POINT ( 'NONE', ( 3.065142597748999886, 190.8985884971000075, 103.7227387430999954 ) ) ; +#37427 = CARTESIAN_POINT ( 'NONE', ( 16.21957306974138291, 152.0331141172343621, 181.0156715975031716 ) ) ; +#37428 = EDGE_LOOP ( 'NONE', ( #5204, #36285, #37625, #25611 ) ) ; +#37429 = EDGE_CURVE ( 'NONE', #31968, #37032, #27365, .T. ) ; +#37430 = VERTEX_POINT ( 'NONE', #4721 ) ; +#37431 = PLANE ( 'NONE', #18533 ) ; +#37432 = ADVANCED_FACE ( 'NONE', ( #26622 ), #7161, .F. ) ; +#37433 = ORIENTED_EDGE ( 'NONE', *, *, #22444, .F. ) ; +#37434 = FACE_OUTER_BOUND ( 'NONE', #27925, .T. ) ; +#37435 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26840, #38876, #39283, #1262 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37436 = CARTESIAN_POINT ( 'NONE', ( -16.89138068276333016, 152.4445295977603223, 182.0512411146230818 ) ) ; +#37437 = DIRECTION ( 'NONE', ( 0.0005884949961231158034, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37438 = CARTESIAN_POINT ( 'NONE', ( -12.63854544869962382, 134.4047710097786990, 93.63040981667991502 ) ) ; +#37439 = CARTESIAN_POINT ( 'NONE', ( -2.435581690730916016, 190.9709058671855360, 106.3075837308457352 ) ) ; +#37440 = VERTEX_POINT ( 'NONE', #5746 ) ; +#37441 = FACE_OUTER_BOUND ( 'NONE', #15410, .T. ) ; +#37442 = CARTESIAN_POINT ( 'NONE', ( -20.01829689993581596, 209.7096928646539880, 76.07061354826153377 ) ) ; +#37443 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 108.4362817545589905, 169.8438797714867405 ) ) ; +#37444 = CONICAL_SURFACE ( 'NONE', #27016, 2.503115359310264409, 0.7853981634098280429 ) ; +#37446 = CARTESIAN_POINT ( 'NONE', ( 15.50029466670349620, 151.8594625334012278, 95.21623178078017702 ) ) ; +#37445 = FACE_OUTER_BOUND ( 'NONE', #17183, .T. ) ; +#37447 = ORIENTED_EDGE ( 'NONE', *, *, #171, .F. ) ; +#37448 = EDGE_CURVE ( 'NONE', #15910, #34777, #34616, .T. ) ; +#37449 = CIRCLE ( 'NONE', #24423, 2.500000000000002220 ) ; +#37450 = ORIENTED_EDGE ( 'NONE', *, *, #15867, .T. ) ; +#37451 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27162, #14061, #17098, #33250 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37452 = VERTEX_POINT ( 'NONE', #8622 ) ; +#37453 = CARTESIAN_POINT ( 'NONE', ( 8.471855298021594649, 160.9702727382075125, 99.37648202509593887 ) ) ; +#37454 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; +#37455 = DIRECTION ( 'NONE', ( -0.6771712326825871653, 0.7358254695422994374, 0.000000000000000000 ) ) ; +#37456 = CARTESIAN_POINT ( 'NONE', ( 30.80313644631934622, 129.4492109585081039, 89.52002191062021552 ) ) ; +#37457 = CARTESIAN_POINT ( 'NONE', ( 26.00056762447263026, 118.1139028608674408, 90.25209678512123901 ) ) ; +#37458 = ORIENTED_EDGE ( 'NONE', *, *, #29573, .F. ) ; +#37459 = CARTESIAN_POINT ( 'NONE', ( -20.46175974694933331, 113.1258758035523329, 152.4706876829759210 ) ) ; +#37460 = ORIENTED_EDGE ( 'NONE', *, *, #1224, .T. ) ; +#37461 = CARTESIAN_POINT ( 'NONE', ( 5.665001372474884000, 124.5325149493340007, 88.62642709471825242 ) ) ; +#37462 = CARTESIAN_POINT ( 'NONE', ( -13.78572884413053323, 150.0031063907798625, 180.1798338070967418 ) ) ; +#37463 = VERTEX_POINT ( 'NONE', #8422 ) ; +#37464 = CARTESIAN_POINT ( 'NONE', ( -2.942325969950079667, 191.1136005232059745, 103.7716195718440133 ) ) ; +#37465 = CARTESIAN_POINT ( 'NONE', ( 0.8111558242224019555, 188.6256192453763276, 103.2000891457199572 ) ) ; +#37466 = VECTOR ( 'NONE', #20461, 1000.000000000000000 ) ; +#37467 = CIRCLE ( 'NONE', #16545, 47.99999999999142375 ) ; +#37468 = LINE ( 'NONE', #40125, #6416 ) ; +#37469 = ORIENTED_EDGE ( 'NONE', *, *, #24285, .F. ) ; +#37470 = EDGE_CURVE ( 'NONE', #13325, #27876, #34980, .T. ) ; +#37471 = AXIS2_PLACEMENT_3D ( 'NONE', #25988, #34937, #32118 ) ; +#37472 = ORIENTED_EDGE ( 'NONE', *, *, #39052, .F. ) ; +#37473 = FACE_OUTER_BOUND ( 'NONE', #1759, .T. ) ; +#37474 = EDGE_CURVE ( 'NONE', #30526, #33415, #28279, .T. ) ; +#37475 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; +#37476 = CARTESIAN_POINT ( 'NONE', ( 36.45779463145590427, 191.3327406263113062, 103.8035477994775562 ) ) ; +#37477 = CARTESIAN_POINT ( 'NONE', ( -39.49580106672456736, 114.5726794337774237, 151.3694230698880290 ) ) ; +#37478 = ORIENTED_EDGE ( 'NONE', *, *, #10528, .T. ) ; +#37479 = CARTESIAN_POINT ( 'NONE', ( 25.99891797325151543, 119.8743747107293842, 87.31240407691905148 ) ) ; +#37480 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567900 ) ) ; +#37481 = CARTESIAN_POINT ( 'NONE', ( 19.99905349769186458, 193.8169544161346494, 102.6908434160864800 ) ) ; +#37482 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557741681312, -0.2249510933750812069 ) ) ; +#37483 = EDGE_LOOP ( 'NONE', ( #11702, #224, #39091, #10270 ) ) ; +#37484 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; +#37486 = CARTESIAN_POINT ( 'NONE', ( 4.035676232561270282, 167.9352507711567171, 100.9871535387873962 ) ) ; +#37485 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023854076 ) ) ; +#37487 = ORIENTED_EDGE ( 'NONE', *, *, #39770, .F. ) ; +#37488 = EDGE_CURVE ( 'NONE', #20595, #26011, #2077, .T. ) ; +#37489 = VECTOR ( 'NONE', #7541, 1000.000000000000114 ) ; +#37490 = CIRCLE ( 'NONE', #11369, 2.000000000000011546 ) ; +#37491 = ORIENTED_EDGE ( 'NONE', *, *, #6567, .T. ) ; +#37492 = CYLINDRICAL_SURFACE ( 'NONE', #27807, 2.000000000000011546 ) ; +#37493 = CARTESIAN_POINT ( 'NONE', ( 37.35388853291757982, 168.2165014478888168, 182.6366471215059448 ) ) ; +#37495 = ORIENTED_EDGE ( 'NONE', *, *, #30101, .F. ) ; +#37494 = VECTOR ( 'NONE', #25339, 1000.000000000000227 ) ; +#37496 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29622, #7939, #19993, #14088 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37497 = ORIENTED_EDGE ( 'NONE', *, *, #40131, .F. ) ; +#37498 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#37499 = DIRECTION ( 'NONE', ( -0.6087614115774527823, 0.7730004600455669950, 0.1785492440296760075 ) ) ; +#37500 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363196004925E-14, 0.9999998176071845934 ) ) ; +#37501 = ORIENTED_EDGE ( 'NONE', *, *, #30795, .F. ) ; +#37502 = EDGE_CURVE ( 'NONE', #7652, #30359, #22627, .T. ) ; +#37503 = ORIENTED_EDGE ( 'NONE', *, *, #38166, .F. ) ; +#37504 = LINE ( 'NONE', #18478, #31781 ) ; +#37505 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#37506 = CARTESIAN_POINT ( 'NONE', ( -3.334859946289175703, 185.2690421836657606, 105.3355436155169684 ) ) ; +#37507 = CARTESIAN_POINT ( 'NONE', ( 45.03858804126006277, 180.7763372603838832, 104.2690891899409706 ) ) ; +#37508 = EDGE_CURVE ( 'NONE', #22242, #10930, #21086, .T. ) ; +#37509 = EDGE_LOOP ( 'NONE', ( #33893, #2946, #22288, #21222 ) ) ; +#37510 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37511 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #5958, #12106, #27865, #12488 ), + ( #6544, #12298, #24989, #24593 ), + ( #15950, #40295, #24791, #28249 ), + ( #28444, #420, #21715, #6152 ), + ( #34741, #22715, #35140, #13503 ), + ( #32315, #6743, #32115, #7153 ), + ( #38429, #26382, #22518, #34935 ), + ( #13902, #20021, #22915, #10643 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.07810317900020000148, 0.000000000000000000, 0.3333394298244000131, 0.6666766092639999641, 1.000000000000000000, 1.071387485245000049 ), + ( -1.136779366749999998E-06, 0.9999977618324999984 ), + .UNSPECIFIED. ) ; +#37512 = DIRECTION ( 'NONE', ( -0.0005884949961266395689, 0.2249510543439048882, -0.9743698870671267942 ) ) ; +#37513 = DIRECTION ( 'NONE', ( -0.7933533411653341805, -0.5931840316264885837, -0.1368326740407639630 ) ) ; +#37514 = VERTEX_POINT ( 'NONE', #21298 ) ; +#37515 = EDGE_CURVE ( 'NONE', #2503, #5869, #15442, .T. ) ; +#37516 = CARTESIAN_POINT ( 'NONE', ( 3.827148334468458923, 174.7479281440749617, 102.7742494057653744 ) ) ; +#37517 = EDGE_CURVE ( 'NONE', #23911, #19715, #24574, .T. ) ; +#37518 = LINE ( 'NONE', #704, #14461 ) ; +#37519 = PRODUCT_DEFINITION_FORMATION_WITH_SPECIFIED_SOURCE ( '', '', #16623, .NOT_KNOWN. ) ; +#37520 = VECTOR ( 'NONE', #22661, 1000.000000000000227 ) ; +#37521 = EDGE_CURVE ( 'NONE', #21872, #572, #39439, .T. ) ; +#37522 = CARTESIAN_POINT ( 'NONE', ( -2.452854086982368287, 209.7096538831000032, 78.05998645676569936 ) ) ; +#37523 = AXIS2_PLACEMENT_3D ( 'NONE', #36320, #5851, #30604 ) ; +#37524 = VECTOR ( 'NONE', #17274, 1000.000000000000000 ) ; +#37525 = CARTESIAN_POINT ( 'NONE', ( -19.70071604027683065, 149.4445624503525778, 181.7665744593643637 ) ) ; +#37526 = VERTEX_POINT ( 'NONE', #10230 ) ; +#37527 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319383117124 ) ) ; +#37528 = ORIENTED_EDGE ( 'NONE', *, *, #37276, .T. ) ; +#37529 = AXIS2_PLACEMENT_3D ( 'NONE', #30967, #33409, #14829 ) ; +#37530 = CARTESIAN_POINT ( 'NONE', ( 36.28487897179775246, 77.14301703113186193, 291.5366287775435126 ) ) ; +#37531 = DIRECTION ( 'NONE', ( -0.0005884949961258157921, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#37532 = CARTESIAN_POINT ( 'NONE', ( 94.27346847287640230, 222.2365666497040024, 195.1387431474686309 ) ) ; +#37533 = CARTESIAN_POINT ( 'NONE', ( 15.99998354046833526, 185.2802125521836274, 102.4185673416719595 ) ) ; +#37534 = VERTEX_POINT ( 'NONE', #13286 ) ; +#37535 = DIRECTION ( 'NONE', ( 3.466267702402558037E-10, 0.9743700558702499404, 0.2249510929589051966 ) ) ; +#37536 = ORIENTED_EDGE ( 'NONE', *, *, #10704, .T. ) ; +#37537 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971559019 ) ) ; +#37538 = CARTESIAN_POINT ( 'NONE', ( 21.57469945311886406, 182.6285438479031029, 101.9740652419444444 ) ) ; +#37539 = EDGE_CURVE ( 'NONE', #16448, #33199, #25769, .T. ) ; +#37540 = ORIENTED_EDGE ( 'NONE', *, *, #1302, .T. ) ; +#37541 = CARTESIAN_POINT ( 'NONE', ( 35.79347699833099483, 148.9204335778105133, 291.5369255720340220 ) ) ; +#37542 = CARTESIAN_POINT ( 'NONE', ( -45.39636767568900666, 130.6771924050837868, 92.41530714614147257 ) ) ; +#37543 = CARTESIAN_POINT ( 'NONE', ( -21.60222517327440883, 158.4634865330191076, 96.25014797633018304 ) ) ; +#37544 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319299392864 ) ) ; +#37545 = ORIENTED_EDGE ( 'NONE', *, *, #35626, .F. ) ; +#37546 = ORIENTED_EDGE ( 'NONE', *, *, #6248, .T. ) ; +#37547 = CARTESIAN_POINT ( 'NONE', ( 17.33255171641533110, 121.2645175805946138, 177.4250592562015925 ) ) ; +#37548 = CARTESIAN_POINT ( 'NONE', ( 13.46662727487878719, 154.4076626936201251, 95.29260641077831906 ) ) ; +#37549 = AXIS2_PLACEMENT_3D ( 'NONE', #8102, #32643, #4622 ) ; +#37550 = VERTEX_POINT ( 'NONE', #6935 ) ; +#37551 = CARTESIAN_POINT ( 'NONE', ( 24.53318176556000196, 104.1131156702031291, 87.25296686499314092 ) ) ; +#37552 = CONICAL_SURFACE ( 'NONE', #21255, 2.499999999403085482, 0.7853981633778843729 ) ; +#37553 = CARTESIAN_POINT ( 'NONE', ( 4.035676231712624684, 167.9352507713281568, 100.9871535380448790 ) ) ; +#37554 = VERTEX_POINT ( 'NONE', #31489 ) ; +#37555 = CARTESIAN_POINT ( 'NONE', ( 5.776391476381944386E-13, 155.6803346353095492, 98.67347229713607248 ) ) ; +#37556 = EDGE_CURVE ( 'NONE', #17270, #36424, #30224, .T. ) ; +#37557 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 130.2931719330197211, 89.72259846333707856 ) ) ; +#37558 = ORIENTED_EDGE ( 'NONE', *, *, #5944, .T. ) ; +#37559 = CARTESIAN_POINT ( 'NONE', ( 28.31864702441999881, 125.4665321470999970, 88.94399801561999652 ) ) ; +#37560 = EDGE_CURVE ( 'NONE', #13652, #9483, #6136, .T. ) ; +#37561 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.261220487827980362E-14, 0.9999998176071844824 ) ) ; +#37562 = CARTESIAN_POINT ( 'NONE', ( -12.63662703291899625, 136.7909212374734977, 93.80698685772726719 ) ) ; +#37563 = DIRECTION ( 'NONE', ( 0.1305262373691798983, -0.9659583596717404852, -0.2233547598295697878 ) ) ; +#37564 = EDGE_CURVE ( 'NONE', #39475, #32051, #2433, .T. ) ; +#37565 = CARTESIAN_POINT ( 'NONE', ( 20.31489494964546694, 159.5155431624664004, 96.46771754143387057 ) ) ; +#37566 = ADVANCED_FACE ( 'NONE', ( #28039 ), #15930, .T. ) ; +#37567 = ORIENTED_EDGE ( 'NONE', *, *, #22963, .F. ) ; +#37568 = CARTESIAN_POINT ( 'NONE', ( -20.89113403792100598, 128.9341314247968455, 92.51124259315015763 ) ) ; +#37569 = EDGE_CURVE ( 'NONE', #10713, #5648, #19907, .T. ) ; +#37570 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#37571 = CARTESIAN_POINT ( 'NONE', ( -15.94440703681848959, 121.4361576967349805, 176.4277666190321270 ) ) ; +#37572 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #19083, #6216, #18876, #21586 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.0007153166800046975365, 0.0007171796110761329175 ), + .UNSPECIFIED. ) ; +#37573 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566790 ) ) ; +#37574 = EDGE_LOOP ( 'NONE', ( #8204, #17465, #15866, #22075, #28502, #20365 ) ) ; +#37575 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37576 = CARTESIAN_POINT ( 'NONE', ( 19.38593967614783153, 149.1387850987350134, 181.1979322825702639 ) ) ; +#37577 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319377938974 ) ) ; +#37578 = VECTOR ( 'NONE', #8227, 1000.000000000000114 ) ; +#37579 = AXIS2_PLACEMENT_3D ( 'NONE', #13988, #4568, #1504 ) ; +#37580 = CARTESIAN_POINT ( 'NONE', ( -14.91027384103292874, 124.4773777159772550, 171.6934768334666899 ) ) ; +#37581 = ORIENTED_EDGE ( 'NONE', *, *, #8213, .F. ) ; +#37582 = VECTOR ( 'NONE', #10569, 1000.000000000000227 ) ; +#37583 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319383098692 ) ) ; +#37584 = VECTOR ( 'NONE', #18583, 1000.000000000000227 ) ; +#37585 = CARTESIAN_POINT ( 'NONE', ( 39.06349078196001301, 191.0388279120988670, 103.7341189576915355 ) ) ; +#37586 = CARTESIAN_POINT ( 'NONE', ( -14.55306309020423505, 135.7870933973037211, 91.01063163966807679 ) ) ; +#37587 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; +#37588 = CARTESIAN_POINT ( 'NONE', ( -20.32205136248488841, 184.3585806804883873, 104.9745027317775481 ) ) ; +#37589 = FACE_OUTER_BOUND ( 'NONE', #36286, .T. ) ; +#37590 = CARTESIAN_POINT ( 'NONE', ( 37.18343360016979915, 191.4782479266900168, 104.3069991309919970 ) ) ; +#37591 = CARTESIAN_POINT ( 'NONE', ( 36.23010250326999682, 191.7113666676000037, 106.5063430098000055 ) ) ; +#37592 = ORIENTED_EDGE ( 'NONE', *, *, #35788, .F. ) ; +#37593 = ORIENTED_EDGE ( 'NONE', *, *, #12049, .T. ) ; +#37594 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -3.519737327345223780E-16, 0.0006039748319385488274 ) ) ; +#37595 = DIRECTION ( 'NONE', ( -0.6087614115774885315, 0.7730004600455400166, 0.1785492440296710670 ) ) ; +#37596 = ADVANCED_FACE ( 'NONE', ( #25169 ), #34519, .F. ) ; +#37597 = EDGE_CURVE ( 'NONE', #407, #16596, #20954, .T. ) ; +#37598 = CARTESIAN_POINT ( 'NONE', ( 20.49930103516235746, 196.1188360154283430, 103.6658478038365558 ) ) ; +#37599 = AXIS2_PLACEMENT_3D ( 'NONE', #17469, #1752, #36498 ) ; +#37600 = DIRECTION ( 'NONE', ( -0.7933535320750288999, 0.5931614265262136199, 0.1369295264925108890 ) ) ; +#37601 = EDGE_CURVE ( 'NONE', #27115, #27579, #27281, .T. ) ; +#37602 = AXIS2_PLACEMENT_3D ( 'NONE', #6158, #28449, #25393 ) ; +#37603 = ORIENTED_EDGE ( 'NONE', *, *, #16628, .F. ) ; +#37604 = CARTESIAN_POINT ( 'NONE', ( 18.08127464052524758, 152.6344612320365286, 184.7492086203702115 ) ) ; +#37605 = EDGE_CURVE ( 'NONE', #32124, #30211, #22095, .T. ) ; +#37606 = LINE ( 'NONE', #31480, #35480 ) ; +#37607 = CARTESIAN_POINT ( 'NONE', ( -20.00002391410913560, 191.9758546681010785, 103.9335315410770448 ) ) ; +#37608 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24959, #384, #22282, #18576, #9007, #5923, #33924, #31081, #6713, #19176 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.002027470929952764501, 0.2515206031974627221, 0.5010137354649751851, 0.7505068677324875370, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37609 = CARTESIAN_POINT ( 'NONE', ( 20.25012552873999994, 118.4641756272000066, 87.50539960479001422 ) ) ; +#37610 = VERTEX_POINT ( 'NONE', #3656 ) ; +#37611 = AXIS2_PLACEMENT_3D ( 'NONE', #11108, #36238, #8241 ) ; +#37612 = EDGE_CURVE ( 'NONE', #17689, #39586, #16144, .T. ) ; +#37613 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; +#37614 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596101196, 131.0247019790142815, 89.88805227296677458 ) ) ; +#37615 = CARTESIAN_POINT ( 'NONE', ( 23.36469433561273235, 176.8669516480852337, 103.2047264528809194 ) ) ; +#37616 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11358, #36302, #8303, #24468 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37617 = AXIS2_PLACEMENT_3D ( 'NONE', #6379, #6981, #32149 ) ; +#37618 = DIRECTION ( 'NONE', ( 0.0006039748319392990953, 2.305558552177526877E-15, 0.9999998176071847045 ) ) ; +#37619 = ORIENTED_EDGE ( 'NONE', *, *, #16268, .F. ) ; +#37620 = ADVANCED_FACE ( 'NONE', ( #22502 ), #18041, .T. ) ; +#37621 = ORIENTED_EDGE ( 'NONE', *, *, #40, .F. ) ; +#37622 = CARTESIAN_POINT ( 'NONE', ( 12.64068429172691665, 176.9138758412513255, 103.2882421082539963 ) ) ; +#37623 = CARTESIAN_POINT ( 'NONE', ( 2.548040970592790444, 190.9966390957640101, 104.2749172799330069 ) ) ; +#37624 = CARTESIAN_POINT ( 'NONE', ( 21.72592390767327686, 135.1711755393868941, 93.92543662762206225 ) ) ; +#37625 = ORIENTED_EDGE ( 'NONE', *, *, #6026, .T. ) ; +#37626 = FACE_OUTER_BOUND ( 'NONE', #26463, .T. ) ; +#37627 = ORIENTED_EDGE ( 'NONE', *, *, #21132, .T. ) ; +#37628 = DIRECTION ( 'NONE', ( 0.6087611427424929333, 0.7731004630501246977, 0.1781166615410725018 ) ) ; +#37629 = EDGE_CURVE ( 'NONE', #21533, #28516, #17300, .T. ) ; +#37630 = FACE_OUTER_BOUND ( 'NONE', #32815, .T. ) ; +#37631 = VECTOR ( 'NONE', #6951, 1000.000000000000227 ) ; +#37632 = AXIS2_PLACEMENT_3D ( 'NONE', #14734, #39444, #32911 ) ; +#37633 = DIRECTION ( 'NONE', ( -0.0002393071182785117045, -0.2252352986010040525, 0.9743043687658490271 ) ) ; +#37634 = CARTESIAN_POINT ( 'NONE', ( -5.659900684199740795, 130.3459505314356477, 92.82798007168634058 ) ) ; +#37635 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#37636 = CARTESIAN_POINT ( 'NONE', ( -20.49852830327300879, 119.8277974066376999, 89.89548907266683386 ) ) ; +#37637 = EDGE_LOOP ( 'NONE', ( #14142, #40197, #16522, #39077 ) ) ; +#37638 = AXIS2_PLACEMENT_3D ( 'NONE', #38208, #19174, #22079 ) ; +#37639 = PLANE ( 'NONE', #14626 ) ; +#37640 = CARTESIAN_POINT ( 'NONE', ( 19.33916236813157141, 149.2574392882847576, 181.2554555184128446 ) ) ; +#37641 = CARTESIAN_POINT ( 'NONE', ( 23.68440576545748755, 137.3587804155124843, 91.34731897728055117 ) ) ; +#37642 = VECTOR ( 'NONE', #3455, 1000.000000000000114 ) ; +#37643 = CARTESIAN_POINT ( 'NONE', ( 15.50029467790899496, 185.7974155947267718, 103.0514270424844483 ) ) ; +#37644 = ORIENTED_EDGE ( 'NONE', *, *, #27108, .F. ) ; +#37645 = VERTEX_POINT ( 'NONE', #29836 ) ; +#37646 = ORIENTED_EDGE ( 'NONE', *, *, #14871, .T. ) ; +#37647 = CARTESIAN_POINT ( 'NONE', ( -30.09883670037504189, 202.4139200980250166, 28.35470564401785865 ) ) ; +#37648 = ADVANCED_FACE ( 'NONE', ( #35934 ), #10426, .F. ) ; +#37649 = CARTESIAN_POINT ( 'NONE', ( 35.54678039743919271, 205.1071296091639056, 76.08337964661465946 ) ) ; +#37650 = EDGE_CURVE ( 'NONE', #7935, #24453, #4869, .T. ) ; +#37651 = VERTEX_POINT ( 'NONE', #16924 ) ; +#37652 = ADVANCED_FACE ( 'NONE', ( #35328 ), #40173, .F. ) ; +#37653 = ORIENTED_EDGE ( 'NONE', *, *, #4637, .F. ) ; +#37654 = DIRECTION ( 'NONE', ( -0.9999998176071820399, 0.000000000000000000, 0.0006039748360328516322 ) ) ; +#37655 = CARTESIAN_POINT ( 'NONE', ( -38.54565934514999981, 119.1564762388999981, 90.30561916639000231 ) ) ; +#37656 = CARTESIAN_POINT ( 'NONE', ( -38.01592745802000195, 119.2010240264000061, 87.30145059880000247 ) ) ; +#37657 = DIRECTION ( 'NONE', ( 0.1779895592101686796, 0.3532431349384635433, -0.9184437949221587738 ) ) ; +#37658 = ORIENTED_EDGE ( 'NONE', *, *, #20759, .F. ) ; +#37659 = CARTESIAN_POINT ( 'NONE', ( 5.667983148732107956, 187.2950682004077407, 105.4557345120219480 ) ) ; +#37660 = ORIENTED_EDGE ( 'NONE', *, *, #5719, .T. ) ; +#37661 = VECTOR ( 'NONE', #21592, 1000.000000000000114 ) ; +#37662 = DIRECTION ( 'NONE', ( -0.0005884949961242402295, 0.2249510543439063315, -0.9743698870671264611 ) ) ; +#37663 = VECTOR ( 'NONE', #30246, 1000.000000000000114 ) ; +#37664 = CARTESIAN_POINT ( 'NONE', ( 3.166376970775131028, 185.9099593149100542, 102.5717182116986521 ) ) ; +#37665 = ADVANCED_FACE ( 'NONE', ( #26170 ), #14292, .F. ) ; +#37666 = ORIENTED_EDGE ( 'NONE', *, *, #22412, .F. ) ; +#37667 = CARTESIAN_POINT ( 'NONE', ( -20.00062605139820704, 196.5784656963837733, 103.8871944330217048 ) ) ; +#37668 = CARTESIAN_POINT ( 'NONE', ( 1.993582469418050174, 189.0625797058357307, 103.3002552791548965 ) ) ; +#37669 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; +#37670 = VECTOR ( 'NONE', #4141, 1000.000000000000227 ) ; +#37671 = ORIENTED_EDGE ( 'NONE', *, *, #4883, .T. ) ; +#37672 = ADVANCED_FACE ( 'NONE', ( #38609 ), #30482, .F. ) ; +#37673 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498907891, 132.2978364233970581, 93.26432363115026192 ) ) ; +#37674 = CARTESIAN_POINT ( 'NONE', ( -25.50129508846853099, 118.1132512059233335, 87.78307593003776788 ) ) ; +#37675 = EDGE_LOOP ( 'NONE', ( #33020, #2647, #3416, #19304, #25707, #29366, #15370, #12680, #19983, #22543, #9619, #12299 ) ) ; +#37676 = CARTESIAN_POINT ( 'NONE', ( 20.81604738696258039, 116.8538761181823133, 89.75547759989828478 ) ) ; +#37677 = CARTESIAN_POINT ( 'NONE', ( 36.24124945375172047, 191.4454296738790333, 103.8296949086555543 ) ) ; +#37678 = CARTESIAN_POINT ( 'NONE', ( -26.83585668902999899, 123.2446041209999947, 91.07657256299999915 ) ) ; +#37679 = ORIENTED_EDGE ( 'NONE', *, *, #37203, .T. ) ; +#37680 = CARTESIAN_POINT ( 'NONE', ( 2.102344972559205161, 188.8904649364737054, 106.3393666415465191 ) ) ; +#37681 = LINE ( 'NONE', #19857, #21246 ) ; +#37682 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265227786, 0.1368326740407719844 ) ) ; +#37683 = ORIENTED_EDGE ( 'NONE', *, *, #40413, .T. ) ; +#37684 = VECTOR ( 'NONE', #23135, 1000.000000000000000 ) ; +#37685 = LINE ( 'NONE', #9686, #23450 ) ; +#37686 = CARTESIAN_POINT ( 'NONE', ( 36.06343484178082548, 196.1181868591233410, 103.6579563381249471 ) ) ; +#37687 = AXIS2_PLACEMENT_3D ( 'NONE', #18658, #25441, #3136 ) ; +#37689 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37688 = CARTESIAN_POINT ( 'NONE', ( 19.46059643144436535, 126.3442427331793141, 175.5385488862945635 ) ) ; +#37690 = ORIENTED_EDGE ( 'NONE', *, *, #26731, .F. ) ; +#37691 = LINE ( 'NONE', #27921, #35317 ) ; +#37692 = EDGE_LOOP ( 'NONE', ( #18418, #17770, #21701, #30992, #7679, #20050, #17658, #32363, #13210, #25357 ) ) ; +#37693 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265228896, -0.1368326740407719011 ) ) ; +#37694 = CARTESIAN_POINT ( 'NONE', ( 38.25240742236346847, 118.6016279957657673, 87.66725807459630460 ) ) ; +#37695 = CARTESIAN_POINT ( 'NONE', ( -16.15354643030308424, 152.0177870148501427, 180.9315030652959422 ) ) ; +#37696 = EDGE_CURVE ( 'NONE', #23754, #26491, #40258, .T. ) ; +#37697 = ORIENTED_EDGE ( 'NONE', *, *, #9089, .T. ) ; +#37698 = ORIENTED_EDGE ( 'NONE', *, *, #9281, .F. ) ; +#37699 = CARTESIAN_POINT ( 'NONE', ( -25.49734792034949038, 118.8155664120999973, 94.28318532801205265 ) ) ; +#37700 = CARTESIAN_POINT ( 'NONE', ( 45.66847487909335257, 187.6390301656441579, 105.4819989478330058 ) ) ; +#37701 = FACE_OUTER_BOUND ( 'NONE', #20936, .T. ) ; +#37702 = CARTESIAN_POINT ( 'NONE', ( -3.070807994882999825, 190.8479820821999908, 106.9334771579000005 ) ) ; +#37703 = VERTEX_POINT ( 'NONE', #16524 ) ; +#37704 = ORIENTED_EDGE ( 'NONE', *, *, #2088, .F. ) ; +#37705 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251387812, 132.4055461763574328, 92.79778151956126919 ) ) ; +#37706 = CARTESIAN_POINT ( 'NONE', ( 35.80487162792000078, 199.6921533858000259, 89.47993692238999586 ) ) ; +#37707 = CARTESIAN_POINT ( 'NONE', ( 13.55396812693271791, 164.5266522499701409, 98.14185902086070712 ) ) ; +#37708 = ORIENTED_EDGE ( 'NONE', *, *, #31570, .F. ) ; +#37709 = CARTESIAN_POINT ( 'NONE', ( -19.99825438583805237, 190.8509747501094580, 106.8052823956111013 ) ) ; +#37710 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799573900, 175.3514230958744520, 100.1541516780990406 ) ) ; +#37711 = VERTEX_POINT ( 'NONE', #10826 ) ; +#37712 = AXIS2_PLACEMENT_3D ( 'NONE', #14946, #5935, #37419 ) ; +#37713 = CARTESIAN_POINT ( 'NONE', ( 25.45436037924796224, 118.1131156702000169, 13.52888003454015298 ) ) ; +#37714 = ORIENTED_EDGE ( 'NONE', *, *, #13177, .T. ) ; +#37715 = CARTESIAN_POINT ( 'NONE', ( -13.50718409113456886, 124.3648481134796242, 88.37302201493642428 ) ) ; +#37716 = VECTOR ( 'NONE', #23165, 1000.000000000000000 ) ; +#37717 = EDGE_CURVE ( 'NONE', #37352, #17526, #35649, .T. ) ; +#37718 = CARTESIAN_POINT ( 'NONE', ( -0.3660935641670999829, 188.8524035398000080, 105.8564355347999992 ) ) ; +#37719 = CARTESIAN_POINT ( 'NONE', ( -3.503019623618541800, 126.7262776985570127, 89.25421175367505100 ) ) ; +#37720 = ORIENTED_EDGE ( 'NONE', *, *, #11675, .F. ) ; +#37721 = FACE_OUTER_BOUND ( 'NONE', #8386, .T. ) ; +#37722 = CARTESIAN_POINT ( 'NONE', ( 36.79222982050293922, 77.14301703112145958, 291.5363223503569543 ) ) ; +#37723 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178570903572E-05, -0.0002331579774915885982 ) ) ; +#37724 = DIRECTION ( 'NONE', ( 0.7066795775144187886, 2.423636307971748040E-16, -0.7075337269162810250 ) ) ; +#37725 = VERTEX_POINT ( 'NONE', #20200 ) ; +#37726 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37727 = ORIENTED_EDGE ( 'NONE', *, *, #38301, .T. ) ; +#37728 = ADVANCED_FACE ( 'NONE', ( #4463 ), #17125, .F. ) ; +#37729 = CARTESIAN_POINT ( 'NONE', ( 20.06673176399057823, 211.8719179876182466, 76.04897356089666971 ) ) ; +#37730 = CARTESIAN_POINT ( 'NONE', ( 22.59299433171564431, 158.3069224608609886, 96.18730950046148109 ) ) ; +#37731 = CARTESIAN_POINT ( 'NONE', ( -38.37885564745000977, 118.5498700796999998, 89.85180666872000188 ) ) ; +#37732 = ORIENTED_EDGE ( 'NONE', *, *, #12396, .F. ) ; +#37733 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #33446, #15260, #37129, #6239 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37734 = ORIENTED_EDGE ( 'NONE', *, *, #5055, .T. ) ; +#37735 = CARTESIAN_POINT ( 'NONE', ( -14.16977585978846754, 176.4938143369288355, 100.9214410357033529 ) ) ; +#37736 = CARTESIAN_POINT ( 'NONE', ( -26.23387527696571198, 122.3264975654227698, 87.91006257957754144 ) ) ; +#37737 = CARTESIAN_POINT ( 'NONE', ( -20.18587004200604085, 159.8158404907537431, 96.56150810225138059 ) ) ; +#37738 = EDGE_CURVE ( 'NONE', #27892, #7971, #38804, .T. ) ; +#37739 = ADVANCED_FACE ( 'NONE', ( #10628 ), #3143, .F. ) ; +#37740 = VERTEX_POINT ( 'NONE', #7531 ) ; +#37741 = CARTESIAN_POINT ( 'NONE', ( 25.83405065666187639, 120.1395552130028932, 90.28158168838656650 ) ) ; +#37742 = CIRCLE ( 'NONE', #24046, 2.000000000527294208 ) ; +#37743 = ORIENTED_EDGE ( 'NONE', *, *, #695, .F. ) ; +#37744 = ORIENTED_EDGE ( 'NONE', *, *, #2980, .T. ) ; +#37745 = FACE_OUTER_BOUND ( 'NONE', #33328, .T. ) ; +#37746 = CARTESIAN_POINT ( 'NONE', ( -44.79353637294777002, 181.5138299656995287, 101.5857470109101399 ) ) ; +#37747 = LINE ( 'NONE', #12220, #31417 ) ; +#37748 = CARTESIAN_POINT ( 'NONE', ( -26.00898928064792059, 209.7096528057114710, 76.07444037909847623 ) ) ; +#37749 = EDGE_CURVE ( 'NONE', #38350, #10050, #16005, .T. ) ; +#37750 = VERTEX_POINT ( 'NONE', #14093 ) ; +#37751 = CARTESIAN_POINT ( 'NONE', ( 15.99999411728631671, 174.5114300543024513, 99.93239967722463746 ) ) ; +#37752 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 5.029100215316657124E-18, 0.0006039748319386160479 ) ) ; +#37753 = EDGE_LOOP ( 'NONE', ( #25351, #11141, #25047, #37660 ) ) ; +#37754 = FACE_OUTER_BOUND ( 'NONE', #24039, .T. ) ; +#37755 = CARTESIAN_POINT ( 'NONE', ( 14.55129770294257341, 129.4786662571763998, 92.61555079168689986 ) ) ; +#37756 = ORIENTED_EDGE ( 'NONE', *, *, #191, .F. ) ; +#37757 = DIRECTION ( 'NONE', ( 0.7933310414247660702, 0.5931044597393384521, 0.1373060761554397435 ) ) ; +#37758 = CARTESIAN_POINT ( 'NONE', ( 25.75082660724000405, 201.9934155195000187, 90.46283731303999787 ) ) ; +#37759 = FACE_OUTER_BOUND ( 'NONE', #28601, .T. ) ; +#37760 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7393, #28291, #15795, #22560 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37761 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971554578 ) ) ; +#37762 = CARTESIAN_POINT ( 'NONE', ( 3.534086375177905914, 137.3581944094399603, 91.36238397499714381 ) ) ; +#37763 = EDGE_LOOP ( 'NONE', ( #2563, #11468, #40426, #20640 ) ) ; +#37764 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319379894875 ) ) ; +#37765 = CIRCLE ( 'NONE', #1216, 2.500000000050627946 ) ; +#37766 = CARTESIAN_POINT ( 'NONE', ( 0.8775314245327620055, 189.0249473761942909, 103.6920809060072628 ) ) ; +#37767 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37768 = VECTOR ( 'NONE', #3807, 1000.000000000000227 ) ; +#37769 = CARTESIAN_POINT ( 'NONE', ( 25.99885467711333931, 118.5825379493838341, 87.25211441482672114 ) ) ; +#37770 = AXIS2_PLACEMENT_3D ( 'NONE', #23010, #510, #6642 ) ; +#37771 = CARTESIAN_POINT ( 'NONE', ( 15.94114414956070114, 147.2998714242159224, 179.5451065918014422 ) ) ; +#37772 = CARTESIAN_POINT ( 'NONE', ( 19.37944463171710296, 148.4918504680572369, 180.6383071375771010 ) ) ; +#37773 = AXIS2_PLACEMENT_3D ( 'NONE', #15616, #28116, #12548 ) ; +#37774 = CARTESIAN_POINT ( 'NONE', ( -40.70502761438000050, 219.0860688542000219, 75.83308940067000492 ) ) ; +#37775 = LINE ( 'NONE', #28783, #3347 ) ; +#37776 = CARTESIAN_POINT ( 'NONE', ( -25.50530527114885615, 190.9616050397809772, 106.3210494999302540 ) ) ; +#37777 = ORIENTED_EDGE ( 'NONE', *, *, #4249, .F. ) ; +#37778 = EDGE_CURVE ( 'NONE', #29879, #19255, #15592, .T. ) ; +#37779 = CARTESIAN_POINT ( 'NONE', ( -16.41310484999783981, 121.9323406599082062, 177.7806045521944043 ) ) ; +#37780 = ADVANCED_FACE ( 'NONE', ( #33082 ), #18344, .T. ) ; +#37781 = CARTESIAN_POINT ( 'NONE', ( -20.02016821360482268, 211.0854730039747267, 73.07052224373646254 ) ) ; +#37782 = LINE ( 'NONE', #6697, #19979 ) ; +#37783 = ORIENTED_EDGE ( 'NONE', *, *, #16875, .T. ) ; +#37784 = CARTESIAN_POINT ( 'NONE', ( 42.93322021095036689, 121.2550468398670631, 90.69983607254528124 ) ) ; +#37785 = CARTESIAN_POINT ( 'NONE', ( 46.51720693556681852, 124.8110556520572771, 91.00548902218217506 ) ) ; +#37786 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15802, #37289, #12538, #21766, #18657, #3135, #15607, #28301, #28108, #76, #34405, #25241, #22169, #869 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000001889600, 0.3750000000002450817, 0.4375000000002627343, 0.4687500000002153833, 0.4843750000001907918, 0.5000000000001662004, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37787 = CARTESIAN_POINT ( 'NONE', ( 20.50029383489984980, 127.3219018132126479, 89.54826866284827247 ) ) ; +#37788 = CARTESIAN_POINT ( 'NONE', ( 37.68744279206340764, 191.4246164574499858, 104.2866415772560060 ) ) ; +#37789 = EDGE_CURVE ( 'NONE', #37005, #21678, #27601, .T. ) ; +#37790 = EDGE_CURVE ( 'NONE', #40179, #24908, #1386, .T. ) ; +#37791 = CARTESIAN_POINT ( 'NONE', ( 36.37271987246000293, 191.1008199325999897, 106.6920003910999952 ) ) ; +#37792 = EDGE_LOOP ( 'NONE', ( #36347, #2718, #36209 ) ) ; +#37793 = EDGE_CURVE ( 'NONE', #17075, #36516, #14382, .T. ) ; +#37794 = VERTEX_POINT ( 'NONE', #40223 ) ; +#37796 = CIRCLE ( 'NONE', #14983, 2.000000000000011546 ) ; +#37795 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37797 = EDGE_CURVE ( 'NONE', #8372, #36951, #21454, .T. ) ; +#37798 = CARTESIAN_POINT ( 'NONE', ( -20.11930665488561942, 184.9326558166844450, 102.4826600882946082 ) ) ; +#37799 = AXIS2_PLACEMENT_3D ( 'NONE', #17128, #11226, #11638 ) ; +#37800 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971547084 ) ) ; +#37801 = ORIENTED_EDGE ( 'NONE', *, *, #37225, .F. ) ; +#37802 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; +#37803 = AXIS2_PLACEMENT_3D ( 'NONE', #35434, #13007, #28546 ) ; +#37804 = CIRCLE ( 'NONE', #6446, 2.500000000000002220 ) ; +#37805 = VERTEX_POINT ( 'NONE', #15303 ) ; +#37806 = FACE_OUTER_BOUND ( 'NONE', #32355, .T. ) ; +#37807 = CARTESIAN_POINT ( 'NONE', ( -4.472739938169342899, 130.7266529636161749, 89.83624843479562116 ) ) ; +#37808 = CARTESIAN_POINT ( 'NONE', ( -25.76127051822999903, 210.3999399800999868, 73.32280028488999335 ) ) ; +#37809 = ORIENTED_EDGE ( 'NONE', *, *, #31513, .F. ) ; +#37810 = PLANE ( 'NONE', #27167 ) ; +#37811 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30197, #29991, #39580, #39989 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37812 = CARTESIAN_POINT ( 'NONE', ( -94.47778922392247125, 77.18266397892847408, 291.6156061525086898 ) ) ; +#37813 = CARTESIAN_POINT ( 'NONE', ( 22.50176647123733886, 126.7590398625532089, 91.98595248688171466 ) ) ; +#37814 = CARTESIAN_POINT ( 'NONE', ( -43.55091172766087482, 114.1088728472931138, 121.9228533734353306 ) ) ; +#37815 = ORIENTED_EDGE ( 'NONE', *, *, #14023, .F. ) ; +#37816 = CARTESIAN_POINT ( 'NONE', ( 21.49510836992397955, 129.8183861006403106, 89.61087453915679646 ) ) ; +#37817 = EDGE_CURVE ( 'NONE', #18309, #4383, #12038, .T. ) ; +#37818 = CARTESIAN_POINT ( 'NONE', ( 2.156482154607000101, 189.5564015033000373, 103.7090349261000028 ) ) ; +#37819 = CARTESIAN_POINT ( 'NONE', ( -14.78542622577100119, 175.8938623147257374, 100.7833030093998303 ) ) ; +#37820 = CARTESIAN_POINT ( 'NONE', ( -35.77829887421999899, 191.5311805108999863, 103.7655102736000146 ) ) ; +#37821 = VERTEX_POINT ( 'NONE', #24322 ) ; +#37822 = ORIENTED_EDGE ( 'NONE', *, *, #13067, .T. ) ; +#37823 = CARTESIAN_POINT ( 'NONE', ( -6.957132718426895401, 133.0026170453613190, 282.5627442275269914 ) ) ; +#37824 = ORIENTED_EDGE ( 'NONE', *, *, #25083, .F. ) ; +#37825 = DIRECTION ( 'NONE', ( 0.0005884949961242684187, -0.2249510543439056376, 0.9743698870671265722 ) ) ; +#37826 = ADVANCED_FACE ( 'NONE', ( #2231 ), #22859, .F. ) ; +#37827 = AXIS2_PLACEMENT_3D ( 'NONE', #4978, #11130, #1924 ) ; +#37828 = LINE ( 'NONE', #19009, #36744 ) ; +#37829 = VECTOR ( 'NONE', #16997, 1000.000000000000227 ) ; +#37830 = CARTESIAN_POINT ( 'NONE', ( -12.63338249442217354, 177.0290861143981545, 103.4924640678001282 ) ) ; +#37831 = CARTESIAN_POINT ( 'NONE', ( 15.50147166558119594, 185.3474886484798390, 105.0001610792874942 ) ) ; +#37832 = EDGE_CURVE ( 'NONE', #38178, #23972, #21238, .T. ) ; +#37833 = DIRECTION ( 'NONE', ( -0.0005884949961238158727, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#37834 = CARTESIAN_POINT ( 'NONE', ( 25.65719135372745185, 209.7100065642696904, 73.37632326619605294 ) ) ; +#37835 = VERTEX_POINT ( 'NONE', #30645 ) ; +#37836 = EDGE_CURVE ( 'NONE', #23012, #25669, #2639, .T. ) ; +#37837 = LINE ( 'NONE', #21717, #29656 ) ; +#37838 = CARTESIAN_POINT ( 'NONE', ( -21.99952075582729094, 137.4670866173397314, 177.5663017614061232 ) ) ; +#37839 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37840 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34099, #6097, #18548, #31453, #37576, #15892, #9579, #22054, #37772, #9782 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.0004309827303015496499, 0.0008619654606030992998, 0.001292948190904649004, 0.001723930921206198600 ), + .UNSPECIFIED. ) ; +#37841 = FACE_OUTER_BOUND ( 'NONE', #32337, .T. ) ; +#37842 = ORIENTED_EDGE ( 'NONE', *, *, #33823, .T. ) ; +#37843 = EDGE_LOOP ( 'NONE', ( #11591, #21608, #17905, #27006 ) ) ; +#37844 = EDGE_CURVE ( 'NONE', #26238, #27254, #3847, .T. ) ; +#37845 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #37464, #19045, #9873, #31951, #38266, #4102, #31540 ), + ( #3499, #15984, #34772, #3712, #16188, #10281, #4925 ), + ( #13937, #14344, #32928, #11074, #29886, #1869, #26018 ), + ( #20674, #39269, #35375, #35566, #17382, #23347, #32345 ), + ( #26824, #20052, #10479, #26418, #1450, #19838, #23141 ), + ( #39063, #29681, #11270, #16785, #36201, #33133, #38863 ), + ( #23749, #29476, #1664, #16976, #7586, #7382, #8205 ), + ( #32540, #35989, #5117, #26220, #29074, #1049, #4512 ), + ( #23538, #10877, #13537, #1247, #38459, #22947, #35777 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 4 ), + ( 4, 3, 4 ), + ( -3.193576140566999920E-12, 0.1666665328658999967, 0.3333330550477999754, 0.4999995772299999919, 0.6666660994122000083, 0.8333326215941999626, 1.000000000000000000 ), + ( 0.1842143742207019985, 0.1904063628586999957, 0.8096052266584999879 ), + .UNSPECIFIED. ) ; +#37846 = VERTEX_POINT ( 'NONE', #16291 ) ; +#37847 = CARTESIAN_POINT ( 'NONE', ( -19.44498994767157996, 147.7083494500389236, 183.5267648320292437 ) ) ; +#37848 = CARTESIAN_POINT ( 'NONE', ( -20.49588010179244790, 118.8154963149460741, 94.28014888049614228 ) ) ; +#37849 = DIRECTION ( 'NONE', ( 0.7072735235669668219, 0.6508952434164523293, 0.2758614597202816432 ) ) ; +#37850 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31291, #3458, #3065, #21506 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37851 = ORIENTED_EDGE ( 'NONE', *, *, #11765, .T. ) ; +#37852 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#37853 = VECTOR ( 'NONE', #2481, 1000.000000000000000 ) ; +#37854 = AXIS2_PLACEMENT_3D ( 'NONE', #1958, #33421, #11564 ) ; +#37855 = CARTESIAN_POINT ( 'NONE', ( 39.79988895049328335, 119.8651423291884726, 87.81508310122019623 ) ) ; +#37856 = CARTESIAN_POINT ( 'NONE', ( -38.03165849778999785, 119.2179435290000100, 87.30229350380000142 ) ) ; +#37857 = CARTESIAN_POINT ( 'NONE', ( 2.943104451508621544, 209.7096517725655644, 76.05672380837390278 ) ) ; +#37858 = EDGE_LOOP ( 'NONE', ( #24171, #32539, #33998, #40104 ) ) ; +#37859 = CARTESIAN_POINT ( 'NONE', ( -32.37402305083713827, 138.3010815212902855, 91.60179504951790364 ) ) ; +#37860 = VECTOR ( 'NONE', #35957, 1000.000000000000000 ) ; +#37861 = AXIS2_PLACEMENT_3D ( 'NONE', #15405, #39520, #21555 ) ; +#37862 = ORIENTED_EDGE ( 'NONE', *, *, #20511, .F. ) ; +#37863 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178536755269E-05, 0.0002331579774905574406 ) ) ; +#37864 = CIRCLE ( 'NONE', #18263, 2.500000004121103903 ) ; +#37865 = CARTESIAN_POINT ( 'NONE', ( 3.333123914796359166, 185.8719596943319061, 102.7338991239209491 ) ) ; +#37866 = VERTEX_POINT ( 'NONE', #6885 ) ; +#37867 = EDGE_LOOP ( 'NONE', ( #9126, #523, #24990, #10248 ) ) ; +#37868 = CARTESIAN_POINT ( 'NONE', ( 22.22396017645197830, 150.3172372291888905, 34.69005226938929809 ) ) ; +#37869 = CARTESIAN_POINT ( 'NONE', ( 2.624500613330938315, 189.6988974143776545, 103.4467797655522503 ) ) ; +#37870 = CARTESIAN_POINT ( 'NONE', ( -8.050307609250221930, 161.2716461841048101, 96.89027781497259184 ) ) ; +#37871 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #27761, #38720, #13603, #28942 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37872 = ORIENTED_EDGE ( 'NONE', *, *, #18385, .T. ) ; +#37873 = VERTEX_POINT ( 'NONE', #9978 ) ; +#37874 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363196006660E-14, -0.9999998176071844824 ) ) ; +#37875 = CARTESIAN_POINT ( 'NONE', ( -20.51998460911297784, 211.0905570173818546, 73.57089872868714053 ) ) ; +#37876 = ORIENTED_EDGE ( 'NONE', *, *, #21296, .T. ) ; +#37877 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363195980786E-14, -0.9999998176071845934 ) ) ; +#37878 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37879 = CARTESIAN_POINT ( 'NONE', ( -26.29003513620000376, 122.2754973729000199, 90.85250693771000385 ) ) ; +#37880 = EDGE_CURVE ( 'NONE', #5869, #24036, #7759, .T. ) ; +#37881 = EDGE_CURVE ( 'NONE', #8275, #5335, #547, .T. ) ; +#37882 = EDGE_LOOP ( 'NONE', ( #20710, #31793, #3681, #25942 ) ) ; +#37883 = DIRECTION ( 'NONE', ( -0.0001408404346092596458, 0.2249510911124608936, -0.9743700461176365568 ) ) ; +#37884 = EDGE_CURVE ( 'NONE', #11575, #30783, #14060, .T. ) ; +#37885 = EDGE_CURVE ( 'NONE', #4758, #35038, #37037, .T. ) ; +#37886 = CARTESIAN_POINT ( 'NONE', ( -37.79864283955629389, 118.7059682267879026, 87.43197624523921263 ) ) ; +#37887 = FACE_OUTER_BOUND ( 'NONE', #25872, .T. ) ; +#37888 = CARTESIAN_POINT ( 'NONE', ( -2.689645513499154816, 191.0567932042151540, 104.0175265168841463 ) ) ; +#37889 = AXIS2_PLACEMENT_3D ( 'NONE', #39617, #11024, #35929 ) ; +#37890 = AXIS2_PLACEMENT_3D ( 'NONE', #36705, #5208, #32824 ) ; +#37891 = VERTEX_POINT ( 'NONE', #37568 ) ; +#37892 = EDGE_CURVE ( 'NONE', #3242, #11953, #12615, .T. ) ; +#37893 = VECTOR ( 'NONE', #25495, 1000.000000000000227 ) ; +#37894 = CIRCLE ( 'NONE', #33946, 5.499999999738637513 ) ; +#37895 = CARTESIAN_POINT ( 'NONE', ( -15.99970515225999179, 151.9770228117144484, 94.74935186622352035 ) ) ; +#37896 = CARTESIAN_POINT ( 'NONE', ( -19.99848660742553008, 137.5076853405834072, 94.48997979116353463 ) ) ; +#37898 = CARTESIAN_POINT ( 'NONE', ( -2.602132166127285373, 190.9309786092318006, 106.4700758378154575 ) ) ; +#37897 = CARTESIAN_POINT ( 'NONE', ( 28.46531727888168817, 183.5661251107103169, 104.5810709919272057 ) ) ; +#37899 = EDGE_CURVE ( 'NONE', #37835, #3089, #35013, .T. ) ; +#37900 = ORIENTED_EDGE ( 'NONE', *, *, #30589, .F. ) ; +#37901 = CYLINDRICAL_SURFACE ( 'NONE', #1004, 5.249999999999986677 ) ; +#37902 = CARTESIAN_POINT ( 'NONE', ( 38.15045221970718359, 118.4868570840783377, 87.66883015867043127 ) ) ; +#37903 = PLANE ( 'NONE', #28920 ) ; +#37904 = FACE_OUTER_BOUND ( 'NONE', #5037, .T. ) ; +#37905 = VERTEX_POINT ( 'NONE', #31234 ) ; +#37906 = ORIENTED_EDGE ( 'NONE', *, *, #20374, .T. ) ; +#37907 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#37908 = CARTESIAN_POINT ( 'NONE', ( 22.78152163348013914, 158.3817186398727017, 98.08602157056807869 ) ) ; +#37909 = EDGE_CURVE ( 'NONE', #18185, #30562, #20430, .T. ) ; +#37910 = CARTESIAN_POINT ( 'NONE', ( 44.83277154663306874, 186.3180907337439578, 107.7244483083414508 ) ) ; +#37911 = DIRECTION ( 'NONE', ( 0.0005884949961217976304, -0.2249510543439088295, 0.9743698870671256840 ) ) ; +#37912 = ORIENTED_EDGE ( 'NONE', *, *, #22899, .T. ) ; +#37913 = ORIENTED_EDGE ( 'NONE', *, *, #44, .T. ) ; +#37914 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#37915 = DIRECTION ( 'NONE', ( 0.9999998268368047727, 0.0001323825927642897275, -0.0005734119021573578405 ) ) ; +#37916 = CARTESIAN_POINT ( 'NONE', ( 36.04442091094806244, 218.5902260770999987, 73.53673424655958968 ) ) ; +#37917 = VECTOR ( 'NONE', #14040, 1000.000000000000114 ) ; +#37918 = ORIENTED_EDGE ( 'NONE', *, *, #38342, .T. ) ; +#37919 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#37920 = VECTOR ( 'NONE', #24796, 1000.000000000000114 ) ; +#37921 = ORIENTED_EDGE ( 'NONE', *, *, #9189, .T. ) ; +#37922 = VECTOR ( 'NONE', #32324, 1000.000000000000341 ) ; +#37923 = ORIENTED_EDGE ( 'NONE', *, *, #23772, .F. ) ; +#37924 = DIRECTION ( 'NONE', ( -0.0006039748319383847876, -4.625770492314939281E-15, -0.9999998176071847045 ) ) ; +#37925 = ORIENTED_EDGE ( 'NONE', *, *, #8015, .F. ) ; +#37926 = CARTESIAN_POINT ( 'NONE', ( -5.666761810104184782, 187.4494786681063374, 105.7117437973159468 ) ) ; +#37927 = CARTESIAN_POINT ( 'NONE', ( -0.9122130542470999748, 189.2064119769000001, 105.6188406109999960 ) ) ; +#37928 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971559019 ) ) ; +#37929 = ORIENTED_EDGE ( 'NONE', *, *, #9328, .T. ) ; +#37930 = CARTESIAN_POINT ( 'NONE', ( -16.56167515404295543, 123.1153088213665114, 172.1613468014946022 ) ) ; +#37931 = ADVANCED_FACE ( 'NONE', ( #19360 ), #8947, .F. ) ; +#37932 = CARTESIAN_POINT ( 'NONE', ( -20.49971785407188563, 191.7873341492787915, 104.4341925847197672 ) ) ; +#37933 = ADVANCED_FACE ( 'NONE', ( #37370 ), #38854, .F. ) ; +#37934 = CARTESIAN_POINT ( 'NONE', ( -38.09728523723426008, 163.5897765857678792, 197.9748090961729190 ) ) ; +#37935 = CARTESIAN_POINT ( 'NONE', ( 13.49986192253402351, 124.0960645453589990, 91.02896376973610870 ) ) ; +#37936 = CARTESIAN_POINT ( 'NONE', ( -29.78153341548664912, 126.4887808801478428, 91.43890526668431562 ) ) ; +#37937 = ORIENTED_EDGE ( 'NONE', *, *, #37556, .T. ) ; +#37938 = CARTESIAN_POINT ( 'NONE', ( 22.59955204320912969, 214.0902768579945530, 76.04506448788464468 ) ) ; +#37939 = DIRECTION ( 'NONE', ( 0.0001408373285424074114, -0.2255194992995608605, 0.9742386440706004569 ) ) ; +#37940 = CARTESIAN_POINT ( 'NONE', ( 26.80533604871084208, 110.6131156702000027, 90.25159508784216200 ) ) ; +#37941 = AXIS2_PLACEMENT_3D ( 'NONE', #25677, #32394, #28923 ) ; +#37942 = VERTEX_POINT ( 'NONE', #31044 ) ; +#37943 = DIRECTION ( 'NONE', ( -0.0006039748319386907495, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#37944 = CIRCLE ( 'NONE', #14462, 2.000000000021383340 ) ; +#37945 = ORIENTED_EDGE ( 'NONE', *, *, #32556, .T. ) ; +#37946 = CARTESIAN_POINT ( 'NONE', ( 31.79542158357201487, 220.4002260771000294, 75.53930090045915335 ) ) ; +#37947 = AXIS2_PLACEMENT_3D ( 'NONE', #8958, #22032, #34461 ) ; +#37948 = CARTESIAN_POINT ( 'NONE', ( 16.23201905896638308, 152.0606143167149185, 181.0564827348360382 ) ) ; +#37949 = CARTESIAN_POINT ( 'NONE', ( 30.06906075427000502, 177.1956492926942985, 101.0567532828530233 ) ) ; +#37950 = CIRCLE ( 'NONE', #20308, 1.749999999939591433 ) ; +#37951 = DIRECTION ( 'NONE', ( 0.0006039748319380209294, 1.272479560138527092E-14, 0.9999998176071845934 ) ) ; +#37952 = CARTESIAN_POINT ( 'NONE', ( -4.036264727041273481, 174.7924093549539180, 102.5751288760997966 ) ) ; +#37953 = LINE ( 'NONE', #22630, #6923 ) ; +#37954 = ORIENTED_EDGE ( 'NONE', *, *, #25648, .F. ) ; +#37955 = VERTEX_POINT ( 'NONE', #6089 ) ; +#37956 = FACE_BOUND ( 'NONE', #15889, .T. ) ; +#37957 = EDGE_CURVE ( 'NONE', #23072, #36964, #22047, .T. ) ; +#37958 = DIRECTION ( 'NONE', ( -0.0005884949961242684187, 0.2249510543439056376, -0.9743698870671265722 ) ) ; +#37959 = CARTESIAN_POINT ( 'NONE', ( -35.45487758071271855, 209.7096534091000137, 76.07991848633032816 ) ) ; +#37960 = ORIENTED_EDGE ( 'NONE', *, *, #28102, .F. ) ; +#37961 = LINE ( 'NONE', #38162, #4960 ) ; +#37962 = ORIENTED_EDGE ( 'NONE', *, *, #4164, .T. ) ; +#37963 = CARTESIAN_POINT ( 'NONE', ( -45.08822124451242530, 123.2541779049768280, 91.19028666418968498 ) ) ; +#37964 = LINE ( 'NONE', #35069, #33880 ) ; +#37965 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1938, #20946, #27519, #27101 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#37966 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 3.427539337001264681E-16, -0.0006039748319384838837 ) ) ; +#37967 = ORIENTED_EDGE ( 'NONE', *, *, #18528, .T. ) ; +#37968 = CARTESIAN_POINT ( 'NONE', ( 21.26009108512010570, 128.3999477444776574, 91.84930485354649932 ) ) ; +#37969 = DIRECTION ( 'NONE', ( -0.0005884949961247776685, 0.2249510543439061094, -0.9743698870671263501 ) ) ; +#37970 = DIRECTION ( 'NONE', ( 0.9914448496449769221, -0.1271493821533873914, -0.02949821571656870492 ) ) ; +#37971 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#37972 = CARTESIAN_POINT ( 'NONE', ( 22.49960432933178822, 158.3069096095373993, 96.18736459073451783 ) ) ; +#37973 = ORIENTED_EDGE ( 'NONE', *, *, #849, .F. ) ; +#37974 = CIRCLE ( 'NONE', #17703, 48.00000000000002132 ) ; +#37975 = CARTESIAN_POINT ( 'NONE', ( 20.15079215819618241, 211.0873987128438500, 75.87692249624042518 ) ) ; +#37976 = CIRCLE ( 'NONE', #18376, 4.999999999999990230 ) ; +#37977 = CARTESIAN_POINT ( 'NONE', ( 0.5626164669235433902, 188.9999987160578598, 103.6843922204118940 ) ) ; +#37978 = CARTESIAN_POINT ( 'NONE', ( -1.963506278948965011, 188.9017754806783103, 106.3444335591781851 ) ) ; +#37979 = DIRECTION ( 'NONE', ( 0.7069397808360943225, -0.6508952239913948778, -0.2767156548816978590 ) ) ; +#37980 = EDGE_CURVE ( 'NONE', #23210, #19682, #18539, .T. ) ; +#37981 = CARTESIAN_POINT ( 'NONE', ( -38.94661729375095405, 128.0727087836083911, 89.75751053645129218 ) ) ; +#37982 = ADVANCED_FACE ( 'NONE', ( #31652 ), #17399, .F. ) ; +#37983 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#37984 = DIRECTION ( 'NONE', ( -0.0006039748319392653766, -3.841674172953530792E-18, -0.9999998176071845934 ) ) ; +#37985 = CARTESIAN_POINT ( 'NONE', ( -26.28989206232940035, 188.3523932612100111, 105.7157182448219856 ) ) ; +#37986 = VERTEX_POINT ( 'NONE', #9774 ) ; +#37987 = CARTESIAN_POINT ( 'NONE', ( -19.00228709110520953, 148.6728657431648628, 182.7289924287499900 ) ) ; +#37988 = ORIENTED_EDGE ( 'NONE', *, *, #25972, .F. ) ; +#37989 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; +#37990 = DIRECTION ( 'NONE', ( 0.0005884949961296528920, -0.2249510543439046939, 0.9743698870671267942 ) ) ; +#37991 = CARTESIAN_POINT ( 'NONE', ( -20.01777344647963730, 205.1071326358727163, 76.11698016271346035 ) ) ; +#37992 = CARTESIAN_POINT ( 'NONE', ( 36.06507414729499317, 192.5944866880060147, 106.3721272616880071 ) ) ; +#37993 = AXIS2_PLACEMENT_3D ( 'NONE', #36817, #37618, #12469 ) ; +#37994 = CARTESIAN_POINT ( 'NONE', ( 22.45974714935999828, 167.3597764858999994, 28.07991271570000080 ) ) ; +#37995 = ORIENTED_EDGE ( 'NONE', *, *, #21096, .T. ) ; +#37996 = CARTESIAN_POINT ( 'NONE', ( 75.24056455973224899, 196.4820008462166641, 189.1802437148639058 ) ) ; +#37997 = VECTOR ( 'NONE', #4069, 999.9999999999998863 ) ; +#37998 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364886824597, 136.5649596138813706, 181.4686487119530511 ) ) ; +#37999 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36558, #1596, #17726, #5261, #11014, #23688, #26970, #4855 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 4 ), + ( 1.154700540210073570E-15, 0.0004329834460427705472, 0.0008659668920843864191, 0.001731933784167665868 ), + .UNSPECIFIED. ) ; +#38000 = DIRECTION ( 'NONE', ( -0.0004161288024487093526, -0.5299192578742120130, -0.8480479980348188951 ) ) ; +#38001 = ORIENTED_EDGE ( 'NONE', *, *, #20290, .T. ) ; +#38002 = FACE_OUTER_BOUND ( 'NONE', #1805, .T. ) ; +#38003 = ORIENTED_EDGE ( 'NONE', *, *, #39679, .F. ) ; +#38004 = CARTESIAN_POINT ( 'NONE', ( 22.30994511369541655, 117.4496609881286844, 177.0551398655643709 ) ) ; +#38005 = CARTESIAN_POINT ( 'NONE', ( 3.856354911035337896, 168.4251820707296190, 98.86504003729989165 ) ) ; +#38006 = CARTESIAN_POINT ( 'NONE', ( -36.60686137602164791, 191.6395055713826423, 104.3895888317887568 ) ) ; +#38007 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971541810 ) ) ; +#38008 = EDGE_CURVE ( 'NONE', #15536, #26493, #11182, .T. ) ; +#38009 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; +#38010 = PLANE ( 'NONE', #36577 ) ; +#38011 = CARTESIAN_POINT ( 'NONE', ( -44.90705422830284732, 186.7765192746497291, 105.8797162406083174 ) ) ; +#38012 = VERTEX_POINT ( 'NONE', #26123 ) ; +#38013 = EDGE_CURVE ( 'NONE', #11548, #37352, #6321, .T. ) ; +#38014 = CARTESIAN_POINT ( 'NONE', ( 12.64071457670788057, 176.8991890015799697, 103.2647382212043539 ) ) ; +#38015 = CARTESIAN_POINT ( 'NONE', ( -20.26858147528999865, 210.4001054583000041, 75.82073865856999362 ) ) ; +#38016 = FACE_OUTER_BOUND ( 'NONE', #10969, .T. ) ; +#38017 = CARTESIAN_POINT ( 'NONE', ( -37.65075021393000299, 191.3226513556000157, 104.2390354988000070 ) ) ; +#38018 = EDGE_CURVE ( 'NONE', #18856, #17411, #20358, .T. ) ; +#38019 = ORIENTED_EDGE ( 'NONE', *, *, #4222, .T. ) ; +#38020 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; +#38021 = VERTEX_POINT ( 'NONE', #7894 ) ; +#38022 = EDGE_CURVE ( 'NONE', #4942, #35551, #6869, .T. ) ; +#38023 = EDGE_CURVE ( 'NONE', #12808, #5169, #8282, .T. ) ; +#38024 = DIRECTION ( 'NONE', ( 0.7856637149787890628, -0.6186538021912806329, -2.803352852331656654E-15 ) ) ; +#38025 = EDGE_CURVE ( 'NONE', #13780, #31100, #39477, .T. ) ; +#38026 = VECTOR ( 'NONE', #11805, 1000.000000000000000 ) ; +#38027 = CARTESIAN_POINT ( 'NONE', ( 36.73294452760477213, 115.7847013455190535, 89.70041604681827607 ) ) ; +#38028 = CARTESIAN_POINT ( 'NONE', ( 19.99963098261158123, 196.3881442804596702, 104.3113798016861580 ) ) ; +#38029 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#38030 = CARTESIAN_POINT ( 'NONE', ( -12.63562338462310741, 176.7996745866113315, 103.1253305348305105 ) ) ; +#38031 = CARTESIAN_POINT ( 'NONE', ( -15.66516191008950010, 160.1415665644281887, 99.37085485008498154 ) ) ; +#38032 = PLANE ( 'NONE', #25196 ) ; +#38033 = CARTESIAN_POINT ( 'NONE', ( 38.32695982823999969, 118.7440985934999986, 90.10258810038000377 ) ) ; +#38034 = ORIENTED_EDGE ( 'NONE', *, *, #25624, .T. ) ; +#38035 = FACE_OUTER_BOUND ( 'NONE', #23545, .T. ) ; +#38036 = CARTESIAN_POINT ( 'NONE', ( 25.25244696082440754, 117.1946158480437248, 170.8386649222292704 ) ) ; +#38037 = CARTESIAN_POINT ( 'NONE', ( -40.95638651216200543, 219.5549399801000163, 73.58324080466002215 ) ) ; +#38038 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #7006, #870, #35201, #13354, #19672, #28693, #25846, #19866, #677, #4336, #10904, #32172, #4535, #25647, #31973, #4128, #17001, #38094 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999945599, 0.1874999999999868994, 0.2187499999999872047, 0.2499999999999875100, 0.4999999999999995559, 0.6250000000000022204, 0.6875000000000041078, 0.7187500000000051070, 0.7500000000000061062, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#38039 = DIRECTION ( 'NONE', ( 0.0005884949961235717104, -0.2249510543439064147, 0.9743698870671262391 ) ) ; +#38040 = ORIENTED_EDGE ( 'NONE', *, *, #26991, .T. ) ; +#38041 = ORIENTED_EDGE ( 'NONE', *, *, #1544, .T. ) ; +#38042 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12418, #30434, #28180, #21638, #34276, #24512 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.0008096972284214351513, 0.001619394456842870303 ), + .UNSPECIFIED. ) ; +#38043 = ORIENTED_EDGE ( 'NONE', *, *, #6944, .T. ) ; +#38044 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#38045 = VECTOR ( 'NONE', #24879, 1000.000000000000227 ) ; +#38046 = CARTESIAN_POINT ( 'NONE', ( 22.99909745638999681, 115.1133511170128969, 87.25389341346352978 ) ) ; +#38047 = DIRECTION ( 'NONE', ( 0.0006039748319384539597, 1.295170900108887039E-14, 0.9999998176071845934 ) ) ; +#38048 = CIRCLE ( 'NONE', #28922, 1.999999999963394837 ) ; +#38049 = ORIENTED_EDGE ( 'NONE', *, *, #37832, .F. ) ; +#38050 = DIRECTION ( 'NONE', ( 0.6087614115774502288, 0.7729348350655650401, 0.1788331191820961841 ) ) ; +#38051 = VECTOR ( 'NONE', #19665, 1000.000000000000000 ) ; +#38052 = CARTESIAN_POINT ( 'NONE', ( -38.25695912633000262, 118.9336418487000060, 90.29207677415999456 ) ) ; +#38053 = CARTESIAN_POINT ( 'NONE', ( -38.12891303324000347, 119.0716168431000170, 87.44155862881000019 ) ) ; +#38054 = CARTESIAN_POINT ( 'NONE', ( -22.49823187728737395, 151.2919806023961939, 97.67717024395707881 ) ) ; +#38055 = CYLINDRICAL_SURFACE ( 'NONE', #19738, 2.000000000000000000 ) ; +#38056 = ORIENTED_EDGE ( 'NONE', *, *, #25307, .T. ) ; +#38057 = CARTESIAN_POINT ( 'NONE', ( -20.49921872406353529, 118.1134456025284152, 89.78002774633898753 ) ) ; +#38058 = EDGE_CURVE ( 'NONE', #17966, #4210, #23049, .T. ) ; +#38059 = ORIENTED_EDGE ( 'NONE', *, *, #24581, .T. ) ; +#38060 = CARTESIAN_POINT ( 'NONE', ( -24.99919627279852463, 116.5767028336385636, 89.78285475179252728 ) ) ; +#38061 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24249, #9103, #2942, #14840, #28119, #40158 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 1.133930764694885689E-15, 0.0005038667338457266482, 0.001007733467690319221 ), + .UNSPECIFIED. ) ; +#38062 = CARTESIAN_POINT ( 'NONE', ( -20.39154081812865371, 183.6048944875886377, 102.0537691888108043 ) ) ; +#38063 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #27224, #39654, #24143, #11664 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.712388980384689674, 4.994529182805674594 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9933774026859373274, 0.9933774026859373274, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#38064 = CARTESIAN_POINT ( 'NONE', ( -2.455538055765680738, 209.0000002601700544, 73.61629604161946361 ) ) ; +#38065 = VERTEX_POINT ( 'NONE', #10182 ) ; +#38066 = EDGE_CURVE ( 'NONE', #13870, #29201, #11618, .T. ) ; +#38067 = CARTESIAN_POINT ( 'NONE', ( -25.91302100391000351, 181.3103559555999880, 104.3497047787000156 ) ) ; +#38068 = CARTESIAN_POINT ( 'NONE', ( 6.042308921164076807, 177.7921139377573638, 100.6958234779730645 ) ) ; +#38069 = DIRECTION ( 'NONE', ( -0.0003200578985547136018, 0.8480480961564359488, -0.5299191675797225720 ) ) ; +#38070 = CARTESIAN_POINT ( 'NONE', ( 8.046776639317595681, 161.2737771581006996, 96.88104755365348808 ) ) ; +#38071 = ADVANCED_FACE ( 'NONE', ( #23443 ), #7482, .F. ) ; +#38072 = ORIENTED_EDGE ( 'NONE', *, *, #7046, .T. ) ; +#38073 = VERTEX_POINT ( 'NONE', #4815 ) ; +#38074 = LINE ( 'NONE', #3718, #16544 ) ; +#38075 = DIRECTION ( 'NONE', ( -0.6087611483135560997, 0.7728367167708899421, 0.1792575619457988101 ) ) ; +#38076 = EDGE_CURVE ( 'NONE', #40029, #16264, #33029, .T. ) ; +#38077 = ORIENTED_EDGE ( 'NONE', *, *, #35470, .F. ) ; +#38078 = EDGE_CURVE ( 'NONE', #23754, #3145, #24816, .T. ) ; +#38079 = CYLINDRICAL_SURFACE ( 'NONE', #19929, 22.50000000000000000 ) ; +#38080 = FACE_OUTER_BOUND ( 'NONE', #31075, .T. ) ; +#38081 = CARTESIAN_POINT ( 'NONE', ( -39.69814225588821444, 114.9854446628631450, 150.7514082625260130 ) ) ; +#38082 = VECTOR ( 'NONE', #30608, 999.9999999999997726 ) ; +#38083 = ORIENTED_EDGE ( 'NONE', *, *, #30279, .T. ) ; +#38084 = AXIS2_PLACEMENT_3D ( 'NONE', #16073, #36288, #14633 ) ; +#38085 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#38086 = CARTESIAN_POINT ( 'NONE', ( -3.669944098339545935, 125.3049322094074114, 88.58406047461089372 ) ) ; +#38087 = CYLINDRICAL_SURFACE ( 'NONE', #15886, 2.000000000000000000 ) ; +#38088 = VECTOR ( 'NONE', #11560, 1000.000000000000000 ) ; +#38089 = ORIENTED_EDGE ( 'NONE', *, *, #3762, .T. ) ; +#38090 = CARTESIAN_POINT ( 'NONE', ( 25.66719153581999890, 120.2149646579000120, 90.12512969946000396 ) ) ; +#38091 = CARTESIAN_POINT ( 'NONE', ( -15.99850559934605521, 152.2995707326747947, 94.82371111949458964 ) ) ; +#38092 = CARTESIAN_POINT ( 'NONE', ( 24.53469179838298331, 103.6131156702338671, 89.75296640900199918 ) ) ; +#38094 = CARTESIAN_POINT ( 'NONE', ( -13.46391575659845685, 154.4039982810205629, 95.30803284751881677 ) ) ; +#38093 = CARTESIAN_POINT ( 'NONE', ( 12.63611452238018984, 129.9736765176137965, 92.21783751031847487 ) ) ; +#38095 = ORIENTED_EDGE ( 'NONE', *, *, #14062, .T. ) ; +#38096 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; +#38097 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #31437, #28573, #32052, #37968 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#38098 = ORIENTED_EDGE ( 'NONE', *, *, #7825, .F. ) ; +#38099 = CARTESIAN_POINT ( 'NONE', ( -14.99990232847155625, 129.4478439323167436, 89.71842115305724974 ) ) ; +#38100 = CARTESIAN_POINT ( 'NONE', ( 22.50006375536335312, 158.5567136586353740, 96.58713672006965112 ) ) ; +#38101 = ORIENTED_EDGE ( 'NONE', *, *, #210, .F. ) ; +#38102 = ORIENTED_EDGE ( 'NONE', *, *, #37011, .T. ) ; +#38103 = CARTESIAN_POINT ( 'NONE', ( 38.69099149694999795, 119.0634568547999947, 90.12535802993001255 ) ) ; +#38104 = CARTESIAN_POINT ( 'NONE', ( -41.54213446450223302, 190.5842469323372086, 103.6778548217435372 ) ) ; +#38105 = LINE ( 'NONE', #3946, #16124 ) ; +#38106 = CARTESIAN_POINT ( 'NONE', ( 43.53522452129121945, 122.0089640226160981, 87.79461538354614447 ) ) ; +#38107 = ORIENTED_EDGE ( 'NONE', *, *, #5150, .F. ) ; +#38108 = CIRCLE ( 'NONE', #33547, 5.999999999929131356 ) ; +#38109 = EDGE_CURVE ( 'NONE', #20831, #5670, #16439, .T. ) ; +#38110 = EDGE_LOOP ( 'NONE', ( #12329, #68, #10364, #7514, #24164, #22221, #21794, #3960 ) ) ; +#38111 = EDGE_CURVE ( 'NONE', #32145, #27892, #4621, .T. ) ; +#38112 = VERTEX_POINT ( 'NONE', #25728 ) ; +#38113 = DIRECTION ( 'NONE', ( 0.1943643238945209628, -0.07321898756438961764, 0.9781929714821464561 ) ) ; +#38114 = EDGE_CURVE ( 'NONE', #3943, #5068, #29384, .T. ) ; +#38115 = CARTESIAN_POINT ( 'NONE', ( 35.04524256069632315, 217.7719116313981544, 73.53733772525205836 ) ) ; +#38116 = AXIS2_PLACEMENT_3D ( 'NONE', #13970, #32771, #20485 ) ; +#38117 = EDGE_CURVE ( 'NONE', #37155, #1289, #35280, .T. ) ; +#38118 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#38119 = VERTEX_POINT ( 'NONE', #10777 ) ; +#38120 = PLANE ( 'NONE', #32818 ) ; +#38121 = ORIENTED_EDGE ( 'NONE', *, *, #15590, .F. ) ; +#38122 = CARTESIAN_POINT ( 'NONE', ( -20.52004672817496100, 211.4177853712151034, 73.57089035650061248 ) ) ; +#38123 = EDGE_LOOP ( 'NONE', ( #33472, #28391, #27401, #29254 ) ) ; +#38124 = EDGE_CURVE ( 'NONE', #20598, #31048, #4211, .T. ) ; +#38125 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #34718, #15538, #24966, #21889 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999992929045289358 ), + .UNSPECIFIED. ) ; +#38126 = ORIENTED_EDGE ( 'NONE', *, *, #36679, .T. ) ; +#38127 = DIRECTION ( 'NONE', ( 0.0005884949961229053597, -0.2249510543439064147, 0.9743698870671262391 ) ) ; +#38128 = LINE ( 'NONE', #12786, #11126 ) ; +#38129 = ORIENTED_EDGE ( 'NONE', *, *, #26829, .T. ) ; +#38130 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457974003905, -32.89481530046831637, 142.2936922234670760 ) ) ; +#38131 = EDGE_CURVE ( 'NONE', #10087, #11263, #7692, .T. ) ; +#38132 = CARTESIAN_POINT ( 'NONE', ( -2.818102608662000019, 190.7172409561999871, 106.6369364776000026 ) ) ; +#38133 = CARTESIAN_POINT ( 'NONE', ( -20.49852833623671700, 173.9502348347849363, 102.3906403207337945 ) ) ; +#38134 = ORIENTED_EDGE ( 'NONE', *, *, #7547, .T. ) ; +#38135 = CARTESIAN_POINT ( 'NONE', ( 23.36232515670999987, 177.1947614372178919, 101.0605990067274860 ) ) ; +#38136 = PLANE ( 'NONE', #6172 ) ; +#38137 = CARTESIAN_POINT ( 'NONE', ( 21.64659700640633844, 213.7792641208693283, 73.04543008022091044 ) ) ; +#38138 = CARTESIAN_POINT ( 'NONE', ( -25.98970585344537199, 191.9759150222000130, 106.9371459003730820 ) ) ; +#38139 = ADVANCED_FACE ( 'NONE', ( #32642 ), #20464, .F. ) ; +#38140 = CIRCLE ( 'NONE', #21809, 4.749999999995120348 ) ; +#38141 = VECTOR ( 'NONE', #30839, 1000.000000000000000 ) ; +#38142 = CARTESIAN_POINT ( 'NONE', ( 45.12699821176128978, 130.9347303581116364, 89.85432989627193479 ) ) ; +#38143 = ORIENTED_EDGE ( 'NONE', *, *, #10107, .T. ) ; +#38144 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988446460639, 156.3551877982853000, 95.75036263590625651 ) ) ; +#38145 = FACE_OUTER_BOUND ( 'NONE', #401, .T. ) ; +#38146 = CARTESIAN_POINT ( 'NONE', ( -35.82577198247000183, 112.4014516645000157, 89.91121576333999599 ) ) ; +#38147 = EDGE_LOOP ( 'NONE', ( #512, #12824, #13957, #10748 ) ) ; +#38148 = CARTESIAN_POINT ( 'NONE', ( 41.55397567426885530, 120.6681361272677577, 87.99940985657048031 ) ) ; +#38149 = DIRECTION ( 'NONE', ( 0.0006039748319292908250, 1.314021223879979801E-14, 0.9999998176071847045 ) ) ; +#38150 = VERTEX_POINT ( 'NONE', #17889 ) ; +#38151 = CARTESIAN_POINT ( 'NONE', ( 8.861833597925741657, 160.2547524075112904, 96.64529483589464576 ) ) ; +#38152 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480527206264441, 0.5299193337450082142 ) ) ; +#38153 = CARTESIAN_POINT ( 'NONE', ( 23.36294425673206732, 177.5614284443948918, 100.8314797030197809 ) ) ; +#38154 = CARTESIAN_POINT ( 'NONE', ( -35.93807696457169953, 196.5784392894729820, 103.8968090370881896 ) ) ; +#38155 = ORIENTED_EDGE ( 'NONE', *, *, #18754, .T. ) ; +#38156 = ORIENTED_EDGE ( 'NONE', *, *, #29573, .T. ) ; +#38157 = DIRECTION ( 'NONE', ( 0.0004161288024355817784, 0.5299192579128034764, 0.8480479980107041849 ) ) ; +#38158 = CARTESIAN_POINT ( 'NONE', ( -10.03626368673904246, 167.9332148063899410, 100.9951825985159957 ) ) ; +#38159 = ORIENTED_EDGE ( 'NONE', *, *, #38342, .F. ) ; +#38160 = EDGE_CURVE ( 'NONE', #37645, #16377, #13066, .T. ) ; +#38161 = VERTEX_POINT ( 'NONE', #29982 ) ; +#38162 = CARTESIAN_POINT ( 'NONE', ( -18.46843443665382978, 153.9052539544929914, 180.6508572568318414 ) ) ; +#38163 = EDGE_CURVE ( 'NONE', #206, #11332, #2847, .T. ) ; +#38164 = PLANE ( 'NONE', #12634 ) ; +#38165 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971564570 ) ) ; +#38166 = EDGE_CURVE ( 'NONE', #9311, #18814, #23758, .T. ) ; +#38167 = CARTESIAN_POINT ( 'NONE', ( 3.046005780481993774, 209.2052046650086083, 76.12019302384355512 ) ) ; +#38168 = CARTESIAN_POINT ( 'NONE', ( -15.49931385541658457, 185.6434956935997889, 103.7188176754347779 ) ) ; +#38169 = ORIENTED_EDGE ( 'NONE', *, *, #8007, .T. ) ; +#38170 = CARTESIAN_POINT ( 'NONE', ( 75.33799679939463090, 195.3233842313971707, 195.0706613604953930 ) ) ; +#38171 = AXIS2_PLACEMENT_3D ( 'NONE', #39421, #23915, #36374 ) ; +#38172 = CIRCLE ( 'NONE', #26443, 1.999999999912203341 ) ; +#38173 = EDGE_CURVE ( 'NONE', #19312, #7165, #11792, .T. ) ; +#38174 = CARTESIAN_POINT ( 'NONE', ( -20.51774922679897983, 207.6505144753610352, 76.65074302234292247 ) ) ; +#38175 = DIRECTION ( 'NONE', ( 0.0005884949961231158034, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#38176 = CARTESIAN_POINT ( 'NONE', ( 20.16676214620377294, 120.3527716555780529, 87.59741557435995674 ) ) ; +#38177 = FACE_OUTER_BOUND ( 'NONE', #94, .T. ) ; +#38178 = VERTEX_POINT ( 'NONE', #20564 ) ; +#38180 = EDGE_CURVE ( 'NONE', #7061, #19255, #12030, .T. ) ; +#38179 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 67.27946979429627561, 310.0857197240632104 ) ) ; +#38181 = CARTESIAN_POINT ( 'NONE', ( 0.5732175548287413713, 188.9999392055002261, 103.6969148967344552 ) ) ; +#38182 = CARTESIAN_POINT ( 'NONE', ( 36.42166835727676499, 191.8075644629787746, 104.3595393062645797 ) ) ; +#38183 = CARTESIAN_POINT ( 'NONE', ( -26.00133086711789687, 118.1131156701862892, 87.28349311522542564 ) ) ; +#38184 = CARTESIAN_POINT ( 'NONE', ( 38.48136045787376247, 119.0247563911853632, 90.24990605984262970 ) ) ; +#38185 = CARTESIAN_POINT ( 'NONE', ( 10.03596943924904039, 143.5399299914107587, 95.86457705219089576 ) ) ; +#38186 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 1.092943067225001162E-14, 0.7075337269147008445 ) ) ; +#38187 = EDGE_CURVE ( 'NONE', #11904, #40156, #16016, .T. ) ; +#38188 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #32995, #4992, #17456, #29951 ), + ( #1944, #14411, #26897, #36688 ), + ( #40345, #5605, #30766, #21579 ), + ( #15613, #11755, #6208, #18662 ), + ( #12162, #31173, #27923, #27524 ), + ( #12348, #8700, #11552, #20951 ), + ( #39740, #27715, #24851, #5403 ), + ( #39949, #27313, #30567, #24647 ), + ( #11961, #3140, #24444, #36896 ), + ( #15224, #24240, #8897, #21371 ), + ( #39541, #37298, #33814, #18464 ), + ( #5817, #8489, #18063, #37095 ), + ( #9088, #24024, #2756, #9296 ), + ( #21157, #40150, #21772, #17853 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -8.226917624016999464E-05, 0.01033686631024999941, 0.02075600179673000104, 0.04159427276969999976, 0.08327081471564999615, 0.1249473566616000064, 0.1666238986074999873, 0.2499769824994000078, 0.3333300663912999728, 0.6666654435796000033, 1.000000000000000000, 1.160103838099999951 ), + ( 8.741884557905999614E-08, 1.000000307112000053 ), + .UNSPECIFIED. ) ; +#38189 = CARTESIAN_POINT ( 'NONE', ( 25.50051830703121780, 120.2145355607603534, 89.95699753438390189 ) ) ; +#38190 = VERTEX_POINT ( 'NONE', #33645 ) ; +#38191 = DIRECTION ( 'NONE', ( -4.163336342338107392E-15, 0.9743700557921585181, 0.2249510932971564015 ) ) ; +#38192 = CIRCLE ( 'NONE', #24499, 58.90509898899682639 ) ; +#38193 = CARTESIAN_POINT ( 'NONE', ( -19.00244483772789295, 148.9001918165677125, 181.7428417728492605 ) ) ; +#38194 = LINE ( 'NONE', #31671, #21358 ) ; +#38195 = CIRCLE ( 'NONE', #30998, 2.000000000000011546 ) ; +#38196 = CIRCLE ( 'NONE', #14720, 2.000000000000011546 ) ; +#38197 = ORIENTED_EDGE ( 'NONE', *, *, #38885, .T. ) ; +#38198 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250614502, 179.6252109630515861, 101.6466942236996545 ) ) ; +#38199 = CARTESIAN_POINT ( 'NONE', ( 18.99779093548555409, 149.2112913899639466, 180.2913438554751622 ) ) ; +#38200 = CARTESIAN_POINT ( 'NONE', ( -14.31059678795166867, 190.8510141132511819, 106.8019081697394483 ) ) ; +#38201 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250903932, 179.1753088543885610, 103.5954339978220275 ) ) ; +#38202 = AXIS2_PLACEMENT_3D ( 'NONE', #40198, #33863, #27370 ) ; +#38203 = CARTESIAN_POINT ( 'NONE', ( 36.54765335729929632, 115.9165150380169820, 87.70490190100063899 ) ) ; +#38204 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921572969, -0.2249510932971618138 ) ) ; +#38205 = ORIENTED_EDGE ( 'NONE', *, *, #34366, .F. ) ; +#38206 = CARTESIAN_POINT ( 'NONE', ( 10.03449820175210050, 144.1023076273136212, 93.42865233452057794 ) ) ; +#38207 = CARTESIAN_POINT ( 'NONE', ( 35.72133043294194721, 114.6570628451127618, 87.24620950355091509 ) ) ; +#38208 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825027092, 126.8721902444253971, 91.49584442702865772 ) ) ; +#38209 = ORIENTED_EDGE ( 'NONE', *, *, #2494, .F. ) ; +#38210 = DIRECTION ( 'NONE', ( -4.376840770101431617E-14, 0.9743700557921589622, 0.2249510932971541810 ) ) ; +#38211 = EDGE_CURVE ( 'NONE', #33670, #16617, #28976, .T. ) ; +#38212 = ADVANCED_FACE ( 'NONE', ( #26721 ), #17850, .F. ) ; +#38213 = VERTEX_POINT ( 'NONE', #8726 ) ; +#38214 = CARTESIAN_POINT ( 'NONE', ( -35.44445577042502293, 86.86693592215954141, 286.9319308200167029 ) ) ; +#38215 = CARTESIAN_POINT ( 'NONE', ( -3.668796569718617562, 128.1725765626999021, 91.12766564069485753 ) ) ; +#38216 = CARTESIAN_POINT ( 'NONE', ( -44.99234402510556663, 186.0463934164131672, 106.3673110047960506 ) ) ; +#38217 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989907490, 0.1373964268091705798 ) ) ; +#38218 = CYLINDRICAL_SURFACE ( 'NONE', #32769, 5.000000000000022204 ) ; +#38219 = ORIENTED_EDGE ( 'NONE', *, *, #20944, .F. ) ; +#38220 = CARTESIAN_POINT ( 'NONE', ( 37.31693588142861273, 172.3309151562380919, 164.9673944986862466 ) ) ; +#38221 = CARTESIAN_POINT ( 'NONE', ( -5.072027095213130998, 177.6015855243536237, 100.6585432524953916 ) ) ; +#38222 = AXIS2_PLACEMENT_3D ( 'NONE', #21351, #30950, #17837 ) ; +#38223 = CARTESIAN_POINT ( 'NONE', ( 5.384453718119554644, 177.7301722179466026, 100.6819143828688397 ) ) ; +#38224 = CONICAL_SURFACE ( 'NONE', #1001, 17.00000000000409273, 0.7853981633973132759 ) ; +#38225 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; +#38226 = ORIENTED_EDGE ( 'NONE', *, *, #7380, .T. ) ; +#38227 = AXIS2_PLACEMENT_3D ( 'NONE', #10806, #25550, #34705 ) ; +#38228 = ORIENTED_EDGE ( 'NONE', *, *, #38889, .F. ) ; +#38229 = FACE_OUTER_BOUND ( 'NONE', #9563, .T. ) ; +#38230 = ORIENTED_EDGE ( 'NONE', *, *, #30017, .F. ) ; +#38231 = EDGE_CURVE ( 'NONE', #9860, #29667, #23855, .T. ) ; +#38232 = LINE ( 'NONE', #10238, #7095 ) ; +#38233 = DIRECTION ( 'NONE', ( 0.5399741663421816495, -0.8200377969059812200, -0.1896468067979279470 ) ) ; +#38234 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7071067167009886800, 0.7071068456721004702 ) ) ; +#38235 = CARTESIAN_POINT ( 'NONE', ( -2.576359560463000076, 208.9113141535999887, 73.50994362621000278 ) ) ; +#38236 = CARTESIAN_POINT ( 'NONE', ( 38.51934278294999814, 118.5830806632000076, 89.80757908325999495 ) ) ; +#38237 = ORIENTED_EDGE ( 'NONE', *, *, #20668, .F. ) ; +#38238 = ADVANCED_FACE ( 'NONE', ( #36311 ), #5641, .F. ) ; +#38239 = CIRCLE ( 'NONE', #31812, 10.00000000000072831 ) ; +#38240 = FACE_OUTER_BOUND ( 'NONE', #2761, .T. ) ; +#38241 = FACE_OUTER_BOUND ( 'NONE', #20747, .T. ) ; +#38242 = CARTESIAN_POINT ( 'NONE', ( -26.20112735025328377, 189.6309894264402942, 106.5274248102679593 ) ) ; +#38243 = AXIS2_PLACEMENT_3D ( 'NONE', #36429, #13743, #38669 ) ; +#38244 = ORIENTED_EDGE ( 'NONE', *, *, #35868, .T. ) ; +#38245 = EDGE_LOOP ( 'NONE', ( #13973, #35047, #29087, #37403 ) ) ; +#38246 = VERTEX_POINT ( 'NONE', #39573 ) ; +#38247 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; +#38248 = CONICAL_SURFACE ( 'NONE', #8914, 8.499999999972359888, 0.7853981633972975107 ) ; +#38249 = CARTESIAN_POINT ( 'NONE', ( 5.666881758531304492, 123.8790441587746614, 91.16841673835540405 ) ) ; +#38250 = AXIS2_PLACEMENT_3D ( 'NONE', #8511, #27132, #7680 ) ; +#38251 = ADVANCED_FACE ( 'NONE', ( #11175 ), #8314, .F. ) ; +#38252 = ORIENTED_EDGE ( 'NONE', *, *, #3082, .T. ) ; +#38253 = ORIENTED_EDGE ( 'NONE', *, *, #17037, .T. ) ; +#38254 = EDGE_CURVE ( 'NONE', #30803, #5465, #31107, .T. ) ; +#38255 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474974863243018, 155.7928101624827946, 98.18628735359689585 ) ) ; +#38256 = CARTESIAN_POINT ( 'NONE', ( 20.16836658598267817, 118.8155847327597030, 90.08898221329239675 ) ) ; +#38257 = CARTESIAN_POINT ( 'NONE', ( 6.271598195383973895, 163.6071748240002250, 98.96028355598751602 ) ) ; +#38258 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#38259 = EDGE_LOOP ( 'NONE', ( #30029, #13762, #39650, #38001 ) ) ; +#38260 = CYLINDRICAL_SURFACE ( 'NONE', #25838, 7.999999999999993783 ) ; +#38261 = ORIENTED_EDGE ( 'NONE', *, *, #11119, .F. ) ; +#38262 = CARTESIAN_POINT ( 'NONE', ( 19.98244285516242869, 208.9307805169470100, 76.16354082693111138 ) ) ; +#38263 = FACE_OUTER_BOUND ( 'NONE', #38245, .T. ) ; +#38264 = DIRECTION ( 'NONE', ( 0.0005884949961233868539, -0.2249510543439054988, 0.9743698870671265722 ) ) ; +#38265 = ORIENTED_EDGE ( 'NONE', *, *, #29027, .F. ) ; +#38266 = CARTESIAN_POINT ( 'NONE', ( -2.770536616719000200, 191.0749790456000028, 103.9388038315000102 ) ) ; +#38267 = CARTESIAN_POINT ( 'NONE', ( 15.50029468041041980, 185.7974155947003112, 103.0514270425986325 ) ) ; +#38268 = CARTESIAN_POINT ( 'NONE', ( 2.685595935758000596, 190.9413773800000058, 106.4228114910000045 ) ) ; +#38269 = CIRCLE ( 'NONE', #24584, 2.000000000000011546 ) ; +#38270 = ORIENTED_EDGE ( 'NONE', *, *, #37717, .F. ) ; +#38271 = DIRECTION ( 'NONE', ( -0.7716293354502457014, 0.6291556465476403348, -0.09354860282138378891 ) ) ; +#38272 = CARTESIAN_POINT ( 'NONE', ( -25.50006284340070906, 118.1130153187805689, 89.78316558933853742 ) ) ; +#38273 = ORIENTED_EDGE ( 'NONE', *, *, #18840, .T. ) ; +#38274 = CIRCLE ( 'NONE', #4966, 5.499999999884110480 ) ; +#38275 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385907860 ) ) ; +#38276 = CARTESIAN_POINT ( 'NONE', ( 6.035116358040530038, 134.7953873012855297, 93.37716266042390600 ) ) ; +#38277 = CIRCLE ( 'NONE', #20654, 2.499999999981690646 ) ; +#38278 = ORIENTED_EDGE ( 'NONE', *, *, #35326, .T. ) ; +#38279 = AXIS2_PLACEMENT_3D ( 'NONE', #32585, #32387, #4360 ) ; +#38280 = CARTESIAN_POINT ( 'NONE', ( 2.978288450619526184, 190.2180736835273365, 106.6453402794937233 ) ) ; +#38281 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#38282 = LINE ( 'NONE', #34589, #4522 ) ; +#38283 = ORIENTED_EDGE ( 'NONE', *, *, #36186, .T. ) ; +#38284 = CARTESIAN_POINT ( 'NONE', ( 26.00589438745670634, 120.1009206316479947, 90.44882784922441488 ) ) ; +#38285 = CARTESIAN_POINT ( 'NONE', ( 1.447658035571014024, 144.9407251426433447, 129.0349007182348657 ) ) ; +#38287 = CARTESIAN_POINT ( 'NONE', ( 27.29350369004999877, 103.8631156702000027, 87.50129974532001143 ) ) ; +#38286 = CARTESIAN_POINT ( 'NONE', ( 20.48137403145198476, 209.5894841463820342, 75.54614556716059326 ) ) ; +#38288 = ORIENTED_EDGE ( 'NONE', *, *, #18385, .F. ) ; +#38289 = EDGE_CURVE ( 'NONE', #38119, #15715, #33441, .T. ) ; +#38290 = VERTEX_POINT ( 'NONE', #29080 ) ; +#38291 = PLANE ( 'NONE', #21901 ) ; +#38292 = CARTESIAN_POINT ( 'NONE', ( -28.26067782467530520, 125.1269179218217857, 91.12357580992288320 ) ) ; +#38293 = FACE_OUTER_BOUND ( 'NONE', #26821, .T. ) ; +#38294 = ORIENTED_EDGE ( 'NONE', *, *, #26632, .T. ) ; +#38295 = EDGE_CURVE ( 'NONE', #11374, #1723, #10710, .T. ) ; +#38296 = AXIS2_PLACEMENT_3D ( 'NONE', #19725, #26098, #3582 ) ; +#38297 = EDGE_CURVE ( 'NONE', #22792, #26158, #26754, .T. ) ; +#38298 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #14204, #29333, #11320, #7846 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.532607311606953182, 4.712388980384698556 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973083591495172096, 0.9973083591495172096, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#38299 = ORIENTED_EDGE ( 'NONE', *, *, #26866, .T. ) ; +#38301 = EDGE_CURVE ( 'NONE', #28925, #12094, #38074, .T. ) ; +#38300 = CARTESIAN_POINT ( 'NONE', ( 38.85612909692999750, 118.8963570784000012, 89.83544490924001025 ) ) ; +#38302 = CARTESIAN_POINT ( 'NONE', ( -35.44810745619992787, 112.9281708664996984, 87.28919406064997588 ) ) ; +#38303 = EDGE_CURVE ( 'NONE', #23127, #23715, #36962, .T. ) ; +#38304 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001011, 134.2394347309543434, 93.74516030700213776 ) ) ; +#38305 = CARTESIAN_POINT ( 'NONE', ( -44.97035487161856793, 124.6095424173942803, 91.35670517576666327 ) ) ; +#38306 = PLANE ( 'NONE', #13058 ) ; +#38307 = CIRCLE ( 'NONE', #20024, 4.499999999969428011 ) ; +#38308 = ORIENTED_EDGE ( 'NONE', *, *, #33448, .T. ) ; +#38309 = ORIENTED_EDGE ( 'NONE', *, *, #11295, .T. ) ; +#38310 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #28008, #5497, #40443, #30463 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#38311 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251384259, 130.2132135508113038, 92.29164155970235583 ) ) ; +#38312 = DIRECTION ( 'NONE', ( -0.0005884949961254158299, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#38313 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#38314 = ORIENTED_EDGE ( 'NONE', *, *, #6659, .F. ) ; +#38315 = ORIENTED_EDGE ( 'NONE', *, *, #3629, .T. ) ; +#38316 = PLANE ( 'NONE', #20623 ) ; +#38317 = EDGE_LOOP ( 'NONE', ( #17664, #9154, #36960, #19063 ) ) ; +#38318 = CARTESIAN_POINT ( 'NONE', ( -37.56294621074515305, 117.4321712499414758, 89.72245835561675165 ) ) ; +#38319 = ORIENTED_EDGE ( 'NONE', *, *, #21748, .T. ) ; +#38320 = CARTESIAN_POINT ( 'NONE', ( -16.00000031268763934, 184.9628657724767606, 102.3646292465979855 ) ) ; +#38321 = VERTEX_POINT ( 'NONE', #38465 ) ; +#38322 = CARTESIAN_POINT ( 'NONE', ( -20.49970531044686695, 189.2256923798826449, 103.8646662894091151 ) ) ; +#38323 = DIRECTION ( 'NONE', ( 3.469446952062275440E-15, 0.9743700557921587402, 0.2249510932971553467 ) ) ; +#38324 = DIRECTION ( 'NONE', ( 0.7933535320750499942, -0.5931614265261869745, -0.1369295264925045885 ) ) ; +#38325 = AXIS2_PLACEMENT_3D ( 'NONE', #24235, #5598, #11545 ) ; +#38326 = ORIENTED_EDGE ( 'NONE', *, *, #14619, .F. ) ; +#38327 = CARTESIAN_POINT ( 'NONE', ( -20.49970532950636937, 191.6000458281059764, 104.4127958363113606 ) ) ; +#38328 = VECTOR ( 'NONE', #36183, 999.9999999999998863 ) ; +#38329 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#38330 = CIRCLE ( 'NONE', #37035, 2.000000000000011546 ) ; +#38331 = PLANE ( 'NONE', #10500 ) ; +#38332 = CARTESIAN_POINT ( 'NONE', ( -20.01839840245581570, 211.0893415776789936, 76.07059839062316087 ) ) ; +#38333 = ORIENTED_EDGE ( 'NONE', *, *, #4637, .T. ) ; +#38334 = EDGE_CURVE ( 'NONE', #37942, #15550, #13339, .T. ) ; +#38336 = ADVANCED_FACE ( 'NONE', ( #22952 ), #31546, .T. ) ; +#38335 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319411731388 ) ) ; +#38337 = CARTESIAN_POINT ( 'NONE', ( -37.76416279167000312, 117.8877880277999992, 89.85641046381000763 ) ) ; +#38339 = ORIENTED_EDGE ( 'NONE', *, *, #19681, .F. ) ; +#38338 = EDGE_CURVE ( 'NONE', #38686, #1598, #32903, .T. ) ; +#38340 = VERTEX_POINT ( 'NONE', #19248 ) ; +#38341 = DIRECTION ( 'NONE', ( -0.7066795775021793569, 8.797476192434283764E-15, 0.7075337269285058017 ) ) ; +#38342 = EDGE_CURVE ( 'NONE', #40361, #38835, #31346, .T. ) ; +#38343 = DIRECTION ( 'NONE', ( -0.0005884949961221076038, 0.2249510543439052768, -0.9743698870671265722 ) ) ; +#38344 = DIRECTION ( 'NONE', ( 0.0005884949950032587751, -0.2249510543438477117, 0.9743698870671404499 ) ) ; +#38345 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672065478, 127.1823533459056961, 91.57288700727464459 ) ) ; +#38346 = DIRECTION ( 'NONE', ( -0.0004161288024530142857, 0.8480480897951311325, -0.5299191110270028426 ) ) ; +#38347 = EDGE_LOOP ( 'NONE', ( #560, #9231, #32754, #28144 ) ) ; +#38348 = FACE_BOUND ( 'NONE', #9399, .T. ) ; +#38349 = EDGE_LOOP ( 'NONE', ( #38409, #9872, #10343, #10650 ) ) ; +#38350 = VERTEX_POINT ( 'NONE', #10285 ) ; +#38352 = EDGE_CURVE ( 'NONE', #24492, #34116, #1562, .T. ) ; +#38351 = CARTESIAN_POINT ( 'NONE', ( 5.670201816268967576, 188.2581808524728331, 103.1863035028179780 ) ) ; +#38353 = CARTESIAN_POINT ( 'NONE', ( 29.78094704533299364, 126.4966686442676149, 91.40475157444033982 ) ) ; +#38354 = CARTESIAN_POINT ( 'NONE', ( -13.55720484940897030, 164.6355387680630429, 97.67021978066252075 ) ) ; +#38355 = AXIS2_PLACEMENT_3D ( 'NONE', #38115, #25867, #10324 ) ; +#38356 = ORIENTED_EDGE ( 'NONE', *, *, #30327, .T. ) ; +#38357 = CARTESIAN_POINT ( 'NONE', ( -25.50995787358820266, 209.2762579043570099, 73.57326757446821830 ) ) ; +#38358 = CARTESIAN_POINT ( 'NONE', ( -25.50991579498579398, 209.7152486954105086, 73.57374465072240355 ) ) ; +#38359 = CARTESIAN_POINT ( 'NONE', ( 36.89736173421999865, 117.5051806407000043, 87.34911898881000525 ) ) ; +#38360 = CARTESIAN_POINT ( 'NONE', ( -38.38010894157000052, 119.1894012325000034, 90.45925847721001389 ) ) ; +#38361 = FACE_OUTER_BOUND ( 'NONE', #28124, .T. ) ; +#38362 = FACE_OUTER_BOUND ( 'NONE', #31250, .T. ) ; +#38363 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 132.9726895863780385, 90.34121396988766151 ) ) ; +#38364 = EDGE_LOOP ( 'NONE', ( #35758, #38635, #15656, #12117 ) ) ; +#38365 = CARTESIAN_POINT ( 'NONE', ( 25.87290347845999960, 122.7597973085000120, 88.49195514234999393 ) ) ; +#38366 = CARTESIAN_POINT ( 'NONE', ( -41.44647100807553386, 120.2182348193094015, 89.99828044825905238 ) ) ; +#38367 = LINE ( 'NONE', #10374, #24075 ) ; +#38368 = CARTESIAN_POINT ( 'NONE', ( 19.99999382154498662, 120.3902235794415816, 87.43511282661482653 ) ) ; +#38369 = CARTESIAN_POINT ( 'NONE', ( 19.99902741543100859, 160.4248104870491716, 96.67782925827370377 ) ) ; +#38370 = VERTEX_POINT ( 'NONE', #15785 ) ; +#38371 = CARTESIAN_POINT ( 'NONE', ( -13.46215051151162889, 153.7291600434821532, 98.23113887026609348 ) ) ; +#38372 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#38373 = CARTESIAN_POINT ( 'NONE', ( -29.78271044658185218, 126.9386829446179377, 89.49016549083705740 ) ) ; +#38374 = CARTESIAN_POINT ( 'NONE', ( -2.695942817310999828, 199.6921533858000259, 89.50319044955999459 ) ) ; +#38375 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #6889, #13445, #19751, #25525 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.1766062648735380325, 0.3157706852075154447 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9983867564016681850, 0.9983867564016681850, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#38376 = CARTESIAN_POINT ( 'NONE', ( -25.35823072494000030, 191.6420941174999939, 104.5491859340999952 ) ) ; +#38377 = FACE_OUTER_BOUND ( 'NONE', #40387, .T. ) ; +#38378 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; +#38379 = CARTESIAN_POINT ( 'NONE', ( -15.49970617362840919, 138.0805224087925751, 92.05383544148693886 ) ) ; +#38380 = EDGE_CURVE ( 'NONE', #27146, #7306, #457, .T. ) ; +#38381 = ORIENTED_EDGE ( 'NONE', *, *, #39628, .T. ) ; +#38382 = EDGE_CURVE ( 'NONE', #5749, #1845, #38140, .T. ) ; +#38383 = VECTOR ( 'NONE', #35512, 1000.000000000000000 ) ; +#38384 = ADVANCED_FACE ( 'NONE', ( #10076 ), #22553, .F. ) ; +#38385 = EDGE_CURVE ( 'NONE', #10328, #5648, #27705, .T. ) ; +#38386 = VECTOR ( 'NONE', #40003, 1000.000000000000114 ) ; +#38387 = DIRECTION ( 'NONE', ( 0.5634794340701355653, -0.8261300910752492621, 0.000000000000000000 ) ) ; +#38388 = CARTESIAN_POINT ( 'NONE', ( 19.99339512836239052, 197.5803468065060713, 93.82480951519328016 ) ) ; +#38389 = ORIENTED_EDGE ( 'NONE', *, *, #39117, .F. ) ; +#38390 = CARTESIAN_POINT ( 'NONE', ( 37.33254290421506028, 104.0199313033473345, 184.2130203058457880 ) ) ; +#38391 = DIRECTION ( 'NONE', ( 0.0006039748319391171662, 1.156185249762965862E-14, 0.9999998176071845934 ) ) ; +#38392 = EDGE_CURVE ( 'NONE', #34191, #19444, #6240, .T. ) ; +#38393 = CARTESIAN_POINT ( 'NONE', ( -2.938441474952925514, 191.9759150222000130, 101.9232220853079411 ) ) ; +#38394 = DIRECTION ( 'NONE', ( -0.0005884949961234662175, 0.2249510543439052490, -0.9743698870671265722 ) ) ; +#38395 = FACE_OUTER_BOUND ( 'NONE', #14990, .T. ) ; +#38396 = EDGE_LOOP ( 'NONE', ( #20333, #26511, #36849, #19939 ) ) ; +#38397 = CARTESIAN_POINT ( 'NONE', ( 21.10880003438571251, 175.5356891742621031, 102.9025923018732271 ) ) ; +#38398 = ORIENTED_EDGE ( 'NONE', *, *, #24062, .T. ) ; +#38399 = ORIENTED_EDGE ( 'NONE', *, *, #18065, .F. ) ; +#38401 = EDGE_CURVE ( 'NONE', #39205, #89, #20057, .T. ) ; +#38400 = CARTESIAN_POINT ( 'NONE', ( -5.669849310683051868, 181.2163897477299201, 104.3984882632009743 ) ) ; +#38402 = DIRECTION ( 'NONE', ( 0.0005884949961264505924, -0.2249510543439044719, 0.9743698870671267942 ) ) ; +#38403 = CARTESIAN_POINT ( 'NONE', ( 18.98509384253694421, 148.2879009998192714, 184.3674135999851273 ) ) ; +#38404 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; +#38405 = ORIENTED_EDGE ( 'NONE', *, *, #12266, .T. ) ; +#38406 = CARTESIAN_POINT ( 'NONE', ( -35.95405601968204223, 218.5902260770999987, 76.08021997845068540 ) ) ; +#38407 = ORIENTED_EDGE ( 'NONE', *, *, #9506, .T. ) ; +#38408 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 7.515125404477462028E-16, -0.0006039748319388944710 ) ) ; +#38409 = ORIENTED_EDGE ( 'NONE', *, *, #1989, .T. ) ; +#38410 = LINE ( 'NONE', #3251, #35958 ) ; +#38411 = VECTOR ( 'NONE', #12614, 999.9999999999998863 ) ; +#38412 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554023 ) ) ; +#38413 = FACE_OUTER_BOUND ( 'NONE', #31095, .T. ) ; +#38414 = LINE ( 'NONE', #25363, #30183 ) ; +#38415 = ORIENTED_EDGE ( 'NONE', *, *, #7920, .F. ) ; +#38416 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#38417 = CARTESIAN_POINT ( 'NONE', ( -30.07064833235158474, 177.3992996866407736, 100.9590083430528580 ) ) ; +#38418 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282898364, 148.0700263536679984, 93.85134194391106632 ) ) ; +#38419 = CARTESIAN_POINT ( 'NONE', ( -36.02886085861999987, 191.3486044203000347, 103.7195778210000014 ) ) ; +#38420 = ORIENTED_EDGE ( 'NONE', *, *, #8633, .F. ) ; +#38421 = LINE ( 'NONE', #20625, #6144 ) ; +#38422 = CARTESIAN_POINT ( 'NONE', ( 8.048542121204103950, 160.5989240000510279, 99.80415721606205182 ) ) ; +#38423 = EDGE_CURVE ( 'NONE', #7887, #37534, #30093, .T. ) ; +#38424 = EDGE_CURVE ( 'NONE', #19923, #11505, #4698, .T. ) ; +#38425 = FACE_OUTER_BOUND ( 'NONE', #19196, .T. ) ; +#38426 = CARTESIAN_POINT ( 'NONE', ( 20.33489173372807457, 119.7903715517339407, 90.03324753095370170 ) ) ; +#38427 = AXIS2_PLACEMENT_3D ( 'NONE', #30931, #19031, #30731 ) ; +#38428 = CARTESIAN_POINT ( 'NONE', ( -2.831545756241999889, 208.8168945399000052, 73.26525557386000287 ) ) ; +#38429 = CARTESIAN_POINT ( 'NONE', ( -37.92530404122999954, 190.2020722073000059, 106.8053324585000041 ) ) ; +#38430 = VERTEX_POINT ( 'NONE', #1873 ) ; +#38431 = VECTOR ( 'NONE', #6732, 1000.000000000000000 ) ; +#38432 = CARTESIAN_POINT ( 'NONE', ( 47.97461142298704573, 82.27946979429644614, 322.5295741262542606 ) ) ; +#38433 = VECTOR ( 'NONE', #9947, 1000.000000000000000 ) ; +#38434 = AXIS2_PLACEMENT_3D ( 'NONE', #6540, #18599, #209 ) ; +#38435 = CARTESIAN_POINT ( 'NONE', ( -15.99999411491280199, 138.1989450468032601, 91.56832761027415302 ) ) ; +#38436 = ORIENTED_EDGE ( 'NONE', *, *, #6897, .F. ) ; +#38437 = ORIENTED_EDGE ( 'NONE', *, *, #7401, .F. ) ; +#38438 = ORIENTED_EDGE ( 'NONE', *, *, #3518, .T. ) ; +#38439 = CARTESIAN_POINT ( 'NONE', ( -13.50514475104697532, 124.4029596900451082, 88.43414899398538864 ) ) ; +#38440 = FACE_OUTER_BOUND ( 'NONE', #2493, .T. ) ; +#38441 = CARTESIAN_POINT ( 'NONE', ( 5.666570111846160884, 124.1682743494144177, 90.98768579075735374 ) ) ; +#38442 = ORIENTED_EDGE ( 'NONE', *, *, #14071, .T. ) ; +#38443 = VERTEX_POINT ( 'NONE', #14557 ) ; +#38444 = LINE ( 'NONE', #39051, #15299 ) ; +#38445 = EDGE_CURVE ( 'NONE', #20110, #33611, #16938, .T. ) ; +#38446 = CARTESIAN_POINT ( 'NONE', ( -38.39983396593000720, 119.0472737981999956, 90.29717073674000005 ) ) ; +#38447 = CARTESIAN_POINT ( 'NONE', ( -38.24620936299999840, 118.9481072208999990, 87.58021371626999496 ) ) ; +#38448 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825887818095019, 0.0005734119031303735623 ) ) ; +#38449 = EDGE_LOOP ( 'NONE', ( #39998, #21093, #19492, #25574, #23929, #28875, #30870, #33279, #1747, #10885 ) ) ; +#38450 = LINE ( 'NONE', #23338, #23848 ) ; +#38451 = ORIENTED_EDGE ( 'NONE', *, *, #26552, .F. ) ; +#38452 = CARTESIAN_POINT ( 'NONE', ( -3.535986895436823207, 167.8052092920482039, 101.4748507491612912 ) ) ; +#38453 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#38454 = CARTESIAN_POINT ( 'NONE', ( -37.83658322688275888, 190.9636381155321203, 106.3289620680116343 ) ) ; +#38455 = CARTESIAN_POINT ( 'NONE', ( -3.535851989103623971, 143.5328828484186943, 95.87118806634899215 ) ) ; +#38456 = ORIENTED_EDGE ( 'NONE', *, *, #5141, .T. ) ; +#38457 = VERTEX_POINT ( 'NONE', #38868 ) ; +#38458 = CIRCLE ( 'NONE', #19514, 22.50000000000000000 ) ; +#38459 = CARTESIAN_POINT ( 'NONE', ( -0.4375701469493999962, 188.7416664959999935, 103.3602241911000021 ) ) ; +#38460 = CARTESIAN_POINT ( 'NONE', ( 25.49182901039327831, 209.7089661076149127, 75.54314178666862745 ) ) ; +#38461 = CARTESIAN_POINT ( 'NONE', ( 18.98506067126258046, 148.2070439170772431, 184.7168109706149721 ) ) ; +#38462 = CIRCLE ( 'NONE', #28674, 4.999999999999990230 ) ; +#38463 = AXIS2_PLACEMENT_3D ( 'NONE', #26241, #1894, #8231 ) ; +#38464 = ORIENTED_EDGE ( 'NONE', *, *, #8406, .T. ) ; +#38465 = CARTESIAN_POINT ( 'NONE', ( 44.24772793393911030, 122.2367175089034959, 90.92567871579780103 ) ) ; +#38466 = CARTESIAN_POINT ( 'NONE', ( -26.01326056281665089, 211.0902258159713085, 76.07393268928584007 ) ) ; +#38467 = ORIENTED_EDGE ( 'NONE', *, *, #9636, .T. ) ; +#38468 = AXIS2_PLACEMENT_3D ( 'NONE', #33395, #5391, #17842 ) ; +#38469 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; +#38470 = EDGE_LOOP ( 'NONE', ( #6411, #38261, #38389, #3789 ) ) ; +#38471 = EDGE_CURVE ( 'NONE', #39651, #14192, #16792, .T. ) ; +#38472 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13819, #5631, #14435, #39353 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#38473 = EDGE_CURVE ( 'NONE', #33399, #15062, #23109, .T. ) ; +#38474 = CARTESIAN_POINT ( 'NONE', ( 13.55543936468217581, 147.3999835650271848, 96.75361558816608465 ) ) ; +#38475 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#38476 = CARTESIAN_POINT ( 'NONE', ( 22.50170152449286221, 153.4847644705970424, 97.81088946422735830 ) ) ; +#38477 = ORIENTED_EDGE ( 'NONE', *, *, #27288, .F. ) ; +#38478 = ORIENTED_EDGE ( 'NONE', *, *, #27414, .F. ) ; +#38479 = CARTESIAN_POINT ( 'NONE', ( 25.50057794482474449, 120.1935418996727805, 89.93170405457649963 ) ) ; +#38480 = DIRECTION ( 'NONE', ( 0.7933533411653058698, -0.5930537057989958560, -0.1373964268091568131 ) ) ; +#38482 = CARTESIAN_POINT ( 'NONE', ( 3.061557431404703156, 191.9759150222000130, 101.9195982364082056 ) ) ; +#38481 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569047542183, -0.8480481632226759547 ) ) ; +#38483 = AXIS2_PLACEMENT_3D ( 'NONE', #36303, #11359, #17068 ) ; +#38484 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; +#38485 = ORIENTED_EDGE ( 'NONE', *, *, #2515, .F. ) ; +#38486 = CARTESIAN_POINT ( 'NONE', ( -3.669581222364402873, 126.6894591277509221, 89.41685568663245931 ) ) ; +#38487 = AXIS2_PLACEMENT_3D ( 'NONE', #14319, #14522, #26797 ) ; +#38488 = AXIS2_PLACEMENT_3D ( 'NONE', #36122, #30003, #5663 ) ; +#38489 = DIRECTION ( 'NONE', ( -0.7933535320750506603, 0.5931614265261859753, 0.1369295264925043665 ) ) ; +#38490 = ORIENTED_EDGE ( 'NONE', *, *, #13981, .T. ) ; +#38491 = VECTOR ( 'NONE', #34448, 1000.000000000000000 ) ; +#38492 = ORIENTED_EDGE ( 'NONE', *, *, #30138, .F. ) ; +#38493 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; +#38494 = DIRECTION ( 'NONE', ( -0.0005884949961253164085, 0.2249510543439028898, -0.9743698870671272383 ) ) ; +#38495 = CARTESIAN_POINT ( 'NONE', ( -3.070531973001000114, 190.8181423560999974, 106.9269511051000023 ) ) ; +#38496 = ORIENTED_EDGE ( 'NONE', *, *, #18518, .T. ) ; +#38497 = ORIENTED_EDGE ( 'NONE', *, *, #31456, .T. ) ; +#38498 = LINE ( 'NONE', #13576, #28504 ) ; +#38499 = DIRECTION ( 'NONE', ( -0.7933531821952553020, 0.5930539076840665169, 0.1373964733219922574 ) ) ; +#38500 = FACE_OUTER_BOUND ( 'NONE', #12181, .T. ) ; +#38501 = VERTEX_POINT ( 'NONE', #35782 ) ; +#38502 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #6059, #12207, #2983, #37142 ), + ( #18507, #125, #37731, #9338 ), + ( #21618, #9137, #31012, #13009 ), + ( #15469, #40395, #318, #9744 ), + ( #21813, #34251, #18915, #6643 ), + ( #22220, #6252, #31412, #10946 ), + ( #3976, #20113, #26480, #25893 ), + ( #4581, #7248, #10737, #32217 ), + ( #38527, #38932, #7052, #1119 ), + ( #26088, #32802, #23206, #4173 ), + ( #10545, #10348, #38718, #13600 ), + ( #29347, #1316, #38337, #28742 ), + ( #32602, #25696, #16649, #17042 ), + ( #32016, #19521, #22817, #13405 ), + ( #13209, #23408, #13799, #20323 ), + ( #35435, #4782, #16452, #23011 ), + ( #26284, #35848, #7855, #14003 ), + ( #7447, #35640, #10146, #19908 ), + ( #29543, #22619, #32414, #721 ), + ( #35245, #4382, #38146, #16842 ), + ( #35043, #28940, #919, #7655 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.0007490278349774999933, 0.000000000000000000, 3.474638108047999990E-05, 0.001983274684462999881, 0.003936385303643000211, 0.007842606542005000139, 0.01565504901873999988, 0.03127993397217999905, 0.06252970387907000327, 0.09377947378598000538, 0.1250292436927999962, 0.1875287835065999886, 0.2500283233205000122, 0.3750236086952000170, 0.5000188940699999973, 0.6250141794446000265, 0.7500094648192999758, 1.000000000000000000, 1.014439647481000017 ), + ( -0.0001383384667056999950, 1.000650266732000082 ), + .UNSPECIFIED. ) ; +#38503 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927856766183, 0.0005734119022057102217 ) ) ; +#38504 = ORIENTED_EDGE ( 'NONE', *, *, #5013, .F. ) ; +#38505 = EDGE_CURVE ( 'NONE', #9915, #14771, #39472, .T. ) ; +#38506 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.274821093756980153E-14, 0.9999998176071844824 ) ) ; +#38507 = EDGE_LOOP ( 'NONE', ( #6861, #8942, #6524, #11965 ) ) ; +#38508 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 134.8228298562323744, 92.32955159241861054 ) ) ; +#38509 = CONICAL_SURFACE ( 'NONE', #2652, 3.002820406140098264, 0.7853589219061751781 ) ; +#38510 = EDGE_CURVE ( 'NONE', #36415, #32868, #4271, .T. ) ; +#38511 = VECTOR ( 'NONE', #7263, 1000.000000000000000 ) ; +#38512 = CARTESIAN_POINT ( 'NONE', ( -0.5631384182448999631, 189.1604183121999938, 105.6044017097000136 ) ) ; +#38513 = CARTESIAN_POINT ( 'NONE', ( 37.32819269845482069, 107.3988016090549422, 169.6034496416073409 ) ) ; +#38514 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -1.676366911794336136E-18, -0.0006039748319371601813 ) ) ; +#38515 = ORIENTED_EDGE ( 'NONE', *, *, #14548, .T. ) ; +#38516 = CONICAL_SURFACE ( 'NONE', #18934, 6.500000000082327034, 0.7853981634697572156 ) ; +#38518 = EDGE_CURVE ( 'NONE', #11248, #20347, #27039, .T. ) ; +#38517 = LINE ( 'NONE', #26474, #32332 ) ; +#38519 = EDGE_CURVE ( 'NONE', #1188, #25578, #35993, .T. ) ; +#38520 = DIRECTION ( 'NONE', ( -0.9999998268368619492, -0.0001323825708487058237, 0.0005734118074949707536 ) ) ; +#38521 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#38522 = EDGE_CURVE ( 'NONE', #29530, #21600, #19847, .T. ) ; +#38523 = ADVANCED_FACE ( 'NONE', ( #5121 ), #33138, .T. ) ; +#38524 = DIRECTION ( 'NONE', ( 0.6087604435314231122, 0.7731012422272365292, 0.1781156693222946674 ) ) ; +#38525 = ORIENTED_EDGE ( 'NONE', *, *, #14530, .T. ) ; +#38526 = LINE ( 'NONE', #13404, #38433 ) ; +#38527 = CARTESIAN_POINT ( 'NONE', ( -37.84200445841999993, 118.7313177170999978, 90.44745268466000709 ) ) ; +#38528 = ORIENTED_EDGE ( 'NONE', *, *, #39725, .T. ) ; +#38529 = DIRECTION ( 'NONE', ( 0.0005884949961247222657, -0.2249510543439059984, 0.9743698870671263501 ) ) ; +#38530 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #6661, #2811, #15289, #6463, #2621, #12822, #15671, #3396, #142, #28364 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#38531 = VERTEX_POINT ( 'NONE', #17388 ) ; +#38532 = CARTESIAN_POINT ( 'NONE', ( 37.31639193983529879, 111.9096183688354245, 150.0649592369359766 ) ) ; +#38533 = LINE ( 'NONE', #10355, #39834 ) ; +#38534 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13731, #38656, #20256, #10676 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#38535 = CARTESIAN_POINT ( 'NONE', ( -40.55516615315095663, 184.2569486434040869, 105.2953989892096445 ) ) ; +#38536 = VERTEX_POINT ( 'NONE', #36210 ) ; +#38537 = ORIENTED_EDGE ( 'NONE', *, *, #14646, .T. ) ; +#38538 = CARTESIAN_POINT ( 'NONE', ( 25.66728632891432582, 120.1770448847769757, 90.11928726968523051 ) ) ; +#38539 = ORIENTED_EDGE ( 'NONE', *, *, #40094, .F. ) ; +#38540 = VERTEX_POINT ( 'NONE', #23965 ) ; +#38541 = EDGE_LOOP ( 'NONE', ( #26429, #14495, #8935, #18286 ) ) ; +#38542 = CARTESIAN_POINT ( 'NONE', ( 22.11658946403013815, 136.0358612623089982, 91.55906883338052182 ) ) ; +#38543 = CARTESIAN_POINT ( 'NONE', ( -15.10537794304822512, 128.9348610681433911, 92.50791545010099526 ) ) ; +#38544 = VECTOR ( 'NONE', #14890, 1000.000000000000000 ) ; +#38545 = CARTESIAN_POINT ( 'NONE', ( -20.49852807266789867, 190.9630690214611946, 106.3183227610936541 ) ) ; +#38546 = VECTOR ( 'NONE', #39143, 1000.000000000000227 ) ; +#38547 = ORIENTED_EDGE ( 'NONE', *, *, #1065, .T. ) ; +#38548 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 89.47423874572474745, 291.5876487235610171 ) ) ; +#38549 = AXIS2_PLACEMENT_3D ( 'NONE', #25327, #37984, #13251 ) ; +#38550 = LINE ( 'NONE', #32432, #21542 ) ; +#38551 = CARTESIAN_POINT ( 'NONE', ( 36.06619636834999909, 191.4156479609000314, 103.6926474936999938 ) ) ; +#38552 = DIRECTION ( 'NONE', ( -0.7933533175743878729, 0.5931616988744193852, 0.1369295895054284395 ) ) ; +#38553 = ORIENTED_EDGE ( 'NONE', *, *, #16578, .F. ) ; +#38554 = FACE_OUTER_BOUND ( 'NONE', #15064, .T. ) ; +#38555 = ORIENTED_EDGE ( 'NONE', *, *, #15527, .F. ) ; +#38556 = EDGE_CURVE ( 'NONE', #39608, #23183, #2340, .T. ) ; +#38557 = DIRECTION ( 'NONE', ( 0.7933531821952553020, -0.5930539076840665169, -0.1373964733219922574 ) ) ; +#38558 = CARTESIAN_POINT ( 'NONE', ( 39.60379206711759537, 77.57075965540369111, 291.0398443752740718 ) ) ; +#38559 = CARTESIAN_POINT ( 'NONE', ( 3.655476994516294376, 175.3312194581858421, 100.2535053625421142 ) ) ; +#38560 = CARTESIAN_POINT ( 'NONE', ( 45.11849344886014990, 186.2994542042779074, 106.5243038294286180 ) ) ; +#38561 = EDGE_LOOP ( 'NONE', ( #35676, #37708, #208, #13112 ) ) ; +#38562 = CARTESIAN_POINT ( 'NONE', ( 21.05331647436627307, 136.0919339282447709, 93.96736470811812580 ) ) ; +#38563 = EDGE_CURVE ( 'NONE', #14638, #6589, #26383, .T. ) ; +#38564 = CARTESIAN_POINT ( 'NONE', ( 0.9394191060261165571, 189.0348601105310138, 103.6946623460256944 ) ) ; +#38565 = CARTESIAN_POINT ( 'NONE', ( 40.02829803166415701, 120.8820227754755905, 90.61547142951589251 ) ) ; +#38566 = ADVANCED_FACE ( 'NONE', ( #38662 ), #10682, .T. ) ; +#38567 = CARTESIAN_POINT ( 'NONE', ( 12.63719627440727677, 130.1455350695279662, 92.49286791247519091 ) ) ; +#38568 = CARTESIAN_POINT ( 'NONE', ( -26.13641317868000158, 191.6419861777999927, 103.7719022052999946 ) ) ; +#38569 = FACE_OUTER_BOUND ( 'NONE', #641, .T. ) ; +#38570 = DIRECTION ( 'NONE', ( 0.0005884949961247609718, -0.2249510543439061094, 0.9743698870671263501 ) ) ; +#38571 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#38572 = EDGE_CURVE ( 'NONE', #25314, #1172, #27249, .T. ) ; +#38573 = VECTOR ( 'NONE', #40176, 1000.000000000000000 ) ; +#38574 = AXIS2_PLACEMENT_3D ( 'NONE', #26061, #38118, #38313 ) ; +#38575 = CARTESIAN_POINT ( 'NONE', ( -15.99798258269242623, 173.8482551488953050, 102.8774467584792802 ) ) ; +#38576 = ORIENTED_EDGE ( 'NONE', *, *, #36064, .T. ) ; +#38577 = AXIS2_PLACEMENT_3D ( 'NONE', #37009, #9006, #27825 ) ; +#38578 = DIRECTION ( 'NONE', ( -0.0005884949961222141809, 0.2249510543439070531, -0.9743698870671262391 ) ) ; +#38579 = CARTESIAN_POINT ( 'NONE', ( -19.99931527105535878, 118.1256151686936420, 90.27945241601419468 ) ) ; +#38580 = ORIENTED_EDGE ( 'NONE', *, *, #7029, .T. ) ; +#38581 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927736883238, 0.0005734119022084779730 ) ) ; +#38582 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; +#38583 = CARTESIAN_POINT ( 'NONE', ( 37.38080420394999948, 190.2420884969000383, 106.7700743806000077 ) ) ; +#38584 = CARTESIAN_POINT ( 'NONE', ( 36.08394658407680566, 192.1911192938459862, 104.3432420703000076 ) ) ; +#38585 = CARTESIAN_POINT ( 'NONE', ( -1.762796035792233207, 151.6652447683722471, 130.5904578368917441 ) ) ; +#38586 = CARTESIAN_POINT ( 'NONE', ( -21.21399076556896546, 136.5867924462192207, 91.71243192711530412 ) ) ; +#38587 = ORIENTED_EDGE ( 'NONE', *, *, #9878, .F. ) ; +#38588 = CARTESIAN_POINT ( 'NONE', ( -45.35096104214093060, 123.9731305825091709, 91.38067696071810531 ) ) ; +#38589 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11473, #18782, #37422, #15543 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#38590 = CARTESIAN_POINT ( 'NONE', ( 20.50107847364380831, 184.5549759110466255, 104.1299709246699052 ) ) ; +#38591 = CARTESIAN_POINT ( 'NONE', ( 24.33241291692780806, 117.2920445016514748, 170.8609620625155117 ) ) ; +#38592 = CYLINDRICAL_SURFACE ( 'NONE', #22015, 2.000000000000014655 ) ; +#38593 = ORIENTED_EDGE ( 'NONE', *, *, #37291, .F. ) ; +#38594 = PLANE ( 'NONE', #4936 ) ; +#38595 = ORIENTED_EDGE ( 'NONE', *, *, #7545, .F. ) ; +#38596 = AXIS2_PLACEMENT_3D ( 'NONE', #3764, #10333, #18894 ) ; +#38597 = AXIS2_PLACEMENT_3D ( 'NONE', #9294, #28695, #80 ) ; +#38598 = CARTESIAN_POINT ( 'NONE', ( -34.28801115370752228, 89.15625349133107136, 280.9732277762227000 ) ) ; +#38599 = ORIENTED_EDGE ( 'NONE', *, *, #16135, .T. ) ; +#38600 = DIRECTION ( 'NONE', ( -0.0005884949961258157921, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#38601 = ADVANCED_FACE ( 'NONE', ( #15551 ), #2223, .F. ) ; +#38602 = ADVANCED_FACE ( 'NONE', ( #3070 ), #33341, .F. ) ; +#38604 = EDGE_CURVE ( 'NONE', #33023, #25308, #22340, .T. ) ; +#38603 = CARTESIAN_POINT ( 'NONE', ( 25.66578042932543013, 118.1143697066197262, 87.58559124276200691 ) ) ; +#38605 = CARTESIAN_POINT ( 'NONE', ( -23.36033136076990502, 129.9689112135512232, 92.23847830418463900 ) ) ; +#38606 = ADVANCED_FACE ( 'NONE', ( #14764 ), #24579, .F. ) ; +#38607 = FACE_OUTER_BOUND ( 'NONE', #1807, .T. ) ; +#38608 = ORIENTED_EDGE ( 'NONE', *, *, #18612, .F. ) ; +#38609 = FACE_OUTER_BOUND ( 'NONE', #38147, .T. ) ; +#38610 = CARTESIAN_POINT ( 'NONE', ( -4.973729523541181585, 177.5597541351575046, 100.6488263443078068 ) ) ; +#38611 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; +#38612 = EDGE_CURVE ( 'NONE', #24320, #14055, #5539, .T. ) ; +#38613 = CARTESIAN_POINT ( 'NONE', ( -6.272775202316941190, 163.3805630214683333, 99.94184687166684000 ) ) ; +#38614 = ORIENTED_EDGE ( 'NONE', *, *, #35817, .T. ) ; +#38615 = VERTEX_POINT ( 'NONE', #39883 ) ; +#38616 = FACE_OUTER_BOUND ( 'NONE', #20393, .T. ) ; +#38617 = EDGE_CURVE ( 'NONE', #16126, #22698, #21155, .T. ) ; +#38618 = CARTESIAN_POINT ( 'NONE', ( -20.00135284697726590, 137.8251893417238136, 91.48445388004111578 ) ) ; +#38619 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971552357 ) ) ; +#38620 = CIRCLE ( 'NONE', #1417, 1.999999999792658079 ) ; +#38621 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13411, #10550, #924, #32419 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#38622 = CARTESIAN_POINT ( 'NONE', ( -28.26067782467530520, 125.1269179218217857, 91.12357580992288320 ) ) ; +#38623 = AXIS2_PLACEMENT_3D ( 'NONE', #20622, #10833, #33087 ) ; +#38624 = CARTESIAN_POINT ( 'NONE', ( 28.46433317244940753, 130.4256741595737310, 90.26002097211915043 ) ) ; +#38625 = EDGE_CURVE ( 'NONE', #6048, #25223, #20797, .T. ) ; +#38626 = CIRCLE ( 'NONE', #117, 22.50000000000899902 ) ; +#38627 = CARTESIAN_POINT ( 'NONE', ( 82.74177079105341193, 105.0784892597221614, 24.20931121009731157 ) ) ; +#38628 = CARTESIAN_POINT ( 'NONE', ( 38.73759991229999855, 118.4494500935000048, 89.51229521514001419 ) ) ; +#38629 = EDGE_LOOP ( 'NONE', ( #25629, #9730, #19160, #20924 ) ) ; +#38630 = PLANE ( 'NONE', #14001 ) ; +#38631 = PLANE ( 'NONE', #608 ) ; +#38632 = DIRECTION ( 'NONE', ( 0.0006039748319395907457, 1.291365685536980287E-14, 0.9999998176071847045 ) ) ; +#38633 = DIRECTION ( 'NONE', ( 0.0005884949961246861618, -0.2249510543439068866, 0.9743698870671261281 ) ) ; +#38634 = ORIENTED_EDGE ( 'NONE', *, *, #1555, .T. ) ; +#38635 = ORIENTED_EDGE ( 'NONE', *, *, #5376, .T. ) ; +#38636 = VERTEX_POINT ( 'NONE', #11895 ) ; +#38637 = CARTESIAN_POINT ( 'NONE', ( 36.05442839919999898, 109.6131156806000035, 88.74600859430999833 ) ) ; +#38638 = LINE ( 'NONE', #35156, #12199 ) ; +#38639 = EDGE_LOOP ( 'NONE', ( #15552, #20049, #27076, #28399 ) ) ; +#38640 = FACE_BOUND ( 'NONE', #33285, .T. ) ; +#38641 = CARTESIAN_POINT ( 'NONE', ( -38.50870567158000313, 118.9338527051999961, 90.10241371018000223 ) ) ; +#38642 = CARTESIAN_POINT ( 'NONE', ( -38.88297749613000320, 119.5273426671000152, 87.63529162099999326 ) ) ; +#38643 = CARTESIAN_POINT ( 'NONE', ( 20.49908935505346719, 194.2769733015968541, 102.8866291927022303 ) ) ; +#38644 = CARTESIAN_POINT ( 'NONE', ( 16.57143971460371645, 121.7462941270641608, 177.4474421254334970 ) ) ; +#38645 = VERTEX_POINT ( 'NONE', #24379 ) ; +#38646 = CARTESIAN_POINT ( 'NONE', ( -19.46376836227414486, 126.0579724767783318, 176.8041766879045440 ) ) ; +#38647 = EDGE_CURVE ( 'NONE', #8964, #34749, #294, .T. ) ; +#38648 = CARTESIAN_POINT ( 'NONE', ( -24.25908385616899920, 115.9286338645677432, 89.78240454819975014 ) ) ; +#38649 = AXIS2_PLACEMENT_3D ( 'NONE', #26366, #29834, #19996 ) ; +#38650 = EDGE_CURVE ( 'NONE', #17689, #39586, #30286, .T. ) ; +#38651 = DIRECTION ( 'NONE', ( -0.0005884949961255136249, 0.2249510543439060539, -0.9743698870671263501 ) ) ; +#38652 = FACE_OUTER_BOUND ( 'NONE', #17943, .T. ) ; +#38653 = ORIENTED_EDGE ( 'NONE', *, *, #17414, .T. ) ; +#38654 = VECTOR ( 'NONE', #18627, 1000.000000000000227 ) ; +#38655 = EDGE_LOOP ( 'NONE', ( #34731, #35403, #163, #19472 ) ) ; +#38656 = CARTESIAN_POINT ( 'NONE', ( -20.16763707502682479, 193.9703149646331326, 102.7801441390361958 ) ) ; +#38657 = VECTOR ( 'NONE', #18509, 1000.000000000000114 ) ; +#38658 = LINE ( 'NONE', #29682, #32931 ) ; +#38659 = CARTESIAN_POINT ( 'NONE', ( -116.6809178989064293, 205.2853165843886245, 191.1682151682985307 ) ) ; +#38660 = EDGE_CURVE ( 'NONE', #27307, #16595, #24228, .T. ) ; +#38661 = VERTEX_POINT ( 'NONE', #9026 ) ; +#38662 = FACE_OUTER_BOUND ( 'NONE', #35838, .T. ) ; +#38663 = CARTESIAN_POINT ( 'NONE', ( -23.41147556997512780, 214.0900415524863263, 76.07246192447139777 ) ) ; +#38664 = ORIENTED_EDGE ( 'NONE', *, *, #15556, .F. ) ; +#38665 = EDGE_CURVE ( 'NONE', #32373, #34215, #34870, .T. ) ; +#38666 = ORIENTED_EDGE ( 'NONE', *, *, #442, .F. ) ; +#38667 = ORIENTED_EDGE ( 'NONE', *, *, #28430, .T. ) ; +#38668 = CARTESIAN_POINT ( 'NONE', ( -26.38221732644195328, 189.9151541007786648, 103.5142258954548993 ) ) ; +#38669 = DIRECTION ( 'NONE', ( -0.9914447795421099663, 0.1270909273343945323, 0.02975139169821508847 ) ) ; +#38670 = CARTESIAN_POINT ( 'NONE', ( 24.86314881519125919, 182.1858644890795063, 102.2119796893761503 ) ) ; +#38671 = CARTESIAN_POINT ( 'NONE', ( -20.00004361580415591, 118.8155695144462669, 87.27991261026372172 ) ) ; +#38672 = EDGE_CURVE ( 'NONE', #20371, #30524, #30904, .T. ) ; +#38673 = EDGE_LOOP ( 'NONE', ( #35973, #6788 ) ) ; +#38674 = AXIS2_PLACEMENT_3D ( 'NONE', #30925, #40307, #36444 ) ; +#38675 = ORIENTED_EDGE ( 'NONE', *, *, #9840, .F. ) ; +#38676 = CARTESIAN_POINT ( 'NONE', ( 26.01213538887559906, 120.4375336583399871, 90.52293421452910138 ) ) ; +#38677 = CARTESIAN_POINT ( 'NONE', ( -26.00133086711789687, 118.1131156701862892, 87.28349311522542564 ) ) ; +#38678 = AXIS2_PLACEMENT_3D ( 'NONE', #4209, #15882, #13039 ) ; +#38680 = CARTESIAN_POINT ( 'NONE', ( -13.49836365434320484, 188.0284789784863619, 103.3392430051065531 ) ) ; +#38679 = CARTESIAN_POINT ( 'NONE', ( 20.48253891412411321, 207.4083879957671002, 77.06951181954761410 ) ) ; +#38681 = ORIENTED_EDGE ( 'NONE', *, *, #6909, .T. ) ; +#38682 = ORIENTED_EDGE ( 'NONE', *, *, #20945, .F. ) ; +#38683 = CARTESIAN_POINT ( 'NONE', ( -36.09391041316947479, 191.9872661771537139, 104.4222228648927739 ) ) ; +#38684 = PLANE ( 'NONE', #13613 ) ; +#38685 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13400, #16839, #38332, #10342 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.0005627318540861992423 ), + .UNSPECIFIED. ) ; +#38686 = VERTEX_POINT ( 'NONE', #12291 ) ; +#38687 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#38688 = CARTESIAN_POINT ( 'NONE', ( 15.50147165555466522, 173.9550007109359342, 102.3699975152791239 ) ) ; +#38689 = CARTESIAN_POINT ( 'NONE', ( -20.51870197069307977, 210.1700258258141503, 75.57088353280735760 ) ) ; +#38690 = CARTESIAN_POINT ( 'NONE', ( -45.44849478851434554, 124.1418171532125712, 91.75068805776987801 ) ) ; +#38691 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927757477116, -0.0005734119022080025503 ) ) ; +#38692 = VERTEX_POINT ( 'NONE', #24778 ) ; +#38693 = VERTEX_POINT ( 'NONE', #9230 ) ; +#38694 = ORIENTED_EDGE ( 'NONE', *, *, #27708, .T. ) ; +#38695 = FACE_OUTER_BOUND ( 'NONE', #18605, .T. ) ; +#38696 = ADVANCED_FACE ( 'NONE', ( #12898 ), #22100, .F. ) ; +#38697 = ORIENTED_EDGE ( 'NONE', *, *, #34371, .T. ) ; +#38698 = ORIENTED_EDGE ( 'NONE', *, *, #20290, .F. ) ; +#38699 = CARTESIAN_POINT ( 'NONE', ( -35.76980907163999746, 192.7327729514000225, 106.5479348372000032 ) ) ; +#38700 = CIRCLE ( 'NONE', #13276, 59.40509898896999630 ) ; +#38701 = CARTESIAN_POINT ( 'NONE', ( -38.24380932803833844, 118.2428607222824297, 89.71149949636749454 ) ) ; +#38702 = VECTOR ( 'NONE', #27724, 1000.000000000000114 ) ; +#38703 = CARTESIAN_POINT ( 'NONE', ( 3.069914059221602542, 190.8760762271834039, 106.8043974371660738 ) ) ; +#38704 = ORIENTED_EDGE ( 'NONE', *, *, #6875, .F. ) ; +#38705 = CARTESIAN_POINT ( 'NONE', ( -30.07340899595924100, 135.1666636124964498, 91.22132312044659841 ) ) ; +#38706 = CARTESIAN_POINT ( 'NONE', ( 29.20104124104027576, 148.3999055379004517, 96.97501579703776997 ) ) ; +#38707 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; +#38708 = DIRECTION ( 'NONE', ( 0.0006039748319361434165, 0.000000000000000000, 0.9999998176071844824 ) ) ; +#38709 = EDGE_LOOP ( 'NONE', ( #12580, #28065, #23400, #12988 ) ) ; +#38710 = EDGE_LOOP ( 'NONE', ( #5388, #10891, #27644, #19130 ) ) ; +#38711 = DIRECTION ( 'NONE', ( 0.0005884949961216828134, -0.2249510543439096344, 0.9743698870671254619 ) ) ; +#38712 = CARTESIAN_POINT ( 'NONE', ( -22.98725314475650450, 177.7874483475983709, 100.7122734217378053 ) ) ; +#38713 = CARTESIAN_POINT ( 'NONE', ( 26.00894374567046441, 191.9425530329557716, 103.9054621679136261 ) ) ; +#38714 = ADVANCED_FACE ( 'NONE', ( #7139 ), #10026, .F. ) ; +#38715 = CARTESIAN_POINT ( 'NONE', ( -42.47220679908992480, 189.9442792002049316, 106.2657712603332385 ) ) ; +#38716 = ORIENTED_EDGE ( 'NONE', *, *, #35093, .F. ) ; +#38717 = CARTESIAN_POINT ( 'NONE', ( 32.50483906253111144, 78.62122269805516339, 290.8219053273109012 ) ) ; +#38718 = CARTESIAN_POINT ( 'NONE', ( -37.94605339308999703, 118.0983039059999982, 89.85439327327999592 ) ) ; +#38719 = VERTEX_POINT ( 'NONE', #13294 ) ; +#38720 = CARTESIAN_POINT ( 'NONE', ( -20.16498553255008730, 118.8155446846155030, 90.11323255110787045 ) ) ; +#38721 = VECTOR ( 'NONE', #28199, 1000.000000000000227 ) ; +#38722 = CARTESIAN_POINT ( 'NONE', ( 38.57273346403590608, 118.4650864938980277, 89.66263907190824511 ) ) ; +#38723 = ORIENTED_EDGE ( 'NONE', *, *, #18967, .F. ) ; +#38724 = CARTESIAN_POINT ( 'NONE', ( 46.08267618988084280, 184.7865884867546242, 107.4179575081553253 ) ) ; +#38725 = ADVANCED_FACE ( 'NONE', ( #28829 ), #3665, .F. ) ; +#38726 = FACE_OUTER_BOUND ( 'NONE', #29561, .T. ) ; +#38727 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251395983, 176.9829762288560744, 103.0892940378084432 ) ) ; +#38729 = ORIENTED_EDGE ( 'NONE', *, *, #18862, .T. ) ; +#38728 = AXIS2_PLACEMENT_3D ( 'NONE', #4751, #30116, #13763 ) ; +#38730 = ORIENTED_EDGE ( 'NONE', *, *, #2538, .F. ) ; +#38731 = CARTESIAN_POINT ( 'NONE', ( -42.58663445218865462, 120.8392962345444062, 90.80939073592341515 ) ) ; +#38732 = VERTEX_POINT ( 'NONE', #24976 ) ; +#38733 = EDGE_LOOP ( 'NONE', ( #16072, #14169, #31126, #36795 ) ) ; +#38734 = CARTESIAN_POINT ( 'NONE', ( 46.08149919947196338, 185.2364907546973711, 105.4692170442124279 ) ) ; +#38735 = ADVANCED_FACE ( 'NONE', ( #13096 ), #16150, .T. ) ; +#38736 = AXIS2_PLACEMENT_3D ( 'NONE', #1039, #17173, #7374 ) ; +#38737 = DIRECTION ( 'NONE', ( -0.0004272100170959573784, 0.7071067811864920616, -0.7071066521336647481 ) ) ; +#38738 = ORIENTED_EDGE ( 'NONE', *, *, #4544, .T. ) ; +#38739 = PLANE ( 'NONE', #23932 ) ; +#38740 = ADVANCED_FACE ( 'NONE', ( #32106 ), #15934, .T. ) ; +#38741 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; +#38742 = CARTESIAN_POINT ( 'NONE', ( -25.49000752893273614, 191.9759150222000130, 106.4368436005040479 ) ) ; +#38743 = EDGE_CURVE ( 'NONE', #30903, #7054, #25775, .T. ) ; +#38744 = DIRECTION ( 'NONE', ( -0.7933530821293339752, -0.5932640870757631690, -0.1364866662427065558 ) ) ; +#38745 = ADVANCED_FACE ( 'NONE', ( #38229 ), #6534, .F. ) ; +#38746 = ORIENTED_EDGE ( 'NONE', *, *, #15653, .T. ) ; +#38747 = CARTESIAN_POINT ( 'NONE', ( -82.80843920860921514, 105.1411378422745315, 24.32376295616780482 ) ) ; +#38748 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 0.000000000000000000 ) ) ; +#38749 = CARTESIAN_POINT ( 'NONE', ( -28.70758035546699460, 163.1500623791996816, 99.90218165579484833 ) ) ; +#38750 = ORIENTED_EDGE ( 'NONE', *, *, #27808, .T. ) ; +#38751 = CARTESIAN_POINT ( 'NONE', ( -6.042234299931061869, 134.2432640563548318, 93.72802809502178434 ) ) ; +#38752 = CARTESIAN_POINT ( 'NONE', ( 14.42706621632168229, 176.1815076080119127, 103.2267775782339925 ) ) ; +#38753 = CARTESIAN_POINT ( 'NONE', ( -12.60649365401999944, 163.2729245447999915, 152.4718672074000381 ) ) ; +#38754 = CARTESIAN_POINT ( 'NONE', ( 44.93442337153953758, 186.4047720418488723, 107.1349748693987038 ) ) ; +#38755 = ORIENTED_EDGE ( 'NONE', *, *, #15074, .T. ) ; +#38756 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; +#38757 = CARTESIAN_POINT ( 'NONE', ( 2.039013461118012849, 189.6457011487741511, 103.8698668457489021 ) ) ; +#38758 = AXIS2_PLACEMENT_3D ( 'NONE', #29402, #37989, #32071 ) ; +#38759 = CARTESIAN_POINT ( 'NONE', ( -15.99992728601997527, 142.7916292484897838, 92.62870526400769222 ) ) ; +#38760 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#38761 = CIRCLE ( 'NONE', #6122, 4.999999999999990230 ) ; +#38762 = CARTESIAN_POINT ( 'NONE', ( -25.61429564027000083, 191.7252838869000016, 104.3010191375000062 ) ) ; +#38763 = CARTESIAN_POINT ( 'NONE', ( 23.36366901687428310, 174.6829506628683930, 103.0496233664125754 ) ) ; +#38764 = CARTESIAN_POINT ( 'NONE', ( 25.37591215464999905, 192.1184558962999915, 104.5441819273000021 ) ) ; +#38765 = CARTESIAN_POINT ( 'NONE', ( -35.95405601968200671, 218.5902260770999987, 76.08021997850752882 ) ) ; +#38766 = AXIS2_PLACEMENT_3D ( 'NONE', #37324, #11022, #5266 ) ; +#38767 = FACE_OUTER_BOUND ( 'NONE', #4595, .T. ) ; +#38768 = ORIENTED_EDGE ( 'NONE', *, *, #26039, .F. ) ; +#38769 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17028, #23195, #38918, #4369 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 4.196392522635492678E-05, 0.004030228606235266263 ), + .UNSPECIFIED. ) ; +#38770 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989941907, 0.1373964268091566465 ) ) ; +#38771 = DIRECTION ( 'NONE', ( -0.9914446600486714889, 0.1270322995874082761, 0.03000468167652007440 ) ) ; +#38772 = CARTESIAN_POINT ( 'NONE', ( -20.16502541160679485, 119.7528545781853779, 90.22005970173493949 ) ) ; +#38773 = ADVANCED_FACE ( 'NONE', ( #35126 ), #34524, .T. ) ; +#38774 = LINE ( 'NONE', #4230, #18260 ) ; +#38775 = CARTESIAN_POINT ( 'NONE', ( 36.08395067039340631, 192.1917151384730005, 104.3500077209999972 ) ) ; +#38776 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -4.622231866529367416E-33, 0.0006039748319394906738 ) ) ; +#38777 = CARTESIAN_POINT ( 'NONE', ( 13.50184736293237542, 188.1187807092373987, 103.2695674776543484 ) ) ; +#38778 = ORIENTED_EDGE ( 'NONE', *, *, #28394, .T. ) ; +#38779 = VECTOR ( 'NONE', #10642, 1000.000000000000114 ) ; +#38780 = ORIENTED_EDGE ( 'NONE', *, *, #13073, .T. ) ; +#38781 = CARTESIAN_POINT ( 'NONE', ( -2.370968452985501962, 209.5715231741518210, 75.55993778019829676 ) ) ; +#38782 = EDGE_CURVE ( 'NONE', #1537, #25244, #13332, .T. ) ; +#38783 = VECTOR ( 'NONE', #24327, 1000.000000000000114 ) ; +#38784 = CARTESIAN_POINT ( 'NONE', ( 19.99933118494021755, 196.5785306413737601, 103.8628508136982731 ) ) ; +#38785 = VECTOR ( 'NONE', #33551, 1000.000000000000000 ) ; +#38786 = ADVANCED_FACE ( 'NONE', ( #12681 ), #37431, .F. ) ; +#38787 = DIRECTION ( 'NONE', ( 0.0004161288024508938573, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#38788 = ORIENTED_EDGE ( 'NONE', *, *, #31766, .F. ) ; +#38789 = CARTESIAN_POINT ( 'NONE', ( -39.51513552280039931, 119.6153294146334929, 90.20002341431117543 ) ) ; +#38790 = CARTESIAN_POINT ( 'NONE', ( 3.587153585141939605, 136.6967892697166462, 94.23604787298746999 ) ) ; +#38791 = EDGE_CURVE ( 'NONE', #26229, #6484, #36170, .T. ) ; +#38792 = ORIENTED_EDGE ( 'NONE', *, *, #23721, .F. ) ; +#38793 = ADVANCED_FACE ( 'NONE', ( #6940 ), #28434, .T. ) ; +#38794 = EDGE_CURVE ( 'NONE', #5278, #37162, #31294, .T. ) ; +#38795 = CARTESIAN_POINT ( 'NONE', ( 20.49882255135672793, 191.9760415900621808, 101.9090510850346476 ) ) ; +#38796 = ORIENTED_EDGE ( 'NONE', *, *, #18216, .T. ) ; +#38797 = CARTESIAN_POINT ( 'NONE', ( 36.48557081826953663, 191.5952041950502860, 106.3706920858186180 ) ) ; +#38798 = DIRECTION ( 'NONE', ( -0.0006039748319382295299, 5.238646599373848640E-18, -0.9999998176071845934 ) ) ; +#38799 = CARTESIAN_POINT ( 'NONE', ( 25.49921019565536184, 118.1133140256443426, 87.75227232668940758 ) ) ; +#38800 = CARTESIAN_POINT ( 'NONE', ( -12.63400679888185785, 130.2556748615208448, 92.68897315470272247 ) ) ; +#38801 = CARTESIAN_POINT ( 'NONE', ( -37.15110912804633614, 71.94901892143192867, 323.0119659673088677 ) ) ; +#38802 = CARTESIAN_POINT ( 'NONE', ( -3.668404236601097601, 185.3449489774860979, 105.0111528754605530 ) ) ; +#38803 = ORIENTED_EDGE ( 'NONE', *, *, #22810, .T. ) ; +#38804 = LINE ( 'NONE', #35724, #39590 ) ; +#38805 = DIRECTION ( 'NONE', ( 0.7075229308291650643, 0.000000000000000000, 0.7066903864854172657 ) ) ; +#38806 = PLANE ( 'NONE', #35789 ) ; +#38807 = ORIENTED_EDGE ( 'NONE', *, *, #35704, .F. ) ; +#38808 = CARTESIAN_POINT ( 'NONE', ( -20.01736593119981222, 207.8686407175673594, 77.28911966098117148 ) ) ; +#38809 = VERTEX_POINT ( 'NONE', #34928 ) ; +#38810 = DIRECTION ( 'NONE', ( -0.6087614115774880874, -0.7729348350621346730, -0.1788331191967953981 ) ) ; +#38811 = CC_DESIGN_APPROVAL ( #17932, ( #37519 ) ) ; +#38812 = AXIS2_PLACEMENT_3D ( 'NONE', #39181, #17701, #14458 ) ; +#38813 = CARTESIAN_POINT ( 'NONE', ( -3.893460979042753678, 148.0324882923159464, 129.7501302153316090 ) ) ; +#38814 = CARTESIAN_POINT ( 'NONE', ( 5.015789737050391217, 130.9602074356647847, 89.88443790896025121 ) ) ; +#38815 = CIRCLE ( 'NONE', #39466, 2.000000000000011546 ) ; +#38816 = VECTOR ( 'NONE', #3861, 1000.000000000000000 ) ; +#38817 = DIRECTION ( 'NONE', ( -0.0006039748319379697550, -1.040973592985965549E-14, -0.9999998176071845934 ) ) ; +#38818 = LINE ( 'NONE', #3871, #17786 ) ; +#38819 = CONICAL_SURFACE ( 'NONE', #21224, 6.000000000011051604, 0.7853981633778843729 ) ; +#38820 = DIRECTION ( 'NONE', ( -0.0005884949961216158097, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#38821 = CARTESIAN_POINT ( 'NONE', ( 26.14344731694000146, 191.2796326829000009, 106.9994950030999945 ) ) ; +#38822 = CARTESIAN_POINT ( 'NONE', ( 20.48021663872660625, 209.7101073659619601, 73.54617496015868028 ) ) ; +#38823 = CARTESIAN_POINT ( 'NONE', ( 38.58832625067999800, 118.9641734523000025, 90.10804234095999732 ) ) ; +#38824 = VERTEX_POINT ( 'NONE', #28241 ) ; +#38825 = ADVANCED_FACE ( 'NONE', ( #37626 ), #19841, .F. ) ; +#38826 = CARTESIAN_POINT ( 'NONE', ( 15.68164426048544691, 125.5719652010231471, 88.63402203514193900 ) ) ; +#38827 = LINE ( 'NONE', #34792, #36141 ) ; +#38828 = PLANE ( 'NONE', #25118 ) ; +#38829 = EDGE_CURVE ( 'NONE', #16448, #4624, #23785, .T. ) ; +#38830 = CARTESIAN_POINT ( 'NONE', ( 15.94070757266567995, 152.8237909711254190, 181.6389010276846818 ) ) ; +#38831 = DIRECTION ( 'NONE', ( -1.117039843155982209E-18, -1.000000000000000000, 1.110223092091563281E-14 ) ) ; +#38832 = EDGE_CURVE ( 'NONE', #23778, #27521, #8157, .T. ) ; +#38833 = LINE ( 'NONE', #7560, #6250 ) ; +#38834 = ORIENTED_EDGE ( 'NONE', *, *, #20896, .F. ) ; +#38835 = VERTEX_POINT ( 'NONE', #13686 ) ; +#38836 = EDGE_CURVE ( 'NONE', #6773, #26891, #32529, .T. ) ; +#38837 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( + ( #37311, #21982, #17867, #11769 ), + ( #21387, #36908, #27538, #15624 ), + ( #39964, #33828, #24659, #16615 ), + ( #31984, #13574, #25860, #28910 ), + ( #28314, #31790, #16223, #22783 ), + ( #19687, #280, #28711, #29114 ), + ( #26054, #12766, #19085, #25458 ), + ( #9706, #6610, #9914, #6815 ), + ( #20709, #39302, #20298, #10920 ), + ( #17216, #35608, #4554, #1704 ), + ( #17628, #39101, #11509, #36031 ), + ( #13768, #29920, #1908, #23784 ), + ( #36241, #33165, #5154, #30119 ) ), + .UNSPECIFIED., .F., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), + ( 4, 4 ), + ( -0.01999999998011999999, 0.000000000000000000, 0.2499829833937000090, 0.4999876733701000275, 0.7499923633463999595, 0.9999960213830000333, 1.000000000000000000, 1.010000000003000054, 1.012500000004000089, 1.015000000004999903, 1.020000000006999974 ), + ( 0.1710241378436999915, 0.8289761189929000240 ), + .UNSPECIFIED. ) ; +#38838 = VERTEX_POINT ( 'NONE', #33090 ) ; +#38839 = DIRECTION ( 'NONE', ( 0.0005884949961231208991, -0.2249510543439063315, 0.9743698870671262391 ) ) ; +#38840 = EDGE_CURVE ( 'NONE', #3287, #1872, #4193, .T. ) ; +#38841 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; +#38842 = CARTESIAN_POINT ( 'NONE', ( 5.667111978802364725, 124.2427620186889925, 90.94114045841693894 ) ) ; +#38843 = ORIENTED_EDGE ( 'NONE', *, *, #8830, .T. ) ; +#38844 = AXIS2_PLACEMENT_3D ( 'NONE', #2539, #19468, #28686 ) ; +#38845 = FACE_BOUND ( 'NONE', #39284, .T. ) ; +#38846 = EDGE_CURVE ( 'NONE', #21808, #25434, #12051, .T. ) ; +#38847 = CARTESIAN_POINT ( 'NONE', ( -37.76330523427410668, 161.5949354398074433, 190.7626080688544619 ) ) ; +#38848 = CARTESIAN_POINT ( 'NONE', ( -27.84084126295215000, 134.9153899916640000, 90.81744799035887183 ) ) ; +#38849 = CARTESIAN_POINT ( 'NONE', ( -39.43595796038999879, 119.9338082146999938, 87.70772880011000439 ) ) ; +#38850 = FACE_OUTER_BOUND ( 'NONE', #26603, .T. ) ; +#38851 = AXIS2_PLACEMENT_3D ( 'NONE', #26322, #38973, #17079 ) ; +#38852 = CARTESIAN_POINT ( 'NONE', ( -37.03565995587000970, 117.3953279389999977, 87.62651510543000200 ) ) ; +#38853 = ORIENTED_EDGE ( 'NONE', *, *, #39501, .T. ) ; +#38854 = CONICAL_SURFACE ( 'NONE', #29832, 2.503000000187090901, 0.7853981634530804445 ) ; +#38855 = CARTESIAN_POINT ( 'NONE', ( 3.667815738790128677, 185.3461555468956590, 105.0070005413519993 ) ) ; +#38856 = ORIENTED_EDGE ( 'NONE', *, *, #20059, .F. ) ; +#38857 = PLANE ( 'NONE', #32496 ) ; +#38858 = AXIS2_PLACEMENT_3D ( 'NONE', #6315, #37795, #12654 ) ; +#38859 = CARTESIAN_POINT ( 'NONE', ( -16.11981483129142134, 123.6845644638803208, 173.7931095964873691 ) ) ; +#38860 = CARTESIAN_POINT ( 'NONE', ( 45.24519689809859813, 116.5437060779667036, 124.8975000631534158 ) ) ; +#38861 = ADVANCED_FACE ( 'NONE', ( #7950 ), #29841, .T. ) ; +#38862 = ORIENTED_EDGE ( 'NONE', *, *, #6525, .T. ) ; +#38863 = CARTESIAN_POINT ( 'NONE', ( -1.429285596916000101, 189.2366507591000016, 103.7539362638000000 ) ) ; +#38864 = CARTESIAN_POINT ( 'NONE', ( 25.49183330667664293, 209.2218471681004530, 75.54326001368504251 ) ) ; +#38865 = CARTESIAN_POINT ( 'NONE', ( 28.47200544777919262, 130.2255745777155767, 92.60852335989604001 ) ) ; +#38866 = CARTESIAN_POINT ( 'NONE', ( 31.05302410638193678, 145.1862230213489511, 291.5397886867950206 ) ) ; +#38867 = ORIENTED_EDGE ( 'NONE', *, *, #6715, .F. ) ; +#38868 = CARTESIAN_POINT ( 'NONE', ( -25.49003114136341352, 191.3825488810288107, 106.3975518461934371 ) ) ; +#38869 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319350685384 ) ) ; +#38870 = ORIENTED_EDGE ( 'NONE', *, *, #5754, .T. ) ; +#38871 = ORIENTED_EDGE ( 'NONE', *, *, #11907, .T. ) ; +#38872 = ORIENTED_EDGE ( 'NONE', *, *, #31070, .F. ) ; +#38873 = ORIENTED_EDGE ( 'NONE', *, *, #29624, .T. ) ; +#38874 = AXIS2_PLACEMENT_3D ( 'NONE', #37049, #24797, #1427 ) ; +#38875 = LINE ( 'NONE', #29490, #1644 ) ; +#38876 = CARTESIAN_POINT ( 'NONE', ( -20.01179132838112551, 204.1052452926227261, 86.15514299590407177 ) ) ; +#38877 = AXIS2_PLACEMENT_3D ( 'NONE', #11381, #17904, #26736 ) ; +#38878 = ORIENTED_EDGE ( 'NONE', *, *, #19999, .T. ) ; +#38880 = CONICAL_SURFACE ( 'NONE', #14747, 5.499999999948422591, 0.7853981634197699790 ) ; +#38879 = CARTESIAN_POINT ( 'NONE', ( 31.91041241775748105, 138.0070370287062644, 92.00823547631698318 ) ) ; +#38881 = CIRCLE ( 'NONE', #4258, 4.500000000003897327 ) ; +#38882 = VERTEX_POINT ( 'NONE', #23297 ) ; +#38883 = VECTOR ( 'NONE', #11357, 1000.000000000000000 ) ; +#38884 = CARTESIAN_POINT ( 'NONE', ( 26.00422603943780686, 120.1012956696319947, 90.44720422082960454 ) ) ; +#38885 = EDGE_CURVE ( 'NONE', #17944, #6941, #15919, .T. ) ; +#38886 = CARTESIAN_POINT ( 'NONE', ( -14.16977583430312926, 135.9878589137828726, 91.56990267135316230 ) ) ; +#38887 = EDGE_CURVE ( 'NONE', #13652, #34680, #38421, .T. ) ; +#38888 = AXIS2_PLACEMENT_3D ( 'NONE', #37218, #6129, #31090 ) ; +#38889 = EDGE_CURVE ( 'NONE', #38838, #4989, #39432, .T. ) ; +#38891 = CARTESIAN_POINT ( 'NONE', ( -13.49877723215485226, 188.1557838371874709, 103.2596942952441736 ) ) ; +#38890 = CARTESIAN_POINT ( 'NONE', ( 20.48150073456040232, 209.0342438232059692, 75.63892168965546148 ) ) ; +#38892 = ORIENTED_EDGE ( 'NONE', *, *, #36075, .F. ) ; +#38893 = ORIENTED_EDGE ( 'NONE', *, *, #32799, .F. ) ; +#38894 = ADVANCED_FACE ( 'NONE', ( #26181 ), #4678, .F. ) ; +#38895 = CARTESIAN_POINT ( 'NONE', ( -36.13178510555328415, 191.9453641854885859, 104.4190089974630808 ) ) ; +#38896 = FACE_OUTER_BOUND ( 'NONE', #20086, .T. ) ; +#38897 = EDGE_LOOP ( 'NONE', ( #37644, #20040, #39729, #29663 ) ) ; +#38898 = LINE ( 'NONE', #19880, #4117 ) ; +#38899 = ADVANCED_FACE ( 'NONE', ( #38616 ), #6800, .F. ) ; +#38900 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15100, #33890, #28187, #9168 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#38901 = CARTESIAN_POINT ( 'NONE', ( 39.35815683041339952, 128.4401884161088958, 92.36081652595443359 ) ) ; +#38902 = VERTEX_POINT ( 'NONE', #39021 ) ; +#38903 = EDGE_LOOP ( 'NONE', ( #21582, #39854, #38407, #4937 ) ) ; +#38904 = AXIS2_PLACEMENT_3D ( 'NONE', #530, #13025, #13424 ) ; +#38905 = CARTESIAN_POINT ( 'NONE', ( 20.48021663872660625, 209.7101073659619601, 73.54617496015868028 ) ) ; +#38906 = CARTESIAN_POINT ( 'NONE', ( -2.604557554923932816, 194.1237596199664779, 102.8347267027521497 ) ) ; +#38907 = VECTOR ( 'NONE', #19318, 1000.000000000000114 ) ; +#38908 = ORIENTED_EDGE ( 'NONE', *, *, #19491, .F. ) ; +#38909 = CARTESIAN_POINT ( 'NONE', ( -35.76774411862999870, 192.5904637550000018, 106.5722673717000077 ) ) ; +#38910 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2497, #14773, #27258, #14966 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.003386932291534215222 ), + .UNSPECIFIED. ) ; +#38911 = AXIS2_PLACEMENT_3D ( 'NONE', #37848, #9857, #28064 ) ; +#38912 = VECTOR ( 'NONE', #12515, 1000.000000000000114 ) ; +#38913 = CARTESIAN_POINT ( 'NONE', ( 2.897735416623014704, 190.9277563016652550, 106.6392879545087453 ) ) ; +#38914 = ORIENTED_EDGE ( 'NONE', *, *, #9925, .F. ) ; +#38915 = CARTESIAN_POINT ( 'NONE', ( 38.98506659676601060, 118.8295563346720769, 89.67030295764752168 ) ) ; +#38916 = FACE_OUTER_BOUND ( 'NONE', #1733, .T. ) ; +#38917 = DIRECTION ( 'NONE', ( -1.433424368938233622E-14, -0.9743700557873516965, -0.2249510933179768024 ) ) ; +#38918 = CARTESIAN_POINT ( 'NONE', ( 44.04052364156038379, 178.1055087129866479, 148.0270100442815817 ) ) ; +#38919 = ORIENTED_EDGE ( 'NONE', *, *, #35373, .F. ) ; +#38920 = ORIENTED_EDGE ( 'NONE', *, *, #6032, .T. ) ; +#38921 = CARTESIAN_POINT ( 'NONE', ( -16.68652574534681321, 121.9722270641570390, 177.8556191836182450 ) ) ; +#38922 = DIRECTION ( 'NONE', ( 1.437432060320536772E-10, -0.9743700558244570153, -0.2249510931572557271 ) ) ; +#38923 = CARTESIAN_POINT ( 'NONE', ( -0.02657825335728297364, 128.5632152146144449, 291.5585599878308471 ) ) ; +#38924 = VERTEX_POINT ( 'NONE', #4877 ) ; +#38925 = AXIS2_PLACEMENT_3D ( 'NONE', #3468, #15369, #33959 ) ; +#38926 = DIRECTION ( 'NONE', ( 0.0005884949671858177161, -0.2249510543353067382, 0.9743698870691291924 ) ) ; +#38927 = EDGE_CURVE ( 'NONE', #22341, #27218, #32276, .T. ) ; +#38928 = EDGE_CURVE ( 'NONE', #2746, #19509, #1208, .T. ) ; +#38929 = AXIS2_PLACEMENT_3D ( 'NONE', #35858, #4792, #17251 ) ; +#38930 = VECTOR ( 'NONE', #26996, 1000.000000000000000 ) ; +#38932 = CARTESIAN_POINT ( 'NONE', ( -38.02385641131999705, 118.5542190637000033, 90.14964594503000228 ) ) ; +#38931 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971571786 ) ) ; +#38933 = ORIENTED_EDGE ( 'NONE', *, *, #5150, .T. ) ; +#38934 = CARTESIAN_POINT ( 'NONE', ( 38.57701359922251072, 118.4688917518772513, 89.66257366145818253 ) ) ; +#38935 = VERTEX_POINT ( 'NONE', #20006 ) ; +#38937 = VECTOR ( 'NONE', #6711, 1000.000000000000114 ) ; +#38936 = CARTESIAN_POINT ( 'NONE', ( -19.99829785685910011, 119.7153791177249502, 90.38236254249699186 ) ) ; +#38938 = LINE ( 'NONE', #23016, #6255 ) ; +#38939 = CARTESIAN_POINT ( 'NONE', ( 37.82795171624675845, 190.9635177071786813, 106.2837781323803341 ) ) ; +#38940 = CARTESIAN_POINT ( 'NONE', ( -3.418257151934999793, 127.0749628277000056, 91.81488911481000059 ) ) ; +#38941 = VECTOR ( 'NONE', #29187, 1000.000000000000114 ) ; +#38942 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -3.370379598151327408E-34, 0.0006039748319386880390 ) ) ; +#38943 = VERTEX_POINT ( 'NONE', #1409 ) ; +#38944 = ORIENTED_EDGE ( 'NONE', *, *, #35921, .T. ) ; +#38945 = CARTESIAN_POINT ( 'NONE', ( -3.669803043821980637, 182.6274357622465914, 101.8180055092276035 ) ) ; +#38946 = ORIENTED_EDGE ( 'NONE', *, *, #36268, .F. ) ; +#38947 = ORIENTED_EDGE ( 'NONE', *, *, #35227, .T. ) ; +#38948 = CARTESIAN_POINT ( 'NONE', ( -33.70405643010219876, 218.5902260770999987, 76.07886103507885878 ) ) ; +#38949 = PLANE ( 'NONE', #25676 ) ; +#38950 = CARTESIAN_POINT ( 'NONE', ( 30.77752414631618194, 157.1438219166013823, 186.2335371180630830 ) ) ; +#38951 = CARTESIAN_POINT ( 'NONE', ( -2.946865378000000035, 209.3288521576999983, 76.09373086713999612 ) ) ; +#38952 = VERTEX_POINT ( 'NONE', #29638 ) ; +#38953 = CARTESIAN_POINT ( 'NONE', ( 1.447658035571014024, 144.9407251426433447, 129.0349007182348657 ) ) ; +#38954 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; +#38955 = PLANE ( 'NONE', #39133 ) ; +#38956 = CARTESIAN_POINT ( 'NONE', ( 25.83261180745369145, 120.1051782784308841, 90.24386527476539754 ) ) ; +#38957 = CARTESIAN_POINT ( 'NONE', ( -25.83466592350999846, 120.7331548140000024, 87.71422404701002051 ) ) ; +#38958 = EDGE_CURVE ( 'NONE', #23946, #14571, #2249, .T. ) ; +#38959 = ORIENTED_EDGE ( 'NONE', *, *, #22063, .F. ) ; +#38960 = CARTESIAN_POINT ( 'NONE', ( -35.93657502954287253, 192.7057404805565568, 106.3835757455632063 ) ) ; +#38961 = CARTESIAN_POINT ( 'NONE', ( 0.5984374266184000479, 191.0000000000000000, 162.9824824849000322 ) ) ; +#38962 = ORIENTED_EDGE ( 'NONE', *, *, #31292, .T. ) ; +#38963 = CIRCLE ( 'NONE', #18052, 2.499999999996476152 ) ; +#38964 = CARTESIAN_POINT ( 'NONE', ( -20.51799340739946942, 207.9362841214596358, 76.29088018949011030 ) ) ; +#38965 = CARTESIAN_POINT ( 'NONE', ( 16.42900653985290660, 122.6518335374459809, 174.4917712166376873 ) ) ; +#38966 = CIRCLE ( 'NONE', #19384, 10.00000000000000888 ) ; +#38967 = CARTESIAN_POINT ( 'NONE', ( -6.272775202316941190, 163.3805630214683333, 99.94184687166684000 ) ) ; +#38968 = CARTESIAN_POINT ( 'NONE', ( -21.70069621165131224, 182.1648337868624594, 104.4589070693949822 ) ) ; +#38969 = AXIS2_PLACEMENT_3D ( 'NONE', #7548, #11041, #32504 ) ; +#38970 = ORIENTED_EDGE ( 'NONE', *, *, #32488, .T. ) ; +#38971 = CARTESIAN_POINT ( 'NONE', ( 20.00000190450869653, 184.9707748627797912, 102.3447125600660002 ) ) ; +#38972 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36387, #29648, #23507, #32902, #1624, #14113, #26591, #4893, #1835, #11240, #33100, #15128, #3035, #21470, #12443, #9192, #27615, #36995, #40046, #21670 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1249999999999487632, 0.1874999999999337474, 0.2187499999999377998, 0.2343749999999398537, 0.2499999999999418798, 0.4999999999999397149, 0.6249999999999382716, 0.6874999999999377165, 0.7187499999999319433, 0.7343749999999324984, 0.7499999999999329425, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#38973 = DIRECTION ( 'NONE', ( -0.0005884949961184574203, 0.2249510543439044719, -0.9743698870671267942 ) ) ; +#38974 = CARTESIAN_POINT ( 'NONE', ( 8.470678308075262564, 161.4201748467667983, 97.42774225087779882 ) ) ; +#38975 = VECTOR ( 'NONE', #39506, 1000.000000000000114 ) ; +#38976 = EDGE_CURVE ( 'NONE', #21181, #15150, #1614, .T. ) ; +#38977 = ORIENTED_EDGE ( 'NONE', *, *, #16540, .T. ) ; +#38978 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624405657, -0.1792657018023829929 ) ) ; +#38979 = CARTESIAN_POINT ( 'NONE', ( -25.37711299161999889, 191.2846165128000280, 104.4837167168000178 ) ) ; +#38980 = FACE_OUTER_BOUND ( 'NONE', #22152, .T. ) ; +#38981 = CARTESIAN_POINT ( 'NONE', ( 15.10588229656246639, 129.6118588884834537, 89.56705289901165656 ) ) ; +#38982 = DIRECTION ( 'NONE', ( 0.7075388627048109225, 2.466988180792839033E-19, 0.7066744354809949558 ) ) ; +#38983 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; +#38984 = ORIENTED_EDGE ( 'NONE', *, *, #38612, .T. ) ; +#38985 = ADVANCED_FACE ( 'NONE', ( #24526 ), #12686, .F. ) ; +#38986 = ADVANCED_FACE ( 'NONE', ( #15309 ), #33493, .T. ) ; +#38987 = DIRECTION ( 'NONE', ( -0.0006039748319391913256, 0.000000000000000000, -0.9999998176071847045 ) ) ; +#38988 = LINE ( 'NONE', #8334, #3531 ) ; +#38989 = CARTESIAN_POINT ( 'NONE', ( -16.54486418118989022, 122.1240419071647523, 174.7656150134046413 ) ) ; +#38990 = EDGE_CURVE ( 'NONE', #34917, #29659, #30318, .T. ) ; +#38991 = CIRCLE ( 'NONE', #24009, 5.000000000000007994 ) ; +#38992 = CARTESIAN_POINT ( 'NONE', ( -14.78424366467106665, 136.1377412980438351, 93.65748546644259420 ) ) ; +#38993 = DIRECTION ( 'NONE', ( -0.0005884949961212385073, 0.2249510543439022514, -0.9743698870671273493 ) ) ; +#38994 = DIRECTION ( 'NONE', ( 0.0005884949961230292841, -0.2249510543439062205, 0.9743698870671264611 ) ) ; +#38995 = CARTESIAN_POINT ( 'NONE', ( -16.89287681940586339, 152.3621173710822916, 181.9638245443325388 ) ) ; +#38996 = CARTESIAN_POINT ( 'NONE', ( 21.17532367120271530, 115.6972542624342992, 90.25499547431961389 ) ) ; +#38997 = CIRCLE ( 'NONE', #3075, 1.749999999939591433 ) ; +#38998 = VERTEX_POINT ( 'NONE', #36986 ) ; +#38999 = DIRECTION ( 'NONE', ( -0.0002393071182782277790, -0.2252352986010052460, 0.9743043687658488050 ) ) ; +#39000 = CARTESIAN_POINT ( 'NONE', ( -31.72059812955714619, 135.5117662268001197, 90.95743610326634609 ) ) ; +#39001 = ORIENTED_EDGE ( 'NONE', *, *, #24940, .F. ) ; +#39002 = CARTESIAN_POINT ( 'NONE', ( 35.62684683417209897, 82.24867230276376517, 284.3280258707958978 ) ) ; +#39003 = CARTESIAN_POINT ( 'NONE', ( 25.50043400004976490, 118.5815211324333092, 89.75241963774004716 ) ) ; +#39004 = ORIENTED_EDGE ( 'NONE', *, *, #29342, .T. ) ; +#39005 = CARTESIAN_POINT ( 'NONE', ( 6.272186690383747099, 163.3822237695354147, 99.93465344309498732 ) ) ; +#39006 = VERTEX_POINT ( 'NONE', #34098 ) ; +#39007 = CARTESIAN_POINT ( 'NONE', ( 35.04645050414097085, 226.4002260770962778, 75.53733736050621417 ) ) ; +#39008 = CARTESIAN_POINT ( 'NONE', ( 3.632499201418514456, 167.8476872159760376, 101.3812074453261829 ) ) ; +#39009 = FACE_OUTER_BOUND ( 'NONE', #32825, .T. ) ; +#39010 = CYLINDRICAL_SURFACE ( 'NONE', #13715, 10.00000000000000000 ) ; +#39011 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#39012 = ORIENTED_EDGE ( 'NONE', *, *, #17794, .T. ) ; +#39013 = DIRECTION ( 'NONE', ( 0.6188015000093136653, -0.7855473910504848778, 0.000000000000000000 ) ) ; +#39014 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#39015 = PLANE ( 'NONE', #37799 ) ; +#39016 = EDGE_CURVE ( 'NONE', #15694, #20455, #21244, .T. ) ; +#39017 = CIRCLE ( 'NONE', #1818, 2.999999999975996534 ) ; +#39018 = LINE ( 'NONE', #32884, #11866 ) ; +#39019 = EDGE_LOOP ( 'NONE', ( #37176, #29305, #24090, #35975 ) ) ; +#39020 = EDGE_LOOP ( 'NONE', ( #15029, #25243, #17573, #30801 ) ) ; +#39021 = CARTESIAN_POINT ( 'NONE', ( 12.64209925790531308, 131.0231129754641302, 89.89439459407216759 ) ) ; +#39022 = AXIS2_PLACEMENT_3D ( 'NONE', #38482, #1272, #10503 ) ; +#39023 = DIRECTION ( 'NONE', ( -0.0001358647731615390223, -0.9743700655807135957, -0.2249510098688140558 ) ) ; +#39024 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#39025 = ADVANCED_FACE ( 'NONE', ( #5485 ), #5898, .T. ) ; +#39026 = CARTESIAN_POINT ( 'NONE', ( 20.49943975712684008, 154.7948711043053436, 183.6022678106032231 ) ) ; +#39027 = CARTESIAN_POINT ( 'NONE', ( -15.49970617126520445, 160.6260167168586293, 97.25887387978653464 ) ) ; +#39028 = EDGE_CURVE ( 'NONE', #22377, #24370, #6096, .T. ) ; +#39029 = EDGE_CURVE ( 'NONE', #27866, #23690, #10599, .T. ) ; +#39030 = CARTESIAN_POINT ( 'NONE', ( -20.16513161867054649, 160.0945457268390442, 99.53356579039633800 ) ) ; +#39031 = EDGE_CURVE ( 'NONE', #16668, #29541, #12533, .T. ) ; +#39032 = CARTESIAN_POINT ( 'NONE', ( 25.37814744239999953, 191.6834400436999886, 106.2641627654000018 ) ) ; +#39033 = EDGE_CURVE ( 'NONE', #906, #23019, #8792, .T. ) ; +#39034 = CYLINDRICAL_SURFACE ( 'NONE', #15936, 9.999999999999996447 ) ; +#39035 = CYLINDRICAL_SURFACE ( 'NONE', #34378, 2.499999999999999112 ) ; +#39036 = ORIENTED_EDGE ( 'NONE', *, *, #23364, .T. ) ; +#39037 = CARTESIAN_POINT ( 'NONE', ( -40.80719639505100105, 126.7988830470261092, 92.03030911972437877 ) ) ; +#39038 = CARTESIAN_POINT ( 'NONE', ( -0.02993291085645299193, 92.27946995574508549, 297.5585631083172302 ) ) ; +#39039 = CARTESIAN_POINT ( 'NONE', ( 19.84759055312880704, 148.9730819504834756, 184.3419776361884885 ) ) ; +#39040 = CARTESIAN_POINT ( 'NONE', ( -30.96737657860713355, 184.1206350860066152, 102.1792248493828055 ) ) ; +#39041 = CARTESIAN_POINT ( 'NONE', ( -38.46044104337040181, 118.4609804511839286, 89.70916240556151422 ) ) ; +#39042 = ORIENTED_EDGE ( 'NONE', *, *, #15055, .F. ) ; +#39043 = ORIENTED_EDGE ( 'NONE', *, *, #38471, .T. ) ; +#39044 = CYLINDRICAL_SURFACE ( 'NONE', #32038, 6.000000000000008882 ) ; +#39045 = AXIS2_PLACEMENT_3D ( 'NONE', #30440, #14895, #2635 ) ; +#39046 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#39047 = CARTESIAN_POINT ( 'NONE', ( -20.89285663966641238, 176.3787109218369551, 100.3857757381706222 ) ) ; +#39048 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2933, #6007, #22170, #24846 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39049 = CIRCLE ( 'NONE', #37083, 5.500000000011748824 ) ; +#39050 = ORIENTED_EDGE ( 'NONE', *, *, #21096, .F. ) ; +#39051 = CARTESIAN_POINT ( 'NONE', ( 22.49999746303471682, 154.4130087049401254, 95.28531927624969455 ) ) ; +#39052 = EDGE_CURVE ( 'NONE', #16108, #31399, #2236, .T. ) ; +#39053 = DIRECTION ( 'NONE', ( 0.7933533411653074241, 0.5931840316265225566, 0.1368326740407711517 ) ) ; +#39054 = CARTESIAN_POINT ( 'NONE', ( -36.34733598288000422, 115.9999055177000145, 87.64047360899999717 ) ) ; +#39055 = VERTEX_POINT ( 'NONE', #2833 ) ; +#39056 = CARTESIAN_POINT ( 'NONE', ( -19.21661266601579854, 125.6427568102140810, 176.7081128588468175 ) ) ; +#39057 = EDGE_LOOP ( 'NONE', ( #31043, #2670, #26659, #26458 ) ) ; +#39058 = FACE_OUTER_BOUND ( 'NONE', #10926, .T. ) ; +#39059 = CARTESIAN_POINT ( 'NONE', ( 5.669239325943234320, 130.1664129347483652, 92.53175120781416751 ) ) ; +#39060 = LINE ( 'NONE', #20451, #37853 ) ; +#39061 = CARTESIAN_POINT ( 'NONE', ( 27.83965598682951992, 177.7949683626683850, 100.6833510721430542 ) ) ; +#39062 = ORIENTED_EDGE ( 'NONE', *, *, #8875, .T. ) ; +#39063 = CARTESIAN_POINT ( 'NONE', ( -1.680089689788329732, 188.9049530417860296, 103.2619686274020125 ) ) ; +#39064 = CARTESIAN_POINT ( 'NONE', ( 0.7119102185202000888, 189.0148120467000012, 103.6943891261000061 ) ) ; +#39065 = CARTESIAN_POINT ( 'NONE', ( -30.07082631362985836, 134.8398731441967868, 93.36708164982407254 ) ) ; +#39066 = EDGE_CURVE ( 'NONE', #34329, #6692, #36856, .T. ) ; +#39067 = VERTEX_POINT ( 'NONE', #24116 ) ; +#39068 = CARTESIAN_POINT ( 'NONE', ( -25.50870663471662780, 209.7066555246269104, 75.57407794464953099 ) ) ; +#39069 = ORIENTED_EDGE ( 'NONE', *, *, #19062, .T. ) ; +#39070 = ORIENTED_EDGE ( 'NONE', *, *, #27581, .F. ) ; +#39071 = CIRCLE ( 'NONE', #1877, 2.500000000086348706 ) ; +#39072 = EDGE_CURVE ( 'NONE', #2798, #34249, #35392, .T. ) ; +#39073 = EDGE_CURVE ( 'NONE', #21095, #1901, #36572, .T. ) ; +#39074 = CONICAL_SURFACE ( 'NONE', #16880, 4.999999999912411397, 0.7853981634347277918 ) ; +#39075 = ORIENTED_EDGE ( 'NONE', *, *, #27778, .T. ) ; +#39076 = AXIS2_PLACEMENT_3D ( 'NONE', #25041, #12340, #11747 ) ; +#39077 = ORIENTED_EDGE ( 'NONE', *, *, #27707, .F. ) ; +#39078 = CARTESIAN_POINT ( 'NONE', ( -27.40037233577605136, 188.3537917825017303, 103.1543718757085486 ) ) ; +#39079 = CARTESIAN_POINT ( 'NONE', ( -27.86226992038220374, 186.6938930634679537, 105.3320624031430270 ) ) ; +#39080 = VECTOR ( 'NONE', #17662, 1000.000000000000114 ) ; +#39081 = CARTESIAN_POINT ( 'NONE', ( -20.02002437005085511, 209.7095682957761085, 73.07054393135327075 ) ) ; +#39082 = EDGE_CURVE ( 'NONE', #29484, #27835, #1585, .T. ) ; +#39083 = VERTEX_POINT ( 'NONE', #33287 ) ; +#39084 = CARTESIAN_POINT ( 'NONE', ( 29.62444489005903492, 185.2955461511815827, 104.9796392865187613 ) ) ; +#39085 = ORIENTED_EDGE ( 'NONE', *, *, #26681, .F. ) ; +#39086 = CARTESIAN_POINT ( 'NONE', ( 28.22758490474300430, 124.4186838343800048, 91.44260002119000319 ) ) ; +#39087 = CARTESIAN_POINT ( 'NONE', ( 36.95653322929180007, 86.97535859511968681, 287.8064994082558883 ) ) ; +#39089 = CARTESIAN_POINT ( 'NONE', ( 30.10554067372000020, 123.2470639583000178, 152.4718672074000381 ) ) ; +#39088 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971585109 ) ) ; +#39090 = ORIENTED_EDGE ( 'NONE', *, *, #6334, .T. ) ; +#39091 = ORIENTED_EDGE ( 'NONE', *, *, #26833, .T. ) ; +#39092 = CARTESIAN_POINT ( 'NONE', ( -36.25534212287539759, 191.8348339277909815, 104.4077102864487756 ) ) ; +#39093 = ORIENTED_EDGE ( 'NONE', *, *, #6680, .T. ) ; +#39094 = CARTESIAN_POINT ( 'NONE', ( 38.93148201702999955, 119.4912731960999963, 90.44571384572999762 ) ) ; +#39095 = FACE_OUTER_BOUND ( 'NONE', #26176, .T. ) ; +#39096 = CIRCLE ( 'NONE', #8453, 2.000000000065532024 ) ; +#39097 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13134, #25614, #22546, #38064 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39098 = CARTESIAN_POINT ( 'NONE', ( -20.51876290927583568, 210.6302914306680805, 75.57087059609588664 ) ) ; +#39099 = CARTESIAN_POINT ( 'NONE', ( 13.76428958127423741, 125.4663756326015402, 174.1938355030699483 ) ) ; +#39100 = CARTESIAN_POINT ( 'NONE', ( -5.669412827411000499, 187.7434695952159132, 103.5134950630966557 ) ) ; +#39101 = CARTESIAN_POINT ( 'NONE', ( 36.22321703693000217, 191.6094071333000102, 104.0120110401999938 ) ) ; +#39102 = ORIENTED_EDGE ( 'NONE', *, *, #33538, .F. ) ; +#39103 = AXIS2_PLACEMENT_3D ( 'NONE', #23051, #37767, #19362 ) ; +#39104 = VERTEX_POINT ( 'NONE', #2443 ) ; +#39105 = CIRCLE ( 'NONE', #2595, 6.499999999889569224 ) ; +#39106 = CARTESIAN_POINT ( 'NONE', ( 22.78045900286099368, 148.0760582945774786, 93.82521474199010925 ) ) ; +#39107 = CARTESIAN_POINT ( 'NONE', ( -29.94780647573006149, 103.6131156702304992, 87.78587210766562521 ) ) ; +#39108 = AXIS2_PLACEMENT_3D ( 'NONE', #13098, #13299, #31913 ) ; +#39109 = CARTESIAN_POINT ( 'NONE', ( 26.22129837218000148, 123.4649048998000183, 88.65453169520000642 ) ) ; +#39110 = ORIENTED_EDGE ( 'NONE', *, *, #33198, .T. ) ; +#39111 = CARTESIAN_POINT ( 'NONE', ( -35.63572620277000169, 192.2657345707000047, 106.7753187434000068 ) ) ; +#39113 = EDGE_CURVE ( 'NONE', #21433, #18878, #9455, .T. ) ; +#39112 = CARTESIAN_POINT ( 'NONE', ( -38.38147336650155239, 118.3854775865508913, 89.70984624231221005 ) ) ; +#39114 = EDGE_CURVE ( 'NONE', #14369, #31713, #2925, .T. ) ; +#39115 = EDGE_CURVE ( 'NONE', #21095, #31941, #22767, .T. ) ; +#39116 = ORIENTED_EDGE ( 'NONE', *, *, #37094, .T. ) ; +#39117 = EDGE_CURVE ( 'NONE', #36005, #17425, #17918, .T. ) ; +#39118 = CARTESIAN_POINT ( 'NONE', ( 2.564076329950748523, 190.9814211239933570, 106.3071458285015183 ) ) ; +#39119 = ORIENTED_EDGE ( 'NONE', *, *, #36932, .T. ) ; +#39120 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#39121 = LINE ( 'NONE', #33387, #27160 ) ; +#39122 = CARTESIAN_POINT ( 'NONE', ( 3.062029414131564931, 193.8169247290821318, 102.7010603508924191 ) ) ; +#39123 = FACE_OUTER_BOUND ( 'NONE', #22099, .T. ) ; +#39124 = ADVANCED_FACE ( 'NONE', ( #28586 ), #3022, .T. ) ; +#39125 = ORIENTED_EDGE ( 'NONE', *, *, #3660, .F. ) ; +#39126 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #10311, #272, #3337, #19481 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39127 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11854, #21667, #39639, #2839 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999992929598684466 ), + .UNSPECIFIED. ) ; +#39128 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#39129 = CARTESIAN_POINT ( 'NONE', ( 20.48673967653602901, 211.0896571907997554, 75.54495990469186495 ) ) ; +#39130 = ADVANCED_FACE ( 'NONE', ( #12848 ), #31863, .T. ) ; +#39131 = CIRCLE ( 'NONE', #24807, 2.499999842035334652 ) ; +#39132 = VERTEX_POINT ( 'NONE', #19369 ) ; +#39133 = AXIS2_PLACEMENT_3D ( 'NONE', #7070, #7880, #38741 ) ; +#39134 = CARTESIAN_POINT ( 'NONE', ( 39.71118933309595178, 120.0401689410542332, 87.68449441950606627 ) ) ; +#39135 = AXIS2_PLACEMENT_3D ( 'NONE', #12529, #3924, #37482 ) ; +#39137 = CARTESIAN_POINT ( 'NONE', ( 15.01467670299223656, 158.7773337856645242, 96.30048964586330840 ) ) ; +#39136 = CARTESIAN_POINT ( 'NONE', ( -37.24436734876973532, 107.5967902977559305, 168.6045324416054996 ) ) ; +#39138 = EDGE_CURVE ( 'NONE', #36888, #38809, #6485, .T. ) ; +#39139 = ORIENTED_EDGE ( 'NONE', *, *, #38058, .T. ) ; +#39140 = CARTESIAN_POINT ( 'NONE', ( -4.036264727520263662, 143.6503695267791727, 95.38542116167025142 ) ) ; +#39141 = EDGE_LOOP ( 'NONE', ( #39673, #13625, #26294 ) ) ; +#39142 = FACE_OUTER_BOUND ( 'NONE', #27123, .T. ) ; +#39143 = DIRECTION ( 'NONE', ( 0.3095850547605887848, 0.7852246974590433304, -0.5362641777792332975 ) ) ; +#39144 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620729128, 0.0004744508866335444284 ) ) ; +#39145 = ORIENTED_EDGE ( 'NONE', *, *, #27591, .F. ) ; +#39146 = ORIENTED_EDGE ( 'NONE', *, *, #34899, .T. ) ; +#39147 = CARTESIAN_POINT ( 'NONE', ( -3.488521955165103883, 182.8912935819007259, 101.8788124086412097 ) ) ; +#39148 = ORIENTED_EDGE ( 'NONE', *, *, #20975, .F. ) ; +#39149 = ORIENTED_EDGE ( 'NONE', *, *, #35536, .F. ) ; +#39150 = FACE_OUTER_BOUND ( 'NONE', #23196, .T. ) ; +#39151 = CARTESIAN_POINT ( 'NONE', ( 2.641714212161000219, 209.5450904688000264, 73.39022784082000328 ) ) ; +#39152 = ORIENTED_EDGE ( 'NONE', *, *, #16231, .T. ) ; +#39153 = CARTESIAN_POINT ( 'NONE', ( 20.50141158344984404, 191.9758728513155575, 106.4093071483684696 ) ) ; +#39154 = CARTESIAN_POINT ( 'NONE', ( -36.33569152581000594, 191.9269841567999890, 104.5567655966000018 ) ) ; +#39155 = CARTESIAN_POINT ( 'NONE', ( 37.78283638816999712, 191.5199205812999992, 104.5101298729999968 ) ) ; +#39156 = CARTESIAN_POINT ( 'NONE', ( -25.66813629712000022, 120.7641189082000039, 87.89123204253000665 ) ) ; +#39157 = AXIS2_PLACEMENT_3D ( 'NONE', #33480, #23901, #27398 ) ; +#39158 = VERTEX_POINT ( 'NONE', #18954 ) ; +#39159 = FACE_OUTER_BOUND ( 'NONE', #37014, .T. ) ; +#39160 = FACE_OUTER_BOUND ( 'NONE', #21596, .T. ) ; +#39161 = VECTOR ( 'NONE', #17215, 1000.000000000000000 ) ; +#39162 = ORIENTED_EDGE ( 'NONE', *, *, #2688, .F. ) ; +#39163 = AXIS2_PLACEMENT_3D ( 'NONE', #2989, #24294, #30621 ) ; +#39164 = CARTESIAN_POINT ( 'NONE', ( 0.6274659588453800341, 188.6153583805931930, 103.1978311820718517 ) ) ; +#39165 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5467, #2219, #30018, #21026 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 1.210202674097414542E-06, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39166 = AXIS2_PLACEMENT_3D ( 'NONE', #39830, #30855, #24937 ) ; +#39167 = CARTESIAN_POINT ( 'NONE', ( -38.45586748819795986, 218.5902260770999987, 73.08173046273398654 ) ) ; +#39168 = EDGE_CURVE ( 'NONE', #6123, #31429, #21850, .T. ) ; +#39169 = EDGE_CURVE ( 'NONE', #11287, #15246, #31027, .T. ) ; +#39170 = CARTESIAN_POINT ( 'NONE', ( -14.16977585978846754, 176.4938143369288355, 100.9214410357033529 ) ) ; +#39171 = AXIS2_PLACEMENT_3D ( 'NONE', #34838, #917, #9740 ) ; +#39172 = CARTESIAN_POINT ( 'NONE', ( -19.53692352085504069, 149.3682945783864113, 181.5378042029076369 ) ) ; +#39173 = VERTEX_POINT ( 'NONE', #15891 ) ; +#39174 = CARTESIAN_POINT ( 'NONE', ( -5.668109640120363224, 183.4491314654635801, 105.0878260507181778 ) ) ; +#39175 = CARTESIAN_POINT ( 'NONE', ( 2.235475728327229739, 189.9035752844333445, 103.9441533979629924 ) ) ; +#39176 = CARTESIAN_POINT ( 'NONE', ( 25.50040748627628773, 118.8155663766999481, 89.75240507814876878 ) ) ; +#39177 = EDGE_LOOP ( 'NONE', ( #12659, #3227, #38456, #36495 ) ) ; +#39178 = CARTESIAN_POINT ( 'NONE', ( -38.87029739955395513, 169.2267822088134892, 183.8778481530477791 ) ) ; +#39179 = ORIENTED_EDGE ( 'NONE', *, *, #19133, .F. ) ; +#39180 = CARTESIAN_POINT ( 'NONE', ( -25.35525560430000169, 191.8359866865000072, 104.5586871365999997 ) ) ; +#39181 = CARTESIAN_POINT ( 'NONE', ( 17.97063383948572124, 149.1908938068557404, 179.6779205776294361 ) ) ; +#39182 = CARTESIAN_POINT ( 'NONE', ( 25.89285108626999943, 192.1487801751000006, 104.0221552793999962 ) ) ; +#39183 = FACE_OUTER_BOUND ( 'NONE', #16266, .T. ) ; +#39184 = VERTEX_POINT ( 'NONE', #358 ) ; +#39185 = PLANE ( 'NONE', #1730 ) ; +#39186 = AXIS2_PLACEMENT_3D ( 'NONE', #16237, #22995, #22400 ) ; +#39187 = EDGE_CURVE ( 'NONE', #12347, #36214, #31242, .T. ) ; +#39188 = DIRECTION ( 'NONE', ( 0.0005884949905463371812, -0.2249510543438333898, 0.9743698870671464451 ) ) ; +#39189 = AXIS2_PLACEMENT_3D ( 'NONE', #37555, #9760, #6465 ) ; +#39190 = CARTESIAN_POINT ( 'NONE', ( -35.94055828177000222, 192.4035622650000334, 104.1758260217000043 ) ) ; +#39191 = DIRECTION ( 'NONE', ( -0.6088835995545407442, -0.7728434649458200134, -0.1788120266761852595 ) ) ; +#39192 = VECTOR ( 'NONE', #28852, 1000.000000000000114 ) ; +#39193 = CARTESIAN_POINT ( 'NONE', ( 37.48996430735000018, 190.8515886636000118, 106.3794466851000067 ) ) ; +#39194 = CARTESIAN_POINT ( 'NONE', ( 45.36467309445081497, 70.87416510410297121, 322.7139789007268291 ) ) ; +#39195 = VECTOR ( 'NONE', #8324, 999.9999999999998863 ) ; +#39196 = CARTESIAN_POINT ( 'NONE', ( -15.10513900131456388, 175.7048190624925610, 103.3056127689209376 ) ) ; +#39197 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; +#39198 = DIRECTION ( 'NONE', ( -0.0005884949672441799938, 0.2249510543775923299, -0.9743698870593667793 ) ) ; +#39199 = CARTESIAN_POINT ( 'NONE', ( -38.38765349727361098, 118.8474376092554508, 87.72134797196410716 ) ) ; +#39200 = ORIENTED_EDGE ( 'NONE', *, *, #17874, .T. ) ; +#39201 = CARTESIAN_POINT ( 'NONE', ( 3.671230113708026099, 144.1856367755248982, 93.07912818882560657 ) ) ; +#39202 = CARTESIAN_POINT ( 'NONE', ( -30.70212612791577556, 134.9734613206348399, 90.83254346907035881 ) ) ; +#39203 = ORIENTED_EDGE ( 'NONE', *, *, #1225, .T. ) ; +#39204 = CARTESIAN_POINT ( 'NONE', ( 33.83294458002807659, 83.70316674797169298, 284.1460533327533540 ) ) ; +#39205 = VERTEX_POINT ( 'NONE', #12431 ) ; +#39206 = CARTESIAN_POINT ( 'NONE', ( 23.31785698356683056, 213.5902233258594265, 73.54422726498407314 ) ) ; +#39207 = CARTESIAN_POINT ( 'NONE', ( 30.09291612660999959, 109.6131156702000027, 152.4718672074000381 ) ) ; +#39208 = ORIENTED_EDGE ( 'NONE', *, *, #35445, .T. ) ; +#39209 = CARTESIAN_POINT ( 'NONE', ( 29.05382570111806118, 110.6131156702000027, 87.75023660053001606 ) ) ; +#39210 = CARTESIAN_POINT ( 'NONE', ( 28.90769808291203091, 225.0820812890804348, 73.04104455706797694 ) ) ; +#39211 = CARTESIAN_POINT ( 'NONE', ( -12.63527048312528756, 130.1801778034788413, 92.56815356418299245 ) ) ; +#39212 = ADVANCED_FACE ( 'NONE', ( #9379 ), #24935, .T. ) ; +#39213 = EDGE_CURVE ( 'NONE', #4424, #15600, #554, .T. ) ; +#39214 = CARTESIAN_POINT ( 'NONE', ( 15.05197310825490398, 136.6013035982805661, 91.18072662319218580 ) ) ; +#39215 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #17139, #36377, #24119, #29640 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.002783951876392748090, 0.002790143392383074520 ), + .UNSPECIFIED. ) ; +#39216 = CARTESIAN_POINT ( 'NONE', ( 6.034204648359921208, 177.7921235470974466, 100.6958268401488539 ) ) ; +#39217 = ORIENTED_EDGE ( 'NONE', *, *, #1089, .F. ) ; +#39218 = CARTESIAN_POINT ( 'NONE', ( 76.10630783111388098, 156.2450968845424768, 96.19213091947902683 ) ) ; +#39219 = CONICAL_SURFACE ( 'NONE', #10524, 2.502992089562209976, 0.7853981633619750991 ) ; +#39220 = LINE ( 'NONE', #8367, #24478 ) ; +#39221 = CARTESIAN_POINT ( 'NONE', ( -25.49121842733731569, 191.8361208170296379, 104.4329317390898950 ) ) ; +#39222 = CIRCLE ( 'NONE', #28816, 2.499999999980133225 ) ; +#39223 = AXIS2_PLACEMENT_3D ( 'NONE', #39378, #30199, #32845 ) ; +#39224 = CARTESIAN_POINT ( 'NONE', ( -20.68588240384768540, 105.5805168953082926, 90.28027859384218345 ) ) ; +#39225 = ORIENTED_EDGE ( 'NONE', *, *, #2009, .T. ) ; +#39226 = DIRECTION ( 'NONE', ( 0.7933533411653075351, -0.5930537057989938576, -0.1373964268091553698 ) ) ; +#39227 = CARTESIAN_POINT ( 'NONE', ( -43.10569259267042952, 120.6546256101410819, 92.20669626011783748 ) ) ; +#39228 = CARTESIAN_POINT ( 'NONE', ( 37.96340687623389698, 191.0388351520254560, 103.7347888148996446 ) ) ; +#39229 = DIRECTION ( 'NONE', ( 0.7072734958804502980, 0.6509141195175901506, 0.2758169883050842763 ) ) ; +#39230 = CARTESIAN_POINT ( 'NONE', ( -18.08817325877299353, 126.3818500937895521, 175.0046273759002986 ) ) ; +#39231 = CARTESIAN_POINT ( 'NONE', ( -34.95638759933999040, 226.4002260770912187, 73.57961695570894278 ) ) ; +#39232 = CARTESIAN_POINT ( 'NONE', ( 45.68950646426466733, 77.14301703112153064, 297.5309497125679741 ) ) ; +#39233 = CARTESIAN_POINT ( 'NONE', ( -25.63747034653302137, 209.7120552166697962, 73.44645162493029034 ) ) ; +#39234 = CARTESIAN_POINT ( 'NONE', ( 31.51045601729466483, 191.4722053967683451, 106.4044942133964895 ) ) ; +#39235 = FACE_OUTER_BOUND ( 'NONE', #9582, .T. ) ; +#39236 = ORIENTED_EDGE ( 'NONE', *, *, #11155, .F. ) ; +#39237 = FACE_OUTER_BOUND ( 'NONE', #18577, .T. ) ; +#39238 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; +#39239 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #531, #22436, #31841, #3796 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39240 = CARTESIAN_POINT ( 'NONE', ( -36.24552557991719226, 191.7319245521262303, 106.4277516671341601 ) ) ; +#39241 = CARTESIAN_POINT ( 'NONE', ( -22.60314354626212463, 115.1134007281406610, 87.28143602434546722 ) ) ; +#39242 = CIRCLE ( 'NONE', #22951, 5.249999999999986677 ) ; +#39244 = ORIENTED_EDGE ( 'NONE', *, *, #8257, .T. ) ; +#39243 = CARTESIAN_POINT ( 'NONE', ( 22.49999922077102354, 138.5120027357655204, 91.61734752330174558 ) ) ; +#39245 = ORIENTED_EDGE ( 'NONE', *, *, #27589, .F. ) ; +#39246 = ORIENTED_EDGE ( 'NONE', *, *, #37105, .T. ) ; +#39247 = AXIS2_PLACEMENT_3D ( 'NONE', #19407, #38225, #9832 ) ; +#39248 = VECTOR ( 'NONE', #7404, 1000.000000000000000 ) ; +#39249 = ORIENTED_EDGE ( 'NONE', *, *, #27345, .T. ) ; +#39250 = CARTESIAN_POINT ( 'NONE', ( -20.00089539691495233, 118.1272453392662527, 87.27993277136866368 ) ) ; +#39251 = ADVANCED_FACE ( 'NONE', ( #6289 ), #2279, .T. ) ; +#39252 = LINE ( 'NONE', #17769, #13498 ) ; +#39253 = ORIENTED_EDGE ( 'NONE', *, *, #14621, .T. ) ; +#39254 = CARTESIAN_POINT ( 'NONE', ( -14.16859883678303689, 135.5379567964818648, 93.51864244317933128 ) ) ; +#39255 = EDGE_CURVE ( 'NONE', #18545, #31494, #38195, .T. ) ; +#39256 = CARTESIAN_POINT ( 'NONE', ( -13.49693341779290989, 187.4925040631788420, 105.7867476294317441 ) ) ; +#39257 = CARTESIAN_POINT ( 'NONE', ( -37.59159439311999762, 118.9392194373999985, 87.16591189003000295 ) ) ; +#39258 = ORIENTED_EDGE ( 'NONE', *, *, #36893, .T. ) ; +#39259 = DIRECTION ( 'NONE', ( 8.589097300323509265E-16, -0.9743700557925334405, -0.2249510932955323117 ) ) ; +#39260 = ORIENTED_EDGE ( 'NONE', *, *, #33062, .T. ) ; +#39261 = LINE ( 'NONE', #27239, #7672 ) ; +#39262 = EDGE_CURVE ( 'NONE', #11054, #37554, #25239, .T. ) ; +#39263 = ADVANCED_FACE ( 'NONE', ( #35285 ), #35896, .F. ) ; +#39264 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178539432571E-05, -0.0002331579774923554001 ) ) ; +#39265 = CARTESIAN_POINT ( 'NONE', ( -20.51978786315646630, 209.7094320854081104, 73.57086927696296641 ) ) ; +#39266 = PLANE ( 'NONE', #18401 ) ; +#39267 = ADVANCED_FACE ( 'NONE', ( #4216 ), #31659, .F. ) ; +#39268 = VERTEX_POINT ( 'NONE', #8322 ) ; +#39269 = CARTESIAN_POINT ( 'NONE', ( -2.618946344219839517, 189.8260961747400017, 103.4762868850679922 ) ) ; +#39270 = EDGE_CURVE ( 'NONE', #13086, #26477, #2273, .T. ) ; +#39271 = CARTESIAN_POINT ( 'NONE', ( 1.010702454887000057, 188.7857919939000055, 103.3724372331000154 ) ) ; +#39272 = CARTESIAN_POINT ( 'NONE', ( -36.07039677004318889, 191.0804747272522661, 106.8625041541564826 ) ) ; +#39273 = VERTEX_POINT ( 'NONE', #17698 ) ; +#39274 = AXIS2_PLACEMENT_3D ( 'NONE', #13535, #38264, #3908 ) ; +#39275 = CARTESIAN_POINT ( 'NONE', ( 5.696651444342763604, 176.3366686086371828, 152.9217692962174056 ) ) ; +#39276 = ORIENTED_EDGE ( 'NONE', *, *, #35575, .T. ) ; +#39277 = EDGE_LOOP ( 'NONE', ( #12914, #35398, #27389, #15593 ) ) ; +#39278 = AXIS2_PLACEMENT_3D ( 'NONE', #15504, #14904, #162 ) ; +#39279 = AXIS2_PLACEMENT_3D ( 'NONE', #23304, #4272, #26185 ) ; +#39280 = ORIENTED_EDGE ( 'NONE', *, *, #38976, .T. ) ; +#39281 = VERTEX_POINT ( 'NONE', #14456 ) ; +#39282 = PLANE ( 'NONE', #38243 ) ; +#39283 = CARTESIAN_POINT ( 'NONE', ( -20.00621178664383848, 200.3418422895910282, 95.02116311134024329 ) ) ; +#39284 = EDGE_LOOP ( 'NONE', ( #8905, #16812 ) ) ; +#39285 = CARTESIAN_POINT ( 'NONE', ( 25.99877579885739820, 118.1142373747355663, 87.25208168292309097 ) ) ; +#39286 = EDGE_LOOP ( 'NONE', ( #1994, #28712, #14406, #7942, #8866, #36037, #19037, #40308, #696, #28997, #19747, #38984, #1485, #26391, #39258, #25067, #12229, #33340, #34006, #17921, #5548, #18729, #38356, #21085, #31216, #7997, #30113, #1054 ) ) ; +#39287 = CARTESIAN_POINT ( 'NONE', ( 26.93751574495999890, 123.1570194396999938, 91.14867748372999756 ) ) ; +#39288 = CARTESIAN_POINT ( 'NONE', ( -23.01874678158921839, 213.5902083388722303, 75.57231541044464507 ) ) ; +#39290 = CARTESIAN_POINT ( 'NONE', ( 45.27414176412918323, 117.1178249393933726, 122.5865242744168313 ) ) ; +#39289 = FACE_OUTER_BOUND ( 'NONE', #7701, .T. ) ; +#39291 = ORIENTED_EDGE ( 'NONE', *, *, #12704, .T. ) ; +#39292 = VERTEX_POINT ( 'NONE', #5650 ) ; +#39294 = ADVANCED_FACE ( 'NONE', ( #27352 ), #8825, .F. ) ; +#39293 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #13208, #37730, #16057, #19713 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39295 = LINE ( 'NONE', #32565, #36079 ) ; +#39296 = ORIENTED_EDGE ( 'NONE', *, *, #5807, .T. ) ; +#39298 = AXIS2_PLACEMENT_3D ( 'NONE', #30536, #21331, #25009 ) ; +#39297 = CARTESIAN_POINT ( 'NONE', ( -37.67574118798827243, 118.8155645602721222, 87.29053938956874958 ) ) ; +#39299 = EDGE_CURVE ( 'NONE', #22051, #8671, #23263, .T. ) ; +#39300 = CARTESIAN_POINT ( 'NONE', ( 44.87380033613943198, 186.3390555487907818, 107.7765436004285249 ) ) ; +#39301 = CARTESIAN_POINT ( 'NONE', ( -22.78246931443002055, 153.3538690588717941, 97.63697319274456277 ) ) ; +#39302 = CARTESIAN_POINT ( 'NONE', ( 36.21553018070000007, 191.6173947560000101, 104.0137019355999968 ) ) ; +#39303 = EDGE_CURVE ( 'NONE', #28860, #22525, #10768, .T. ) ; +#39304 = VERTEX_POINT ( 'NONE', #36936 ) ; +#39305 = ORIENTED_EDGE ( 'NONE', *, *, #29580, .T. ) ; +#39306 = CARTESIAN_POINT ( 'NONE', ( 19.97967439332015260, 209.7095903781859647, 78.04647941570243574 ) ) ; +#39307 = EDGE_CURVE ( 'NONE', #30145, #27328, #33449, .T. ) ; +#39308 = CARTESIAN_POINT ( 'NONE', ( 14.46550548851596574, 188.1567857891429298, 103.0836035089503611 ) ) ; +#39309 = VERTEX_POINT ( 'NONE', #17900 ) ; +#39310 = EDGE_CURVE ( 'NONE', #12120, #17036, #38815, .T. ) ; +#39311 = VERTEX_POINT ( 'NONE', #36723 ) ; +#39312 = FACE_OUTER_BOUND ( 'NONE', #12263, .T. ) ; +#39313 = DIRECTION ( 'NONE', ( 0.1305261395647899503, 0.9660146223279441058, 0.2231113541237025599 ) ) ; +#39314 = ORIENTED_EDGE ( 'NONE', *, *, #8494, .T. ) ; +#39315 = CARTESIAN_POINT ( 'NONE', ( 19.85164219301282884, 148.9679372099747638, 184.3407892933917651 ) ) ; +#39316 = CARTESIAN_POINT ( 'NONE', ( -12.63810005728112529, 128.5846432257639549, 89.34357918520186104 ) ) ; +#39317 = CARTESIAN_POINT ( 'NONE', ( 20.23755415208006525, 153.0108581511728971, 94.96603911703473955 ) ) ; +#39318 = CARTESIAN_POINT ( 'NONE', ( 22.50176656077194792, 184.2919631277355847, 105.2686329678909516 ) ) ; +#39319 = ORIENTED_EDGE ( 'NONE', *, *, #3159, .F. ) ; +#39320 = FACE_OUTER_BOUND ( 'NONE', #21389, .T. ) ; +#39321 = CYLINDRICAL_SURFACE ( 'NONE', #9743, 5.999999999999998224 ) ; +#39322 = AXIS2_PLACEMENT_3D ( 'NONE', #36582, #39427, #36779 ) ; +#39323 = ORIENTED_EDGE ( 'NONE', *, *, #34137, .F. ) ; +#39324 = CARTESIAN_POINT ( 'NONE', ( 39.62249010496272206, 120.2151953967769060, 87.55390591794386523 ) ) ; +#39325 = CARTESIAN_POINT ( 'NONE', ( 15.49018687885868850, 159.2326036880797346, 96.40530980764773972 ) ) ; +#39326 = ORIENTED_EDGE ( 'NONE', *, *, #4350, .T. ) ; +#39327 = EDGE_LOOP ( 'NONE', ( #17093, #22755, #13708 ) ) ; +#39328 = ORIENTED_EDGE ( 'NONE', *, *, #15282, .T. ) ; +#39329 = ADVANCED_FACE ( 'NONE', ( #33042 ), #13391, .F. ) ; +#39330 = CARTESIAN_POINT ( 'NONE', ( -31.91217790952610756, 137.5486857473001407, 93.99357256101205849 ) ) ; +#39331 = ADVANCED_FACE ( 'NONE', ( #24484 ), #12090, .T. ) ; +#39332 = CARTESIAN_POINT ( 'NONE', ( 22.78189145297202245, 157.6320869253407011, 99.11031191928994133 ) ) ; +#39333 = EDGE_CURVE ( 'NONE', #5478, #11864, #21219, .T. ) ; +#39334 = CARTESIAN_POINT ( 'NONE', ( 14.84511533378980808, 136.7808273136949992, 91.56439923258074032 ) ) ; +#39335 = ORIENTED_EDGE ( 'NONE', *, *, #1544, .F. ) ; +#39336 = ORIENTED_EDGE ( 'NONE', *, *, #4964, .F. ) ; +#39337 = CARTESIAN_POINT ( 'NONE', ( -3.169906973560626895, 184.1222312815566795, 102.1628149875517408 ) ) ; +#39338 = ORIENTED_EDGE ( 'NONE', *, *, #25524, .T. ) ; +#39339 = EDGE_LOOP ( 'NONE', ( #39847, #16753, #35682, #18926 ) ) ; +#39340 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#39341 = CARTESIAN_POINT ( 'NONE', ( 2.544461029613999781, 209.0000000565999869, 73.61327619537000544 ) ) ; +#39342 = ORIENTED_EDGE ( 'NONE', *, *, #4429, .T. ) ; +#39343 = AXIS2_PLACEMENT_3D ( 'NONE', #13759, #1277, #1900 ) ; +#39344 = EDGE_CURVE ( 'NONE', #32791, #8772, #18302, .T. ) ; +#39345 = ORIENTED_EDGE ( 'NONE', *, *, #527, .T. ) ; +#39346 = EDGE_LOOP ( 'NONE', ( #2092, #19177, #32992 ) ) ; +#39347 = CARTESIAN_POINT ( 'NONE', ( -20.00000737806465523, 151.9608748777371545, 94.74793644920653435 ) ) ; +#39348 = CARTESIAN_POINT ( 'NONE', ( -35.32660592495999907, 192.4436246767999990, 103.7337747834999959 ) ) ; +#39350 = VECTOR ( 'NONE', #38157, 1000.000000000000000 ) ; +#39349 = DIRECTION ( 'NONE', ( 0.8142022563026397597, 0.000000000000000000, 0.5805813343810587446 ) ) ; +#39351 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #38706, #23799 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39352 = ORIENTED_EDGE ( 'NONE', *, *, #31578, .T. ) ; +#39353 = CARTESIAN_POINT ( 'NONE', ( -2.937264483321980979, 191.5260295968394928, 103.8719657109621295 ) ) ; +#39354 = ADVANCED_FACE ( 'NONE', ( #14865 ), #5032, .T. ) ; +#39355 = EDGE_LOOP ( 'NONE', ( #32949, #28038, #23957, #4659 ) ) ; +#39356 = CIRCLE ( 'NONE', #834, 5.500000707771594222 ) ; +#39357 = CARTESIAN_POINT ( 'NONE', ( 29.57849398920695094, 202.8601875879691931, 28.89883253923506246 ) ) ; +#39358 = DIRECTION ( 'NONE', ( 0.0006039748319384539597, 1.295170900108887039E-14, 0.9999998176071845934 ) ) ; +#39359 = FACE_OUTER_BOUND ( 'NONE', #33216, .T. ) ; +#39360 = ORIENTED_EDGE ( 'NONE', *, *, #12790, .T. ) ; +#39361 = CARTESIAN_POINT ( 'NONE', ( 0.6972021641108145928, 188.6142014775118128, 103.1975219709808727 ) ) ; +#39362 = CARTESIAN_POINT ( 'NONE', ( 16.56127283256421734, 122.5154997165936521, 174.6307753585464582 ) ) ; +#39363 = LINE ( 'NONE', #23645, #27504 ) ; +#39364 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #15098, #5885, #12232, #27397, #39616, #11631 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 4 ), + ( 0.000000000000000000, 0.3333337457304020313, 0.6666668737132039890, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39365 = CARTESIAN_POINT ( 'NONE', ( -43.21068176890801027, 118.0105506722982369, 104.8630716126889126 ) ) ; +#39366 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #39401, #24097, #30433, #2426 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 3.069965523459847745, 3.070702649259505090 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999547204634354, 0.9999999547204634354, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#39367 = EDGE_LOOP ( 'NONE', ( #9780, #11887, #31176, #22383, #15102, #5830 ) ) ; +#39368 = EDGE_CURVE ( 'NONE', #10860, #29915, #8733, .T. ) ; +#39369 = DIRECTION ( 'NONE', ( -0.0006039748319380813194, -1.041532381956747772E-14, -0.9999998176071845934 ) ) ; +#39370 = CARTESIAN_POINT ( 'NONE', ( 1.637629675866425272, 189.3131617310740751, 103.7741813652591247 ) ) ; +#39371 = CARTESIAN_POINT ( 'NONE', ( -28.46687737262882578, 130.4181374544887717, 90.29266601121980784 ) ) ; +#39372 = EDGE_LOOP ( 'NONE', ( #1529, #8821, #3021, #37732 ) ) ; +#39373 = CARTESIAN_POINT ( 'NONE', ( -22.49860963037942341, 157.8259877977732515, 99.01136938669759502 ) ) ; +#39374 = VERTEX_POINT ( 'NONE', #33238 ) ; +#39375 = ORIENTED_EDGE ( 'NONE', *, *, #5050, .F. ) ; +#39376 = CARTESIAN_POINT ( 'NONE', ( -25.91135228618000141, 191.2905648374000123, 103.9456188779000030 ) ) ; +#39377 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066550434, 185.3448273526182959, 105.0123327472739163 ) ) ; +#39378 = CARTESIAN_POINT ( 'NONE', ( -28.46590577390798771, 128.0194952136861275, 91.79150371819520160 ) ) ; +#39379 = AXIS2_PLACEMENT_3D ( 'NONE', #34010, #3333, #10092 ) ; +#39380 = CARTESIAN_POINT ( 'NONE', ( 6.033058578775539083, 135.0436587837527043, 90.99612091764669231 ) ) ; +#39381 = EDGE_LOOP ( 'NONE', ( #12952, #32927, #11786, #39483 ) ) ; +#39382 = CARTESIAN_POINT ( 'NONE', ( 12.63493752644979118, 130.4235786262125032, 90.26909773778339741 ) ) ; +#39383 = VECTOR ( 'NONE', #26915, 1000.000000000000114 ) ; +#39384 = LINE ( 'NONE', #32659, #12687 ) ; +#39385 = CARTESIAN_POINT ( 'NONE', ( 44.64491191134371917, 188.7542347311224376, 105.7690686227471559 ) ) ; +#39386 = EDGE_CURVE ( 'NONE', #4624, #26260, #37811, .T. ) ; +#39387 = CARTESIAN_POINT ( 'NONE', ( -43.28155790953776005, 183.2190586267475680, 137.8991672664744499 ) ) ; +#39388 = DIRECTION ( 'NONE', ( -0.0004270746993281996219, -0.7071067811865993091, -0.7071066522152992251 ) ) ; +#39389 = EDGE_CURVE ( 'NONE', #34119, #32373, #12712, .T. ) ; +#39390 = CARTESIAN_POINT ( 'NONE', ( -26.69810905257040901, 110.6131156702000027, 87.28390928083501876 ) ) ; +#39391 = EDGE_CURVE ( 'NONE', #23133, #35236, #28735, .T. ) ; +#39392 = CARTESIAN_POINT ( 'NONE', ( 21.51436008770080832, 115.4748947878985916, 90.25479070481955546 ) ) ; +#39393 = EDGE_LOOP ( 'NONE', ( #18084, #9095, #30679, #22578 ) ) ; +#39394 = CARTESIAN_POINT ( 'NONE', ( 3.639365772014297118, 144.1947402466412598, 93.04856585393400792 ) ) ; +#39395 = CARTESIAN_POINT ( 'NONE', ( -32.27067804272475371, 136.1434003866072260, 91.10359260027512107 ) ) ; +#39396 = EDGE_CURVE ( 'NONE', #29827, #21279, #18695, .T. ) ; +#39397 = ORIENTED_EDGE ( 'NONE', *, *, #28070, .F. ) ; +#39398 = LINE ( 'NONE', #2420, #12136 ) ; +#39399 = ORIENTED_EDGE ( 'NONE', *, *, #6350, .T. ) ; +#39400 = ADVANCED_FACE ( 'NONE', ( #9938 ), #35524, .F. ) ; +#39401 = CARTESIAN_POINT ( 'NONE', ( 16.23201905896638308, 152.0606143167149185, 181.0564827348360382 ) ) ; +#39402 = CARTESIAN_POINT ( 'NONE', ( -25.49734792034996289, 118.8155664120999973, 94.28318532801205265 ) ) ; +#39403 = CARTESIAN_POINT ( 'NONE', ( 25.99874167938696345, 118.1131156663084738, 87.25205387058410622 ) ) ; +#39404 = ORIENTED_EDGE ( 'NONE', *, *, #22403, .F. ) ; +#39405 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#39406 = VECTOR ( 'NONE', #20261, 1000.000000000000227 ) ; +#39407 = CLOSED_SHELL ( 'NONE', ( #35723, #32215, #14115, #26398, #25815, #893, #2338, #10300, #26874, #27062, #25346, #27619, #38740, #8210, #38139, #14281, #13518, #27353, #6361, #38212, #9559, #1892, #21183, #33779, #17719, #14810, #2602, #33907, #12918, #32846, #30203, #8532, #19138, #351, #5147, #7643, #2400, #9247, #2911, #22759, #83, #36730, #3032, #26966, #29000, #20004, #29621, #37147, #3893, #8853, #15760, #16847, #19818, #9463, #15988, #7859, #24297, #9530, #32803, #26314, #21476, #11112, #31432, #36411, #10157, #19861, #2128, #17949, #9885, #33345, #24047, #35316, #20900, #14027, #24662, #21528, #19309, #40051, #2661, #17600, #37245, #9320, #5522, #35890, #16905, #16450, #14182, #2040, #28396, #28324, #34995, #1050, #515, #29808, #27152, #4162, #10535, #15899, #29700, #6181, #33913, #21668, #22349, #16325, #25852, #13495, #14732, #29018, #40285, #13570, #9926, #16139, #35685, #19365, #16783, #38071, #22016, #15103, #4891, #16106, #22780, #10208, #8987, #26777, #29085, #33906, #33306, #20557, #27041, #4962, #38786, #34574, #11298, #24840, #17743, #38735, #19269, #36121, #2087, #6967, #13278, #28409, #7864, #37053, #1465, #29136, #25621, #28299, #39624, #26042, #6582, #30368, #21001, #36826, #9901, #33632, #2361, #11207, #27988, #12417, #3312, #2296, #21422, #29694, #9424, #1560, #17923, #26395, #20312, #19270, #5380, #8634, #13452, #27495, #13517, #670, #39025, #37151, #2399, #31576, #32264, #7357, #23074, #24679, #4809, #38523, #23160, #36782, #40280, #26139, #31348, #22532, #32389, #2702, #5802, #19897, #15569, #18338, #7313, #14691, #8696, #31478, #6071, #7000, #29970, #7779, #23534, #15788, #39212, #38773, #13601, #38793, #20139, #3025, #22165, #16496, #2728, #39329, #2892, #33699, #8878, #13978, #28832, #25806, #36216, #3003, #3529, #2640, #38238, #9329, #35356, #4116, #30706, #26836, #15554, #10395, #39885, #28654, #35716, #4378, #5238, #29353, #8469, #8547, #31867, #25382, #30074, #6087, #14177, #38861, #79, #9051, #22158, #36423, #4862, #6297, #39761, #13341, #4311, #21999, #32842, #22018, #15315, #32441, #7739, #39294, #1498, #10152, #23438, #29646, #16587, #19554, #21388, #25871, #38825, #21928, #32850, #10609, #17279, #23139, #27202, #35634, #13371, #4483, #34943, #13955, #5011, #24022, #25157, #33254, #11484, #34255, #17700, #33419, #2800, #16913, #35736, #33131, #37652, #32391, #1837, #35084, #3850, #1846, #33302, #6314, #17789, #20565, #27665, #10900, #22497, #1129, #29489, #5633, #31665, #17598, #21845, #6762, #2597, #16472, #12753, #25764, #10295, #7549, #22942, #1782, #28522, #12322, #25435, #5140, #26038, #3610, #1606, #5571, #40109, #6506, #25022, #16280, #4994, #25174, #36452, #29858, #20568, #34358, #33625, #25392, #25992, #20089, #26934, #15553, #16768, #14268, #24848, #19127, #39130, #15766, #8364, #8569, #25398, #10841, #25389, #33256, #28082, #35137, #28957, #18432, #37338, #36502, #31817, #22584, #10063, #3793, #16084, #6689, #7784, #38985, #36924, #4451, #29868, #11125, #36136, #18575, #5797, #3381, #6483, #3987, #3800, #9762, #4268, #18891, #26127, #26572, #24001, #34635, #38899, #35186, #34918, #30648, #29583, #18172, #28980, #4736, #13017, #231, #12630, #34809, #26677, #34817, #31916, #36752, #30558, #32538, #22669, #27065, #28349, #18307, #9382, #30425, #11157, #12826, #31078, #40366, #32523, #39584, #11384, #18655, #38566, #29496, #29943, #15411, #1925, #23697, #10290, #12319, #19254, #36971, #37387, #12571, #4767, #7883, #3569, #19363, #15140, #19552, #20518, #24405, #18154, #5529, #40288, #1792, #19535, #36589, #13057, #28669, #22070, #2526, #19122, #9234, #12931, #2185, #26466, #33815, #24431, #13606, #24916, #24244, #33590, #34844, #25123, #8312, #13833, #38745, #26129, #21328, #9788, #6995, #33630, #33022, #6665, #8347, #9637, #2425, #32119, #38696, #14818, #6134, #26299, #21783, #5624, #23648, #25312, #221, #36115, #34898, #28749, #6011, #991, #567, #10064, #16898, #30845, #24502, #32680, #34675, #8834, #36020, #24889, #33544, #3166, #17046, #1404, #18550, #11588, #20061, #16298, #2164, #25212, #3126, #24176, #11596, #30412, #39816, #29261, #13156, #23129, #26321, #29723, #18113, #17267, #36018, #39812, #28254, #24144, #20513, #29171, #7944, #36537, #7590, #31614, #14820, #21876, #32043, #1662, #33860, #9284, #4017, #4269, #649, #17749, #23056, #718, #3909, #32575, #26878, #32461, #7633, #10069, #30798, #27257, #9333, #38384, #20277, #11169, #23525, #10444, #21568, #812, #9991, #30824, #12881, #6346, #29084, #23392, #35269, #12624, #15144, #24524, #7253, #11210, #14959, #39592, #8413, #34865, #12969, #4406, #17869, #36432, #5640, #3076, #1557, #21436, #26545, #9072, #40266, #14030, #17277, #12583, #28515, #38606, #21056, #39716, #29778, #8332, #394, #23388, #9430, #23581, #10859, #35281, #25180, #16850, #37204, #3809, #36706, #7969, #31567, #25741, #9370, #9555, #36256, #38602, #12623, #31438, #15763, #35026, #24482, #10801, #38986, #12530, #5095, #6851, #12679, #34095, #28604, #3160, #26729, #19124, #16750, #22161, #26604, #31612, #34044, #31639, #26350, #16382, #5810, #30649, #10387, #17503, #3522, #344, #10255, #7270, #19700, #31377, #757, #8449, #14535, #4036, #28611, #7598, #22309, #8680, #12399, #905, #22888, #29641, #20713, #31717, #5057, #992, #16845, #19191, #32089, #10384, #13247, #7508, #28123, #14803, #36926, #34534, #24660, #29525, #15943, #1553, #10660, #21324, #24440, #20866, #24801, #21292, #21836, #20577, #1320, #16367, #10014, #179, #2651, #17813, #15167, #15199, #15732, #21830, #39267, #14444, #27514, #3671, #39474, #17609, #20630, #8963, #30151, #34977, #36595, #24856, #10792, #5806, #3117, #8690, #1379, #2860, #8153, #9097, #20505, #1268, #36055, #38601, #23504, #11954, #31391, #22157, #30973, #31019, #33927, #12526, #1883, #36468, #37728, #18155, #34848, #40055, #31382, #36556, #7542, #32046, #10723, #39496, #21182, #620, #19087, #28802, #14122, #9332, #19770, #4567, #30607, #6845, #8786, #22257, #15999, #35920, #27466, #6260, #7927, #25630, #10206, #30416, #31243, #15675, #34417, #23065, #2264, #20898, #15631, #33246, #40287, #8168, #28528, #24346, #15585, #27392, #37826, #32605, #5839, #20913, #19458, #9374, #23256, #16153, #17186, #13223, #28063, #13836, #25678, #20007, #5862, #14978, #10150, #37931, #16327, #37672, #25282, #18204, #11389, #35127, #14758, #34403, #35498, #21184, #24665, #34757, #19217, #32838, #19297, #17973, #15416, #31220, #293, #23359, #14681, #32252, #10993, #22887, #23117, #39263, #34232, #17040, #5108, #11774, #26175, #34766, #27544, #21770, #31716, #20230, #25910, #17095, #20684, #6915, #27179, #2402, #6572, #17133, #33587, #32147, #15848, #1832, #39804, #22988, #32307, #14902, #34767, #39331, #1934, #26199, #37620, #25293, #34804, #23082, #12768, #9838, #11035, #24300, #11630, #37933, #8586, #8605, #17283, #4778, #4398, #1273, #4124, #37392, #21040, #12103, #17226, #13648, #32308, #15242, #39354, #17547, #18943, #5893, #37432, #39932, #30676, #32970, #30034, #4420, #15324, #39251, #35182, #11027, #6077, #31104, #22307, #32760, #23906, #29861, #8117, #37566, #6536, #32609, #15325, #34362, #28804, #10754, #9895, #15509, #11325, #1310, #28775, #29743, #12004, #33854, #6760, #10439, #1124, #35827, #12841, #25765, #10848, #21503, #30949, #17319, #39400, #311, #8684, #27627, #14545, #10827, #30091, #23482, #40147, #16451, #15332, #299, #949, #1720, #2813, #31561, #11787, #7635, #35657, #12158, #4761, #7992, #18980, #31198, #30896, #6081, #894, #12682, #12653, #24893, #20756, #37373, #22392, #37067, #33392, #2697, #15285, #36869, #39491, #24573, #14312, #37110, #26763, #8582, #8867, #13877, #25530, #35035, #17647, #8492, #36829, #19506, #35776, #6532, #2414, #7605, #15407, #39124, #37982, #20266, #21881, #6539, #33259, #14128, #33774, #586, #2601, #33921, #11176, #9602, #20816, #23921, #32035, #5276, #8123, #2350, #8682, #17652, #720, #4777, #16730, #34384, #11524, #8315, #29441, #14861, #12872, #26871, #18706, #22667, #24955, #13793, #21924, #14236, #22026, #23985, #24674, #532, #1600, #29082, #32082, #3384, #6714, #12401, #3161, #23554, #29028, #20763, #21405, #2889, #31803, #25787, #15053, #5610, #24057, #8152, #22071, #5473, #28704, #16867, #19076, #23294, #5606, #31897, #2473, #32805, #11082, #467, #28653, #30129, #21519, #28435, #2126, #2309, #35493, #8919, #767, #28934, #13389, #30274, #20470, #30131, #10935, #29865, #16373, #20810, #21652, #4549, #33777, #10582, #25455, #26179, #32896, #6213, #29414, #13108, #28605, #6746, #1740, #17985, #32890, #33794, #32726, #22912, #27861, #31860, #73, #25438, #18796, #25573, #26184, #3119, #20442, #21878, #3297, #39535, #10045, #21475, #38714, #18252, #40411, #37596, #38251, #38336, #1263, #37780, #18388, #25579, #2817, #1698, #16074, #4859, #27670, #3208, #11436, #19868, #27448, #28580, #7311, #39910, #32860, #14874, #39718, #30927, #4683, #39738, #11872, #9541, #34770, #37739, #31738, #5899, #12394, #11460, #32193, #40357, #25490, #28179, #30354, #4578, #22850, #18345, #38894, #27172, #3766, #2407, #13741, #11689, #15946, #23036, #1842, #29248, #31811, #35042, #32887, #37648, #36379, #25820, #15270, #27686, #36369, #21937, #18479, #6793, #33585, #19042, #33770, #37665, #9186, #39442, #31989, #3183, #38725, #28019, #11628 ) ) ; +#39408 = CARTESIAN_POINT ( 'NONE', ( -14.78542622577100119, 175.8938623147257374, 100.7833030093998303 ) ) ; +#39409 = CARTESIAN_POINT ( 'NONE', ( -12.63530928661225694, 130.1704632573847391, 92.55260706672754623 ) ) ; +#39410 = CONICAL_SURFACE ( 'NONE', #4149, 5.000000000367158748, 0.7853981634347277918 ) ; +#39411 = PLANE ( 'NONE', #9150 ) ; +#39412 = CARTESIAN_POINT ( 'NONE', ( 35.56355292849995209, 196.5784392899758188, 103.8536238432048293 ) ) ; +#39413 = ORIENTED_EDGE ( 'NONE', *, *, #12967, .F. ) ; +#39414 = EDGE_CURVE ( 'NONE', #9171, #32426, #35828, .T. ) ; +#39415 = CARTESIAN_POINT ( 'NONE', ( 39.08686004016000481, 119.9154263329000116, 87.44177325903000053 ) ) ; +#39416 = CARTESIAN_POINT ( 'NONE', ( -5.713599249648267708, 177.7896720772441199, 100.7023539561611614 ) ) ; +#39417 = DIRECTION ( 'NONE', ( -0.0006039748319379697550, -1.040973592985965549E-14, -0.9999998176071845934 ) ) ; +#39418 = ORIENTED_EDGE ( 'NONE', *, *, #8406, .F. ) ; +#39419 = FACE_OUTER_BOUND ( 'NONE', #6993, .T. ) ; +#39420 = ORIENTED_EDGE ( 'NONE', *, *, #11819, .T. ) ; +#39421 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058052610, 184.0115085080416861, 102.6519039031884546 ) ) ; +#39422 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #11243, #36390, #14520, #23510 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39423 = CARTESIAN_POINT ( 'NONE', ( -42.06110200389634457, 121.7334112014321903, 91.09980221838324610 ) ) ; +#39424 = PLANE ( 'NONE', #22240 ) ; +#39425 = CARTESIAN_POINT ( 'NONE', ( -28.65658060520999939, 124.4956071873000099, 91.63016954471000020 ) ) ; +#39426 = CARTESIAN_POINT ( 'NONE', ( -19.99999816303952471, 191.5261162992163690, 103.8822987450886046 ) ) ; +#39427 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -1.540743955509789367E-33, 0.0006039748319385908944 ) ) ; +#39428 = CARTESIAN_POINT ( 'NONE', ( -25.88782727049006382, 209.7107743092203691, 73.19639644311165227 ) ) ; +#39429 = CARTESIAN_POINT ( 'NONE', ( 19.46059643144436535, 126.3442427331793141, 175.5385488862945635 ) ) ; +#39430 = CARTESIAN_POINT ( 'NONE', ( -31.85495644188857156, 155.6854141731122638, 196.1447383889810396 ) ) ; +#39431 = CARTESIAN_POINT ( 'NONE', ( 38.65125684626000435, 119.3002203842000029, 90.41791267192000703 ) ) ; +#39432 = CIRCLE ( 'NONE', #24477, 2.000000000000011546 ) ; +#39433 = AXIS2_PLACEMENT_3D ( 'NONE', #16285, #18941, #16479 ) ; +#39434 = ORIENTED_EDGE ( 'NONE', *, *, #1555, .F. ) ; +#39435 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; +#39436 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -1.785014166949466476E-16, -0.0006039748319386109522 ) ) ; +#39437 = DIRECTION ( 'NONE', ( 0.0001408404234837714198, -0.2255194953475184727, 0.9742386449849829155 ) ) ; +#39438 = CARTESIAN_POINT ( 'NONE', ( -21.16096952440062751, 115.7114218036305715, 87.28056498737410607 ) ) ; +#39439 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #38220, #16336, #12472, #12676 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 4.205800693865505480, 4.525887359915200747 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9914802524726262778, 0.9914802524726262778, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#39440 = EDGE_CURVE ( 'NONE', #11353, #14571, #943, .T. ) ; +#39441 = AXIS2_PLACEMENT_3D ( 'NONE', #36792, #5912, #12447 ) ; +#39442 = ADVANCED_FACE ( 'NONE', ( #13198 ), #25625, .F. ) ; +#39443 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #12083, #9415, #28230, #198, #37022, #34913, #990, #32289, #15926, #22695 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39444 = DIRECTION ( 'NONE', ( -0.0005884949961198485601, 0.2249510543439084687, -0.9743698870671259060 ) ) ; +#39445 = VERTEX_POINT ( 'NONE', #6242 ) ; +#39446 = ORIENTED_EDGE ( 'NONE', *, *, #36729, .T. ) ; +#39447 = CARTESIAN_POINT ( 'NONE', ( -1.882816931228917801, 189.0601662987910174, 103.3020393482379831 ) ) ; +#39448 = ORIENTED_EDGE ( 'NONE', *, *, #33343, .T. ) ; +#39449 = CARTESIAN_POINT ( 'NONE', ( -23.36147737338983177, 177.1885760160717211, 101.0873909945826341 ) ) ; +#39450 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#39451 = ORIENTED_EDGE ( 'NONE', *, *, #1122, .T. ) ; +#39452 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; +#39453 = CARTESIAN_POINT ( 'NONE', ( -38.19787524881999730, 118.4369483671000012, 87.84294828311999481 ) ) ; +#39454 = ORIENTED_EDGE ( 'NONE', *, *, #27943, .T. ) ; +#39455 = CARTESIAN_POINT ( 'NONE', ( -41.90907465551327249, 121.4486244169956279, 92.84837845933365941 ) ) ; +#39456 = EDGE_LOOP ( 'NONE', ( #20604, #27139, #22140, #25810, #26097 ) ) ; +#39457 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 77.27946979429631824, 312.5857197240631535 ) ) ; +#39458 = CARTESIAN_POINT ( 'NONE', ( -15.99974174651862313, 174.5231975350379514, 99.95452847233616467 ) ) ; +#39459 = DIRECTION ( 'NONE', ( -0.9999998268368094356, -0.0001323825909798406200, 0.0005734118944141585296 ) ) ; +#39460 = DIRECTION ( 'NONE', ( 0.0002393071182785538528, 0.2252352986010040803, -0.9743043687658491381 ) ) ; +#39461 = APPROVAL_PERSON_ORGANIZATION ( #30863, #30192, #37194 ) ; +#39462 = ORIENTED_EDGE ( 'NONE', *, *, #11701, .T. ) ; +#39463 = EDGE_CURVE ( 'NONE', #585, #14957, #14036, .T. ) ; +#39464 = CARTESIAN_POINT ( 'NONE', ( -25.84141903064000090, 190.0987420465000071, 103.9446973517000004 ) ) ; +#39465 = CARTESIAN_POINT ( 'NONE', ( 0.5732737145059999539, 188.9926135734999946, 103.6981316242000162 ) ) ; +#39466 = AXIS2_PLACEMENT_3D ( 'NONE', #17494, #39781, #18098 ) ; +#39467 = VECTOR ( 'NONE', #23904, 1000.000000000000114 ) ; +#39468 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#39469 = CARTESIAN_POINT ( 'NONE', ( 26.02962131058879791, 120.6627111924913009, 90.57329420178653834 ) ) ; +#39470 = CONICAL_SURFACE ( 'NONE', #21866, 2.503114778588952483, 0.7853981634133299083 ) ; +#39471 = VERTEX_POINT ( 'NONE', #18904 ) ; +#39472 = LINE ( 'NONE', #14350, #7416 ) ; +#39473 = ORIENTED_EDGE ( 'NONE', *, *, #848, .F. ) ; +#39474 = ADVANCED_FACE ( 'NONE', ( #31401 ), #25277, .F. ) ; +#39475 = VERTEX_POINT ( 'NONE', #28538 ) ; +#39476 = LINE ( 'NONE', #24178, #21087 ) ; +#39478 = ORIENTED_EDGE ( 'NONE', *, *, #13662, .F. ) ; +#39477 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38971, #13832, #17282, #10379 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39479 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #22228, #12400, #22423, #13217, #9344, #22628, #519, #19333, #6650, #25702, #37952 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000233147, 0.3750000000000660583, 0.4375000000000756617, 0.4687500000000567324, 0.5000000000000377476, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39480 = CARTESIAN_POINT ( 'NONE', ( -31.91217790274522415, 174.0284854049060073, 102.4155994567338155 ) ) ; +#39481 = DIRECTION ( 'NONE', ( 0.0004161288024777938348, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#39482 = CARTESIAN_POINT ( 'NONE', ( 6.272186697316835868, 148.2050572955672862, 96.43072783368462808 ) ) ; +#39483 = ORIENTED_EDGE ( 'NONE', *, *, #36599, .F. ) ; +#39484 = FACE_OUTER_BOUND ( 'NONE', #31208, .T. ) ; +#39485 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #21227, #9162, #40417, #3005 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 4.854478445487932390E-07, 0.0007736064448116313549 ), + .UNSPECIFIED. ) ; +#39486 = CARTESIAN_POINT ( 'NONE', ( -5.670692261820892810, 181.9297596791197975, 101.9891440848351181 ) ) ; +#39487 = ORIENTED_EDGE ( 'NONE', *, *, #30743, .F. ) ; +#39488 = CARTESIAN_POINT ( 'NONE', ( 28.53189929785749968, 124.6104551036400068, 91.48497847473261402 ) ) ; +#39489 = CARTESIAN_POINT ( 'NONE', ( 20.00162197757413196, 118.5784925787999953, 90.25570436073203950 ) ) ; +#39490 = EDGE_CURVE ( 'NONE', #25663, #24195, #14430, .T. ) ; +#39491 = ADVANCED_FACE ( 'NONE', ( #504 ), #38136, .T. ) ; +#39493 = FACE_OUTER_BOUND ( 'NONE', #10803, .T. ) ; +#39492 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250096516, 135.0477809104833966, 91.35518170534504634 ) ) ; +#39494 = CC_DESIGN_SECURITY_CLASSIFICATION ( #26440, ( #37519 ) ) ; +#39495 = CIRCLE ( 'NONE', #29709, 6.500000000118505206 ) ; +#39496 = ADVANCED_FACE ( 'NONE', ( #7041 ), #36884, .F. ) ; +#39497 = VERTEX_POINT ( 'NONE', #13787 ) ; +#39498 = FACE_OUTER_BOUND ( 'NONE', #21828, .T. ) ; +#39499 = AXIS2_PLACEMENT_3D ( 'NONE', #27141, #34235, #6044 ) ; +#39500 = ORIENTED_EDGE ( 'NONE', *, *, #31380, .T. ) ; +#39501 = EDGE_CURVE ( 'NONE', #31188, #6720, #4884, .T. ) ; +#39502 = VECTOR ( 'NONE', #24753, 1000.000000000000000 ) ; +#39503 = ORIENTED_EDGE ( 'NONE', *, *, #8111, .F. ) ; +#39504 = CARTESIAN_POINT ( 'NONE', ( -28.25630607419124019, 186.6792666402525640, 104.3077506217996131 ) ) ; +#39505 = CARTESIAN_POINT ( 'NONE', ( -20.51863885680050359, 209.7097602209678939, 75.57089512796630970 ) ) ; +#39506 = DIRECTION ( 'NONE', ( 0.0001408278996873626944, -0.2255194025968528804, 0.9742386664569731014 ) ) ; +#39507 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7071067167008887600, 0.7071068456722005013 ) ) ; +#39508 = ORIENTED_EDGE ( 'NONE', *, *, #256, .T. ) ; +#39509 = ORIENTED_EDGE ( 'NONE', *, *, #27949, .F. ) ; +#39510 = CARTESIAN_POINT ( 'NONE', ( -39.69707251849492025, 114.7084905227599450, 151.9490217007608805 ) ) ; +#39511 = CARTESIAN_POINT ( 'NONE', ( 25.90705744506000485, 121.8343370017999945, 87.93600534850999395 ) ) ; +#39512 = ORIENTED_EDGE ( 'NONE', *, *, #24829, .T. ) ; +#39513 = EDGE_LOOP ( 'NONE', ( #14418, #15308, #1406, #7564 ) ) ; +#39514 = CARTESIAN_POINT ( 'NONE', ( 3.069989720717164694, 190.8891895217091417, 106.8081807335384212 ) ) ; +#39515 = ORIENTED_EDGE ( 'NONE', *, *, #23409, .T. ) ; +#39516 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748612898, 176.9877420030217365, 103.0686512058572788 ) ) ; +#39517 = DIRECTION ( 'NONE', ( -0.0005884949961206531466, 0.2249510543439048327, -0.9743698870671267942 ) ) ; +#39518 = AXIS2_PLACEMENT_3D ( 'NONE', #15561, #28054, #24 ) ; +#39519 = AXIS2_PLACEMENT_3D ( 'NONE', #18147, #38469, #26025 ) ; +#39520 = DIRECTION ( 'NONE', ( -0.0006039748319368648446, -1.157494911401840404E-14, -0.9999998176071845934 ) ) ; +#39521 = CARTESIAN_POINT ( 'NONE', ( 3.720974031714894714, 145.7221224061216844, 93.29327717358505367 ) ) ; +#39522 = AXIS2_PLACEMENT_3D ( 'NONE', #28946, #35049, #923 ) ; +#39523 = EDGE_CURVE ( 'NONE', #12603, #19108, #20282, .T. ) ; +#39524 = ORIENTED_EDGE ( 'NONE', *, *, #29027, .T. ) ; +#39525 = AXIS2_PLACEMENT_3D ( 'NONE', #9115, #27938, #34041 ) ; +#39526 = PLANE ( 'NONE', #31022 ) ; +#39527 = FACE_OUTER_BOUND ( 'NONE', #39540, .T. ) ; +#39528 = EDGE_CURVE ( 'NONE', #36287, #4731, #909, .T. ) ; +#39529 = EDGE_LOOP ( 'NONE', ( #17618, #30255, #241, #1234 ) ) ; +#39530 = FACE_OUTER_BOUND ( 'NONE', #37278, .T. ) ; +#39531 = EDGE_CURVE ( 'NONE', #12675, #35226, #31964, .T. ) ; +#39532 = EDGE_CURVE ( 'NONE', #34118, #21690, #16603, .T. ) ; +#39534 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971542088 ) ) ; +#39533 = CARTESIAN_POINT ( 'NONE', ( 13.05874798126192715, 135.0013260624673421, 90.81254608138048923 ) ) ; +#39535 = ADVANCED_FACE ( 'NONE', ( #16642 ), #29141, .F. ) ; +#39536 = ORIENTED_EDGE ( 'NONE', *, *, #1186, .T. ) ; +#39537 = VERTEX_POINT ( 'NONE', #26076 ) ; +#39538 = DIRECTION ( 'NONE', ( -0.0005884949961250434064, 0.2249510543439061094, -0.9743698870671263501 ) ) ; +#39539 = EDGE_CURVE ( 'NONE', #25223, #28955, #38517, .T. ) ; +#39540 = EDGE_LOOP ( 'NONE', ( #29769, #36373, #29720, #33190 ) ) ; +#39541 = CARTESIAN_POINT ( 'NONE', ( 3.173484558985000259, 209.3707192315999919, 76.22248684881000713 ) ) ; +#39542 = AXIS2_PLACEMENT_3D ( 'NONE', #35867, #7674, #20134 ) ; +#39543 = CARTESIAN_POINT ( 'NONE', ( 36.89975980456834037, 191.2518832777249997, 106.3227935573031289 ) ) ; +#39544 = CARTESIAN_POINT ( 'NONE', ( 29.05503365078199707, 110.6131156702000027, 89.75023623571587450 ) ) ; +#39545 = CARTESIAN_POINT ( 'NONE', ( -10.03744067672847606, 144.0996504514500884, 93.44016182556791250 ) ) ; +#39546 = ORIENTED_EDGE ( 'NONE', *, *, #25384, .T. ) ; +#39547 = AXIS2_PLACEMENT_3D ( 'NONE', #7158, #38633, #6958 ) ; +#39548 = ORIENTED_EDGE ( 'NONE', *, *, #444, .T. ) ; +#39549 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178570922545E-05, 0.0002331579774915894113 ) ) ; +#39550 = VERTEX_POINT ( 'NONE', #10538 ) ; +#39551 = ORIENTED_EDGE ( 'NONE', *, *, #1479, .T. ) ; +#39552 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901141, 129.6183187699430164, 92.64570812446640957 ) ) ; +#39553 = DIRECTION ( 'NONE', ( 0.0006039748319386249384, 0.000000000000000000, 0.9999998176071845934 ) ) ; +#39554 = CYLINDRICAL_SURFACE ( 'NONE', #36331, 2.500000000000002220 ) ; +#39555 = CARTESIAN_POINT ( 'NONE', ( 2.510969621544000052, 209.3808403806999934, 73.56099024588000646 ) ) ; +#39556 = CARTESIAN_POINT ( 'NONE', ( -2.437851586972803020, 194.2771770550226336, 102.8997479777824537 ) ) ; +#39557 = CIRCLE ( 'NONE', #38911, 4.500000040501689114 ) ; +#39558 = ORIENTED_EDGE ( 'NONE', *, *, #24619, .F. ) ; +#39559 = ORIENTED_EDGE ( 'NONE', *, *, #23963, .F. ) ; +#39560 = CARTESIAN_POINT ( 'NONE', ( 5.666638401078976983, 126.6906950807946686, 89.41150218689625717 ) ) ; +#39561 = CARTESIAN_POINT ( 'NONE', ( -35.96708566011999864, 191.9661441250000280, 104.3089233010000072 ) ) ; +#39562 = CARTESIAN_POINT ( 'NONE', ( 36.57765404231000161, 191.8474788542000056, 104.5077614389000047 ) ) ; +#39563 = ORIENTED_EDGE ( 'NONE', *, *, #25583, .T. ) ; +#39564 = CARTESIAN_POINT ( 'NONE', ( -25.50087462243000047, 120.6586440635999935, 88.03806651040000020 ) ) ; +#39565 = EDGE_LOOP ( 'NONE', ( #19634, #39882, #23417, #11534 ) ) ; +#39566 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384538513 ) ) ; +#39567 = CARTESIAN_POINT ( 'NONE', ( -40.09967836303732014, 190.2663693115700880, 106.6916270309068580 ) ) ; +#39568 = ORIENTED_EDGE ( 'NONE', *, *, #36604, .F. ) ; +#39569 = CARTESIAN_POINT ( 'NONE', ( -6.037602912117780996, 134.6461054605402410, 93.47636828169308387 ) ) ; +#39570 = DIRECTION ( 'NONE', ( -0.7075229308291650643, 0.000000000000000000, -0.7066903864854172657 ) ) ; +#39571 = CARTESIAN_POINT ( 'NONE', ( -3.600972167898018217, 167.8303938013165180, 101.4140376877321188 ) ) ; +#39572 = ORIENTED_EDGE ( 'NONE', *, *, #39925, .F. ) ; +#39573 = CARTESIAN_POINT ( 'NONE', ( -35.93866694401108219, 194.2771771401957324, 102.9199814310981935 ) ) ; +#39574 = CARTESIAN_POINT ( 'NONE', ( 2.240107920744488723, 189.9106889621689334, 103.9462041502783620 ) ) ; +#39575 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; +#39576 = EDGE_CURVE ( 'NONE', #30329, #3915, #5558, .T. ) ; +#39577 = EDGE_LOOP ( 'NONE', ( #32770, #15020, #19689, #35831 ) ) ; +#39578 = DIRECTION ( 'NONE', ( 0.5986917825334768795, 0.8009794122048727871, -0.0003615948347011540827 ) ) ; +#39579 = EDGE_LOOP ( 'NONE', ( #8012, #31642, #14628, #39524, #15483, #7457, #19837, #6199, #33747, #2559, #39487, #32866, #17520, #33772, #6971, #8513, #8211, #12531, #12269, #39451, #6462, #29813, #27669, #19546, #15531, #14943, #4262, #6263, #31544, #16365, #8885, #18582, #24184, #25451, #36818, #2810, #25576, #13749, #24449, #10634, #10876, #25705, #28525, #25186, #17355, #3515, #2958, #31479, #859, #29972, #35436, #26705, #28234, #37332, #3232, #6863, #9987, #7462, #8510, #30563, #29289, #19146, #144, #6221, #39260, #19695, #24669, #22052, #5309, #17199, #17798, #15513, #14224, #19664, #37347, #33694, #32530, #14843, #2753 ) ) ; +#39580 = CARTESIAN_POINT ( 'NONE', ( 8.189646485733250714, 150.7151143592648737, 97.35116360727698748 ) ) ; +#39581 = AXIS2_PLACEMENT_3D ( 'NONE', #2005, #5459, #39599 ) ; +#39582 = CARTESIAN_POINT ( 'NONE', ( 36.21095379737665354, 191.6236208997618746, 104.0193308707671491 ) ) ; +#39583 = CARTESIAN_POINT ( 'NONE', ( 25.63260490920000478, 192.0990437881999924, 104.2855897946000141 ) ) ; +#39584 = ADVANCED_FACE ( 'NONE', ( #29335 ), #4225, .F. ) ; +#39585 = CARTESIAN_POINT ( 'NONE', ( -28.81944710292443546, 225.0820812887928071, 73.07591030630263162 ) ) ; +#39586 = VERTEX_POINT ( 'NONE', #35629 ) ; +#39587 = AXIS2_PLACEMENT_3D ( 'NONE', #6509, #28606, #7114 ) ; +#39588 = EDGE_CURVE ( 'NONE', #30585, #15817, #7646, .T. ) ; +#39589 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364818587623, 136.5649596138779884, 181.4686487119677167 ) ) ; +#39590 = VECTOR ( 'NONE', #20407, 1000.000000000000000 ) ; +#39591 = LINE ( 'NONE', #28152, #9628 ) ; +#39592 = ADVANCED_FACE ( 'NONE', ( #22542 ), #38260, .T. ) ; +#39593 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#39594 = CARTESIAN_POINT ( 'NONE', ( -16.77991322171150301, 122.0828549981512623, 174.9337942664223249 ) ) ; +#39595 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #32534, #29471, #26412, #20251, #4716, #1659, #39059, #15540, #39668, #21499, #40269 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000004229395, 0.3750000000006343814, 0.4375000000007119860, 0.4687500000006832312, 0.5000000000006543655, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39596 = CARTESIAN_POINT ( 'NONE', ( 20.00000190450869653, 184.9707748627797912, 102.3447125600660002 ) ) ; +#39597 = LINE ( 'NONE', #5044, #24196 ) ; +#39598 = CARTESIAN_POINT ( 'NONE', ( -13.73975480782840286, 149.7280840183181283, 179.8128424031934003 ) ) ; +#39599 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; +#39600 = ORIENTED_EDGE ( 'NONE', *, *, #11288, .T. ) ; +#39601 = CARTESIAN_POINT ( 'NONE', ( 3.667815739890954330, 183.5629855106878381, 104.5953232237532688 ) ) ; +#39602 = FACE_OUTER_BOUND ( 'NONE', #21622, .T. ) ; +#39603 = VECTOR ( 'NONE', #15707, 1000.000000000000000 ) ; +#39604 = ORIENTED_EDGE ( 'NONE', *, *, #30352, .F. ) ; +#39605 = CARTESIAN_POINT ( 'NONE', ( 5.665211763448865234, 181.8706688165354137, 101.8856771814886315 ) ) ; +#39606 = CARTESIAN_POINT ( 'NONE', ( -21.48405399125571336, 115.4938544794857194, 90.28076066947326694 ) ) ; +#39607 = AXIS2_PLACEMENT_3D ( 'NONE', #1028, #35757, #32325 ) ; +#39608 = VERTEX_POINT ( 'NONE', #38057 ) ; +#39610 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( + ( #36538, #36339, #11810 ), + ( #17712, #8542, #30207 ), + ( #17910, #26953, #23668 ), + ( #2001, #8337, #33459 ) ), + .UNSPECIFIED., .F., .F., .F. ) + B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), + ( 3, 3 ), + ( 0.5322943122596603960, 0.5323199423158530008 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) + GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( + ( 1.000000000000000000, 0.7510960344373828201, 1.000000000000000000), + ( 1.000000000000000000, 0.7511072375234925103, 1.000000000000000000), + ( 1.000000000000000000, 0.7511184402484004652, 1.000000000000000000), + ( 1.000000000000000000, 0.7511296426121506498, 1.000000000000000000) ) ) + REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); +#39609 = LINE ( 'NONE', #34272, #12436 ) ; +#39611 = AXIS2_PLACEMENT_3D ( 'NONE', #25786, #10245, #22713 ) ; +#39612 = FACE_OUTER_BOUND ( 'NONE', #39739, .T. ) ; +#39613 = ORIENTED_EDGE ( 'NONE', *, *, #28070, .T. ) ; +#39614 = CARTESIAN_POINT ( 'NONE', ( 35.66555862191038528, 192.0488609114880774, 106.9001169760940542 ) ) ; +#39615 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566790 ) ) ; +#39616 = CARTESIAN_POINT ( 'NONE', ( -38.49678016213000831, 119.1204962500000022, 90.30251346168999760 ) ) ; +#39617 = CARTESIAN_POINT ( 'NONE', ( 39.06246240375268997, 183.7310523487591354, 102.0469865154631322 ) ) ; +#39618 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178662923876E-05, -0.0002331579774918193435 ) ) ; +#39619 = EDGE_LOOP ( 'NONE', ( #23746, #32513 ) ) ; +#39620 = CARTESIAN_POINT ( 'NONE', ( 38.52263288177000078, 118.6682988694000045, 87.79308722659999376 ) ) ; +#39621 = CARTESIAN_POINT ( 'NONE', ( 12.63705158234716919, 181.9329688235127378, 101.9799032954709617 ) ) ; +#39622 = DIRECTION ( 'NONE', ( 0.0004161288024532937930, -0.8480480897973873278, 0.5299191110233921753 ) ) ; +#39623 = EDGE_CURVE ( 'NONE', #37866, #6712, #6566, .T. ) ; +#39625 = ORIENTED_EDGE ( 'NONE', *, *, #39414, .F. ) ; +#39624 = ADVANCED_FACE ( 'NONE', ( #9459 ), #13323, .T. ) ; +#39626 = CARTESIAN_POINT ( 'NONE', ( -13.46631090406734543, 154.2041329885244352, 95.43294494049737864 ) ) ; +#39627 = EDGE_LOOP ( 'NONE', ( #10359, #32039, #23492, #29964 ) ) ; +#39628 = EDGE_CURVE ( 'NONE', #23190, #13580, #9481, .T. ) ; +#39629 = VERTEX_POINT ( 'NONE', #12507 ) ; +#39630 = CARTESIAN_POINT ( 'NONE', ( 16.00200912906086614, 173.8361395730204322, 102.8554915256801650 ) ) ; +#39631 = FACE_OUTER_BOUND ( 'NONE', #33788, .T. ) ; +#39632 = FACE_BOUND ( 'NONE', #28107, .T. ) ; +#39633 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422246606, 137.8359581293988469, 94.54561789153326856 ) ) ; +#39634 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#39635 = EDGE_CURVE ( 'NONE', #39184, #14606, #31136, .T. ) ; +#39636 = LINE ( 'NONE', #27416, #32113 ) ; +#39637 = CARTESIAN_POINT ( 'NONE', ( -25.63981584361267707, 209.7119832914303288, 73.44410892234432708 ) ) ; +#39638 = CIRCLE ( 'NONE', #23987, 6.000000000000007994 ) ; +#39639 = CARTESIAN_POINT ( 'NONE', ( 15.00009851376446868, 183.1875483699981828, 102.1070925222888093 ) ) ; +#39640 = EDGE_CURVE ( 'NONE', #23821, #35918, #34264, .T. ) ; +#39641 = DIRECTION ( 'NONE', ( 1.000000000000000000, 0.000000000000000000, 0.000000000000000000 ) ) ; +#39642 = CARTESIAN_POINT ( 'NONE', ( 25.99214530618421648, 205.1071296100486450, 76.08915040447824651 ) ) ; +#39643 = VERTEX_POINT ( 'NONE', #439 ) ; +#39644 = FACE_OUTER_BOUND ( 'NONE', #9664, .T. ) ; +#39645 = CARTESIAN_POINT ( 'NONE', ( 40.92144267131096314, 126.9198679979903517, 91.49572650408431684 ) ) ; +#39646 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#39647 = CARTESIAN_POINT ( 'NONE', ( -35.95366953737766380, 209.7096538831000032, 78.08022010983800953 ) ) ; +#39648 = ORIENTED_EDGE ( 'NONE', *, *, #35628, .F. ) ; +#39649 = CARTESIAN_POINT ( 'NONE', ( 37.28741399843698900, 124.9789241431960392, 93.24647550195996359 ) ) ; +#39650 = ORIENTED_EDGE ( 'NONE', *, *, #37790, .F. ) ; +#39651 = VERTEX_POINT ( 'NONE', #37659 ) ; +#39652 = LINE ( 'NONE', #17968, #17954 ) ; +#39653 = ORIENTED_EDGE ( 'NONE', *, *, #7688, .F. ) ; +#39654 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319697021, 137.8288108841867938, 291.5295797804309359 ) ) ; +#39655 = FACE_OUTER_BOUND ( 'NONE', #33319, .T. ) ; +#39656 = EDGE_LOOP ( 'NONE', ( #7040, #23547, #24654, #7461 ) ) ; +#39657 = FACE_OUTER_BOUND ( 'NONE', #5972, .T. ) ; +#39658 = CARTESIAN_POINT ( 'NONE', ( -20.24838124913999948, 144.4613572835999946, 95.83902025839000771 ) ) ; +#39659 = CARTESIAN_POINT ( 'NONE', ( -13.49529623641413068, 187.5771546723863423, 105.9222156747747761 ) ) ; +#39660 = CARTESIAN_POINT ( 'NONE', ( -20.99836224703339838, 128.8472059438258555, 92.32018788974323797 ) ) ; +#39661 = PLANE ( 'NONE', #33378 ) ; +#39662 = ORIENTED_EDGE ( 'NONE', *, *, #17567, .T. ) ; +#39663 = DIRECTION ( 'NONE', ( -0.7730662169443226484, -0.5272861007345266415, -0.3526159273084134571 ) ) ; +#39664 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26745, #23265, #20800, #2411, #21011, #20594, #14881, #14272, #39392, #38996, #33058, #33257, #11610, #17716, #36127, #14683, #33463, #29605, #30210, #27170 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000252853, 0.1875000000000367761, 0.2187500000000425215, 0.2343750000000454081, 0.2500000000000482947, 0.5000000000000808242, 0.6250000000000933698, 0.6875000000000954792, 0.7187500000000928146, 0.7343750000000875966, 0.7500000000000823785, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39665 = VECTOR ( 'NONE', #4306, 1000.000000000000114 ) ; +#39666 = CARTESIAN_POINT ( 'NONE', ( 12.31735976862525561, 134.2421354939541800, 93.71979015959720982 ) ) ; +#39667 = CARTESIAN_POINT ( 'NONE', ( -33.21561771824055143, 142.2211279827451733, 287.8488816290605996 ) ) ; +#39668 = CARTESIAN_POINT ( 'NONE', ( 5.669429426318635556, 130.0958497786469366, 92.41882637154506597 ) ) ; +#39669 = FACE_OUTER_BOUND ( 'NONE', #34747, .T. ) ; +#39670 = CARTESIAN_POINT ( 'NONE', ( -3.330101313777913408, 186.7657347127359344, 102.7732021051896680 ) ) ; +#39671 = CONICAL_SURFACE ( 'NONE', #16805, 2.502997546632800940, 0.7853981634134501455 ) ; +#39672 = CARTESIAN_POINT ( 'NONE', ( 44.95760039392538943, 114.7448431369936230, 133.6882517851541650 ) ) ; +#39673 = ORIENTED_EDGE ( 'NONE', *, *, #39396, .F. ) ; +#39674 = CARTESIAN_POINT ( 'NONE', ( -28.67959411740000064, 187.5200541186000009, 102.8237240085999957 ) ) ; +#39675 = CARTESIAN_POINT ( 'NONE', ( 0.8182017989226511023, 189.0227397806419845, 103.7000179739869878 ) ) ; +#39676 = CARTESIAN_POINT ( 'NONE', ( 27.79802923844109230, 124.0706386133946495, 91.35900831036548198 ) ) ; +#39677 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #25405, #637, #22734, #13125, #19438, #31936, #7979, #16963, #1438, #20444, #17575, #38847, #26809, #14333, #23333, #1646, #11258, #35762, #30076, #23736, #36187, #22932 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.001939772655765043810, 0.002909658983647559535, 0.003879545311530075476, 0.005819317967295106926, 0.007759090623060138810, 0.009698863278825171561, 0.01066874960670771352, 0.01163863593459025549, 0.01357840859035542788, 0.01551818124612059854 ), + .UNSPECIFIED. ) ; +#39678 = VERTEX_POINT ( 'NONE', #31533 ) ; +#39679 = EDGE_CURVE ( 'NONE', #15031, #853, #34177, .T. ) ; +#39680 = EDGE_LOOP ( 'NONE', ( #86, #32453, #4186, #36807 ) ) ; +#39681 = DIRECTION ( 'NONE', ( -0.9999998176059869959, -1.547563064684605134E-06, 0.0006039748319373232453 ) ) ; +#39682 = EDGE_CURVE ( 'NONE', #23984, #8550, #16635, .T. ) ; +#39683 = EDGE_LOOP ( 'NONE', ( #15290, #22438, #18079, #25863 ) ) ; +#39684 = ORIENTED_EDGE ( 'NONE', *, *, #14212, .T. ) ; +#39685 = ORIENTED_EDGE ( 'NONE', *, *, #3019, .F. ) ; +#39686 = CARTESIAN_POINT ( 'NONE', ( -21.18256684378343024, 163.8812283386195361, 152.8157487814327169 ) ) ; +#39687 = CARTESIAN_POINT ( 'NONE', ( 15.00165026029782567, 175.6217250206921392, 103.0971961977437701 ) ) ; +#39688 = CARTESIAN_POINT ( 'NONE', ( 20.50100932471902482, 118.1127835883590365, 89.75563873136169946 ) ) ; +#39689 = ORIENTED_EDGE ( 'NONE', *, *, #17415, .F. ) ; +#39690 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #112, #9325, #39779, #24066 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39691 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971563737 ) ) ; +#39692 = ORIENTED_EDGE ( 'NONE', *, *, #35500, .T. ) ; +#39693 = CARTESIAN_POINT ( 'NONE', ( 27.92742672377000090, 124.9274734904000042, 91.04345423159000461 ) ) ; +#39694 = AXIS2_PLACEMENT_3D ( 'NONE', #8199, #17779, #17174 ) ; +#39695 = CARTESIAN_POINT ( 'NONE', ( -39.72145289206626018, 121.0205764120224785, 124.6541090863944561 ) ) ; +#39696 = AXIS2_PLACEMENT_3D ( 'NONE', #39545, #20955, #5405 ) ; +#39698 = CARTESIAN_POINT ( 'NONE', ( -30.31843640017305574, 185.4672666245481025, 102.6607780480165246 ) ) ; +#39697 = LINE ( 'NONE', #2508, #25056 ) ; +#39699 = VERTEX_POINT ( 'NONE', #18629 ) ; +#39700 = EDGE_CURVE ( 'NONE', #21974, #3435, #26468, .T. ) ; +#39701 = PLANE ( 'NONE', #9293 ) ; +#39702 = EDGE_LOOP ( 'NONE', ( #21012, #21408, #2851 ) ) ; +#39703 = ORIENTED_EDGE ( 'NONE', *, *, #17394, .T. ) ; +#39704 = CARTESIAN_POINT ( 'NONE', ( 25.49947988276563393, 121.6390597818636934, 88.23326451243598001 ) ) ; +#39705 = CARTESIAN_POINT ( 'NONE', ( -15.99998378297181745, 127.7446958148473186, 89.15477705487283799 ) ) ; +#39706 = CARTESIAN_POINT ( 'NONE', ( 30.47672985551892566, 130.0726362972774552, 89.66414815853718778 ) ) ; +#39707 = EDGE_LOOP ( 'NONE', ( #26653, #39512, #10305, #2356 ) ) ; +#39708 = ORIENTED_EDGE ( 'NONE', *, *, #18793, .F. ) ; +#39709 = LINE ( 'NONE', #17631, #18485 ) ; +#39710 = LINE ( 'NONE', #20714, #19406 ) ; +#39711 = CARTESIAN_POINT ( 'NONE', ( 27.02806058983000526, 124.3665689137999948, 88.69107529613999930 ) ) ; +#39712 = ORIENTED_EDGE ( 'NONE', *, *, #37343, .T. ) ; +#39713 = CARTESIAN_POINT ( 'NONE', ( -36.29352938653000393, 191.1151839267000128, 106.6914996188999964 ) ) ; +#39714 = AXIS2_PLACEMENT_3D ( 'NONE', #13239, #22043, #25722 ) ; +#39715 = ORIENTED_EDGE ( 'NONE', *, *, #90, .T. ) ; +#39716 = ADVANCED_FACE ( 'NONE', ( #3492 ), #35555, .T. ) ; +#39717 = CARTESIAN_POINT ( 'NONE', ( 2.203927780028000161, 189.2284287703000132, 106.2182838559999993 ) ) ; +#39718 = ADVANCED_FACE ( 'NONE', ( #18827 ), #32647, .F. ) ; +#39719 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #26470, #10725, #33179, #32789 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999982996988420192 ), + .UNSPECIFIED. ) ; +#39720 = DIRECTION ( 'NONE', ( 7.494005416303299686E-14, 0.9743700557921596284, 0.2249510932971514887 ) ) ; +#39721 = VECTOR ( 'NONE', #38489, 1000.000000000000227 ) ; +#39722 = DIRECTION ( 'NONE', ( 0.0005884949961243157984, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#39723 = CARTESIAN_POINT ( 'NONE', ( -28.42925635489000413, 115.9590670145843205, 152.9217693939943388 ) ) ; +#39724 = CARTESIAN_POINT ( 'NONE', ( 19.47142695153164382, 148.9116984539020621, 183.2032397300831406 ) ) ; +#39725 = EDGE_CURVE ( 'NONE', #4191, #21584, #21757, .T. ) ; +#39726 = ORIENTED_EDGE ( 'NONE', *, *, #3756, .F. ) ; +#39727 = CARTESIAN_POINT ( 'NONE', ( -15.10535409822645647, 135.6520233040683934, 94.05869708244797778 ) ) ; +#39728 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178662923876E-05, -0.0002331579774918193435 ) ) ; +#39729 = ORIENTED_EDGE ( 'NONE', *, *, #36326, .F. ) ; +#39730 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5488, #36776, #14507, #2241 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 0.9999999706564445257 ), + .UNSPECIFIED. ) ; +#39731 = CARTESIAN_POINT ( 'NONE', ( 30.04402159321136523, 126.8238645745600195, 89.08542214068437204 ) ) ; +#39732 = ORIENTED_EDGE ( 'NONE', *, *, #28086, .F. ) ; +#39734 = DIRECTION ( 'NONE', ( 0.7066840230495562425, 0.09324023112872850683, -0.7013586463896738232 ) ) ; +#39733 = FACE_OUTER_BOUND ( 'NONE', #22224, .T. ) ; +#39735 = ORIENTED_EDGE ( 'NONE', *, *, #37098, .T. ) ; +#39736 = AXIS2_PLACEMENT_3D ( 'NONE', #45, #233, #34173 ) ; +#39737 = EDGE_LOOP ( 'NONE', ( #928, #40181, #39887, #15240, #20624, #36800 ) ) ; +#39738 = ADVANCED_FACE ( 'NONE', ( #19234 ), #7558, .F. ) ; +#39739 = EDGE_LOOP ( 'NONE', ( #35888, #28344, #3292, #23385 ) ) ; +#39740 = CARTESIAN_POINT ( 'NONE', ( 3.098523672063000056, 209.6781939275000184, 76.19310875697000540 ) ) ; +#39741 = VECTOR ( 'NONE', #33283, 1000.000000000000000 ) ; +#39742 = CARTESIAN_POINT ( 'NONE', ( -25.50006284340070906, 118.1130153187805689, 89.78316558933853742 ) ) ; +#39743 = DIRECTION ( 'NONE', ( -0.1305263947813612435, 0.9660168765824662662, 0.2231014442428296274 ) ) ; +#39744 = CARTESIAN_POINT ( 'NONE', ( 43.53807108224319222, 185.3499265735169388, 107.5016931662128314 ) ) ; +#39745 = CIRCLE ( 'NONE', #12328, 17.00000000000409273 ) ; +#39746 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#39747 = ORIENTED_EDGE ( 'NONE', *, *, #18656, .T. ) ; +#39748 = ORIENTED_EDGE ( 'NONE', *, *, #3526, .T. ) ; +#39749 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; +#39750 = AXIS2_PLACEMENT_3D ( 'NONE', #30457, #39634, #8785 ) ; +#39751 = VERTEX_POINT ( 'NONE', #26814 ) ; +#39752 = ORIENTED_EDGE ( 'NONE', *, *, #13476, .T. ) ; +#39753 = CARTESIAN_POINT ( 'NONE', ( 9.152074098956999748, 130.1605700231000071, 92.51966563137000321 ) ) ; +#39754 = CARTESIAN_POINT ( 'NONE', ( -30.07200330635009067, 135.2897752519686776, 91.41834187752364471 ) ) ; +#39755 = VERTEX_POINT ( 'NONE', #11065 ) ; +#39756 = EDGE_CURVE ( 'NONE', #19097, #36316, #4914, .T. ) ; +#39757 = EDGE_LOOP ( 'NONE', ( #6005, #18317, #21367, #23625, #14640, #27026, #36427, #33428, #1953, #31260, #19086, #36330, #22357, #5190 ) ) ; +#39758 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; +#39759 = CARTESIAN_POINT ( 'NONE', ( -36.35461825064000152, 191.9119039205000092, 104.5553151795000133 ) ) ; +#39760 = CARTESIAN_POINT ( 'NONE', ( -25.83697249613999958, 120.9034817377000053, 87.75236535515999492 ) ) ; +#39761 = ADVANCED_FACE ( 'NONE', ( #22938 ), #35366, .T. ) ; +#39762 = ORIENTED_EDGE ( 'NONE', *, *, #32737, .F. ) ; +#39763 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927785599152, -0.0005734119022073677499 ) ) ; +#39764 = CARTESIAN_POINT ( 'NONE', ( 40.51913295777573154, 190.1118463211006713, 106.6948265151217043 ) ) ; +#39765 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29932, #26877, #29135, #26269 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39766 = EDGE_LOOP ( 'NONE', ( #26631, #4305, #16986, #39236 ) ) ; +#39767 = CARTESIAN_POINT ( 'NONE', ( 1.525580299011169094, 188.7959628186811472, 103.2389845710508922 ) ) ; +#39768 = EDGE_CURVE ( 'NONE', #22555, #2629, #29050, .T. ) ; +#39769 = CARTESIAN_POINT ( 'NONE', ( 20.50113023862372330, 193.2795108210584658, 106.2344642539453901 ) ) ; +#39770 = EDGE_CURVE ( 'NONE', #3835, #654, #12115, .T. ) ; +#39771 = FACE_OUTER_BOUND ( 'NONE', #37483, .T. ) ; +#39772 = CARTESIAN_POINT ( 'NONE', ( -19.32892285413511502, 125.6991259445026401, 176.5170428066118404 ) ) ; +#39773 = VECTOR ( 'NONE', #34908, 1000.000000000000227 ) ; +#39774 = EDGE_CURVE ( 'NONE', #26941, #9438, #35767, .T. ) ; +#39775 = DIRECTION ( 'NONE', ( 0.0005884949961156549746, -0.2249510543439098842, 0.9743698870671255730 ) ) ; +#39776 = CARTESIAN_POINT ( 'NONE', ( -4.037049386316590827, 137.0919393097333341, 92.50288271244329508 ) ) ; +#39777 = VECTOR ( 'NONE', #18951, 1000.000000000000114 ) ; +#39778 = VERTEX_POINT ( 'NONE', #26212 ) ; +#39779 = CARTESIAN_POINT ( 'NONE', ( -38.25208811840489886, 118.7131440739753145, 87.71519576191549561 ) ) ; +#39780 = ORIENTED_EDGE ( 'NONE', *, *, #39774, .F. ) ; +#39781 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#39782 = CARTESIAN_POINT ( 'NONE', ( -45.24641625685059410, 116.3183880878488026, 125.9207951598621236 ) ) ; +#39783 = VECTOR ( 'NONE', #36673, 1000.000000000000227 ) ; +#39784 = CARTESIAN_POINT ( 'NONE', ( 38.09311553484000257, 118.1689180522000129, 89.80818930495999552 ) ) ; +#39785 = CARTESIAN_POINT ( 'NONE', ( 6.031183397126417489, 135.0056560870253293, 90.93530534527089060 ) ) ; +#39786 = ORIENTED_EDGE ( 'NONE', *, *, #23163, .T. ) ; +#39787 = FACE_OUTER_BOUND ( 'NONE', #31424, .T. ) ; +#39788 = EDGE_CURVE ( 'NONE', #14171, #26024, #38450, .T. ) ; +#39789 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, -0.000000000000000000, 0.9999998176071844824 ) ) ; +#39790 = CARTESIAN_POINT ( 'NONE', ( 20.00184274542656837, 191.5977749577908469, 106.9093594267342553 ) ) ; +#39791 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971519606 ) ) ; +#39792 = CARTESIAN_POINT ( 'NONE', ( -16.17928014215196342, 122.0409702652264770, 178.1070844152368409 ) ) ; +#39793 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7071067167008887600, -0.7071068456722005013 ) ) ; +#39794 = FACE_OUTER_BOUND ( 'NONE', #38709, .T. ) ; +#39795 = DIRECTION ( 'NONE', ( 0.0005884949961241158715, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#39796 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #29190, #4020, #1159, #31654, #22254, #22852, #13636, #13043, #25523, #35283, #37978, #955, #9980, #6480, #16486, #10585 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 4 ), + ( 1.743224475509949456E-16, 0.0004902371348658318565, 0.0009804742697314893733, 0.001470711404597146782, 0.001960948539462804407, 0.002451185674328461815, 0.002941422809194119223, 0.003921897078925437943 ), + .UNSPECIFIED. ) ; +#39797 = CARTESIAN_POINT ( 'NONE', ( -14.59022374134706901, 128.1503308081717876, 179.4782974412063936 ) ) ; +#39798 = VERTEX_POINT ( 'NONE', #7775 ) ; +#39799 = CARTESIAN_POINT ( 'NONE', ( 28.46384604140109076, 184.1285027467395992, 102.1451462732341469 ) ) ; +#39801 = CONICAL_SURFACE ( 'NONE', #15009, 2.500000000149071866, 0.7853981634165752013 ) ; +#39800 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178662923876E-05, -0.0002331579774918193435 ) ) ; +#39802 = AXIS2_PLACEMENT_3D ( 'NONE', #27727, #37500, #12174 ) ; +#39803 = FACE_OUTER_BOUND ( 'NONE', #17878, .T. ) ; +#39804 = ADVANCED_FACE ( 'NONE', ( #32923 ), #10669, .T. ) ; +#39805 = CIRCLE ( 'NONE', #37199, 2.000000000040586645 ) ; +#39806 = EDGE_LOOP ( 'NONE', ( #3730, #15146, #18516, #5842 ) ) ; +#39807 = CARTESIAN_POINT ( 'NONE', ( 36.93409409893962447, 81.15548715763938503, 284.6050387078826134 ) ) ; +#39808 = CARTESIAN_POINT ( 'NONE', ( -20.59735040706742737, 116.2729919401682963, 90.28022512272735867 ) ) ; +#39809 = AXIS2_PLACEMENT_3D ( 'NONE', #4476, #10243, #19802 ) ; +#39810 = VERTEX_POINT ( 'NONE', #10271 ) ; +#39811 = CARTESIAN_POINT ( 'NONE', ( -38.38766615763000090, 118.8474237676000058, 87.72136322883000048 ) ) ; +#39812 = ADVANCED_FACE ( 'NONE', ( #16773 ), #4507, .T. ) ; +#39813 = CARTESIAN_POINT ( 'NONE', ( -5.665227795303835023, 130.9595288923176497, 89.94317851865588409 ) ) ; +#39814 = VERTEX_POINT ( 'NONE', #14141 ) ; +#39815 = FACE_OUTER_BOUND ( 'NONE', #17727, .T. ) ; +#39816 = ADVANCED_FACE ( 'NONE', ( #4095 ), #20448, .F. ) ; +#39817 = DIRECTION ( 'NONE', ( 2.081668171179845313E-15, 0.9743700557921582961, 0.2249510932971568178 ) ) ; +#39818 = CARTESIAN_POINT ( 'NONE', ( 16.44924844292772548, 122.1484196991176674, 174.6452774711495977 ) ) ; +#39819 = CARTESIAN_POINT ( 'NONE', ( -12.15421709199686617, 125.0604765512531884, 178.7580882214065525 ) ) ; +#39820 = CARTESIAN_POINT ( 'NONE', ( -5.670628684832168531, 124.6625218183467325, 88.84338314838811357 ) ) ; +#39821 = EDGE_CURVE ( 'NONE', #734, #19175, #14945, .T. ) ; +#39822 = ORIENTED_EDGE ( 'NONE', *, *, #22890, .T. ) ; +#39823 = CARTESIAN_POINT ( 'NONE', ( 38.31413649313999770, 118.8386230496000024, 87.57166059187001395 ) ) ; +#39824 = CARTESIAN_POINT ( 'NONE', ( 22.77977433793355999, 158.3069438176785582, 96.18720162681876218 ) ) ; +#39825 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -5.029100735414826696E-18, -0.0006039748319369899615 ) ) ; +#39826 = CARTESIAN_POINT ( 'NONE', ( 9.583319590155999990, 188.0453190888999870, 103.3173941805000169 ) ) ; +#39827 = VERTEX_POINT ( 'NONE', #13925 ) ; +#39828 = CARTESIAN_POINT ( 'NONE', ( -20.50092100153493746, 194.2771564787859120, 102.9104786413515740 ) ) ; +#39829 = CARTESIAN_POINT ( 'NONE', ( -43.04878996311859396, 120.9978486867018290, 90.91681167607129055 ) ) ; +#39830 = CARTESIAN_POINT ( 'NONE', ( 22.50029346826903165, 160.6303563642724441, 97.23692471953465599 ) ) ; +#39831 = CIRCLE ( 'NONE', #25472, 5.499999999954135355 ) ; +#39832 = CARTESIAN_POINT ( 'NONE', ( 36.13152553141821954, 113.7323836164099475, 89.72779640660465361 ) ) ; +#39833 = CARTESIAN_POINT ( 'NONE', ( 20.00003498291988180, 122.7399499535855796, 87.97762771590346631 ) ) ; +#39834 = VECTOR ( 'NONE', #19525, 999.9999999999998863 ) ; +#39835 = DIRECTION ( 'NONE', ( 0.0005884949961253487178, -0.2249510543439069699, 0.9743698870671261281 ) ) ; +#39836 = AXIS2_PLACEMENT_3D ( 'NONE', #9275, #12524, #19056 ) ; +#39837 = CARTESIAN_POINT ( 'NONE', ( -12.63072017624268106, 177.7897717398484474, 100.7065154983451407 ) ) ; +#39838 = DIRECTION ( 'NONE', ( 0.5988681445390194868, -0.8008476418498040594, 0.000000000000000000 ) ) ; +#39839 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #30594, #30386, #2780, #27554, #20984, #9318, #2381, #17886, #39980, #18491 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 1, 1, 1, 1, 4 ), + ( 0.000000000000000000, 0.3333332752604695748, 0.6666665448735527022, 0.7500002575778695890, 0.8333339702820865558, 0.9166676829865233467, 0.9583345393386918376, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39840 = APPROVAL_DATE_TIME ( #2662, #30192 ) ; +#39841 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; +#39842 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#39843 = CARTESIAN_POINT ( 'NONE', ( 43.75332147006468375, 113.4509643667920500, 129.6325400527374541 ) ) ; +#39844 = CARTESIAN_POINT ( 'NONE', ( -20.07226483837147413, 184.3007399386575287, 105.2172045278962571 ) ) ; +#39845 = CARTESIAN_POINT ( 'NONE', ( -35.79114221331672496, 138.5178166623233267, 284.1865182878368046 ) ) ; +#39846 = CARTESIAN_POINT ( 'NONE', ( -15.46973598943061567, 173.3940168970194975, 152.4730246110422058 ) ) ; +#39847 = ORIENTED_EDGE ( 'NONE', *, *, #13016, .T. ) ; +#39849 = VERTEX_POINT ( 'NONE', #29272 ) ; +#39848 = FACE_OUTER_BOUND ( 'NONE', #22803, .T. ) ; +#39850 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #30458, #14915, #27806, #2042 ), + .UNSPECIFIED., .F., .T. ) + B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), + ( 0.8865655149750637509, 1.570796326794942965 ), + .UNSPECIFIED. ) + CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9613647307355848159, 0.9613647307355848159, 1.000000000000000000 ) ) + REPRESENTATION_ITEM ( '' ) ); +#39851 = ORIENTED_EDGE ( 'NONE', *, *, #39635, .F. ) ; +#39852 = ORIENTED_EDGE ( 'NONE', *, *, #25857, .T. ) ; +#39853 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282901917, 148.0700263536807597, 93.85134194385574347 ) ) ; +#39854 = ORIENTED_EDGE ( 'NONE', *, *, #18020, .F. ) ; +#39855 = CARTESIAN_POINT ( 'NONE', ( 20.39856762060049178, 126.8504759496277501, 91.59777357230447592 ) ) ; +#39856 = EDGE_CURVE ( 'NONE', #12644, #6270, #5665, .T. ) ; +#39857 = EDGE_CURVE ( 'NONE', #8051, #72, #27135, .T. ) ; +#39858 = CARTESIAN_POINT ( 'NONE', ( 18.60795789290834179, 125.1298367273077616, 178.8296990479766748 ) ) ; +#39859 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971545141 ) ) ; +#39860 = EDGE_CURVE ( 'NONE', #13945, #20521, #12082, .T. ) ; +#39861 = EDGE_CURVE ( 'NONE', #4577, #9860, #23952, .T. ) ; +#39862 = VERTEX_POINT ( 'NONE', #2272 ) ; +#39863 = CARTESIAN_POINT ( 'NONE', ( -39.69649258124999847, 119.2917748880999937, 89.64400856733000467 ) ) ; +#39864 = AXIS2_PLACEMENT_3D ( 'NONE', #13922, #23335, #35764 ) ; +#39865 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323826010358517924, 0.0005734119003052979939 ) ) ; +#39866 = CARTESIAN_POINT ( 'NONE', ( -2.952854088960068069, 209.7096538831000032, 78.06028844423795476 ) ) ; +#39867 = ORIENTED_EDGE ( 'NONE', *, *, #21614, .F. ) ; +#39868 = EDGE_CURVE ( 'NONE', #8838, #30783, #3188, .T. ) ; +#39869 = CARTESIAN_POINT ( 'NONE', ( 17.25785173553822460, 152.3545783266395688, 183.2781740268191868 ) ) ; +#39870 = CONICAL_SURFACE ( 'NONE', #3289, 2.250000000020516921, 0.7853981633778843729 ) ; +#39871 = CONICAL_SURFACE ( 'NONE', #9858, 2.503158050545156055, 0.7853981633914167704 ) ; +#39872 = LINE ( 'NONE', #34332, #32517 ) ; +#39873 = CARTESIAN_POINT ( 'NONE', ( -45.28489926060583315, 117.1104644663301428, 122.6183640757826225 ) ) ; +#39874 = CARTESIAN_POINT ( 'NONE', ( -4.725727965766024496, 188.1628219710171948, 103.0965880957095209 ) ) ; +#39875 = FACE_OUTER_BOUND ( 'NONE', #34877, .T. ) ; +#39876 = EDGE_CURVE ( 'NONE', #12120, #28767, #21288, .T. ) ; +#39877 = VERTEX_POINT ( 'NONE', #5931 ) ; +#39878 = CARTESIAN_POINT ( 'NONE', ( 44.86515336672587040, 186.3325894068457274, 107.7750559962146752 ) ) ; +#39879 = CARTESIAN_POINT ( 'NONE', ( 0.8179840527628020608, 189.0240481013839826, 103.7016792968739907 ) ) ; +#39880 = CARTESIAN_POINT ( 'NONE', ( -18.71851310314255556, 125.9964326179262883, 174.7342168340691444 ) ) ; +#39881 = CARTESIAN_POINT ( 'NONE', ( -35.44284610461649976, 192.5525937778500349, 106.9110644015157874 ) ) ; +#39882 = ORIENTED_EDGE ( 'NONE', *, *, #21619, .F. ) ; +#39883 = CARTESIAN_POINT ( 'NONE', ( -26.00760980898482799, 207.8686442861051376, 77.29275028086965449 ) ) ; +#39884 = ORIENTED_EDGE ( 'NONE', *, *, #19557, .T. ) ; +#39885 = ADVANCED_FACE ( 'NONE', ( #30489 ), #8414, .T. ) ; +#39886 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #8988, #15120, #33094, #17546 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39887 = ORIENTED_EDGE ( 'NONE', *, *, #10668, .T. ) ; +#39888 = VERTEX_POINT ( 'NONE', #21496 ) ; +#39889 = CARTESIAN_POINT ( 'NONE', ( -36.23826762833000714, 191.7567847793000055, 105.8251259594999993 ) ) ; +#39890 = PLANE ( 'NONE', #17563 ) ; +#39891 = CIRCLE ( 'NONE', #24896, 5.000000000000022204 ) ; +#39892 = CARTESIAN_POINT ( 'NONE', ( -25.51533646434189961, 211.0902259025884007, 73.57326538444725372 ) ) ; +#39893 = AXIS2_PLACEMENT_3D ( 'NONE', #694, #13378, #492 ) ; +#39894 = ORIENTED_EDGE ( 'NONE', *, *, #30521, .F. ) ; +#39895 = CARTESIAN_POINT ( 'NONE', ( 46.08001025735557477, 185.2443139781923094, 105.4710248038584410 ) ) ; +#39896 = CARTESIAN_POINT ( 'NONE', ( -12.63715494630207736, 134.7931114243770878, 93.38774708601914654 ) ) ; +#39897 = ORIENTED_EDGE ( 'NONE', *, *, #5547, .T. ) ; +#39898 = AXIS2_PLACEMENT_3D ( 'NONE', #16465, #28959, #737 ) ; +#39899 = CARTESIAN_POINT ( 'NONE', ( 25.63602418784000037, 121.4763877717000042, 90.24810266935999437 ) ) ; +#39900 = CONICAL_SURFACE ( 'NONE', #6590, 6.502999999910944240, 0.7853981633952109576 ) ; +#39901 = DIRECTION ( 'NONE', ( 0.0005884949961222141809, -0.2249510543439070531, 0.9743698870671262391 ) ) ; +#39903 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#39902 = FACE_OUTER_BOUND ( 'NONE', #21815, .T. ) ; +#39904 = VERTEX_POINT ( 'NONE', #18387 ) ; +#39905 = CARTESIAN_POINT ( 'NONE', ( 3.789323313120610326, 143.5973985926711407, 95.62144737670534766 ) ) ; +#39906 = ORIENTED_EDGE ( 'NONE', *, *, #27662, .F. ) ; +#39907 = EDGE_CURVE ( 'NONE', #33001, #7231, #4909, .T. ) ; +#39908 = CARTESIAN_POINT ( 'NONE', ( 19.99941580399983110, 118.1025156334579265, 87.25545403306659864 ) ) ; +#39909 = DIRECTION ( 'NONE', ( -0.0005734119072323276903, 0.000000000000000000, -0.9999998355993787724 ) ) ; +#39910 = ADVANCED_FACE ( 'NONE', ( #33735 ), #21080, .T. ) ; +#39911 = EDGE_CURVE ( 'NONE', #726, #10860, #2865, .T. ) ; +#39912 = ORIENTED_EDGE ( 'NONE', *, *, #14295, .T. ) ; +#39913 = CARTESIAN_POINT ( 'NONE', ( -30.45076006172021721, 127.0987129872037116, 89.01436239194951838 ) ) ; +#39914 = CARTESIAN_POINT ( 'NONE', ( -15.99998878844695938, 127.1155804165569094, 89.00952866523211071 ) ) ; +#39915 = DIRECTION ( 'NONE', ( -0.7069870866307825796, 0.6508451585900837388, 0.2767125564139931715 ) ) ; +#39916 = CARTESIAN_POINT ( 'NONE', ( 12.64035708966239469, 130.9607540069779361, 89.93343061172069497 ) ) ; +#39917 = CARTESIAN_POINT ( 'NONE', ( -12.64460002090920199, 134.9330247580281821, 90.83373639382720910 ) ) ; +#39918 = ORIENTED_EDGE ( 'NONE', *, *, #36237, .T. ) ; +#39919 = EDGE_CURVE ( 'NONE', #13582, #38161, #15342, .T. ) ; +#39920 = ORIENTED_EDGE ( 'NONE', *, *, #10307, .F. ) ; +#39921 = CARTESIAN_POINT ( 'NONE', ( -1.852806604127735790, 189.5547471265975332, 103.8459406374928022 ) ) ; +#39922 = PLANE ( 'NONE', #34432 ) ; +#39923 = VECTOR ( 'NONE', #22345, 1000.000000000000227 ) ; +#39924 = CARTESIAN_POINT ( 'NONE', ( 16.03566890003928691, 121.9740942863827797, 174.5072303276584194 ) ) ; +#39925 = EDGE_CURVE ( 'NONE', #15817, #9960, #11262, .T. ) ; +#39926 = ORIENTED_EDGE ( 'NONE', *, *, #21345, .F. ) ; +#39927 = LINE ( 'NONE', #27286, #397 ) ; +#39928 = VECTOR ( 'NONE', #30398, 1000.000000000000114 ) ; +#39929 = CARTESIAN_POINT ( 'NONE', ( 0.5641597396262441055, 188.3807571526811842, 106.2295656640635997 ) ) ; +#39930 = EDGE_LOOP ( 'NONE', ( #14980, #716, #16234, #31366 ) ) ; +#39931 = CARTESIAN_POINT ( 'NONE', ( -20.51954544737882813, 208.5436959433371840, 73.72443719612235213 ) ) ; +#39932 = ADVANCED_FACE ( 'NONE', ( #33526 ), #40069, .F. ) ; +#39933 = CARTESIAN_POINT ( 'NONE', ( 13.50012729195547934, 124.7429919913152929, 88.95710818440272760 ) ) ; +#39934 = CARTESIAN_POINT ( 'NONE', ( -23.32513133998376631, 121.2983238336744733, 152.0219650958596560 ) ) ; +#39935 = CARTESIAN_POINT ( 'NONE', ( 5.025754754826063930, 148.2514616712418558, 93.87643320611178410 ) ) ; +#39936 = ORIENTED_EDGE ( 'NONE', *, *, #16990, .F. ) ; +#39937 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; +#39938 = CARTESIAN_POINT ( 'NONE', ( -5.668109638569103659, 123.6908915871893129, 91.29154949463998037 ) ) ; +#39939 = ORIENTED_EDGE ( 'NONE', *, *, #40041, .T. ) ; +#39940 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971561239 ) ) ; +#39941 = VERTEX_POINT ( 'NONE', #5519 ) ; +#39943 = CARTESIAN_POINT ( 'NONE', ( -41.21889173341337909, 77.14301703112138853, 286.7120891191068495 ) ) ; +#39942 = DIRECTION ( 'NONE', ( -0.6087611434179117653, 0.7728348325624403437, 0.1792657018023851578 ) ) ; +#39944 = ORIENTED_EDGE ( 'NONE', *, *, #29914, .F. ) ; +#39945 = VECTOR ( 'NONE', #2189, 1000.000000000000000 ) ; +#39946 = ORIENTED_EDGE ( 'NONE', *, *, #11253, .T. ) ; +#39947 = AXIS2_PLACEMENT_3D ( 'NONE', #4030, #1171, #35486 ) ; +#39948 = ORIENTED_EDGE ( 'NONE', *, *, #32022, .T. ) ; +#39949 = CARTESIAN_POINT ( 'NONE', ( 3.108838874058000190, 209.6469810035999899, 76.19428017209001780 ) ) ; +#39950 = CARTESIAN_POINT ( 'NONE', ( 39.32082689945465148, 128.7843916429683588, 92.44030466315589933 ) ) ; +#39951 = CARTESIAN_POINT ( 'NONE', ( 28.36925001313300143, 160.2013931541194722, 186.9397811580082021 ) ) ; +#39952 = CARTESIAN_POINT ( 'NONE', ( -12.52440953105373467, 125.9311653633099155, 282.5627442275269914 ) ) ; +#39953 = EDGE_CURVE ( 'NONE', #13040, #35915, #1583, .T. ) ; +#39954 = ORIENTED_EDGE ( 'NONE', *, *, #7766, .F. ) ; +#39955 = EDGE_CURVE ( 'NONE', #11331, #37167, #27024, .T. ) ; +#39956 = VERTEX_POINT ( 'NONE', #14752 ) ; +#39957 = CARTESIAN_POINT ( 'NONE', ( -20.00004361580415591, 118.8155695144462669, 87.27991261026372172 ) ) ; +#39958 = ORIENTED_EDGE ( 'NONE', *, *, #15156, .T. ) ; +#39959 = ORIENTED_EDGE ( 'NONE', *, *, #9520, .F. ) ; +#39960 = DIRECTION ( 'NONE', ( -0.0005559617634689729363, 0.3907311284899303572, -0.9205046855586902499 ) ) ; +#39961 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; +#39962 = CARTESIAN_POINT ( 'NONE', ( -15.49892152314593474, 126.3880536741664713, 90.72282109318840071 ) ) ; +#39963 = CARTESIAN_POINT ( 'NONE', ( 14.72298203570611363, 123.1221558600993973, 178.3646181999850455 ) ) ; +#39964 = CARTESIAN_POINT ( 'NONE', ( 35.54969460229000333, 192.2381900686000051, 103.8743573426999944 ) ) ; +#39965 = ORIENTED_EDGE ( 'NONE', *, *, #5895, .F. ) ; +#39966 = VERTEX_POINT ( 'NONE', #8197 ) ; +#39967 = ORIENTED_EDGE ( 'NONE', *, *, #38111, .F. ) ; +#39968 = CARTESIAN_POINT ( 'NONE', ( -5.675513023005390956, 123.6907347205156924, 91.29157260444318922 ) ) ; +#39969 = EDGE_CURVE ( 'NONE', #14254, #7718, #36833, .T. ) ; +#39970 = CARTESIAN_POINT ( 'NONE', ( -35.82907652810000343, 191.7614052614000002, 104.0414502677000144 ) ) ; +#39971 = EDGE_LOOP ( 'NONE', ( #10835, #22179, #39715, #26035 ) ) ; +#39972 = CARTESIAN_POINT ( 'NONE', ( 39.73110239298318191, 165.1365825546612882, 181.9150604281450114 ) ) ; +#39973 = ORIENTED_EDGE ( 'NONE', *, *, #22234, .F. ) ; +#39974 = LINE ( 'NONE', #2578, #36953 ) ; +#39975 = LINE ( 'NONE', #36918, #19301 ) ; +#39976 = CARTESIAN_POINT ( 'NONE', ( -41.00789709315080245, 189.3422338137688712, 107.0789350927375949 ) ) ; +#39977 = EDGE_LOOP ( 'NONE', ( #14550, #31553, #33675, #31809, #21657, #788, #38595, #18061, #19004, #20142, #14437 ) ) ; +#39978 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #35066, #7072, #19737, #23231, #32047, #10368, #23037, #32626, #4004, #35664 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#39979 = CARTESIAN_POINT ( 'NONE', ( 20.50141158344984404, 191.9758728513155575, 106.4093071483684696 ) ) ; +#39980 = CARTESIAN_POINT ( 'NONE', ( 38.66881667660670274, 119.1641615024088736, 90.25890836112429838 ) ) ; +#39981 = VECTOR ( 'NONE', #18427, 1000.000000000000227 ) ; +#39982 = DIRECTION ( 'NONE', ( 0.6087613186456907188, 0.7730177010543248795, 0.1784749023741044327 ) ) ; +#39983 = EDGE_CURVE ( 'NONE', #2174, #12564, #23186, .T. ) ; +#39984 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#39985 = DIRECTION ( 'NONE', ( -0.0002393071182776102175, -0.2252352986010028590, 0.9743043687658493601 ) ) ; +#39986 = ORIENTED_EDGE ( 'NONE', *, *, #18358, .F. ) ; +#39987 = DIRECTION ( 'NONE', ( -0.9914446600486714889, -0.1273122826259382723, -0.02879355402772574776 ) ) ; +#39988 = ORIENTED_EDGE ( 'NONE', *, *, #5296, .F. ) ; +#39989 = CARTESIAN_POINT ( 'NONE', ( 8.048542122852918368, 150.7638762473669658, 97.53355711752999468 ) ) ; +#39990 = CARTESIAN_POINT ( 'NONE', ( -14.22265864990228401, 129.0629248693782074, 176.7848948385215806 ) ) ; +#39991 = CARTESIAN_POINT ( 'NONE', ( 37.37535261800000086, 117.3179660600000034, 89.81729445893999753 ) ) ; +#39992 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -3.370379598151327408E-34, 0.0006039748319386880390 ) ) ; +#39993 = ORIENTED_EDGE ( 'NONE', *, *, #2345, .T. ) ; +#39994 = EDGE_CURVE ( 'NONE', #11012, #20699, #20786, .T. ) ; +#39995 = PLANE ( 'NONE', #21404 ) ; +#39996 = EDGE_CURVE ( 'NONE', #25396, #13070, #19256, .T. ) ; +#39997 = AXIS2_PLACEMENT_3D ( 'NONE', #31016, #34257, #27968 ) ; +#39998 = ORIENTED_EDGE ( 'NONE', *, *, #32348, .T. ) ; +#39999 = CARTESIAN_POINT ( 'NONE', ( -21.10558147345552271, 175.5300362219209944, 102.9267844786626682 ) ) ; +#40000 = CARTESIAN_POINT ( 'NONE', ( 21.71195827823497737, 154.2857483248134542, 95.25948025584419554 ) ) ; +#40001 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; +#40002 = CARTESIAN_POINT ( 'NONE', ( -15.99970515225999179, 151.9770228117144484, 94.74935186622352035 ) ) ; +#40003 = DIRECTION ( 'NONE', ( 0.7933530821295674551, 0.5932640870152211532, 0.1364866665045049998 ) ) ; +#40004 = EDGE_CURVE ( 'NONE', #18505, #13844, #14170, .T. ) ; +#40005 = CONICAL_SURFACE ( 'NONE', #6036, 2.500000000051350035, 0.7853981633778843729 ) ; +#40006 = CARTESIAN_POINT ( 'NONE', ( -17.26224783785864147, 152.3522462518728560, 183.2690931728076009 ) ) ; +#40007 = EDGE_CURVE ( 'NONE', #29513, #31494, #26641, .T. ) ; +#40008 = FACE_OUTER_BOUND ( 'NONE', #36728, .T. ) ; +#40009 = EDGE_LOOP ( 'NONE', ( #11247, #35010, #20985, #28706, #25195 ) ) ; +#40010 = EDGE_CURVE ( 'NONE', #4584, #10555, #11092, .T. ) ; +#40011 = DIRECTION ( 'NONE', ( -0.7933533411653084233, 0.5930537057989933025, 0.1373964268091529273 ) ) ; +#40012 = FACE_OUTER_BOUND ( 'NONE', #22324, .T. ) ; +#40013 = CIRCLE ( 'NONE', #2808, 5.999999999929131356 ) ; +#40014 = CARTESIAN_POINT ( 'NONE', ( 44.73086057231284229, 168.6464848246152144, 183.7642316016321899 ) ) ; +#40015 = ORIENTED_EDGE ( 'NONE', *, *, #26703, .T. ) ; +#40016 = CARTESIAN_POINT ( 'NONE', ( -23.36589107377781005, 134.9158523539519194, 90.81477344275025132 ) ) ; +#40017 = CARTESIAN_POINT ( 'NONE', ( 36.54456757410444112, 191.0204932105091018, 106.6271468414739729 ) ) ; +#40018 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #24708, #30626, #21822, #34262, #2616, #6265, #18718, #15086, #31219, #13618, #1135, #6865, #19533, #22828, #736, #16859, #13021, #7459, #19925, #31834, #13419, #29164, #28754, #7261 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 2, 2, 2, 2, 2, 1, 1, 2, 2, 2, 4 ), + ( 0.000000000000000000, 0.1250000000000151545, 0.1875000000000228428, 0.2187500000000260347, 0.2500000000000292544, 0.3750000000000328626, 0.4375000000000357492, 0.4687500000000371370, 0.4843750000000389688, 0.4921875000000313083, 0.5000000000000236478, 0.7500000000000118794, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#40019 = ORIENTED_EDGE ( 'NONE', *, *, #14389, .F. ) ; +#40020 = CARTESIAN_POINT ( 'NONE', ( -38.46836053098000008, 118.9254552666999984, 87.72568244094999557 ) ) ; +#40021 = CARTESIAN_POINT ( 'NONE', ( 30.44899542203640408, 126.4319227165660635, 91.90255272003975051 ) ) ; +#40022 = FACE_OUTER_BOUND ( 'NONE', #9356, .T. ) ; +#40023 = ORIENTED_EDGE ( 'NONE', *, *, #39788, .F. ) ; +#40024 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.000000000000000000, 1.000000000000000000 ) ) ; +#40025 = CARTESIAN_POINT ( 'NONE', ( -43.86878163833967648, 122.3260230262551005, 88.14364713971215792 ) ) ; +#40026 = CARTESIAN_POINT ( 'NONE', ( -26.12281312345999851, 191.2058208288000003, 107.0187681231000028 ) ) ; +#40027 = CARTESIAN_POINT ( 'NONE', ( -35.95487748704000097, 225.9002260771000010, 76.08022047461976456 ) ) ; +#40028 = CARTESIAN_POINT ( 'NONE', ( -35.92250688068352105, 148.9769121975630242, 291.4743218914980503 ) ) ; +#40029 = VERTEX_POINT ( 'NONE', #4739 ) ; +#40030 = CARTESIAN_POINT ( 'NONE', ( 38.93086770562999988, 120.1677338017999972, 87.23041171529000337 ) ) ; +#40031 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621345620, 0.1788331191967953704 ) ) ; +#40032 = VECTOR ( 'NONE', #466, 1000.000000000000000 ) ; +#40033 = CARTESIAN_POINT ( 'NONE', ( 36.75525778864385984, 191.6314878030200930, 104.3442272597018246 ) ) ; +#40034 = CARTESIAN_POINT ( 'NONE', ( -16.56513926556643668, 151.9899594182569160, 182.4590145884489516 ) ) ; +#40035 = ORIENTED_EDGE ( 'NONE', *, *, #21975, .F. ) ; +#40036 = CONICAL_SURFACE ( 'NONE', #3450, 48.00000000001436007, 0.7853981633972800802 ) ; +#40037 = CARTESIAN_POINT ( 'NONE', ( 17.99646903002095044, 132.9726891188946922, 90.34121599450540430 ) ) ; +#40038 = CYLINDRICAL_SURFACE ( 'NONE', #31728, 2.000000000000011546 ) ; +#40039 = AXIS2_PLACEMENT_3D ( 'NONE', #10914, #3944, #38687 ) ; +#40040 = CARTESIAN_POINT ( 'NONE', ( -24.53444877736164997, 213.7106621591174473, 73.07332227467423991 ) ) ; +#40041 = EDGE_CURVE ( 'NONE', #6684, #19312, #13958, .T. ) ; +#40042 = FACE_OUTER_BOUND ( 'NONE', #23296, .T. ) ; +#40043 = CARTESIAN_POINT ( 'NONE', ( 6.042240099596939196, 177.1173855813495948, 103.6190021212635770 ) ) ; +#40044 = EDGE_CURVE ( 'NONE', #39608, #12175, #7020, .T. ) ; +#40045 = APPROVAL_DATE_TIME ( #5712, #25220 ) ; +#40046 = CARTESIAN_POINT ( 'NONE', ( 5.342233081412309126, 181.6904643235373840, 101.5962455245849014 ) ) ; +#40047 = LINE ( 'NONE', #3427, #13947 ) ; +#40048 = FACE_OUTER_BOUND ( 'NONE', #23678, .T. ) ; +#40049 = CARTESIAN_POINT ( 'NONE', ( -20.51880467302672173, 211.0905570380611493, 75.57084890002228406 ) ) ; +#40050 = CARTESIAN_POINT ( 'NONE', ( -39.71442208983258837, 169.2236437704519574, 164.3192996581971101 ) ) ; +#40051 = ADVANCED_FACE ( 'NONE', ( #36010 ), #38880, .F. ) ; +#40052 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048999590, 134.2394347308982674, 93.74516030698919167 ) ) ; +#40053 = ORIENTED_EDGE ( 'NONE', *, *, #12838, .T. ) ; +#40054 = ORIENTED_EDGE ( 'NONE', *, *, #5184, .F. ) ; +#40055 = ADVANCED_FACE ( 'NONE', ( #17405 ), #19200, .F. ) ; +#40056 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971576227 ) ) ; +#40057 = EDGE_CURVE ( 'NONE', #33034, #6999, #12781, .T. ) ; +#40058 = LINE ( 'NONE', #30258, #22900 ) ; +#40059 = AXIS2_PLACEMENT_3D ( 'NONE', #14920, #17758, #17557 ) ; +#40060 = FACE_OUTER_BOUND ( 'NONE', #14408, .T. ) ; +#40061 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749388340, 132.8602140592406045, 90.82839891340712768 ) ) ; +#40062 = CIRCLE ( 'NONE', #38116, 2.000000000000011546 ) ; +#40063 = ORIENTED_EDGE ( 'NONE', *, *, #12135, .F. ) ; +#40064 = CARTESIAN_POINT ( 'NONE', ( 13.50164015315887411, 187.2961052408047067, 105.4512425975207464 ) ) ; +#40065 = VECTOR ( 'NONE', #7525, 1000.000000000000000 ) ; +#40066 = CARTESIAN_POINT ( 'NONE', ( -15.99998378297181745, 127.7446958148473186, 89.15477705487283799 ) ) ; +#40067 = CARTESIAN_POINT ( 'NONE', ( -18.61079839510214029, 126.0371735097383095, 174.9248182282352957 ) ) ; +#40068 = ORIENTED_EDGE ( 'NONE', *, *, #38832, .F. ) ; +#40069 = CYLINDRICAL_SURFACE ( 'NONE', #33568, 2.000000000000000000 ) ; +#40070 = FACE_OUTER_BOUND ( 'NONE', #2955, .T. ) ; +#40071 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, + ( #16350, #21910 ), + .UNSPECIFIED., .F., .F., + ( 2, 2 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#40072 = CARTESIAN_POINT ( 'NONE', ( -40.52667274848001000, 173.3654007757000102, 152.4718672074000381 ) ) ; +#40073 = CARTESIAN_POINT ( 'NONE', ( -13.01264633640278312, 134.9181483276104245, 90.80908945356310369 ) ) ; +#40074 = FACE_OUTER_BOUND ( 'NONE', #37637, .T. ) ; +#40075 = EDGE_LOOP ( 'NONE', ( #40035, #36434, #19395, #2147 ) ) ; +#40076 = EDGE_LOOP ( 'NONE', ( #34097, #40019, #27539, #19287 ) ) ; +#40077 = CARTESIAN_POINT ( 'NONE', ( -18.96028624430033105, 148.4102203051928939, 183.7254338880509010 ) ) ; +#40078 = CARTESIAN_POINT ( 'NONE', ( 3.006846131046999826, 190.4615416249000077, 103.6219035456000057 ) ) ; +#40079 = CARTESIAN_POINT ( 'NONE', ( 21.70190315701263017, 123.1837599801819465, 176.5257127422096914 ) ) ; +#40080 = ORIENTED_EDGE ( 'NONE', *, *, #31813, .F. ) ; +#40081 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#40082 = ORIENTED_EDGE ( 'NONE', *, *, #9410, .F. ) ; +#40083 = VECTOR ( 'NONE', #18402, 1000.000000000000227 ) ; +#40084 = AXIS2_PLACEMENT_3D ( 'NONE', #7104, #19574, #13459 ) ; +#40085 = EDGE_CURVE ( 'NONE', #5335, #21013, #23978, .T. ) ; +#40086 = EDGE_CURVE ( 'NONE', #8550, #38531, #30945, .T. ) ; +#40087 = EDGE_CURVE ( 'NONE', #24036, #18328, #33356, .T. ) ; +#40088 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825922896761066, 0.0005734119023223271158 ) ) ; +#40089 = VECTOR ( 'NONE', #22114, 1000.000000000000114 ) ; +#40090 = CARTESIAN_POINT ( 'NONE', ( -37.05652687719999960, 191.1891292050000004, 105.7508132630999995 ) ) ; +#40091 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; +#40092 = CARTESIAN_POINT ( 'NONE', ( -36.61650759155055113, 191.3591673295911733, 106.3831752203444267 ) ) ; +#40093 = CIRCLE ( 'NONE', #27725, 2.250000000041461945 ) ; +#40094 = EDGE_CURVE ( 'NONE', #7297, #7762, #23768, .T. ) ; +#40095 = CARTESIAN_POINT ( 'NONE', ( 36.06588537441000142, 194.9391275604999976, 107.7152975676000040 ) ) ; +#40096 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099476, 177.0629346110185338, 100.5202509416223506 ) ) ; +#40097 = EDGE_LOOP ( 'NONE', ( #475, #20334, #24857, #32220, #32189, #25254 ) ) ; +#40098 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319389023857 ) ) ; +#40099 = CARTESIAN_POINT ( 'NONE', ( -26.01326056281665089, 211.0902258159713085, 76.07393268928584007 ) ) ; +#40100 = FACE_OUTER_BOUND ( 'NONE', #3461, .T. ) ; +#40102 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; +#40101 = CARTESIAN_POINT ( 'NONE', ( 15.66686102866751362, 185.8347106091287628, 102.8888882241695342 ) ) ; +#40103 = EDGE_CURVE ( 'NONE', #23762, #22787, #20693, .T. ) ; +#40104 = ORIENTED_EDGE ( 'NONE', *, *, #20155, .F. ) ; +#40105 = ORIENTED_EDGE ( 'NONE', *, *, #7705, .T. ) ; +#40106 = CIRCLE ( 'NONE', #939, 59.40509898897000340 ) ; +#40107 = CARTESIAN_POINT ( 'NONE', ( 39.55110128785999990, 119.8420530485000199, 90.51490709511000432 ) ) ; +#40108 = FACE_OUTER_BOUND ( 'NONE', #19050, .T. ) ; +#40109 = ADVANCED_FACE ( 'NONE', ( #33147 ), #12684, .F. ) ; +#40110 = CARTESIAN_POINT ( 'NONE', ( -35.69675826569999799, 199.6921533858000259, 89.52312211516000673 ) ) ; +#40111 = FACE_OUTER_BOUND ( 'NONE', #29989, .T. ) ; +#40112 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; +#40113 = VECTOR ( 'NONE', #14104, 1000.000000000000000 ) ; +#40114 = AXIS2_PLACEMENT_3D ( 'NONE', #20619, #5071, #26979 ) ; +#40115 = LINE ( 'NONE', #2905, #21706 ) ; +#40116 = ORIENTED_EDGE ( 'NONE', *, *, #23912, .T. ) ; +#40117 = ORIENTED_EDGE ( 'NONE', *, *, #15074, .F. ) ; +#40118 = CARTESIAN_POINT ( 'NONE', ( 3.064236136099508290, 190.8512031035150471, 106.7914583158460573 ) ) ; +#40119 = CIRCLE ( 'NONE', #13362, 2.000000000383225451 ) ; +#40120 = CARTESIAN_POINT ( 'NONE', ( -23.39890890703999915, 142.7284776650000140, 28.07991271570000080 ) ) ; +#40121 = CARTESIAN_POINT ( 'NONE', ( 16.12678657333407628, 122.0322087771653088, 174.5413712490106093 ) ) ; +#40122 = ORIENTED_EDGE ( 'NONE', *, *, #38958, .F. ) ; +#40123 = ORIENTED_EDGE ( 'NONE', *, *, #17326, .F. ) ; +#40124 = CARTESIAN_POINT ( 'NONE', ( 35.99069571327236616, 209.7096533915727434, 75.59255538986752754 ) ) ; +#40125 = CARTESIAN_POINT ( 'NONE', ( 36.46831602377621806, 265.1087381855853664, 205.0355407830140848 ) ) ; +#40126 = CARTESIAN_POINT ( 'NONE', ( 2.740375152715848195, 189.5745065435120580, 106.5097161501692682 ) ) ; +#40127 = CARTESIAN_POINT ( 'NONE', ( -25.60482124379134916, 148.7605381266695588, 204.9143772677416564 ) ) ; +#40128 = FACE_OUTER_BOUND ( 'NONE', #39286, .T. ) ; +#40129 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; +#40130 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#40131 = EDGE_CURVE ( 'NONE', #29958, #24799, #4528, .T. ) ; +#40132 = EDGE_CURVE ( 'NONE', #36524, #15841, #33659, .T. ) ; +#40133 = ORIENTED_EDGE ( 'NONE', *, *, #4499, .T. ) ; +#40134 = CARTESIAN_POINT ( 'NONE', ( 25.99096411850820942, 206.5437039761336564, 74.14227870554802280 ) ) ; +#40135 = EDGE_CURVE ( 'NONE', #34329, #29279, #3118, .T. ) ; +#40136 = CARTESIAN_POINT ( 'NONE', ( -35.75152918212248920, 165.7724375289338354, 188.2119208754558599 ) ) ; +#40137 = VECTOR ( 'NONE', #11537, 1000.000000000000000 ) ; +#40138 = AXIS2_PLACEMENT_3D ( 'NONE', #22007, #3169, #31810 ) ; +#40139 = EDGE_LOOP ( 'NONE', ( #30291, #13740, #17824, #36676 ) ) ; +#40140 = EDGE_CURVE ( 'NONE', #32027, #18851, #27045, .T. ) ; +#40141 = CARTESIAN_POINT ( 'NONE', ( -5.668304492375956016, 188.0633424520996755, 103.3136157537519466 ) ) ; +#40142 = VERTEX_POINT ( 'NONE', #21314 ) ; +#40143 = AXIS2_PLACEMENT_3D ( 'NONE', #6254, #11808, #9140 ) ; +#40145 = CARTESIAN_POINT ( 'NONE', ( 35.61358792416734786, 192.0416364148001662, 103.8993421123607419 ) ) ; +#40144 = LINE ( 'NONE', #33185, #14183 ) ; +#40146 = ORIENTED_EDGE ( 'NONE', *, *, #34721, .F. ) ; +#40147 = ADVANCED_FACE ( 'NONE', ( #33761 ), #27159, .T. ) ; +#40148 = ORIENTED_EDGE ( 'NONE', *, *, #30882, .F. ) ; +#40149 = VERTEX_POINT ( 'NONE', #21104 ) ; +#40150 = CARTESIAN_POINT ( 'NONE', ( 2.921857347780000058, 209.0164851424000005, 76.05359827459000144 ) ) ; +#40151 = CARTESIAN_POINT ( 'NONE', ( -15.10714335758950888, 136.3268993782255620, 91.13559034338766196 ) ) ; +#40152 = CARTESIAN_POINT ( 'NONE', ( 12.63907793505734567, 177.5251405050551341, 100.8594170221115007 ) ) ; +#40153 = EDGE_LOOP ( 'NONE', ( #8035, #6646, #2257, #16257 ) ) ; +#40154 = ORIENTED_EDGE ( 'NONE', *, *, #11383, .F. ) ; +#40155 = ORIENTED_EDGE ( 'NONE', *, *, #2771, .T. ) ; +#40156 = VERTEX_POINT ( 'NONE', #5760 ) ; +#40157 = LINE ( 'NONE', #33204, #5422 ) ; +#40158 = CARTESIAN_POINT ( 'NONE', ( -19.40198027091592081, 124.9165765156423760, 177.8474014814652264 ) ) ; +#40159 = DIRECTION ( 'NONE', ( 0.0005884931661380672164, -0.2249510543440760013, 0.9743698870681923863 ) ) ; +#40160 = CARTESIAN_POINT ( 'NONE', ( 23.67998985452990368, 134.9222885997251637, 90.78792508986444432 ) ) ; +#40161 = EDGE_LOOP ( 'NONE', ( #29885, #3388, #25907, #26968 ) ) ; +#40162 = VERTEX_POINT ( 'NONE', #30912 ) ; +#40163 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971573174 ) ) ; +#40164 = CARTESIAN_POINT ( 'NONE', ( -13.83171258093479672, 150.2818367448051049, 180.5307641806243453 ) ) ; +#40165 = ORIENTED_EDGE ( 'NONE', *, *, #8830, .F. ) ; +#40166 = LINE ( 'NONE', #39972, #25531 ) ; +#40167 = ORIENTED_EDGE ( 'NONE', *, *, #16494, .F. ) ; +#40168 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971540422 ) ) ; +#40169 = DIRECTION ( 'NONE', ( -0.0006039748319383739456, 3.094196748328522329E-15, -0.9999998176071845934 ) ) ; +#40170 = ORIENTED_EDGE ( 'NONE', *, *, #15854, .T. ) ; +#40171 = VECTOR ( 'NONE', #12717, 1000.000000000000000 ) ; +#40172 = AXIS2_PLACEMENT_3D ( 'NONE', #17231, #35834, #26671 ) ; +#40173 = CONICAL_SURFACE ( 'NONE', #21988, 2.499999999949844565, 0.7853981633810270813 ) ; +#40174 = CONICAL_SURFACE ( 'NONE', #22570, 2.502999999909521822, 0.7853981633426256881 ) ; +#40175 = CARTESIAN_POINT ( 'NONE', ( -30.45076006172021721, 127.0987129872037116, 89.01436239194951838 ) ) ; +#40176 = DIRECTION ( 'NONE', ( -0.0005559617633316433355, 0.3907311284892692194, -0.9205046855589709143 ) ) ; +#40177 = CARTESIAN_POINT ( 'NONE', ( 10.03597125221916642, 167.8227034468253294, 101.4738597986363118 ) ) ; +#40178 = CARTESIAN_POINT ( 'NONE', ( -4.037441716908935163, 137.2418790766312782, 91.85329641515465937 ) ) ; +#40179 = VERTEX_POINT ( 'NONE', #9436 ) ; +#40180 = CARTESIAN_POINT ( 'NONE', ( 25.62068700201966109, 116.5989192260994542, 90.25231058625922742 ) ) ; +#40181 = ORIENTED_EDGE ( 'NONE', *, *, #18850, .T. ) ; +#40182 = EDGE_CURVE ( 'NONE', #18677, #5503, #5586, .T. ) ; +#40183 = CARTESIAN_POINT ( 'NONE', ( 3.044162730076025447, 208.9211496123335507, 73.11923083669719858 ) ) ; +#40184 = EDGE_CURVE ( 'NONE', #1066, #28925, #18009, .T. ) ; +#40185 = CARTESIAN_POINT ( 'NONE', ( -38.23875393712000204, 119.2562791585999946, 87.40938009561999422 ) ) ; +#40186 = CARTESIAN_POINT ( 'NONE', ( 25.99211731546482795, 209.7096512574500480, 76.04280604205342797 ) ) ; +#40187 = DIRECTION ( 'NONE', ( -0.7856246811335054758, -0.6187033702784218159, 0.000000000000000000 ) ) ; +#40188 = ORIENTED_EDGE ( 'NONE', *, *, #5904, .T. ) ; +#40189 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474978707994683, 155.7928101624881378, 98.18628735359374105 ) ) ; +#40190 = ORIENTED_EDGE ( 'NONE', *, *, #26448, .F. ) ; +#40191 = DIRECTION ( 'NONE', ( 0.0005884949961234677354, -0.2249510543439058596, 0.9743698870671263501 ) ) ; +#40192 = CONICAL_SURFACE ( 'NONE', #3072, 2.499999999942751128, 0.7853981634230097209 ) ; +#40193 = AXIS2_PLACEMENT_3D ( 'NONE', #3687, #5964, #6359 ) ; +#40194 = VECTOR ( 'NONE', #26135, 1000.000000000000227 ) ; +#40195 = CARTESIAN_POINT ( 'NONE', ( 6.272186697316835868, 148.2050572955672862, 96.43072783368462808 ) ) ; +#40196 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #1985, #39373, #8319, #40380 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#40197 = ORIENTED_EDGE ( 'NONE', *, *, #15515, .F. ) ; +#40199 = AXIS2_PLACEMENT_3D ( 'NONE', #35068, #1547, #4005 ) ; +#40198 = CARTESIAN_POINT ( 'NONE', ( 13.50176803575202378, 185.2342124180282212, 105.4914585805791347 ) ) ; +#40200 = CARTESIAN_POINT ( 'NONE', ( -0.4543644846839952622, 210.9999999999920988, 75.55877896313789677 ) ) ; +#40201 = AXIS2_PLACEMENT_3D ( 'NONE', #6518, #12466, #25358 ) ; +#40202 = DIRECTION ( 'NONE', ( 0.7066795775021788018, -2.105283132027209225E-15, -0.7075337269285062458 ) ) ; +#40203 = CARTESIAN_POINT ( 'NONE', ( -39.28819007159129484, 119.6036315730871280, 87.80683070790931311 ) ) ; +#40204 = ORIENTED_EDGE ( 'NONE', *, *, #10397, .F. ) ; +#40205 = DIRECTION ( 'NONE', ( -1.387778780732453075E-15, -0.9743700557921584071, -0.2249510932971565402 ) ) ; +#40206 = EDGE_CURVE ( 'NONE', #1917, #407, #2709, .T. ) ; +#40207 = FACE_OUTER_BOUND ( 'NONE', #534, .T. ) ; +#40208 = EDGE_LOOP ( 'NONE', ( #21882, #27384, #32942, #33211 ) ) ; +#40209 = CARTESIAN_POINT ( 'NONE', ( 30.06905116326987937, 134.5124848999242602, 93.54214650380033902 ) ) ; +#40210 = ORIENTED_EDGE ( 'NONE', *, *, #20741, .T. ) ; +#40211 = CARTESIAN_POINT ( 'NONE', ( 30.07038801303579234, 136.6840993378064866, 94.26968325502151913 ) ) ; +#40212 = CARTESIAN_POINT ( 'NONE', ( -3.645810450028442506, 143.5597328077978716, 95.76474948167305001 ) ) ; +#40213 = LINE ( 'NONE', #17525, #18991 ) ; +#40214 = ORIENTED_EDGE ( 'NONE', *, *, #12252, .T. ) ; +#40215 = CARTESIAN_POINT ( 'NONE', ( -21.10566240416878259, 135.9749471196982995, 93.79477015577090526 ) ) ; +#40216 = CARTESIAN_POINT ( 'NONE', ( 13.92061689211388043, 122.0377087247195647, 152.1917184006619266 ) ) ; +#40217 = CARTESIAN_POINT ( 'NONE', ( 19.98271301993268523, 207.8686081833218111, 77.26500776042075813 ) ) ; +#40218 = CIRCLE ( 'NONE', #21308, 2.000000000000011546 ) ; +#40219 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#40220 = CARTESIAN_POINT ( 'NONE', ( 3.467226270562823398, 125.5966026506509792, 88.64708724200714585 ) ) ; +#40221 = ORIENTED_EDGE ( 'NONE', *, *, #1315, .T. ) ; +#40222 = ORIENTED_EDGE ( 'NONE', *, *, #26361, .T. ) ; +#40223 = CARTESIAN_POINT ( 'NONE', ( 46.04655628321543759, 186.9737579288344307, 105.3571666265285245 ) ) ; +#40224 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421484904, 123.6934293455507543, 91.28055725774082418 ) ) ; +#40225 = DIRECTION ( 'NONE', ( -0.0006039748319369898531, 0.000000000000000000, -0.9999998176071844824 ) ) ; +#40226 = VECTOR ( 'NONE', #4140, 1000.000000000000114 ) ; +#40227 = DIRECTION ( 'NONE', ( 0.0006039748319481906373, 1.291365685536979971E-14, 0.9999998176071844824 ) ) ; +#40228 = VECTOR ( 'NONE', #14551, 1000.000000000000114 ) ; +#40229 = EDGE_CURVE ( 'NONE', #12094, #12603, #23115, .T. ) ; +#40230 = ORIENTED_EDGE ( 'NONE', *, *, #4506, .T. ) ; +#40231 = CARTESIAN_POINT ( 'NONE', ( 38.81252283515213009, 118.9905809030176727, 89.96796132571387261 ) ) ; +#40232 = EDGE_CURVE ( 'NONE', #21146, #28773, #8643, .T. ) ; +#40233 = CARTESIAN_POINT ( 'NONE', ( -28.46937268146193745, 181.4099652016123514, 104.2887163838427824 ) ) ; +#40234 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386905326 ) ) ; +#40235 = DIRECTION ( 'NONE', ( -0.0004161288024548141697, 0.8480480897963675879, -0.5299191110250242032 ) ) ; +#40236 = CARTESIAN_POINT ( 'NONE', ( -25.84017943814999896, 190.8761150004999934, 106.6436162250000024 ) ) ; +#40237 = CARTESIAN_POINT ( 'NONE', ( -23.36160746070781613, 128.4700731989668157, 89.83983640152801797 ) ) ; +#40238 = CARTESIAN_POINT ( 'NONE', ( -35.95425951663850839, 207.4083918145487075, 77.10339231471580490 ) ) ; +#40239 = CARTESIAN_POINT ( 'NONE', ( -23.36055974375966571, 134.8407614670647661, 93.36323390285753021 ) ) ; +#40240 = LINE ( 'NONE', #25137, #1075 ) ; +#40241 = ORIENTED_EDGE ( 'NONE', *, *, #29751, .F. ) ; +#40242 = CARTESIAN_POINT ( 'NONE', ( -1.216565595234769148, 139.4623718050729053, 175.9799232390552390 ) ) ; +#40243 = CARTESIAN_POINT ( 'NONE', ( -20.26936642627390128, 184.3467633459427759, 105.0257816482483264 ) ) ; +#40244 = CIRCLE ( 'NONE', #14152, 6.000000000000001776 ) ; +#40245 = DIRECTION ( 'NONE', ( 0.0005884948869652767856, -0.2249510543002911089, 0.9743698870772615761 ) ) ; +#40246 = CARTESIAN_POINT ( 'NONE', ( 36.36530002739970513, 191.8380058348319892, 104.3412478323679835 ) ) ; +#40247 = CONICAL_SURFACE ( 'NONE', #4343, 48.00000000003070255, 0.7853981633973031729 ) ; +#40248 = CARTESIAN_POINT ( 'NONE', ( 36.54410887896000304, 191.3422811494999962, 106.4620144481000068 ) ) ; +#40249 = VECTOR ( 'NONE', #26588, 1000.000000000000227 ) ; +#40250 = ORIENTED_EDGE ( 'NONE', *, *, #12544, .T. ) ; +#40251 = ORIENTED_EDGE ( 'NONE', *, *, #7830, .T. ) ; +#40252 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; +#40253 = EDGE_CURVE ( 'NONE', #6809, #25237, #30517, .T. ) ; +#40254 = CARTESIAN_POINT ( 'NONE', ( 39.04524183112422975, 209.7096538831000032, 73.53492182592451343 ) ) ; +#40255 = CONICAL_SURFACE ( 'NONE', #15468, 6.500001368651339817, 0.7853982200635908351 ) ; +#40256 = CARTESIAN_POINT ( 'NONE', ( 35.56535286263039808, 192.7868339794035251, 106.8337704962199268 ) ) ; +#40257 = FACE_OUTER_BOUND ( 'NONE', #13918, .T. ) ; +#40258 = CIRCLE ( 'NONE', #8857, 40.00000000000000000 ) ; +#40259 = VERTEX_POINT ( 'NONE', #14971 ) ; +#40260 = CARTESIAN_POINT ( 'NONE', ( -39.41844532849000160, 119.6025715269000074, 90.24298619069000438 ) ) ; +#40261 = DIRECTION ( 'NONE', ( 5.286776307738854230E-15, 0.9743700557921585181, 0.2249510932971559851 ) ) ; +#40262 = CARTESIAN_POINT ( 'NONE', ( -20.51767729163077547, 205.5669979433283743, 76.31342074382325791 ) ) ; +#40263 = DIRECTION ( 'NONE', ( 0.7856637146670527594, -0.6186538025871723967, 0.000000000000000000 ) ) ; +#40264 = ORIENTED_EDGE ( 'NONE', *, *, #26267, .T. ) ; +#40265 = LINE ( 'NONE', #12276, #11471 ) ; +#40266 = ADVANCED_FACE ( 'NONE', ( #27656 ), #3087, .T. ) ; +#40267 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; +#40268 = CARTESIAN_POINT ( 'NONE', ( 23.36938019816961898, 177.0806351751306238, 103.5466879961430635 ) ) ; +#40269 = CARTESIAN_POINT ( 'NONE', ( 5.667964583423158231, 129.9727540529065948, 92.22183313054385678 ) ) ; +#40270 = CARTESIAN_POINT ( 'NONE', ( 0.5641566566382231196, 188.3875244742078223, 106.2241826925672257 ) ) ; +#40271 = FACE_OUTER_BOUND ( 'NONE', #19189, .T. ) ; +#40272 = VERTEX_POINT ( 'NONE', #24988 ) ; +#40273 = ORIENTED_EDGE ( 'NONE', *, *, #9550, .F. ) ; +#40274 = EDGE_CURVE ( 'NONE', #6653, #30059, #24146, .T. ) ; +#40275 = CARTESIAN_POINT ( 'NONE', ( -28.65284063177000462, 187.5359740265000141, 102.8273832512000041 ) ) ; +#40276 = CARTESIAN_POINT ( 'NONE', ( 2.674351632222999875, 190.4735952899999916, 103.9537630802000052 ) ) ; +#40277 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#40278 = AXIS2_PLACEMENT_3D ( 'NONE', #6223, #37316, #9507 ) ; +#40279 = ORIENTED_EDGE ( 'NONE', *, *, #13054, .F. ) ; +#40280 = ADVANCED_FACE ( 'NONE', ( #40294 ), #18603, .T. ) ; +#40281 = ORIENTED_EDGE ( 'NONE', *, *, #1784, .T. ) ; +#40282 = DIRECTION ( 'NONE', ( -0.9914446600668047616, -0.1273122756936073130, -0.02879358405500737073 ) ) ; +#40283 = CIRCLE ( 'NONE', #8219, 2.000000000000011546 ) ; +#40284 = ORIENTED_EDGE ( 'NONE', *, *, #16703, .F. ) ; +#40285 = ADVANCED_FACE ( 'NONE', ( #12487 ), #38032, .F. ) ; +#40286 = CIRCLE ( 'NONE', #37687, 22.50000000000899902 ) ; +#40287 = ADVANCED_FACE ( 'NONE', ( #19806 ), #4560, .F. ) ; +#40288 = ADVANCED_FACE ( 'NONE', ( #35139 ), #25187, .T. ) ; +#40289 = FACE_OUTER_BOUND ( 'NONE', #30180, .T. ) ; +#40290 = CARTESIAN_POINT ( 'NONE', ( -34.31311594311140567, 218.5902260770998282, 61.07922615589730952 ) ) ; +#40291 = CARTESIAN_POINT ( 'NONE', ( -13.73941655725531596, 125.3344943124112802, 174.7635725153712372 ) ) ; +#40292 = CARTESIAN_POINT ( 'NONE', ( -37.30470697817465009, 191.0308624572352869, 106.3365180619626784 ) ) ; +#40293 = PLANE ( 'NONE', #17725 ) ; +#40294 = FACE_OUTER_BOUND ( 'NONE', #7, .T. ) ; +#40295 = CARTESIAN_POINT ( 'NONE', ( -36.48933695153999679, 190.8968829416000119, 106.6933567144999984 ) ) ; +#40296 = ORIENTED_EDGE ( 'NONE', *, *, #28173, .F. ) ; +#40297 = CARTESIAN_POINT ( 'NONE', ( -0.4358427445845766135, 188.3875244028057807, 106.2247867227265630 ) ) ; +#40298 = CARTESIAN_POINT ( 'NONE', ( -35.74149330666463698, 191.6983459860854282, 103.9240585978979396 ) ) ; +#40299 = DIRECTION ( 'NONE', ( -0.7942820423213363679, -0.5918950211223027447, -0.1370267171630251690 ) ) ; +#40300 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #5845, #11991, #14859, #24476, #21188, #6236 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( -0.002831826805589694306, -0.001066225054260792546, 0.0006993766970681092147 ), + .UNSPECIFIED. ) ; +#40302 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; +#40301 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749897444, 179.6299767373378700, 101.6260513915634363 ) ) ; +#40303 = EDGE_CURVE ( 'NONE', #9411, #11556, #15949, .T. ) ; +#40304 = VERTEX_POINT ( 'NONE', #6742 ) ; +#40305 = VECTOR ( 'NONE', #10474, 1000.000000000000000 ) ; +#40306 = CARTESIAN_POINT ( 'NONE', ( -20.49970533150650454, 174.4001369415204863, 100.4419005550919906 ) ) ; +#40307 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#40308 = ORIENTED_EDGE ( 'NONE', *, *, #22435, .T. ) ; +#40309 = CARTESIAN_POINT ( 'NONE', ( 39.65655516771000322, 119.6738006429000052, 90.21213854658999765 ) ) ; +#40310 = DIRECTION ( 'NONE', ( 0.0005884949961244347353, -0.2249510543439056098, 0.9743698870671265722 ) ) ; +#40311 = PLANE ( 'NONE', #10380 ) ; +#40312 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; +#40313 = LINE ( 'NONE', #14987, #32146 ) ; +#40314 = EDGE_LOOP ( 'NONE', ( #23058, #8217, #6898, #9759 ) ) ; +#40315 = EDGE_CURVE ( 'NONE', #7971, #645, #34541, .T. ) ; +#40316 = ORIENTED_EDGE ( 'NONE', *, *, #40044, .F. ) ; +#40317 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091564245 ) ) ; +#40318 = CARTESIAN_POINT ( 'NONE', ( 13.53821688301358783, 110.1833198944638639, 152.0219651185704492 ) ) ; +#40319 = VERTEX_POINT ( 'NONE', #28443 ) ; +#40320 = EDGE_CURVE ( 'NONE', #8802, #3689, #6510, .T. ) ; +#40321 = CARTESIAN_POINT ( 'NONE', ( -36.18076212721910423, 190.9506060006740142, 106.8439620012120201 ) ) ; +#40322 = CARTESIAN_POINT ( 'NONE', ( -22.32836078412000091, 134.7284225427999900, 93.84982713985000657 ) ) ; +#40323 = EDGE_CURVE ( 'NONE', #22377, #32129, #26496, .T. ) ; +#40324 = VERTEX_POINT ( 'NONE', #11043 ) ; +#40325 = ORIENTED_EDGE ( 'NONE', *, *, #23305, .F. ) ; +#40326 = CARTESIAN_POINT ( 'NONE', ( 2.086697738779999867, 189.3871111185999894, 106.0559732620999966 ) ) ; +#40327 = EDGE_CURVE ( 'NONE', #9096, #19822, #31727, .T. ) ; +#40328 = CARTESIAN_POINT ( 'NONE', ( 13.49906568490447434, 124.5683833206837363, 88.67767665987204850 ) ) ; +#40329 = CARTESIAN_POINT ( 'NONE', ( -37.70496166274256922, 218.5902260770999987, 74.58127720802590943 ) ) ; +#40330 = CARTESIAN_POINT ( 'NONE', ( 5.219784935304125462, 148.4721570845296412, 93.92726757689347039 ) ) ; +#40331 = ORIENTED_EDGE ( 'NONE', *, *, #20500, .F. ) ; +#40332 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #36120, #14469, #5040, #30205, #29599, #24080, #8539, #11197, #10999, #4440 ), + .UNSPECIFIED., .F., .F., + ( 4, 1, 1, 2, 2, 4 ), + ( 0.000000000000000000, 0.2499999999999653055, 0.3749999999999281686, 0.4374999999999095168, 0.4999999999998909761, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#40333 = DIRECTION ( 'NONE', ( 0.7933533411653073131, -0.5930537057989907490, -0.1373964268091705798 ) ) ; +#40334 = AXIS2_PLACEMENT_3D ( 'NONE', #29956, #8283, #11964 ) ; +#40335 = DIRECTION ( 'NONE', ( -0.5605692184766052355, -0.5785654711199512690, 0.5924729081774768868 ) ) ; +#40336 = VERTEX_POINT ( 'NONE', #16943 ) ; +#40337 = PLANE ( 'NONE', #2557 ) ; +#40338 = ORIENTED_EDGE ( 'NONE', *, *, #7485, .T. ) ; +#40340 = CARTESIAN_POINT ( 'NONE', ( -2.435581690730916016, 190.9709058671855360, 106.3075837308457352 ) ) ; +#40339 = CARTESIAN_POINT ( 'NONE', ( -8.285764499747434897, 124.3653823074882467, 88.36991397916445123 ) ) ; +#40341 = VERTEX_POINT ( 'NONE', #14516 ) ; +#40342 = VERTEX_POINT ( 'NONE', #14112 ) ; +#40343 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #20824, #20196, #33277, #32686 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#40344 = VERTEX_POINT ( 'NONE', #5297 ) ; +#40345 = CARTESIAN_POINT ( 'NONE', ( 3.075208719997000184, 209.7418877938000037, 76.19223627437000346 ) ) ; +#40346 = DIRECTION ( 'NONE', ( 0.0005884949961246526600, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#40347 = ORIENTED_EDGE ( 'NONE', *, *, #8001, .T. ) ; +#40348 = ORIENTED_EDGE ( 'NONE', *, *, #39066, .T. ) ; +#40349 = VERTEX_POINT ( 'NONE', #29245 ) ; +#40350 = LINE ( 'NONE', #19080, #17812 ) ; +#40351 = PLANE ( 'NONE', #30893 ) ; +#40352 = CARTESIAN_POINT ( 'NONE', ( 30.05202364328564713, 126.8409241029907832, 91.48406572326082653 ) ) ; +#40353 = CARTESIAN_POINT ( 'NONE', ( 13.50283896178331311, 187.3734514894470351, 105.5750215595898283 ) ) ; +#40354 = DIRECTION ( 'NONE', ( 0.0002393071182785117316, 0.2252352986010040803, -0.9743043687658490271 ) ) ; +#40355 = CARTESIAN_POINT ( 'NONE', ( 16.84365520870601785, 125.8129638753691069, 178.9888696437699878 ) ) ; +#40356 = ORIENTED_EDGE ( 'NONE', *, *, #30743, .T. ) ; +#40357 = ADVANCED_FACE ( 'NONE', ( #26590 ), #39034, .F. ) ; +#40358 = ORIENTED_EDGE ( 'NONE', *, *, #38289, .F. ) ; +#40359 = EDGE_CURVE ( 'NONE', #36048, #4358, #23506, .T. ) ; +#40360 = AXIS2_PLACEMENT_3D ( 'NONE', #26717, #11171, #13826 ) ; +#40361 = VERTEX_POINT ( 'NONE', #29647 ) ; +#40362 = DIRECTION ( 'NONE', ( -0.7075227810178097432, 0.1590644159616022568, -0.6885564798298096090 ) ) ; +#40363 = EDGE_CURVE ( 'NONE', #6684, #29822, #23314, .T. ) ; +#40364 = FACE_OUTER_BOUND ( 'NONE', #13107, .T. ) ; +#40365 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971550137 ) ) ; +#40366 = ADVANCED_FACE ( 'NONE', ( #14313 ), #24498, .F. ) ; +#40367 = CARTESIAN_POINT ( 'NONE', ( 6.065815740701999914, 163.2729245447999915, 152.4718672074000381 ) ) ; +#40368 = AXIS2_PLACEMENT_3D ( 'NONE', #85, #31174, #22178 ) ; +#40369 = ORIENTED_EDGE ( 'NONE', *, *, #27943, .F. ) ; +#40370 = CARTESIAN_POINT ( 'NONE', ( 1.447658031000570666, 152.0519508845351595, 130.6788418773748219 ) ) ; +#40371 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; +#40372 = ORIENTED_EDGE ( 'NONE', *, *, #10984, .F. ) ; +#40373 = EDGE_CURVE ( 'NONE', #21410, #35217, #29444, .T. ) ; +#40374 = CARTESIAN_POINT ( 'NONE', ( -28.52670407937950969, 187.4270078119665754, 102.9410870260050928 ) ) ; +#40375 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971555410 ) ) ; +#40376 = EDGE_CURVE ( 'NONE', #30873, #23757, #1623, .T. ) ; +#40377 = CARTESIAN_POINT ( 'NONE', ( -37.47510786252718162, 212.6956757039803279, 73.24780480550954564 ) ) ; +#40378 = DIRECTION ( 'NONE', ( -0.1632030863883330296, 0.3417424275059343097, -0.9255143790539797077 ) ) ; +#40379 = ORIENTED_EDGE ( 'NONE', *, *, #15412, .F. ) ; +#40380 = CARTESIAN_POINT ( 'NONE', ( -22.49859347127474152, 158.2257569248202458, 98.76156587771905038 ) ) ; +#40381 = CARTESIAN_POINT ( 'NONE', ( 37.93821029086635122, 79.16788325310130858, 289.8002325176965996 ) ) ; +#40382 = CARTESIAN_POINT ( 'NONE', ( 22.78075325035244703, 147.9635827673721451, 94.31239968548003105 ) ) ; +#40383 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #38605, #16331, #6723, #7126 ), + .UNSPECIFIED., .F., .F., + ( 4, 4 ), + ( 0.000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#40384 = CARTESIAN_POINT ( 'NONE', ( 37.16421317187000284, 117.4633363709999969, 90.10791008674000580 ) ) ; +#40385 = VECTOR ( 'NONE', #37413, 1000.000000000000114 ) ; +#40386 = CARTESIAN_POINT ( 'NONE', ( 45.24519689809859813, 116.5437060779667036, 124.8975000631534158 ) ) ; +#40387 = EDGE_LOOP ( 'NONE', ( #6759, #37249, #5774, #34247 ) ) ; +#40388 = CARTESIAN_POINT ( 'NONE', ( 2.562147502058854442, 194.2771767931535294, 102.8967287192651696 ) ) ; +#40389 = ORIENTED_EDGE ( 'NONE', *, *, #5103, .T. ) ; +#40390 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921578520, 0.2249510932971596766 ) ) ; +#40391 = VECTOR ( 'NONE', #1871, 1000.000000000000114 ) ; +#40392 = AXIS2_PLACEMENT_3D ( 'NONE', #17447, #1513, #4381 ) ; +#40393 = CARTESIAN_POINT ( 'NONE', ( -19.40844160272963137, 149.2436093538031514, 181.3008671212579088 ) ) ; +#40394 = AXIS2_PLACEMENT_3D ( 'NONE', #34528, #37825, #22103 ) ; +#40395 = CARTESIAN_POINT ( 'NONE', ( -38.19661910378999892, 118.7283168909000040, 90.15060258514999703 ) ) ; +#40396 = CARTESIAN_POINT ( 'NONE', ( 29.05352371370200615, 110.6131156702000027, 87.25023669171606855 ) ) ; +#40397 = CARTESIAN_POINT ( 'NONE', ( 38.57248824100825857, 118.4600016709538295, 89.66247826865570403 ) ) ; +#40398 = ORIENTED_EDGE ( 'NONE', *, *, #21370, .F. ) ; +#40399 = PLANE ( 'NONE', #18566 ) ; +#40400 = CARTESIAN_POINT ( 'NONE', ( -0.03375341898833555260, -31.76863880746333280, 137.4221703796379188 ) ) ; +#40401 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825953879981883, 0.0005734119016092298913 ) ) ; +#40402 = PLANE ( 'NONE', #24704 ) ; +#40403 = CARTESIAN_POINT ( 'NONE', ( 17.27169418602116480, 122.3509344318320444, 172.9165784783710933 ) ) ; +#40404 = CARTESIAN_POINT ( 'NONE', ( -36.21229146569522328, 116.0839334804960856, 90.28965615584912996 ) ) ; +#40405 = EDGE_LOOP ( 'NONE', ( #38077, #38244, #38497, #30201 ) ) ; +#40406 = CARTESIAN_POINT ( 'NONE', ( 5.667895119723127095, 187.8687646092461421, 103.4296389354537524 ) ) ; +#40407 = CARTESIAN_POINT ( 'NONE', ( -30.07038801302202913, 174.6765699328746564, 103.0772613391864354 ) ) ; +#40408 = CARTESIAN_POINT ( 'NONE', ( 35.65259997913155132, 138.3326317399398988, 284.1430326337134602 ) ) ; +#40409 = ORIENTED_EDGE ( 'NONE', *, *, #7632, .T. ) ; +#40410 = FACE_OUTER_BOUND ( 'NONE', #30915, .T. ) ; +#40411 = ADVANCED_FACE ( 'NONE', ( #5087 ), #32707, .T. ) ; +#40412 = CARTESIAN_POINT ( 'NONE', ( 15.99999293039724257, 151.9655111556795362, 94.72726368743165892 ) ) ; +#40413 = EDGE_CURVE ( 'NONE', #20649, #21381, #11239, .T. ) ; +#40414 = ORIENTED_EDGE ( 'NONE', *, *, #30469, .F. ) ; +#40415 = DIRECTION ( 'NONE', ( -0.5669487081581161547, -0.8237530954830113439, 0.000000000000000000 ) ) ; +#40416 = VECTOR ( 'NONE', #28368, 1000.000000000000227 ) ; +#40417 = CARTESIAN_POINT ( 'NONE', ( -43.10734247109012784, 121.9064515807241804, 87.96659200322474703 ) ) ; +#40418 = EDGE_LOOP ( 'NONE', ( #8287, #2577 ) ) ; +#40419 = CARTESIAN_POINT ( 'NONE', ( 36.31872422425588098, 190.9500732230917777, 106.7935857671626820 ) ) ; +#40420 = VECTOR ( 'NONE', #25323, 1000.000000000000227 ) ; +#40421 = CARTESIAN_POINT ( 'NONE', ( 22.50029346826757859, 151.8610258625533049, 95.21236487778058688 ) ) ; +#40422 = CARTESIAN_POINT ( 'NONE', ( -26.15709881241999923, 190.6415270226000018, 106.8956296771000041 ) ) ; +#40423 = CARTESIAN_POINT ( 'NONE', ( 30.07151160793498690, 176.9174375397160475, 103.2802541386858053 ) ) ; +#40424 = CONICAL_SURFACE ( 'NONE', #5160, 7.002965970566410014, 0.7854058041637707044 ) ; +#40425 = FACE_OUTER_BOUND ( 'NONE', #39656, .T. ) ; +#40426 = ORIENTED_EDGE ( 'NONE', *, *, #19094, .T. ) ; +#40427 = DIRECTION ( 'NONE', ( -0.0005884949961235566400, 0.2249510543439049437, -0.9743698870671267942 ) ) ; +#40428 = CARTESIAN_POINT ( 'NONE', ( -19.26392064910394808, 124.3392765983403621, 178.4079915668605736 ) ) ; +#40429 = CARTESIAN_POINT ( 'NONE', ( -13.73975480784592307, 125.4641165510608261, 174.2036076504483901 ) ) ; +#40430 = CARTESIAN_POINT ( 'NONE', ( -37.30377723581143812, 168.2094018080552189, 182.6166685593908596 ) ) ; +#40431 = ORIENTED_EDGE ( 'NONE', *, *, #623, .F. ) ; +#40432 = CARTESIAN_POINT ( 'NONE', ( 22.64037623556000156, 158.4942800668000018, 96.48711187617001883 ) ) ; +#40433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, + ( #2903, #34373, #9257, #9055, #18823, #30534 ), + .UNSPECIFIED., .F., .F., + ( 4, 2, 4 ), + ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), + .UNSPECIFIED. ) ; +#40434 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; +#40435 = FACE_OUTER_BOUND ( 'NONE', #15966, .T. ) ; +#40436 = EDGE_CURVE ( 'NONE', #8964, #30098, #15313, .T. ) ; +#40437 = LINE ( 'NONE', #3225, #16116 ) ; +#40438 = CARTESIAN_POINT ( 'NONE', ( -27.14440137765999950, 187.2725072407000084, 105.4703439821000046 ) ) ; +#40439 = CARTESIAN_POINT ( 'NONE', ( -12.64230137995684444, 181.7534649825922770, 101.7124881005001669 ) ) ; +#40440 = AXIS2_PLACEMENT_3D ( 'NONE', #3157, #21598, #40371 ) ; +#40441 = CARTESIAN_POINT ( 'NONE', ( 1.561641312891000055, 129.8597348847000035, 92.71137285944000439 ) ) ; +#40442 = CARTESIAN_POINT ( 'NONE', ( -23.36190171889894529, 184.1216419186529833, 102.1748637788761727 ) ) ; +#40443 = CARTESIAN_POINT ( 'NONE', ( 30.18297413640002702, 185.3389242632447917, 102.7656572717241374 ) ) ; +#40444 = FACE_OUTER_BOUND ( 'NONE', #22921, .T. ) ; +#40445 = CARTESIAN_POINT ( 'NONE', ( -37.56217811679143637, 145.6431275960571838, 282.5778664123586168 ) ) ; +#40446 = AXIS2_PLACEMENT_3D ( 'NONE', #11861, #11245, #14923 ) ; +#40447 = CARTESIAN_POINT ( 'NONE', ( -24.42595481105102451, 104.1131156702295186, 90.28253750387099785 ) ) ; +#40448 = CARTESIAN_POINT ( 'NONE', ( 36.18973506411000329, 192.0171769533999964, 105.0450383464999931 ) ) ; +#40449 = AXIS2_PLACEMENT_3D ( 'NONE', #11319, #26071, #7641 ) ; +#40450 = AXIS2_PLACEMENT_3D ( 'NONE', #27417, #36166, #11437 ) ; +#40452 = VERTEX_POINT ( 'NONE', #13901 ) ; +#40451 = CARTESIAN_POINT ( 'NONE', ( 36.44358477468000501, 191.0363251205000097, 106.6791379425000059 ) ) ; +#40453 = ORIENTED_EDGE ( 'NONE', *, *, #22339, .F. ) ; +#40454 = EDGE_LOOP ( 'NONE', ( #18618, #22192, #17234, #33126 ) ) ; +#40455 = ORIENTED_EDGE ( 'NONE', *, *, #32022, .F. ) ; +#40456 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; +#40457 = CARTESIAN_POINT ( 'NONE', ( 20.48041080035920558, 211.0898936264048587, 74.21271871319238755 ) ) ; +#40458 = PLANE ( 'NONE', #20621 ) ; +#40459 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930882020 ) ) ; +#40460 = EDGE_CURVE ( 'NONE', #26477, #35520, #20516, .T. ) ; +#40461 = EDGE_CURVE ( 'NONE', #22722, #33491, #11455, .T. ) ; +#40462 = ORIENTED_EDGE ( 'NONE', *, *, #30050, .F. ) ; +#40463 = CARTESIAN_POINT ( 'NONE', ( 36.04770605913999759, 191.4287702289000208, 103.6964475062000162 ) ) ; +#40464 = CARTESIAN_POINT ( 'NONE', ( -15.99974174651862313, 174.5231975350379514, 99.95452847233616467 ) ) ; +#40465 = FACE_BOUND ( 'NONE', #708, .T. ) ; +ENDSEC; +END-ISO-10303-21; From b34f29a118ee916db8020eb2818cc6c0b712ed60 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Mon, 1 Dec 2025 09:16:06 +0000 Subject: [PATCH 32/35] fix visualize image size; fix unused comment code; fixed evaluator name --- internnav/evaluator/utils/common.py | 2 +- .../utils/{dataset.py => result_logger.py} | 2 -- .../vln_multi_distributed_evaluator.py | 3 +- .../habitat_default_evaluator.py | 29 +++++++++++++++++-- internnav/model/utils/utils.py | 10 +++---- scripts/eval/bash/eval_vln_distributed.sh | 28 ++++++++++++++---- 6 files changed, 56 insertions(+), 18 deletions(-) rename internnav/evaluator/utils/{dataset.py => result_logger.py} (99%) diff --git a/internnav/evaluator/utils/common.py b/internnav/evaluator/utils/common.py index 1b811b9..08dde7e 100644 --- a/internnav/evaluator/utils/common.py +++ b/internnav/evaluator/utils/common.py @@ -464,7 +464,7 @@ def obs_to_image(obs_lst, action, output_path: str, reference_path, normalize: b topdown_array = first_obs['topdown_rgb'] # draw array on rgb array - rgb_array = draw_action_pil(rgb_array, action) + rgb_array = cv2.resize(draw_action_pil(rgb_array, action), (256, 256)) # draw trajectory on depth topdown_array = crop(draw_trajectory(topdown_array, obs_lst, reference_path)) diff --git a/internnav/evaluator/utils/dataset.py b/internnav/evaluator/utils/result_logger.py similarity index 99% rename from internnav/evaluator/utils/dataset.py rename to internnav/evaluator/utils/result_logger.py index 35e7694..e3826a6 100644 --- a/internnav/evaluator/utils/dataset.py +++ b/internnav/evaluator/utils/result_logger.py @@ -54,8 +54,6 @@ def get_split_map( return split_map def write_now_result_json(self): - # create log file - # log_content = [] self.database_read = lmdb.open( f'{self.lmdb_path}/sample_data.lmdb', map_size=1 * 1024 * 1024 * 1024 * 1024, diff --git a/internnav/evaluator/vln_multi_distributed_evaluator.py b/internnav/evaluator/vln_multi_distributed_evaluator.py index f56732b..2a68df5 100644 --- a/internnav/evaluator/vln_multi_distributed_evaluator.py +++ b/internnav/evaluator/vln_multi_distributed_evaluator.py @@ -10,7 +10,7 @@ from internnav.evaluator.utils.common import set_seed_model from internnav.evaluator.utils.config import get_lmdb_path from internnav.evaluator.utils.data_collector import DataCollector -from internnav.evaluator.utils.dataset import ResultLogger +from internnav.evaluator.utils.result_logger import ResultLogger from internnav.evaluator.utils.visualize_util import VisualizeUtil from internnav.utils import common_log_util, progress_log_multi_util from internnav.utils.common_log_util import common_logger as log @@ -158,7 +158,6 @@ def _need_reset(self, terminated_ls): def env_step(self, action): start_time = time() - # stop_count = [0 for _ in range(self.env_num * self.sim_num)] while True: # stop action maybe also need 50 steps self.runner_status[ diff --git a/internnav/habitat_extensions/habitat_default_evaluator.py b/internnav/habitat_extensions/habitat_default_evaluator.py index 2f65236..c4df86a 100644 --- a/internnav/habitat_extensions/habitat_default_evaluator.py +++ b/internnav/habitat_extensions/habitat_default_evaluator.py @@ -26,8 +26,33 @@ DEFAULT_IMAGE_TOKEN = "" -@Evaluator.register('habitat_vlln') -class HabitatVlnEvaluator(DistributedEvaluator): +@Evaluator.register('habitat_evaluator') +class HabitatDefaultEvaluator(DistributedEvaluator): + """ + A default evaluator class for running Habitat-based evaluations in a distributed environment. + + This evaluator is designed to work with the Habitat simulator and performs evaluation of + agents on local episodes. It provides metrics such as success rate (success), SPL (Success weighted by Path Length), + Oracle success rate (oracle_success), and the distance to the goal (distance_to_goal). + + Attributes: + save_video (bool): Whether to save video during the evaluation. + epoch (int): The current epoch of the evaluation process. + max_steps_per_episode (int): The maximum number of steps allowed per episode. + output_path (str): The path where the evaluation results are saved. + config (habitat.config.default.Config): The Habitat configuration used for the environment setup. + agent_config (habitat.config.default.AgentConfig): Configuration specific to the agent in the Habitat simulator. + sim_sensors_config (dict): Configuration for the sensors used by the agent in the simulation. + + Methods: + eval_action() -> dict: + Runs the local episodes and returns a dictionary of evaluation metrics such as success rate, + success weighted by path length (SPL), oracle success, and distance to the goal. + + calc_metrics(global_metrics: dict) -> dict: + Calculates the global evaluation metrics from the distributed results by aggregating local metrics. + """ + def __init__(self, cfg: EvalCfg): args = argparse.Namespace(**cfg.eval_settings) self.args = args diff --git a/internnav/model/utils/utils.py b/internnav/model/utils/utils.py index 02330ea..692f13c 100755 --- a/internnav/model/utils/utils.py +++ b/internnav/model/utils/utils.py @@ -349,6 +349,9 @@ def get_action(diffusion_output, action_stats, cumsum=True): ndeltas = unnormalize_data(ndeltas, action_stats) if cumsum: + import torch + + torch.use_deterministic_algorithms(False) actions = torch.cumsum(ndeltas, dim=1) # This get the relative actions (not delta) from the diffusion output else: actions = ndeltas @@ -391,11 +394,9 @@ def unnormalize_data(ndata, stats): ndata_part = (ndata[:, :2] + 1) / 2 try: data = ndata_part * (stats['max'].to(device) - stats['min'].to(device)) + stats['min'].to(device) - except Exception as e: + except Exception: data = ndata_part * (stats.max.to(device) - stats.min.to(device)) + stats.min.to(device) - # if len(ndata.shape) == 3: - # data = torch.cat([data, ndata[:, 2:]], dim=1) return data @@ -440,7 +441,7 @@ def load_dataset(dataset_root_dir, split, logger=None, dataset_type='r2r'): item['c_reference_path'].append([path[0], -path[2], path[1]]) item['reference_path'] = item['c_reference_path'] del item['c_reference_path'] - + if dataset_type == 'kujiale': load_data[f'{str(item["trajectory_id"])}_{str(item["episode_id"])}'].append(item) else: @@ -448,4 +449,3 @@ def load_dataset(dataset_root_dir, split, logger=None, dataset_type='r2r'): if logger is not None: logger.info(f'Loaded data with a total of {len(load_data)} items from {split}') return load_data - diff --git a/scripts/eval/bash/eval_vln_distributed.sh b/scripts/eval/bash/eval_vln_distributed.sh index cd7e176..ae2060e 100644 --- a/scripts/eval/bash/eval_vln_distributed.sh +++ b/scripts/eval/bash/eval_vln_distributed.sh @@ -1,10 +1,26 @@ #!/bin/bash -# vlnpe distributed scripts for aliyun dlc -# use habitat or internutopia mode to run distributed eval with 1 gpus on single node -# set use_agent_server=False in config file to use local agent on single node -# internutopia_vec_env mode: collect all GPUs by ray, observations are collected in batch - -# Activate conda automatically +# ---------------------------------------------------------------------------- +# USAGE INSTRUCTIONS: +# +# This script runs a distributed evaluation for Habitat or Internutopia. +# You can choose from the following modes: +# +# 1. **habitat**: Runs evaluation using the Habitat environment. +# 2. **internutopia**: Runs evaluation using the Internutopia environment. +# 3. **internutopia_vec_env**: Runs distributed evaluation with Ray in vectorized environments. +# +# The script automatically activates the appropriate Conda environment based on the mode. +# You can specify a custom configuration file using the `--config` argument. +# +# Example usage: +# ./scripts/eval/bash/eval_vln_distributed.sh habitat --config +# ./ internutopia --config +# ./ internutopia_vec_env --config +# +# Make sure required Conda environments (habitat, internutopia) and Ray (for internutopia_vec_env) are set up. +# ---------------------------------------------------------------------------- + +# Activate conda (update to your local path) source /root/miniconda3/etc/profile.d/conda.sh mode="$1" From ea730752c54cd27b9f6fb2615e984b948fa44a38 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Mon, 1 Dec 2025 09:17:06 +0000 Subject: [PATCH 33/35] bump to version v0.0.2 --- setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/setup.py b/setup.py index ac0a187..f2c5bcb 100644 --- a/setup.py +++ b/setup.py @@ -52,7 +52,7 @@ def parse_readme(readme: str) -> str: setuptools.setup( name='internnav', - version='0.0.1', + version='0.0.2', packages=setuptools.find_packages(), author='Intern Robotics', author_email='embodiedai@pjlab.org.cn', From 80822920f9ad0beee9177e84357d484fd3081132 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Mon, 1 Dec 2025 11:20:52 +0000 Subject: [PATCH 34/35] update vlnmulti to VLN; update habitatVln to HabitatVLN --- internnav/evaluator/__init__.py | 6 ++---- ...istributed_evaluator.py => vln_distributed_evaluator.py} | 4 ++-- internnav/habitat_extensions/__init__.py | 2 +- internnav/habitat_extensions/habitat_vln_evaluator.py | 2 +- scripts/eval/configs/h1_cma_cfg.py | 2 +- scripts/eval/configs/h1_internvla_n1_async_cfg.py | 2 +- scripts/eval/configs/h1_rdp_cfg.py | 2 +- scripts/eval/configs/h1_seq2seq_cfg.py | 2 +- scripts/eval/eval.py | 2 +- setup.py | 2 +- tests/function_test/test_evaluator.py | 2 +- 11 files changed, 13 insertions(+), 15 deletions(-) rename internnav/evaluator/{vln_multi_distributed_evaluator.py => vln_distributed_evaluator.py} (99%) diff --git a/internnav/evaluator/__init__.py b/internnav/evaluator/__init__.py index cdceadc..35968e8 100644 --- a/internnav/evaluator/__init__.py +++ b/internnav/evaluator/__init__.py @@ -1,8 +1,6 @@ from internnav.evaluator.base import Evaluator from internnav.evaluator.distributed_base import DistributedEvaluator -from internnav.evaluator.vln_multi_distributed_evaluator import ( - VLNMultiDistributedEvaluator, -) +from internnav.evaluator.vln_distributed_evaluator import VLNDistributedEvaluator # register habitat try: @@ -11,4 +9,4 @@ print(f"Warning: ({e}), Habitat Evaluation is not loaded in this runtime. Ignore this if not using Habitat.") -__all__ = ['Evaluator', 'DistributedEvaluator', 'VLNMultiDistributedEvaluator', 'HabitatVlnEvaluator'] +__all__ = ['Evaluator', 'DistributedEvaluator', 'VLNDistributedEvaluator', 'HabitatVLNEvaluator'] diff --git a/internnav/evaluator/vln_multi_distributed_evaluator.py b/internnav/evaluator/vln_distributed_evaluator.py similarity index 99% rename from internnav/evaluator/vln_multi_distributed_evaluator.py rename to internnav/evaluator/vln_distributed_evaluator.py index 2a68df5..0ce616b 100644 --- a/internnav/evaluator/vln_multi_distributed_evaluator.py +++ b/internnav/evaluator/vln_distributed_evaluator.py @@ -24,8 +24,8 @@ class runner_status_code(Enum): STOP = 4 -@Evaluator.register('vln_multi_distributed') -class VLNMultiDistributedEvaluator(DistributedEvaluator): +@Evaluator.register('vln_distributed') +class VLNDistributedEvaluator(DistributedEvaluator): def __init__(self, config: EvalCfg): start_time = time() diff --git a/internnav/habitat_extensions/__init__.py b/internnav/habitat_extensions/__init__.py index ee41522..5906e1c 100644 --- a/internnav/habitat_extensions/__init__.py +++ b/internnav/habitat_extensions/__init__.py @@ -1,2 +1,2 @@ from internnav.habitat_extensions.habitat_env import HabitatEnv -from internnav.habitat_extensions.habitat_vln_evaluator import HabitatVlnEvaluator +from internnav.habitat_extensions.habitat_vln_evaluator import HabitatVLNEvaluator diff --git a/internnav/habitat_extensions/habitat_vln_evaluator.py b/internnav/habitat_extensions/habitat_vln_evaluator.py index 75d71f8..2d552fd 100644 --- a/internnav/habitat_extensions/habitat_vln_evaluator.py +++ b/internnav/habitat_extensions/habitat_vln_evaluator.py @@ -46,7 +46,7 @@ @Evaluator.register('habitat_vln') -class HabitatVlnEvaluator(DistributedEvaluator): +class HabitatVLNEvaluator(DistributedEvaluator): def __init__(self, cfg: EvalCfg): args = argparse.Namespace(**cfg.eval_settings) self.save_video = args.save_video diff --git a/scripts/eval/configs/h1_cma_cfg.py b/scripts/eval/configs/h1_cma_cfg.py index ffa5ce9..6c509d4 100644 --- a/scripts/eval/configs/h1_cma_cfg.py +++ b/scripts/eval/configs/h1_cma_cfg.py @@ -47,7 +47,7 @@ 'filter_stairs': True, }, ), - eval_type='vln_multi_distributed', + eval_type='vln_distributed', eval_settings={ 'save_to_json': True, 'vis_output': True, diff --git a/scripts/eval/configs/h1_internvla_n1_async_cfg.py b/scripts/eval/configs/h1_internvla_n1_async_cfg.py index 27b8837..36f1012 100644 --- a/scripts/eval/configs/h1_internvla_n1_async_cfg.py +++ b/scripts/eval/configs/h1_internvla_n1_async_cfg.py @@ -72,7 +72,7 @@ # 'selected_scans': ['8194nk5LbLH', 'pLe4wQe7qrG'], }, ), - eval_type='vln_multi_distributed', + eval_type='vln_distributed', eval_settings={ 'save_to_json': True, 'vis_output': False, diff --git a/scripts/eval/configs/h1_rdp_cfg.py b/scripts/eval/configs/h1_rdp_cfg.py index f7f5695..ef5ff19 100644 --- a/scripts/eval/configs/h1_rdp_cfg.py +++ b/scripts/eval/configs/h1_rdp_cfg.py @@ -45,7 +45,7 @@ 'filter_stairs': True, }, ), - eval_type='vln_multi_distributed', + eval_type='vln_distributed', eval_settings={ 'save_to_json': True, 'vis_output': False, diff --git a/scripts/eval/configs/h1_seq2seq_cfg.py b/scripts/eval/configs/h1_seq2seq_cfg.py index 5145637..b8696be 100644 --- a/scripts/eval/configs/h1_seq2seq_cfg.py +++ b/scripts/eval/configs/h1_seq2seq_cfg.py @@ -47,7 +47,7 @@ 'filter_stairs': True, }, ), - eval_type='vln_multi_distributed', + eval_type='vln_distributed', eval_settings={ 'save_to_json': True, 'vis_output': True, diff --git a/scripts/eval/eval.py b/scripts/eval/eval.py index 617ed62..4c17026 100644 --- a/scripts/eval/eval.py +++ b/scripts/eval/eval.py @@ -34,7 +34,7 @@ def main(): evaluator_cfg = load_eval_cfg(args.config, attr_name='eval_cfg') # fill in evaluator default config - if evaluator_cfg.eval_type == 'vln_multi_distributed': + if evaluator_cfg.eval_type == 'vln_distributed': from internnav.configs.evaluator.vln_default_config import get_config evaluator_cfg = get_config(evaluator_cfg) diff --git a/setup.py b/setup.py index f2c5bcb..ac0a187 100644 --- a/setup.py +++ b/setup.py @@ -52,7 +52,7 @@ def parse_readme(readme: str) -> str: setuptools.setup( name='internnav', - version='0.0.2', + version='0.0.1', packages=setuptools.find_packages(), author='Intern Robotics', author_email='embodiedai@pjlab.org.cn', diff --git a/tests/function_test/test_evaluator.py b/tests/function_test/test_evaluator.py index 4c884a2..36e40d9 100644 --- a/tests/function_test/test_evaluator.py +++ b/tests/function_test/test_evaluator.py @@ -70,7 +70,7 @@ 'filter_stairs': False, }, ), - eval_type='vln_multi_distributed', + eval_type='vln_distributed', eval_settings={ 'save_to_json': False, 'vis_output': False, From da06d229d9f191ef75141fbe8051f957464f2821 Mon Sep 17 00:00:00 2001 From: wangyukai Date: Tue, 2 Dec 2025 03:53:20 +0000 Subject: [PATCH 35/35] :Revert "Merge branch 'main' into vlnpe_refactor" This reverts commit 7a23b729c9d90d0c5fa2e8ec4a7d1b99cc576b47, reversing changes made to ea730752c54cd27b9f6fb2615e984b948fa44a38. --- .pre-commit-config.yaml | 3 +- README.md | 2 +- assets/3d_printing_files/downwards_slope.3mf | Bin 201196 -> 0 bytes assets/3d_printing_files/go2_stand.STEP | 46768 ----------------- 4 files changed, 3 insertions(+), 46770 deletions(-) delete mode 100644 assets/3d_printing_files/downwards_slope.3mf delete mode 100644 assets/3d_printing_files/go2_stand.STEP diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index a66bfcb..47e3a48 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -1,4 +1,5 @@ -exclude: '^internnav/model/basemodel/LongCLIP/|^assets/' +exclude: | + ^internnav/model/basemodel/LongCLIP/ repos: - repo: https://github.com/PyCQA/autoflake diff --git a/README.md b/README.md index 1518bb2..9e17af1 100644 --- a/README.md +++ b/README.md @@ -36,7 +36,7 @@ The toolbox supports the most advanced high-quality navigation dataset, InternDa ## 🔥 News - [2025/10] Add a simple [inference-only demo](scripts/notebooks/inference_only_demo.ipynb) of InternVLA-N1. - [2025/10] InternVLA-N1 [technical report](https://internrobotics.github.io/internvla-n1.github.io/static/pdfs/InternVLA_N1.pdf) is released. Please check our [homepage](https://internrobotics.github.io/internvla-n1.github.io/). -- [2025/09] Real-world deployment code of InternVLA-N1 is released. Upload 3D printing [files](assets/3d_printing_files/go2_stand.STEP) for Unitree Go2. +- [2025/09] Real-world deployment code of InternVLA-N1 is released. - [2025/07] We are hosting 🏆IROS 2025 Grand Challenge, stay tuned at [official website](https://internrobotics.shlab.org.cn/challenge/2025/). - [2025/07] InternNav v0.1.1 released. diff --git a/assets/3d_printing_files/downwards_slope.3mf b/assets/3d_printing_files/downwards_slope.3mf deleted file mode 100644 index 05cf34d0d82e0558b7d466bfb714e8beb2895524..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 201196 zcmeFZ2T)Yowl2K7$&!(rB}mRFNX{Tg5J3mje1)07mW7j#huS5 zqS_jzPtsCjCfeU)YkwSiq0e(iSqbx<-E5!41Ml*_UN{Q7H)T8Y zlzX%BLs`Q48sYX;Cy@$+6~@djAUeSRf(|Xnq3`Hz=V0e;C+6;A=j~`CA?ogWH`>TRoBSN}IdGW#s*Z*+ z06@Ve6d)!9Z#(`&hX6qN_Ns=ei9h7mM0p8|DFXpYflN(JnlnD$XuXJs{NXuvMCiFO z@B1o^hRohc*Bn@X&c3|jwUF_#(a>TyuFGwsGE=d&$P85X@A+|0-A4uo?@o`zooE6o zp-9*v#u0ORba=zS@Cg8rt$JdRWG5*Ka0);?UKw8BxNF#Y>P-*W0$!G<%env}RzD2h zjW&YN{#RpVob={6ZinL4j>?80_mNS%_O#=X# z{!AwiI5uv8;!@fVaU87q9cLrY-acA-gAX({TZ|tj0l?^&joOmUnD0B>_r zvaukY-*y0`LxI5@>M9s70I+*E?#9XDMrsDP&lCx<9<#&25kcn7K|>M%A+M#h1KLBW zt!`}M+!nV)(f}%{;hjgIT8!|oO(k9c;Sbva$B1We5}Yx`Hn^+0GC06_X1xW|jUz>! zxfEW$3p$3s=??~^!WanygRrxXK%VJS8^t-_B8#*5uiDN;@jY-cQgxi6rCQ&4X6MXW z*ZAzC2+*-6Th_y98jvLjt4VUEA`w7{QygpHI*KQG_yB1B=|3@SDqY71S|X9fHXvij zm7VjvX94_^)Sw~QX_|IhWdMi5_c3SEx!L>>KviLqPxmYaoL(>>9L?nz*P(=4BEcS> z*U}lsS;y|TYi(z;)2&m(V!A+66Bq^PT+8U8W+I4C=aB|@1F@s#1&CQs*f-8!ha#vz z|No?dApa>41Ny@cQK5?4k6uez{0K%K%@cu8NVm>D;@XWo{Rp;W9ab5xIHBvv z0gBl{!~AE{V2zo|?wo(8j8zl>Se0->zg)n2Diex?aUGMvH39yX+-x0q7zpvrZFYFV zNhGL77_^;#f-c=elDoeEU5)*5I2HT~A0R5*eab42wb@#)3p~9BfbLSTV;2c*pU?nn zV0r4ux1N3g_#sWAE}$8*6H5XWYT$|I65rQJG|~)61Z>ZPR)0~PeuCx@1DX+FGV(K< zk@+|gbr7HYxar>=t14K65+S?@lt=XY*Bj;|r>DkjApDR)CQtzw>$@hj+cL2cHG(1% zEGUh`u|vy1G9wZM1rbi?)HJ+gce<2VaO z5S0hyCzBCKE+EN24jBbj7_N{t4%tt9C!p$GT1;rCCT;17$kr9IYs{Pfl zR+~0(f^#C&l@ktIPfgr01DlIE#7*CEC4{SeDjc#?t?*c7B2AzXgtQG;3Al1@Lo@Iq z#K9mBTam*k87v*7rUy)773?~ccxF>6p)vB56;AO4_)KxyD<;C>NsX&3GO(bcra=wA zec*?Ndo1zY0n1bcJ-jh!=x{m>7nH>=V!Vv-Q7h=`-KSuwk(?Fsjv^R`F7STrknJ!U zq*8MRuPQTP!GQQ74lc*AEruU(%m_0U2ZT%{5-dubz0pH*SONtuNz{n;$w&K}dSL8l zF0!25Fd#&p`4T{2D+u8-_Wdp1v;xh+k2kHW=q zHi6Gv;HChhi{i=wBfYaKgV7{W0b>GFdmU;7*7_Bf-lUc4)AInrV}Ng>D?_CtUCLlbTSPYD7+FiM+7H#}Sztu}LrX?Q7+c*3s4fjzB1 zNu)#yLe7EMWKw`t7|4c=qeak6wGa43AfdnAVYp(8QMLevVGP;ui(*8lM>b0H8`((! z&TIq@Mw*Dz=g_j9Bh2J5TnS4DMv8+=r@a|z2C3P5aa!Db+DVzcb+oUGpus^RX8aH% zCIawQpKMQ`{;WQS-~y@5V#bc>lzNE2wK#Tw=u{dz1$zaep^IQV;rbqN%1wa!GO(Oh z3}-%Z!(mAh|7qH0>!}+!A($Rv1|D@PZ(Xt4dT}~GeCpf0NUfCTP9mD)JKOE66C00cR#T<;kaMr1vUrY2j@`%V0I-m`*Gyj%jfm z@pa(bO39iQBWZ>A-py&7edI=Z?3IVl52=D#A{nt^F2^8(Irxkx;EZQJBwO=Yx{DTq z>LQv!Yxjd!k*v5KSPI-Sf2(HZIMJ(uDIdHd2E+aeX7Px1NMT0`^T&8Q+HWZmRF_Y7 znjD*<5y)|3sf@=vHS31{rb&&Sx5q6Br*Mqhqd4Sr9E~j|2wc@Rr)^dTDbqxtjq%{r z>b8V;?_*d__#qL%0qr=V}1|CsfA5o1d@mBR3tluH*WvRjyf(=T{+4JKM$`% z69I5V40Anx!?&@iO>G1P6;T}5cXEJei(@rA*#F@)KZFpe(;5a}_d+RxCO}ZdXs|Dk z#W+THaD{G0PaQI${W+c>Xlz#*NG1;7OmF;VEVgk#Pj3uTQt(4@laB1JxBlw4S!_+LOEfHw7 zaTuINI;{FF5s}k{WJSP*;x0$a?tq)nSrp~C_*8MeNn(cKfu2i5t@IFZz7@ll4Z-~q z56lV!lQ%|wCoG=J7X36v8MCNF#7l8Z2D(EAr;db0DCZ{w8=DMFM}q^ikHn3r!Od&# z;qf<|Ge*!faE&Kpl)(PHvV$il1T7$fzY|jp1EYHwHWh?bCE>pbO{O@lw26v9GM+d_ zfQzCL{^bd9E2YiOCb-cPYP_F?=y@?AF;?Bpz^i2x)hIDz@(4yKglq>>%1wF?!* z3T7C!OPF>P+yx8`uP_<$>f}WWxa>y4!0A3SxX~Sig=nhqIIm_$AonqNx`-}R>r^hs zpaZoye;W!6jk5xuA9@EToCts@2!Zpw^N95j@&pm3u576c&f1-d-Rvx|L>SA68O86c z+U(=XV5#v;%xwzXBOnv>kT7i;!qagaR-7Nekr_VtnJkzee~ujDsF;S`GYh;bYB+3E zz{+dOoobDQ5h_#NfYL%dmhR%515Ji;7~yLij{dGE+=K%iMh@q4sF+ZTFXdNv9=!&q zH&G%uWmylwT+l*zRRR@oRe-?LLx7q6c?d}aB(UkQ`hi>y1Q#bB+hIUGr7hms(tL&* zhzGbHfNt}HLENY+Zx{ByG zNZ{&5jrPwj=D^uz#d*jX%7wz^9mvH^QP>s{@oRk9osYYC;ad;DM}}4o&O{p2-~bAw z6U**MVIgV)kV$a4z{9@*Jq(Nk7t@EwfXl)NC=B51iGpL4DiswrcrM2P`j##@FNgrM z7z=z0Wn4ypNS0!J|2Snpcrb_r%?=05-;LPdfmv_TYDfYn0TCiJP!I~L00^F0L)Y&w z4^jdY5@R+b@&U#ZKs=|I z004Q@z+bv#wpYQQ&4ga1;BQmBx|;xi0B(SUf5Q)=3QHs$Hb7^Xk}ZvM|Ei{eMv0nj zDDH?L=WU_-G$jDwzJGm0zzj2=sGi(1_aPk3+j;Aw_3OLOJ%un3;h zLCjNll6(rkttM(GW|!(G^WyVf|1~GSyH0gMQ*R34h}|G!E;4~vN8lH>gyzk z$?lGHBrVE@{0 z`(sgEwc*wUzl`t3QeM~Q+)Q5NbQQ@i^-Tg{0L@iF$mVcwtAnKFU&F^|j zVJbH`cU)O5V!Vf?h^6gvctxBH=ImeYl0hGb4Au=@;fNlzr@E(g^dT<0s1+qeyb_Zg zH^3>LA+7{d9NW;QZ@(BM&n2<77aLQPoddG+w`d*Z-khD4A|}hZ$&sy^BVf?naYHkl zJ&aS;w-W`@r6EeN(NJ>25Y?tm3cqKXL?bDE>eZ)Cd~)k*_2KHs~zQ+S_aJsoA+ zt5#|a+NlmtCV$8pjKNfsQw73)Wkd9^?t?Ux21%zs!)_dOh{`^i5*QVCMFk(p;k zUvI$!gACpWy?f_A95*8m;y!qTQ*CKN+I*>xEV=(MZmQ>LL%R04yFp|YiBpfis}%Xs zn|N*-clv%rdJktmu%b%0xi6HlEMe~PNUS3KYY`+E8F`paM_ zw5fs<5x2p+Q-*IZaC2HlkeezKP^p`|d;if+t6R$BNqPB2(vR$Sw`Ct&R~D}y;QIkf ztoR?|;%;SE3>Foj@?8(`uK?a;P%#b;HA=nrPd-`;ge=hkwfK(kL7E=jKWm_yH4~?3Bok_t=Nfa|X6OnNu&ClHGl^Z>EEe ziIFz!6)&3yV`azG@ArB_0rE#e!Ts$1CYJh?c~rdFp9Ra{y-}Il143;09|paGgRR1| zQe?h-5)o-!wy^j?7>`hox7B3)B>)qZ82+iZbfCE1LlBY@w?V8pzH0UewRrndM5E=f z(dMT~WxFHBcQZYx;L9GyeJ`871F9%94u(ja3xS82q^kD=$&XP!Rl=VG6$a`$pN=h% zzAN>~byV*;DSz6iir~5`w#)ox@J4%QX?uEnwQ%B(X=(IN>fXt7Jx3OPgq9a+D51(A zMuw5I6RkHcR0#*6IDV=sIhIl>{}5V9VJmoK`eazYm20ArHi*jq07Dfhc!aU57WR8~ zA=b~|2|k*AT=J&ARF{T_>J>5c*3$Cath}0AA9Jf?ZshEwzq0i;Q;Uo|f(iZmh9Ty9 zRQPl*OX8~^FF2E3*kS*nwjpM@aiDP=*6u%&h)7kaje$RC%wsKk!Yd7GgF}m?|t3b(Qf( z8-iJ#xZ%`*UU`**794_v@GqXnhBiIY*pk#VVF-j>iV(6K{xBF87k4e2dncoj`I(uL zopaNXUF_~+<^JZpNblz6hVT*QemCGuT*ll5_1KE?J5eDL@)O~hBC+o5Je_xc7e|Tr z_JXRCYClKYeYQ^C9jr5%Bgd&5CC3zFuGv$S#BCBC|J0dTWv>H_S#2*l=Z6?!s?Ng~ zy%)8XXX_qMj)T?uOZ7fjdhv$tq#7ACHwA5_3&Ch7f7#C~!CHwMEb#L(44WS22d1R; z5ezXVA7I!CSjI4zLe9nWXu->C1%a)5t}^RVHG$W@N1Qd_({^aDE5 z%ih}kd_31(FS8igo6pQ<3oxsAHfyzVY~*S6^Qmx7vgo|FZSCzG_!JymJt+0H(~N+) z&ChRM_hwl3jV~l^pTsxLxzo9HDJea+R_i*ze@|F>u1)+>1TT*8Xj4#DRVg>^mNNT{ z6@)4fy$Me`cbR#()9kUu76~rFY#d1RO|;S>M%P$hsd>W+vd*mj#uiVhag%_hcGlEA zG&nRxC9$17JS#hnGS@FbsZq(~xnYwaYH_yJy;hgQX6n02Ki~UX?lkV3&(#cX%#pr_ z!N=Nv%?f#KKGz6KQSn|p&&qL{T*x4HRT^}USmU1}OHS+M zytt_{&TRK`ZbJ@a!jBd&#lPGbFKC!q1L(X_Q5pe7Nmq&!OOLA>Li2wli{p&{r zHc;w6JtDZe*|^-ld(ZoC|8v5*fm$W7bztK420B$ zu$wjT_ld`W&itEx#uxTWl~17nbTZ=99%y>q$PCv80GFk@X+QAH-YJXetcyz8#C7vv zlGs=PFdw`=yFm;f2v`+yUB>m#XQSd~WJqrCA@x%rmJI^9f2`}6q6Pq&njj3WTYmLS z=7l~h3^b5&?+_yo1yHs{F*q5DvN1HS8+nr*XHVgNi3(VaqsfBaloi5qn0?!;#gO zaAcr|8lbYr%n^fwzMl9%8{?HLP*7nyD+G`r)Q<(#s$bLwRH8PYtAp&e-5~p&e2_g# z!r+XZ_l!N^j9mw0r+UQ=vd5Gsa05+fJun1b%ZyoN>atF94_lA<%HE7}#Wl zUya4t@FWH`{gdW7DxhSMSKxnP!^g3y1L7w*2c}a%wiqOjHqH#lI(w!OhSP}o4~=BV z`~sryI7ra!l|mP!QD)%BNFZ7XWKA z<9pYzO0fVaeg|(x#uFdG5Jt;Pfs9iJ>KS=v#k7HrDZGon6sZ32B=J7*`$O51-7Z`W<1r!jkCMJc9np316 z{bOqb7)LiXD0oMV2bnMjxZ{I3Bur_0;>$uo*t#Jos(3Oa4-tY}MG~wyAQrgazz{p7 zlXSNUf?&vtLBbcGDB)26tdOnmVpkAsfdBO#J;NxBHchjBJoU>v9gfYsoz`;y{0$v11 zBqDfICkrwg$F0)n&ok?W@gQEBF5vsk6R>#|H>9pIg4DrkZILm;K!@77|4M;%@bkM( zm|3d$lq_lAYviC2v2*{0Ijje9m!6>~zyfLpk-&))8)3n4zEe^_+Ch(Oj#0!$OaF-w zj|)l`-+S(9n;XvnVwy-BaTYkXnHq(If)VCUjKRg%!NCgo?Nyk1lb#{7{Obsi(qRL# zz}@lBSU>_4v@?L%{H+DU0t)*t;{vAy15g6-#5P}WZ++S(-Ua{Vhzarg4H!6RqX0UL z1~oIp%`u6epoq;;1$P)7u+NmKWbw(6WT&4O>A}o{v4B}WSRrDCJ`di-iv_NBaJUoe zM8MG>iNFCScoQ|}a+ky$@8k0w%O*3XKP5%?!Co1ZH(p<^&vLRsg*R^)((o zQ$`Vk)1L*_bb<3=1suec(V5b)&LK3OEEJT-fQCT%X`Izk*euQkFuRaQgahVGJO-y4 z`gPvk83VzU8EE(H2KJz5J!|_MTqt0rV!Js&7r_9|jDzE#La^#$PM6^7fGqx85eKfP z3{XHCa4y=~M+{;NPh}vWTaDleA#s`kQKNa~#3J`I++w3>3H?@dFnVvD6T#IZAT0g99Nx`^)eI z&|vbkIR>xZ;5D4d|EwJd9`dDr*#}ML#hl6^$pO|L^uUQefHLWr0$sY^0fJ2B1j2!9 zV(_RI;NUqcB0Piy5QdE2t&}Q>9-uE8OaWjs^~+fk zjPP7Kcn$f5g{C-8k}H z`;|PAHTJz+#&Yjez^de9@sXdiO&l9LQB%yv^rw~86oHBm@wxqj=N-@{ARYoBAe?yM zF|!KzY84@Z3_N@Wn82reKoS7N0S5qlW2g%Ny1c@{CjJ#QkQ&N*0c22(jVA+NtI^gW z1XSX=dGG+vF6!qHfNGAo8vuws|A+l=Aaeq<_-g)7P@`Q+kiz$ce`mmDe&NnldkDIP z2=F%pl!j1N5R6fn9|21JncqCFJ!=(!qx+jp(jh1>P12pU0R?3a=XxQ4!}*U}cPRqm z+xXD6mKO;n z9HsuJs#-eS2B)xXS81FcGb!SNvNEo8BC!5Qa5?y&&wn!lzN-*#EoJS++dL?o=6~LL zonWox^58y)`~LOTi+d0F&oip~_7DE{-b;AnAA4_ebh|i}Ml;3eflV@rmA0Pz*IDyajI2kbK(5Am8 zg2TkXzg*TfsU`om_?aP4J16k>F8}{r`_t2F7~+=zKm|BK0Tmz>EIo+rMex}G@z+Ff zmyzYWsCCc86k zaO|@o1n<8_;cun;tRntqp8v~4iBEGo{B1CQ!w%rE|67;;u0*Ax|FSlX*ntyc5Oc~) ze_qymtRVhxJMOQpnNXGVoQ4`5aizmdG(rKXf}JmV2Ic^eWZR%l_?21-MjD>cFuU%c6?n zE?ZK;Xo28YnZ(L#Xr#gSy~Kn{R8>|VAR3GFN7joW)MBN?R7R{@$v?pTZ*4E8OuGf0;98msr1f#%hk ztE=%-FQiC9n!eU5NL_3|_eXvp7#H^q;*JZ__1gG+(7EP~&+^U|Kj-NR;De zFVZs&FU$G*J+Hy2M8k5UkI`PcnlpM;&!E^haQ4VVPr>&2 z+p-HoL@cMxCYDW_$&?;9S*2pKqi;t(ri@vA>ax0^AMca?nd(q;CBkNo@584Xi1IXo zl~)AXOqBfPXto*x!XU~*55Aj@M&I==mV38E@kMjd=@xhA)ajy)Bk6-A1jh0*-F7)%uXwkT!t_)}5>`V5NX&<9W~ zp9PU9W31)lpOuAyNL;!eCfN;A1f3;3V^7F=cMD{lH(?B2UDC z-&ouDq~{P0pCCs7#PQGB`X(BL-uUuSf0@8Id&|_aG>s^qgfwS2_+Qrh@K!W0AoNsc z3nQ(!2XhLVoaC12x}{L`ltxu+(vR6F)4I)vru{xsX2C714j+p-U@t+PDzUl~9_%`} zuuVHXBb-L3nY^&5q8wLf`uwwH&C%s8=Oiob@4})3d4ka?*AuiqR%AF{ecZQgIy-E3 zKe=Q65{=ALgBJnPmS#TXG0E);-DN|j=6q(mwb$Oy%sD3)FAn~ajQ*L~;M@@pJ34=) zE-umNkIDV6_rAa&xd>m2)`BXNZr(G~&N1lCU~a{GXI8ZT%el&7X+SSexY3~JURBig zHjiAkDv>1{Fg~+W?Qm1OD3q{|C5FBEluqZm{r+9en~7fpyU$CMXGrIUKSVhvIQ(!z z1Sa%1&RsQqxpvWRnAhEcrg)~-KsT+@F@eD+;f)l5R1tqnN~-nBk_+g=-kW|z7I*jLh39GjxQA=o@(>&@6QKaS{Rc!(FI1)9Bd zA*7hNRaHWNJ$Y_%muu@f@r7ZYHr~yd@5qK@-oT@Ebe}wy>2AuVPy4WGi+h@iz2rlv z-F=TcA4D`75==OcEVrNNZG4;D{8E>ay;l<)_L|5(P6j4Fck11ZL(4eARo`Y$^2jp~WMeg#)pbYTBxK`*Id zd}EAcu11-AauWhH2+;U0kRzJa~DRi`sfdX#U0b@<*f$E4?)6`R(YdCG?xjnV&7?7rrEM6ibp3p>$oF zBVUoD6C`FWZNv0PC&o2B=?_>G3*@{9BM67nckYCX#B?Ggcj}Bjc)uJLZ#DB(w5x## z^s$*<2}FwaM%}@0`GSqr7F<}vESdSngpHwJJn*S_2`MnFqlg|M_9G*D|5NHC^#fCS z^hW;UJ=*$-2fo;qctrvMDf`pIon;{^qk-D4^R7zZT3_zG1#7Oo_=6Y*6$dUYD+Vhb$IO1jPXWO@ghKc( z>?w{OB)w4X3&bP|AFg1-oocC7TvPb-^LlIWprK*`Hwwue&)xVgKHUKjFYSM1X3o0E zG;+gO0Unjz6*GLByP6rEP+8*Cx~LSNS~WwX9!==o219RQq&IeN(ArdSZjc#_?MGS)aGWsV4css zSe@oK2M?>*{apRfCl95we1uEL#`rTC9qVr!vjl7*)a8O$JY+t%%&y;xKM_bseeC5< z6wO`U{GruWup5D4$7B>-Pn2<9SvMIkKe{ZYUv**DgwOJF2qv(Bb~`|s*)IvJFoGVp zSe*1@F-mN|v-DH{UjOE11G#x3>2g`v7MEe|^%rYo?|%h&R#uYXou`z!V4B#!@#&3O zK7Cmha&%8;0BAO@NP!Ow4z~Qr2@NQOLOkB^9yKPx4ycbsYMDcQrAY=1XDQ$p`KqY&_7JRRJ`WE*SQ7t-M}Ym4YE$`H{B9c`lV6#Dvh&G zRCAjR?V6`qUMr+Pu3AY)?^2th;Bn=($li!_B){fRVnzolF|IM~o#EtNOxq&4&+aco zsns*#!*@?E6-;VY=-sw&Ete6xhE7VxJb_%bzdX2N2 z`+IMj&OA&Cx%vonELlxlY&A zU6J6*!59@BR1C&4X=Bj|YD3?IvT z=ia=I&C(Tz`Sc6)SgsG|7z13Y)#l}!)KwYz_XTFKA26% z1mm?NJ1dGj&FIM2i;CV_h)VTMyPjO|>2o(DexvEwh$qB2geS#APVx4;o&cM{@83mV z2#SfNV)9i4uP{2yr;#ly?f5mFcV|qMQU1<}kjm7DJJ}qF@gF~hAAQp%osn9wD>n1G zHa!#G#IMk)!@X9ur@q(22~54dp#X1={l0JM3%IuJtXWW@L|iWY6ln`gb+)W7Zs%}q zbEqP5V;Z0zWu171^h4vHinC^A-$D_nyU|`7JwL*c5ag@U?V3p8SF0o+wh8cw6D&9c zvLMEJ9Gh1(xuhiY61E6?ja=m<> zFCF?Bqzj%5&{PQut|n%a4k(=?t|Q4f!6UQ|%}`Z{4_Q=k`P{cr7B@(FZbj4a1O94s zY^=DQ*D}hE^fqgTv})y!%n!}+i`??1wk)j%vp*Q-fzVivMp&;QRrEF0W0%a~TMCx@ zB@jkS?k~5*3~6SsMtRqMS;CWHDE|R4kS)~=Lp(?pCRNpY^`hdH?r=Firh0Kj2$SOv zIeOSP(9p3+R^4ZN!IY%z;64B1PSSZN__p$VSHGNCXh-;RXM58^*&-F-c|kcM!ZxbV zf?l)1sO{G62cN$V2D5w!i)j5=Q}{zLvzz=xyIRcw9V25( zLF%D7p(Pgw?|!jlt^}Bveo%2v^5pcVe(rVb#juho>Y`z6{#0U)@O>g{@OMKx$WUz(F?H?>{ z@01-C<7bBI#pAk!@5C0*X>E6nm>RtD**{8pS1NGhRJmOV_@>Lv>^biKY zYL2&PWllfO2jz$h2Hpjnr7@mIX z9{*DzZ1D@=6e@dXlv_@KKk)HX03X$+G~^!n&7ye^ahmV$Zs$*ZI0uMcH9x8AI*+B4 zX4k$&q5bm?-3e)*^)5@$rI9{UgW4bMPo6E3mPZzFO$moCJk7IOH`mT9+!wbKw~6qv zqPv^eNP4u9q*R9DB51@&eZp0W&na_NUL-fLruxQtSkAEMqUpR`;jcpOXk zHE6$FW`wWMxZdZNl#Px#cPQ8T4n<85(HIqKojxjIF(J9dLr6Xf-ZQ6ATm!yjA1==% z;jr=g=x9k+o<05UG-b^7_|Jq->%ZP5|27PpCCQFW_$Y=+u)1N^^Uj0|{M#U$wWUPA zh_`quUlbn_yQKJ4CWOAVo`>m&-@O{s-&{T%@Z9+hK99A$sUEKfNvBA0lM^KS^&HGG zZtxxXx;c!CiE`jhU|2_q_!4STzb4my{C&8mAIWM>+r0f#_Yq$0j+|iMDF1*(h_LO{ zi~XMo;Q=J;hx=_;xYs@D6chN0_4i9wx8!#ik;z%JlT23}mST!TzXetqS>g8sBT^MI z?T%tj4{G(bSvYcQ&WlpP0uL(Z8|bsU!=9bOMt+)WI!RaP#Am0c35v~Z$?RGog?~M8 zdlDp;nH>sgGjHMOb9N((Hva%BPu9n}# zM)bmYwd!%B5Y1Y;=*GoBS+nm2T;UZX8eL3pj(`|IA^B}?_O9SLa-h^m%-*#gqh4@BsL5KH&4j8h5|>I*^+5(Dury$fcH+I@{?B5K*@)y~VFNBRd&uBy4UZWm)iDB7{MynXQnrec7lmV07j4F3@2$K~iLKsae{G?#wr;u6Xrmsp67M3n33#frsC}=k(K)bm@)P%%@f*v^!eZe6+sZkln;M zV{tK;ROc6g!XYn>jLP>+%qzkV)iYVc51wgV=6nOlA+lVsvt7Nil&`l~IS0mF<{hPn z;cr42=>5eVBiD}2j`H!=#?e@O`DOm?+%+@pTS=3H&7^zPC2FVJ#jcy*kXrdCg6>Tp zZ)FrL&BbaG>MgNX$#0P?n$4KB=hv}%yQQmA&c8K$-+zUrCOZ3l!^Jus!+?Bp!^?KA zY!hX>sA|l{Ts3N;zxq~Jb&ClNM@`{X^tG$TN?$z_b=Y!08e5X~;%5^2>oqZ5G)>@H zwK*5j#bd=~A~tYgCeX2VgIsM7`N+3sAS-k*n6U1`9;r@0a{KFrhqdz?x?e)PhPG09biJFfofvr_C6mJ=hQjv+Q1xuk23 zyb)13Y7R=igZ`2dpVBv&uPa?{B#b;VUa`3L(>9f{x9WZ>>SNSQ?@IXREWOP`Vz>@wK4(620&a$a&=fc<3J`L^G5 zO*wRW2d~`&?qEOWaHrLdg|M7({Mbbs#dmoK9n$c+#Z&QlpM0}EHJ_l}x<&M)Zi!&} zfx2JyqpK{VHwAUMUo-Bjt&H%V2oFp37=>8^Ig4H$E4ac=M8t6Qv;Je#j0GRhPH8(Pc>|Lspl7;sxn*x{aE1^b3b|(% z#QuOhPv=Q&Tis9%gCoVK&ensj{?bR?COZck{QAiD{4dfskMEXzUKGG7dxT|pH87auR%>zUY@pn9Wysy*ku4k+L)fn&{?RDbOH;5%ox%e?pqT@dhiFaE%F}_7N#MG0S0NIOHy(Z^%8FO9+E*=TC z-jS|hAU~#Omg`)+u@$z-^i$rca}v^!%UsOdiPNU> z^PP%}7l5W{oN6tLVD^beWzt)MO!A#N=F!2mhglMxq^Xm0a?5EGZn54n*AUu7v%GDb z?Yb@U>g5l=Vw^g;9q(~Jr~lRw11B>zB+hL=X-Hq0oSloW!O1M(} zBQ@p2#aW#MrM#8uDQU#;L%>Bat>^{C=j0fRVv3=Sy|S7WG7Fy;M!VPDw(3c_lXYKi zHq_nKZ!L~Euq5<$_|7D)G3J6=z4YWY$-!3BL(1{J?9UHvVc~+GtY@O(KDSNIv=ZD#Br|g;lxVefzQMdmY&s9APq)9JJKa%~aE!;= zv2?xTfd6*(6x&fU8%dEd^Ar-Tb<)GKBlARviR5D1WQr9T+3H5vRNCiVU4!#7w+{*m z?l}_!_0yNi$*fRrZyGH5{H+_xuMRDx?~{P_lho!i%JifY@71OSc!DDzYr_2H*i$yC zhQum8#$6odj#R9fVjp*-T(6!QIPQp^hCIRFxE9Z%XuR+}@UmXv3N`(lW*_@>tbuis z-bkS|wCso1^h8BM`67)8{@Zm~@rNX$8JZX_+tQ7~7OK^%cf3QTF8*i{B@F!~?|thBOJnsG2@|JMhKc0`_xYjP;{n0_7)FDhOan3JTGuAE8lQHotWZ*U5 zE0!fT5im@{6;GZPH?hFmn*z&voD!REGD!e;cS^skEBj-p!C)@COa@x3Cf_HWt zma|~U)udp|>wvDlx66gc88=sRKSn<)UrVY_^357*ua(ZOypjKnbqbnRw6A}0%7-yPG|adB3i4XlB)5@Q;=j!LDq6Dq zVx{>P@yug&FStif_H@NX7-YD{37_C^rJzN!6a;t=sV#TDW3ZJJe)4&J z&@a=U+#sBis^Ft{d$v360BPk$Jjbq4%SZ*{OZDoSvxil#>YK#xUt#X!YAxE5s|-gppr3R=?^Ak!5OcVp}%JBn}nU&fQ34_CI9v zDccjYu2~Gd>RFEvkW=^C|A6Z4_EK*l?zsLkOD?IFB3e%TUHasqYmRUU_W`{npFpnB z!2Hj|u{uvV^N6_Hh19`oe(F~nf27wwa9N+(2x(Sb+F(U;AU=9cdB3_q)<;#{-ZI?{Kt+vf$$Py9(Qn~8VmpAar-rP`nVx*Q(s&6%!W zY1Z;fd*hg#n8D*^N5D_DAcKMP9~K?YrH6@L5^xjtRMv4`u5Y-p*^x!i@=M6>IQ099 zNQ!>JnoYLSBLaK$=eE4ci|^I#d2K2u0~nvN*`Q7rj!1Xfzbh7M7ZU}4`NCiQe!tJY z^i}Zc(yV0I1Ya=+QHsSwf_Udn==NYRcmDIZ-WRee%Wb5fF-QNZKh3q&E$G*KbDYUsqm@MYfSo*03 zTf)+x!qf}A zR_ZadpWo=eeiEWe$zaY>c%OknDTRSlMyLLvCZVz4h}`DEY<|@L$JbW?#T9g20zrZ& zXdqY!1PE@y-JRe*xVsHHgA*WuBxukCcXt~kKyYVpcXyb98J6$ge|M|4wzle4-P`?M z)qPd{y1Kg0>2t%5Hx{Mf)WywsjCVkB&qIyIfz`*UlAWKm&MlpX`5E0Xbv*!Q(~?}$ zef%SfAAJl**JAHLvp8dsHDnNDX2kZ=uG*H zn`LZr*g2%6;CjdG%D&o&H9eVHrRj zxk4HbKCk6+p)^E~jCW(LqV8B{1P9W*qrn)%jc)&pQE%0O7X5OxcwP-__aBQn!7P1L zqwt%gRsc!)ReJOKg<`afPuBQs5#;@R&iWCS8z`TyCYhNSuTSv#+J?%XR*zVS2_wa*nChN+^wkPW81QPXgBZ$@!0q zxnQP8wc#j2Hp$mG+r5!aR5~4P#&tXei4^oBnsWQ+hpS`6QkWz%_ zjk2GI_v@yya39`lQ55w(wl>_d8+>EPc034O=JFB#&Hmzp89DT$=IY6g*h=(FmKK7CEFUF74b^ zX>zjo2=J~Ol4%PS9Lj*EE{{NMeg-9cy$DBZF^grc_zwGRST&V`ksr4lNAg?Bw5`67 zee_jgzh7geJH>)4ibujhyYWaol@5ER8Ozb{YDFo-z2brbmM=KlWtpe%3yq^(!rY`X}^G@u|c9g3R! zPa_OJD4Q}gdYX$lYT$~a8!ccaU)XX=md7sg$lY27@1EjO;p+A^Z@Y$eH(gydlg68l z+v%V}pdOt#9S`gF@U)+2FBVhESr?T5aW$amw3>Q=hiOS_)FD(KUs5WjeEYT&-FAnKhGYo z@4{(WU-o%Od%e0YOxLK-TqkC(we;Z@g6NxBeR<|qKx^NRbUSjhmV@gfM)4~w^xyr% zGYMx*+xMqG##ZA?!29=shxMrEFC#NoNU7XUn=A%DmWt}kfkHkHC6uT?s~ejiB#}63 zIe%ybEvtk}se@)!0+YTI6qd}|pu*quNb$=0pt(_$k;c#?0>7*CDKzdYv3Mq;i0D`K- zhb_;i$5p@d?-8f1-P}{cHs64dF}d5<8pKploO?*AzV3AWO8oE)5gb*M{82KE@hivP zGQY;EIAC=6swdqKh>kHwhq(WAi?D+(BYkI@&OcL(%HLlw4aj_)31W!L5se)ZG(t;# zf0h#FtvEad>wBoGNxMcFK5T9%V=={9apFtjdb0s#eg~Ug4p4B(NHcEB_E77VmwoEb zt-cgEp5aG(FSq2YMYWlXUPbr!-Dl)|^pXT};|cXYEIssmHn;)PvmEol|Bt2j|I!KL zu(Nt*SaP^n^P@h4P)}Sk^74GLpZK_BWn_7!q-2Ho`31T8cm<{8_~p5|g?RpxEXG~u z=vj68nN|P4lRdNa|8G@yvS$Y8|Dgo_Hv#s)lKsDUoW}?UAme}s2M&0kYF@<-#<3I~ z;Yl;2Z`VPx;QV>6D>c7LZm8A3Tp%4E7ylY{BGdbR%}v(YR#&|S*FKDh#f`(5!B=lK zF`1Nt!b@}!0lyG=*1p`|)`uW^+n#(cFPP4Pt_LUcR;ttiAS8Ti2|7MjB5k2L8gAp+I~I9nr{3*C zAGgSh)-p}cH~^5x$749TNL5Pc-X3`o=QxKOklZd6u-rM1IM^AMI9tbYyRJz$x!sxV zJ4&@{lMoArJvp{(Vit|mWSGEa7hvR^u0SvxjZ+&w@7G-THCt4qtz8I$z@%|6H{o?B zcT zeT#E`Au-0GApsFwLU=Ou*X$K(xK&kJjKqR-Czq}`Eh074$E!3@5V!E_+sDJ&<%i=1 zA*6qR$L00mAzCN#GT7hq>JU$SkQ10)>3?&$nUR=LR0JK@a2-Tu;`8eAD`eQGehzGQAh_{)kEI_Yk;XC2!hxp&CTq@ zlI_(>U()$lLCc*`VOkucJ>J$EU$+ zkf*VUC*=)a+M$(!VK6KF43aIeW@;*GT=d1Q<^fR6JA3*Bhxm@-0iW*F4Iik*Pzqs1 z8=VrpS7RJGSrShiV)xG*)iM65f7%Q`GZL%JGP^nagCC0Yp>}|5Ku4$H8VxOOnJ1e? zyyso_cI?Vl(^IQBp26_w$-&Na9YSNJ;|Xe;e$KtV)T=MtE0k@zoH^T-8xUIW+WhZx zQbT@0Lv?-OBTT{Iapl1mK`eg!;E8yPe4J^dJ#fj=+aohj`S86+zbbS9d6_DL(Usr} z$Xq#H7lZr_-z3?`YjpZh5UHJ_bcVby@@90_71UDS9)yBdgBPD}M{}<5d}(n`)%jbr zXMxJ6>S8V0P+)0*;q-f&v(+c!D+^@%!**4w{u(IIWA41($*6?f-F>8FFVR(mUo+JX z&_SW|FmmR;w$YSv7DpSlOPjWh%8Bwu(^98xAclVJWjG=LcfjK#(bTG`USX)p-Q(uX zXj~#gYo?;Lw4eS&Gvn&h2?YFjV`PO!g0O zi_o%HgY}mKBp%K$m^45s&2Lprgnkr)ij1FffTbb@#b)Us__P`Q(ZX&u0i7G{Y^tc| zY56J?nBY5J>FaKU7TNRq?(n7$KXcq&Yl`>tx~v%*;7$Br{pWe|@Z^OB`y_=NJ_T&B zksOLxy91lG4iNQs>zX5#$mqzAvT}ruIdwi0HkTjYV&@-Tr!_gy?jZo#joGSQy*B@_ zpj)FV4aH5j5ox-sGtFlx3Qc_D?!tl)_Lb zZ1TX*z9F#barp^9?0z(E8ZuEBd;=%TzpUZ_0y53O1WqCXRO{sjlh40eR`~3}^`&8e ztiN5;@bbEL5OYmLlW%dx2Jl7Pavuzz**$r~(p6k}Sh3WR1_lAQJnUVm+>aG47y+es z51b1k--e1uKBk_<1|Mpi^jSNIsrYtD=%;J6-YzU$O+(3>wshq-3~d%AkOxPJ(|b+! z%4J`6rX_-TVK;RW!6Gnz?$NnLI=iS(^`k#($W%G~-~YaRxV*mPZ->ra?FrcR*$TE* zzIla;U)9{)D)b)r;v}xl*%cAc5SYvT`m7U0#?Ne_t_qOZDWB);rYrAtHCTpQubTLd zpuEuc5ta`_Ig&G%m5w`|UGUOmyF5OkC8ZFEe2EB&3T?9Z`_FNE^Kl2p&Nc`=;HVg= zxf%|#O7A*4IwIzgV=6mf8cabr-)(FW`qFM5Z{$*ltr${gaKI>)y=rCTp1K2^qgRI)1p;CX($fOc5-ly+& z&#Ol1(NwDOg`_DlCxAnr!`)lOMw4YtpJ~Flo;SP%PO@+~m}&=Y+SAxj`6(w#tkSuE zc@2jjvfj_xV+^Qt5ntdT(H~Eh&2ga3FVs7QPolf}L5840Z0l%Mcvv4MK~c|@aau2I z0YjbCS#n?LPg9YVd7SfxN{<_tyN}P(agw!~!lvRFg}aq#WCBpdPC4D4Ce67{bSFs4 z&cJv?yBQx^mQuj19@=*^1<*A6P5HtWNA-+PL!Ix1fPj6yQ1C4y8?ph(>V)kC|HvxiERR|rMR_3vkaKIH%sD4hXUz79 z@|FVQ9R#k)sr23&cGic#o|g7lpVuot=?VPwdpfy+P1{Unl#S)Q8x`|^%JPjFcWb5Y z{93IZ(tePF3;5Yv^Ar=*d;TD@?z`MUxCwg@9KFr0va8cONer=QN6$V#yy4eGt5yBZ zN-oZrL5T6e>e6Tq@=k z1UVKmLSbwa`(m)eb0lCK*I*u!@3J;VMCSA@%m6H(_~gy{!4BmcLxcIpC?Pclb!9+i~v!=LzBuVN>gftTHU)bHVjFK&M0S9Ei9{4kt znspTZ`V|q1Cr2rv*09$&0Q_(wz$5^EH(FZ#eW&Tz zgi|#>zIDQE5`C8H{cvA_ic@tqF~iL?Pq-*5uOLKJMCroXpT^-B)_0J~cb8fOeHQKp z1;b%OFD{12iv)f>AfUSNS4Esxl%Z^h%g*Htq5bpga4F-tRi8n;XfFTIQ9>G1ZYWlb&dc+kPB?V+{y5i&9z}? zeech3M0E2HHmq+?($>E#QNkB2EBaRQ&R_nxb?$X3aSTVE26pV!-d<`$b`n!?Q&BK;{N~F(S>HXh9i{|&1To3rEe4K`auOd^6D@cYL2e##A_)MlEzBR}g#vZIr z#ytK^b;oA^43rXB909=^G6Il=!{?3wMU5BnN*iAJ*sE-G=e!^{hJo>Ef-Iz2E?OOZ zaUrxk5xZA#`5w=TCe$NSVp!GDPx)P|#rh$f>K}wHK?^2hgR6+WHk^@X1jR^RC2_jt5?zNka~6{!JR8Gqt4 zxv=vlX$Rfl{Q?BMdNbZBse<#8)$9zkB#HuxdmSF`OIryE&qE_gyxLpa#>&U$xH|DY zIu<#b{);XGy5%E;hz7&aa*U2@5vWqXv%-i;`$D6CY zbNb)VA2xY{>gzw<#w)9Q%_Yr7@D_fdC1p{4a97LTpJ^pj#V>#OQQ1aEeYUj1Qa*Tc zB6lko5{>#^wl2BdkJ$X9K+*WPZ&jsh)coW^uvG}lOaA*6niEOk&gIZvT*fltV22!c-KYoy3u+NQw8RPrEl5@;%#1q81A?|R zW88~(zX=^Z?#r*yvHV4tkFo>NUlu3_ivmu#sOpnyLi2+ z;2N2nPZ!ce)ngO0LH?jCORO~%hRAenWk6;ZkJzH_(@p$50%!HC=^k|E2ni%ahQtBQ z+n-mPCqy9Ap^8n*OxjA|`M?>Knd3z2FyL^i0F~3{V5-^-2dK~c#R2nr{#=vy)lstL zS>#JVWyBNcyB*Scm!jW)cclg~ajQjKrV)FVkVEq1=WGoxTnX2`F>es}TT71Az7{hgg$b|nnVC1M@3q-JyZ+na8!0SqtQHGk_xrN zJ)$A|h4tT480(f-O6uu4F)`UGDG|FZ-n`y+V#DUySUz*@5wVy<(!5DM@bo=N)PiM81Zuql?b7SEU zly^=7sdWl}M2DJ}ylmn_$D@g;<=bNJJN=ml1M)cA$Ik35YAr1;-FlKYB+F<@rwckQ zhk>?#*s*4>R3LlWJAMZ}DbaEGz>95n$#@CKy(@8{lN~R?h`>WOF1LTvJt9Xq55u?C#3~gzDAgE_4B>^}p6s?qs`yCGy5Id$ zzle6{M?`!?SM>%4goB|8C|LwaYb(Yicd2VQU=7Yt0T3vv@%POl&W?)>ujpmzd$D>VfoHRQ&QKb+hAw=C0DWXa`kk5F=r9M`=gyp|YJ0 z=@op7;g_bUFGFlm+p$5tbCP>!Uw%K)@Z%&QU6=VUX2xS7(s6$QS+%{GQ@)&5s&D2p zx@)$Q0(smSU-yt0KIC&a>o5kcodB=SUB%z^R+;U7Z-BLbN)RtM%knbauU0p?#R+#ccY}_#&N$Q6LTf4>G>Hhb;1@Sq!z{CY0Ad!@h!v7dc7{9 z&-OD?)Z&~GjM`X5!l;pTKTOQ^9riw<`HT#wi&jEHPn&s<_y|?c|r`X4pt`A*!rOx zlEwXSiLqIIIQ5yj0^G^to&=AL&vF|y+(3lQvyCaH9$hCc;h^-Hx746zLicNOYeUL&Bub; za?kH-xO(&Eyoasd~zgTL}1gP-|ycXaSn?3x*d-9 ze(m>p1*IY*G{f8;Z`!HpxEh)!pu+}ElH*KE`(J$isr32B&;WuyE;sp*RL)S3#BdOo zne~wuG)4ZqdSo>Cu2qHHjW)jVcAs#=afWXmmRiA--<|^1kwkOA7d2XN)MRBV@1?2p7wPm z6Rgr**|z2$emTB2OC*6vE!aB4WIJptDk9&r-xMF^ei6{=e3zdnTP0h<`a^s>H?EDX zm7|O%Dm6phJuVy5)az~swkLE>5b+UDCf9i(e0FodszI@5>@G0@G90Fbd`Hb^_og$* z7okT=Djofr@?%-n`6Zqj=DvSGycFBtfm^qTD2pkjpMJgw6`67byeiu^kIo!(p3E}=D>I|+}BTB@ed0!S>Y(U$}%(n6;MaZvl;(Hq6lS`8X z2ri}D^O>LF}IA5Xzg^;vhT0rOvC1(r9)a8$FNe| zsV5H8@`{b6zfEc^Rn9+M`}g$JA&dD`#{E14j5gP>)3RV0m6OwUl@IypdLeq z#RitCwM67Q9zW?PQa{_6H>YY+5>Iw?gLc-8f5h`>i>E{5GovygJ9L>mKifu_IrS{M@Ra+6ilJ;)CQ*XhQThk~*vQeZ%F$AN zW6#IQjeQwQ-|t(%z$zcLX_&-79O8Vr0)|0%$4!PRI<`|K-tI*eNnYq_;vj)SnC|V~ z^404Fuvotp7~^hisQ)%!40e_JIHwy0p=qG6owRWG(kVMzq^H^kcu=g}54a#0KtcqR z&Al%9mT6LG0{nHE(!zFJI_%ArIBX66#s8xP58E?1{bp9>adI6Q%qI0Bh&`?;L*qs~?Jd$otPv;V*wr>RvK(l8NsDAIW1bSm*=({GRF0-LOsX}^I{q|pFtAl! zj!#@}Lc<{w0N;AaV97ZO9Bqb%a{nfZRzN=g^*bw3FOSYhsUTF>sry>9B+A>8YDp52vuUG1}baIf=x zc6aV|0fLPjwDDEL0@lY{dCgntl6={dQ@2Gd%7jh<(dDubwsLD0#=tL~hEu(Bq8a%c z2aCeZch&#~lm>QG>q`Gus08#~Qs{zTP_SOF)1gtxhJfi_OD;>HYyPix_)GWye(Am@ z4rL_N4C+1DxpQSg-NVvh9Orfne2ZkmP+wcoHo$%}xB_$zeEnjT<}XG#%~yf*OD#c7 zQv8P;nQekOYSgMXn3HDU3!x5G>^p~*9HC|^+ZRtg>!k^vArXcDQ1Q+j2#kg!Rv9T2lX_i+Lr<;RPiK$^&G)swr!9FI=dyFY%irW4gNHnFVo`uy+& zz%#T04)pm2@7tUTLXMsu6%}y~zn3F*%l*Fbfp9x0x1jUdx$>H?PhHcK*d)6J7%(aT zLe055&fq;g0=Y@tNu#In_`!)pzx&f#bckmfzwQ9iF6xf-XM9Zf)DO?g6Q+9a6YRJT z$kFw@zYO!djJUqm6f-S6GXa#%L6!zZSrpZHK6m6Et$F@JIWfktPA@W+FlykfSt*}| z10ig@sTLZ6Rf)rPuuX7x!V)AIxmnhF#qVZ(J>{4@@~`~pOJ z+4mCZ#R|@Ul#7uOE7T?168?OlRyh#UyBxi8c5_OtJ1l*6#8w}!$)J$*<{S^i6gL4` z-QrV^*~@Hpg=B!VjN5pzeM&d1e1s?4N{{?t5RZPU^32SX)bkc0nqHz1uOok1m<1`O`3VEHcBO#Lp>zV;cmIq4vQF~$_*rBMY9>Du9S1QhPUe8WW+s=kJ zi(s|PHDIjtar~R`L5ny%jkL}7Zq~3yhR3+1E3D%0&s+>6a+@tZLmkNSl}73Q1+=Nm z%(Ud&NEE*LNqtu00m)pVLE=F?%v%^ONTxlSdG^vYBQ1Kt{Z6gF%C`zLovg<+8qR@cQA*Pc>RRSxt(bLm zx&}~gVC<#NJ8dsajla`Wp?HMB4B@ZRxHYH+hq_SY@FR+GSDn}d`~rf#^wI&_g$Xk< zTRX#0CILIZ`a`yuNO%2bx)cWpQMc*0vpVnWkT{+dovhc|ZJCb`JPI=3Smi(F?J`*k z^Ig+ha+<_>Z|K^d>9$BHm2)bu$W#aPEikr!)GafNPK^R<-6Nq&Z&%8OLi-5iWl^}H>Wk{omT*t+)6kxX^SGrN~ zPBp;jfQMCMgl7h?*s<%=`&P=y(Jv+P*1TH4?PSY0t-+|7h`w1lw1=VqKMLXQxwm`I zJNSZZ-GUm-@^BZoE^*Ft_KcYJfQwQ5n;g?LnL}qKt9iepXRKj*rUVPz!r_zc;K@p^ z>{BqNKIe0S*;&yDg!}Ig;||e&V-xfL!CxU3=Pi(Cd?P-5clE-X4?s zc>FmKmG|<`V;bbZL#$raPPDsq?QANbaYpFCCC*JH3}?=m~z00ONtz%M-EATrU>{90Kp<}C3>~)PVC$x)e0@dE z?lOQ`V52X*tovTB+SJI(o7dj@i<5I)%!u6vM&lFOdM_U`5(>Fq^(kUV*23QRAY`Q9{-AwZWQ+R@#`&yROC zhML7Kmf17B!`4j&_v9M4#~vH9XGOW2i}NY$jKLygcGX5Sxb|_>cU2k-|R8B=zsy-(X!zhtglc zH?Pw%*A;sgRp-rBZ-U5yE zdFs{U7Mpf|X9_B!_Whf+{@IOl0(uWQ9cj#To7_y4_jhab1e{6He+fGSp(f(NQdu7O z66tTJ3sc?tu{Q1H@6=tD-;a_yJ^ka9WTK5qb=#b7AFGmbt^y9jaj_Es;l&!b?cVpW zqSMl4Mvk@kDKx6MhFI*{9(GVvlS?a#;qgwLZrIG`bFoz8xuA-vqxL9~jr>QIrPNgF zw|twPJNch|f7wvTj!husO*~Ei9`9Om2pWob7IsPu%guZ~%|9G4YBUa@_ch?4WOg@A>TdN5xV7Db#ln$Mn~3sJx1k zw54yng3Z>s;UEafD+s%brw$mG9ijU9!LN3SrLgVc{k$TQ6vMUV>^}>5YZ1R;JoAR5 z0?-@Tjr`|hWTDa>*}cTG7;0X~-<9aEb;Wxt>Fj&$6=&@&h^S%^!^teArf*cG+h4f_ znPS7(&JJ;r2fIg}r!cFv_7TjX5pW2L)xr8T2Y>4QB^AeuRgjUuL?5m_YIbL*6n**M zW0TaQh5W!fYx~un45OEJOFKM8=`{#X+Ya&#{_V(qZ2o2c=bWJ0@8>s5 zLw-YfkAe8Lu7zOrkcVYrxQHpa zkyh3tWkd>)%^5g?oZjx~^ZV|T=4|}~CK1?B%Z(qg6YmU_Be$Dkpp4V<>Emz4OkV(Q z72_+}Ezy>s7NH#s{4RNEO`qgG`Tk21PJkABWA8pLpS5a~CR>Yor0HaEHQZXgR@mJblWoI|%*#8FJ(941B)*-#oae5%^0`;N!r+8S;VYZ|C%x zcPXufM4|6QV7wtryh6p$JboS&+k4~|P#kubAldAf%21dm(l{a7>V!3# z7sxje@e7u>EPhq&Jucenbv2SFayRxI96blV&w;|$NSjz)>p6i7@7dFc2;b;)*Z4?Y zVExGRO9RgV-$?rtk#o~<`xEck1RF2lfmY$pKH2{|+-FF%RX=a!eWAwgWa1YQpEi}< z$+cXi-N}4~=Z*%s4}bJE*>(N=Azkvy!Uul`9YYH?y> z+zF>ML|6O!H2B;Jw>Q0_$|qbEF2<%b1?s8yR}+1g#lN>C9@=zibVomCES={FINZ8> zM}!(G2rUOYWJyX?vlCzLs0~EqP)e z0GScJPsq-%{HE~jXK+%$r$TTrTjLT>3gb7vzPyjXymhJy4~Xt~-{nz}n-hFoV=geY zFm{-qt0V8Hi+hsr$5>$eTw#pf!4`@$l34D!>~jU~LB?v0$HwI1#wjxe@y|CbN?(I& zZ)rr86WM92I^GNpYE+rQNmAZsvzg)yv&9^rPTEvQ>fv5b6`$-g7bF+Bh94wMsh=~y z^(lp<)re(bCTPVP3o~y}_7yQQ zYN2M|tuAOXUv+9}Sci)xka>|nDbDxzzdfMQ1V1%~D5&ap<+ZY`f8OA%H)TECp+uwM zmv2^*=!#@xU1Uy`ST`_6Dp;@WIUZ0%Q!|lqeAP7-#*=osic!K1$?wEA` zJqKEzLGlVLR)XCy1@1D|$~(tLHy>1uL6D3y9v6m@yvomJyZgc(*RIY-XL$n7mrx1C z_CZ30pg;+&S7aVhZ$NO2r(~_B>G(01i1^)ai1^ca=$U<6#oFXs-y36sUx9bmPG(#J zhsN{wlZz8)%(JYe4>0Nu2N8%(E%WKfwio0`nrmt;T^J zV7%Zmt&CHskt^)-&gG9@jTQ8Cz2V*Rq?XREJs`RzudsW0QY`zE8wYUaI>q?qAFGmI ziB#WQc2@nA%(>U91D7WkMLAd+*i}@kz&T?cWfR~vkjIhdA5)h7_sUfwMs-W4b01Ib zbrZd!7A6;AC&dnryAhZwNfL*PEukZn@eRU8t@YG9A6yh%5*qV5<&6DlYDV%P{!0yc zl}C$T0(6{BX4Jm96gGl-9~w197Ax6+d+$Hyvl5Xq?6%JeyR3udpo4O zLf(IL&iv-=HePZ0>k|;~*o>b%=<;8@ z6Qg=pfsYceXBvXEI{j4eXUO08$q}irLXv{>Shv%x@(z5>s^VRe2pxz!X^+PxEt7^@vn2yS63pL@NS~;ajDY?2bwY22S?1Hp19+X^8nHv6QBk)d}BO^0B zIKC5{wHq8dEGLqo>mVMGMn9?mES@xpls{(a4yrFg<0T#d);A$9Cv9Onh9fiO_nzdG zmmRpAsa*$DT3UVS%MCwy#4Lil_-?J)U6;`_lhXSlU1?81cVlf3!%>COC5&F1&&`B${+7t)zB4|x`-H10Q8#AN46dh z`-ig&jLI^A_O8nap@}`5IE#*lBOvH$`(n^-4R(E@aK2~91OYvECj!8iaVD?`kQ*p( z)@<(Zv${fS5aM!AN6@FF=mvgyOD+QQs$%A+t#iF9sH&{$l+>al-gnz*uuM{lT@(vT zJbLu6Wct)^Wed=)e8TxjlA&no#Lg)y z6Pk3vJfcPpU_F;DH{tNMAJiqN#A}AOvqCrQ)E+d_ddfeXonC+_5-@_o$IX>}nEhaU zT>4wo1Z&}FX|o>z>=IsZIjPDE*T>&{sXTgXP*oiwY>IJ^Q?ueffrpucyd5l6aXa^O z>VYbUxgYRs9$J4YmsX_*!H1Drlih6uq(+P&Z8hS^cJn?a*vvDSs-Q~Z;?TQxZOe-j zWvZJSH=2mKfT&ogLh_~mS*jF9U3K@TaDT_qZ}$f678HNqHfV1h1;RP1Cr4CGt|nx#PIa0Ui^NM zW`L^TfX|9xM4_;4eBwY;jMs=dg`0E>Gkf?^zSQ1EU^n60mz7|1gPPKS56?_|o+zwy zkmzq;l{>k!EiTMQ3qJ`PqQD=o*GvzCCQkn&6wmynL13RbYkl&_8j0${M;`ZEgMfjqKlfXP&FlNRks2%`hCz<~Axtf( zoXl_|U$Nt%H}l?zY6k`?$)oq(g70vt^v*x?FK^Fo&`GI-%Sm4KaP3AvFi_DJ1{BtI zms>rr-n>OA>+>(B@iL={B%6*n$pP#4{iTLLg>4`A$CbYQmUVp6WxS>*YOw&D-Jc^ zWINou%hDjZF#~h1$3eBoMA27~h#h$2=(h|SNVA(oo)C#@AC03|M|{* zv?F5!Ou6~R;;HUk4Pd&twFFMI@xDPgs*TF)N!-pkWOJz)#TqcN{0F=r;Lof zG4b~@mp5PIkm70pqxO3R4+F4KO~NPnRnb(zpV`BWT)CwqmA~eSxV&6SGnnLl79oJUPjvkq! zQu9A4v@9igSkGW?D|hrv*fj|zF?)M@Zv=v`ld-hE9$omLfG)PY5L+e`GQ3VQwQf5g zB37J^pmWEc1QYw+m>&*&{4O`c!`!g;7hT;(35sTzZ^zq3?eaC;Gdd-Pa+5=j(izZ8kut}h`Hu4ak>6> zMx#NGr0$Kq_1G^p#aGE+d_rSs9};3Vf9Z$kGFi){5RAOuvC4hff{h)G^$WhjT$6`) z7|?-RsgJKK{9R~HYUAVsgL*n2=PU7E!Tn4sZ?Qbe(rY^Je{!5x7Kv|vyK{d3DE5-t zm+I>r!6A)%1-!nw8|@`^?;`yQP>YqwUnT`Lf}ja+sCf{7z2qEJ z9Ks?nL3rxIYaeuPd^7WsXP`7QvRO%z42BJ=e)H{Si>_0v>Z&ANUb0%Zo4kWeR|>Auo%)kJIpBR{vO>Hp?k$PdHjP5U!J zxzHxj}KF8o;8ylwy z!+`60)w};ZX0UjRLCkOGifPIPd?%+g%a^732ZvuYQ93_bX;AKtikq*B?^iLixZo20B{(M4d4 zUc87Iqm8FkRJgUp)ZXg_#$qD@y}{~!Y>WLAsw%cVn8eLa+k#3&ChsVWh7l3zQU2NnX!jj(do`{>MIO9^h%u zljbh?F`hQW$P#UUaJ^}%Pbb0ed+@XzPHkz-snnAX;VO4{ov;U)2gxD@-eYyx52?1HOw z41MxkU*2f;U0`ZDQn9jj{eDG-MG}T4`9@Xh&wISW;m?EGs)DEggQl;JYUBCdE>0nM zfB?ZAf&_Od?h>FtLkq#(rBGTRB|vZwTA(c2R8;TN9_DEA(4J{v6HI<^-DJf5%BRk3QyFYMAzhR^m=*J^F zV!ik9>%=YkNP=1E-^=7Ok~f_3Xsp?C9&DWQ;XXKc0LMN<++WuApmmx+hIUUSfhDUUEbS!wZ5S#^ zjU{YxpzI3lKj2Y6?rQ}Ykpj>V&tOIJ0F;I2t2$1(%p2qDRK#M$pzd2 zKbi|FEXP1Y^LAp&5ZW`Xq#*0qy_m1I-6^63FS(DjAjCB4RD!NDHvzI?|>PvF6AA>9tSexjpjC3C@~<;RZUPx^mFT*HjR#d!an7t%N9C+xPo`tf(;beO6z`wbIdI zoiuL8(tDy1M-)N+?Y$tc6o{5aNem;CB-;=)g=SHR53dnyjMx0&T3rJ0R7XXi*c=PV z1=-7vMQz>gJ*YpbBr^8+2ACVx2F)aDc`+uKlQKbWi7b{CPO&z-l1^xy+AVet} z<_Qnf?!P29cAx;94d)0BHxmPxav^6#cCrzuYbQS&7hA%^kU)CE>TJK*xAvM2YFC`G6zY#CYH7Jz z&ODhxxdfJ!TXdHdSFB}_2cr+OJ3>*1*>6J8O!TUAI2EkT>^!{n%`DERwb67QP9cFQ z?*Vd4>ak!ybyHMuJhN03$)~Q{Z%^V;l>{^xHj{OfIBOS|<0r zmVJG4YUz6fg)oL&6dhX1JLO_t!kz45R?=T%+(IlZQ?N@=?ZLwW6ZEL%GQ^hMNAqA} zEa0ySkp&rz*3!)x#@5o3DWrg~G$u>h0pN_F@)BT%pLYp3Q-h0TDKxuG5H2)gs%I%Q zIjqAUX%b1x6oLQ2WU^CW(lXf)7)+*Uh{Vl9pyyAGhf+b6n+Mv*a=T;4q zd2I?hOqo*%M>yv7so>!T{LUq+u-r-iRbiVXddm4mQ6zdgkXnS(uB6&SEuLf=2M@Y1 zn?HxPF}9oBR11Shzs7zG$(ZfnNujHW3vTAoGR19Y7AnqIlovVI z@jOklt=G?xZp=tAkcPa17{J;!Sk__fJespOcq{J=4lc!GGLPO@)D)%P2h0diE&yiu ze#`@BEaUzH-{4P_35Fb9C5o_xKW~6Um^Pz{6^AV+JYb|wK#^cJP_rUE$o4E%VPIH+q|5) zUs%2%7c5gUtsyN_;-i7@)d$}zPC*McK`f({J@KEk&eYH$v9U#Lg(Ajy`4tOBzxtK1 zZKkB4hmK`&S*%tJot=|53CeSV$1%+jL@o$wB5Ar;bEM1$CdgE7)uH=eL-XQt{O3|| z6N&geW|k&?bc~|r4=ZM$w8H_o+}7GQ>vl6bLUC{su?v_SxGZUdfU>~MbUN>gW6F!i zn;`*wAmy!9$1gNlYpWIG`3&tmg0r{*t}*bMV@P|Jll}i}GC2$^)g(6mZ6C6+p>hy% zokHIah~JQ-d0B0LUi_IRy?bsIoX40PqNsu8;WNz`0LlMFI4*}r_SZPmL-a5_oTiQg z6!Pk|PTFURuhBZS;7qiSf+isYyx7kbBIbA4n>@5pZ7jmn6A(u{SHOvLl)81BEl1D^ z=v6`(Ok=h&^ou4bB)S*RXkaQEIr3N@TGI@d)@!p2$+$_xHR|

PL)P?kg?Db859Q3dKR+I9VH>Mh;MJp>wRx5LS4(lG;gjzc=LQAeNwE zdbVX?d3PG@-Kg9RpmHV4KOzXv38G+Z@qY{oNfrl86R}LXW@zUZBsWHS(AH%oTND`P zLq&c_A8YXSeoW*!w*Hj}*O>Zl1=&dzSM;}1-@Y?Mebu0UTzG73F}YX9F@jwdGh5oH z9AVS^HGctGmA`vXYWr%fz0~{6wJwtj#=RaL(UT=Jx^@T8abh8In|~-uID-whfY=;c zk`fL#C_H?6{SkDmyH|0k#;qR_Eo^3$=yUc)?q0VS58w2;4sr6kImL0Qhby(Ch$pi5 zax27N>L@d>fH~B`7+c(}Z>qX)o0@pRDUc+;PW3tj2j~SX+ zv`$7Rp@U;#-$V_QEsJy}`PR>o+D{FY*4d<#7*T^j=S~okCZbCvJ%8v=MJnyjAU%NrLyeW z%gTyMOv%&8NzJPA4-;8NtpN`-t^``^2VlgR)@v#|{?(@yaIg)jE9=}gH_3q={=qLDxBy&S9Gu>^Q$yO3f>Z!frKFEqzomNOfP+43$gN!Z3jW(HHc_pKClkp zKr_nCPN&=-Uf0X@#BGrH7`D+IpY&YGlBq(n&!b|#axwR7tixe1@UFSPdcyN8ihKT2 zJ17L##B3V!J*qRKaQ#Ro<3ZgL<%z@QkoIePk?l61)LSwnIF+Pzs^yle%8fv0qPVl4 znZX3rv+8rs4=jPN^bvAe6-k^IhdQz37Cm8rg~PtSJ&y;b+E}RzeeIlT)>Gx((B9@V zO*+MQw_0==@{ZXmq|7CciNUtsukGc9{mB!=eht1qWw|vfJxai5SyPsxPm?_TX^(-pfXY2 zM~3!6_;b6ffAyN#UFGEl?TU@AN)>Cn#5R28ByQq9xBO!3>Us%olO&HhSW`r+nB&XY zy9XmS!+ouOMA=7v-i;vSp6Jotf*fkf0AFDEmr6tSD_@N0*v-vE-^&gD^ z48+qP<=6UoKYhc#hM4&ADcRk?#*lscqa@RiqY7;&|7g`79LV>d@3vwV8RtXx%Vj7e zXmv|B6&#QlmU1(H@ny`r`fo&3m5gwb^i|hj_s;v$x!=A&H<}2`4H8%qM>xhb)EB+d z5xw)Iw!WPNHr{NGJ#VQb<&5lD36Mh+W>ud@-!=zcVwYwvsM#)`KMng!6*`0MpIkLv zv5eAcIhp!<`uorKn?K)^OWr-peg>Q+V_J4AmGl)mS-PJzv@R zBBsyz&!xP~otDJz-4##R1Y7J9WfEC*n9ui$tp?`6tZ!TRzq8THN1uKOo7iUkofnVx zl(l9O*0Qy>aeKHUg*mj|$~Vla_W}@YI>Yr&+Fz?IrJ~x0m20o4>pks6*2!L%AYaNg zj(iB1w8|2rDIe1yTT40k^|8xB(eY90PINaRm7b@t+E%Vq0PG}1tY}3l$`GjQ+&Wm= zUjD@p-g=~&J-Cxl9sk`xdgv-R!SX}zuXULgDXT4;xxznn0Z;61zxUzz-f(14f4`kh zFNr?g4hmkpF@mW*;HdvnFK`MI1iH%^Xoz=3Jk=v?9#ecw``S8T4v&oEtg>#%e*U2( zzPZs^fkFto`BzG@NoI{m(^Fi^L67Y1JS?=9tOSnk9p;LrwRQZLQOu>vbaXl~bUGkc zF$vFZbU=yxd&p{-?dexRcIq`A!&TpOn;w5;dEzTKo% z?c*rXl}HAQcV6xN3|s2Ax1t$mCCycc3_ztmJLCu>a%*4YJmeF+hP+>GYmcGEVCea& zk_$vurn#{Tjs7o3zWa|#WjI~ym~h2zS0W^R;f5d+$zjXz*Q3VkIgi@wa;|{3&k{P= z6`mEpJNz0g#bLU|BDMyp6w6eT)_)apq{wHQr`e8OQH>{7g>;w|X)1l+mCnc`tU1J# z{dzisKu|V}I}L?|Zc7GsZbro!imav@Vt4owk`@oR0$bB!b9yFkz?O$z%`pAqH@lJ+ z$J^xkE@ZP{n9J}UkfCPEGDF2pfoQpi0Ycz3s5nNSp?`R!SfQVnBkU%`?FO4Rj}s8U z2vh@_g$44c12&_6hrpqjZSzAlf#o9`FxiO6M&?coNRq{lI&tY3JVwwmS+b{4HrNj= z9c;(1K!X?ebp>I@#o}YvwJo&4sEW4u7bYcBW@g+MmIa=Ko|c{{;Yw2$M}R=$Y@RZ% z`A5F1uzt;XpRhnZ>p2Vhz6)gjH0P^S!pKAr@TDKib5G4BYX}KHHgPa#bvZ7vuI&42_;=RHCQPI;ZYk684H!$v`K(V0UkQX=If{4iAy2ywh(RG55oLCV? zQ72^|2c3OKeC4D-uy)E_;SWX0yOBzQn0`#rW)eSR0LzHmL8Mg~ zV)$SiQ@=Y3a(k=}`w4W%vp{|-tLlH;_Zw(EyayO}a9b*^Sl4L(I6&&3qqzNoUE1nz z?Mg|U?_2||5woE&In0en(i&i3r~7~kIYGT~Vk%b7Y8{#*V!iWpASVXAD?RPW}mwk^kFDmvO*DbJxRA5{?ujw@PKGqFa2k~>( zvsw*N8)j2ct;I0*@8cYsKjhxgL3f4 zy&8)4)=xDv5w)!G6Bty0#;JI!Yzw5joh{K;d8(3J{2rU!2*>*Efj()-!?E zXcAkEzGK~Ge+x>5M9XLSvQ2_!DGe9f52S>f0wO)>C?Yc%+2B;UHk13rV}@heErdon zNJ}7_(Q6tvgXcl3L19Fu`(IVRRDStt{>VDgJQ3mSN<0aP)+BK|_>wSuB|8~#+q&Ps z>^!=z$wHADPxpQ?kg9bNfsCyvMN^vsaqrnjL%t$;_Sw!VkirwL#wV#-w4qj6HUsTt ze-Wx5kN4-%$L*ts}u3(YX5H3;_t|5o2_vnG3GIzoleT*~?R+By)7 zAD+HbXSOM2+7Gr2KSoA%^{R3nv}$~$2m)mYOF{A(JiW^4UqoPXhHp zD-9~uP##uX>2Af>kv9*A!Fu~nT+Z>OkU_cwt+$uQqtD3c^F$*J%<}?|equ{t>YL`P zEDExrQ;inPxyXe@3~dL!;%DIE&G~|#DIC?>^a^36GG%w=>E~6fP_qq7L zdK_M5z~tISoLGAGgCEFxUbbN-pQYjtse#d6>Q!Zz2J!@!z3*zDqSH)eCP7O-H0pzr zQO+07l?HjF>hj_pCgpOtar+_1*TNP#%9*XW;*<+o0b-~v2G1qeo5zjY`2(g)*h*E z#FYAqD<_=IG2REKMnpDs^y-6?ea?8SM_vx&xMLQUc2H-z0Hk!`-8r%qcl|ck46iSi z8jjPNA6H~DPw5JVnDwAxkXJ(o?zUV-Xay|K+K}W3ou%6%08*Kj!XTOD^4=Zi(sU)O zIgHW+JauevnJdfnLgN9*74Bv)#0aD$<_-nn&@(q%_jkAcfV7o7VI*Oow8cm1ABUHy#U=G>&Jj4y+^;$A9k`8q1nh2VnNcaTKhPyTwWKGT7qeDne}l zo7PkoVii=_TI}+5-|~I%NVd_z9vw|X4D=BVRVdoY1tjVS(nSey__L@qZVX6D$>`|L zZ4auDXq8G?k7M?nNQ+#)!t=u2B1pYoOGZeVP0S}x&G^{Ax89igR_tN748E{ULAo}_ zhCfXUd*N= zg{G-1H35pQE);@wK4V~N%tJ?N%@Fd)Ls~1LMCkx@z1{4N%#ugZaIBDD_tJ=x9NJlg0wyEXd*x=C8!zP;Yh-X%60-oxG1ootOE#zMg#Tnzd!c4 zDX@(8C?5hx2I!`W<3M%v7#J<@nd0}#Lg=(`VmTD8NCIUYld9nopiw|QzFO~d8d;p+ zP{2x0q$prvMpMOf{ukdBtdZ3T}#@z+OBH(X_Dsbwzb;J~4 zb!P$6NKaN%vSDIb>e;I1c44rj(pYhnf(hyL5z~;g%&VcxY7a;L`RSH~i>K_t=T2$m zu4$^qfi4P^rm%p@-QX8xEO6s*>9B4LpMkw{dAF7CrLOEg3Cl0$L1an>08ejW> zD)|o<3wkQum84jZf)Di>P%YcAz z%G|{tA4EcKdRESOwZgNXJe#*?JH!%^l+6t`mwG$mG`NDm9C^j&fX9`zcfuSuW+!`q z26x>HmiLw=K5=AoE_w89KL8E8`2i%{5G0e3lWUrQunr=vMyLys#vI5X8Ifrj#BrA%^p z<%BDO9!*v)6N~aG(5`4puq&uWxu3TMX*@SvYJS|OB0N3*TMdhq1)f=O=Hyd&crcdpT@3mjS z|2^ldt^(^)+}wT+N7^d6SKNi47*pgVEIrqxg4{YQ881}^yr_E@9Y^w4P?t_=SycZ- zOSnHp;9iG;X3wf3>7ODT%(o1_JV?H6PZ9Ter77$lo4hc&j7p=GV9TePOL_Mb{Y6&7 z5F-tqRm%WM6M|V^Ob7eJ(sI9olOcdde4DCx9?D0)aZr+Jzn z$ijsavR;iMLr`ik72FG}Q- z-zl-NU84~Z(UQhct>d}t-rG;@V9Mm7)~9kPSDz8d+Tg|F*$7-7%e|yGR}hV}*iV&Q zb+8{KM5xKqF6UPq>g$TykBnm{k-1Po`4ckbKjtBwvHmNIjl}XM%pfy4;tdFgoSXSn z*~Ve}YGBcWZ-L&_z?YuFy@P3Gg&m7rI&YAl{eo0|_DkrgTu!pgsSxH~pp^S>#tAlC za|(5xOsESN-YJrg8 zb#Bw*WD*62DXfvRt=?yKCkn_U%_jEybvbWRm-t!^zc`=oTC(n1tng*6O&)`#W$A|= zY0|UkLYF)4AR>ZQ4{OCI>!Fzsy%=Pxy^3981OHxP8HsA&FD&&>dn_%vE)}?wZ zJjYwor>t5WonH6L_yuW9phrrc!Ra#+;d6wzrJckUO&yF(u>Qe3TMACe<#+K@FBFi? zim1Ii?_^>o@1~;qv9wEdke8I#H7GMHr5_`(?3O`s6jCm6$aRtdRYyDa)%cUay#s%8!Bi0Dum2-wC;%){`!+qjxH@_4cgcC-4P#eBKlFqS8vuajKpI z>+j!uN_qcLQ;O*4g;Cj0M2Fr~@ccapQ|*`Mv?!|l529O?>tV-jevQz`8ry(xIY#(S zyNZw!WexgtwEToyet&3A_l)rakDOikAlIW;jW%wQ+$_eA&cxVz{A{Sa_7Pf>{9SV9 z(2vW9XhtOC{V2(T&&y7EtTQJqP}Z)rr)_=jvD{33;6{B?UiYXU@Ft{Tenpq@qmP?y=a&VS9g*b)LTSgP_|`x$tp9&b6+mt6?*4KlkF}lW43F8135?E{1PpWs;?_SeaJLqIKoH6c|L&fi{QcZ`I_-6nzJ`VqIK&GO zXyEnVciV)n!$EjM5D|m)ewY=GXEYEZALKc0^I5KeOtcr28Dua^rJucsBnXt`v4bh) zcA!L;8cXB9^eoFShy9@KkgHKgrilt5oti`UmFgG;RLbz@#4k}9=P&lY3BU)d*A$!U z18Xw14G#4Yr|NwWLxqqHDCjmZQ4?%s6C_Q}x>h9UmqygN@oSbnf*AIMU6Q(uC;fJ0 zW`!8a9TNXrM)M=u{)GY~**BTg#YoRAYut~>lCy?Wx=RarWGUZrr-~m^venI9kXAGF zAZ5sd|4u3uu*Tl#LOwNXl=1hWM)sd0qqw23sF}@TyI0yGYtoiLy^9cb{lH{Z;g$B! z_pEv}NPWHxmhFd#H_op&w|nQA-fsit1YKNG8JAGT=zo>IefGHku23nBIB~m(G2dHn z=k=2!b+>%VK)VGuYo0x<7rIXEDUOUM$M2oPP`3DMtXocyOn*}?8nc15%F7+Jep_-b z5sqeHXDZ%$Zt}!y33M{n@}DF!K|CnfGsAOu9k`k!%|^CD${78FoX5Mw%o1=cZgMD8 znjEIh;tQY>A9J=skm#^&}F zdy=6PzOItNsXdB9wT7mFwV>!)!i2)9MQCl$>?V-W;of|6?J6pRXom3=goAtgQM1-2 ztCF48$ulBF45d$m>xIP3-D^1t?k7_SkXEr+u^6!pu+&fI9v#-MrU|yzYTPXc)%JL? zBMT{UGZwLd!V?wM0*?XpbDty+YsJGmFcpN?kHYpGJ-SlB^;3WGM!8$Ov3@foG7Via zso<4Wm&Hz0=)Ewb*%C-&W~}iymcJT4m!>(BdvaK-@fRg1kYUJYWZYBFjx@YJsm6e$ zX>Bcso>30BkQaDwKruarpTLaTIuk)!DdS(k@;N<2cwds2@V?woO;JI^QB{>zM}BF- z2){rmcI0(|D+k~F;cCKw9@kIV-ziS zA=^m?`+3YTD}cIt0XM2%_of%U32{cTI$u78l3;&E-PmHSoUq^q+oJh^_LuR^d}H^a z0EN~Bk!luYRL*t_davKMaz0>_;Ky4=Gd+!;ndQ6?F#$z2kb}ra$uZ*AE)_=4`g!HC zkUF^$@FGWBCnLb&h^}Q#X_$DYd?>g^c-c>8(+QnR2%I8>9;r)0Xeqbu-*}&Hen+5_ zRE6zG6Y#{L3l!j3j&hO?LYsF>!V*N1onHv$NrK}@6%(9`BUfC31_7(GjB!r1q}+&%}f zNoh6TpnXop;)*<$K3@n_81)EwY>@FsfWTQ#n%|{(K3o>zYF2b*ca=8uGtfi- z(n7Jf@qsp{HC#7!{!ya90fWU@Qa=H){q%2Qfn4chujySyE5#pv>J_Feuzi=A%gIo4 zs$X^@HRLuitU$Sr6w9EU=lZ!)L$&?&ry`E8f3=yJWh+v)j>>Rlh`lx(6EiN5+LdJH z|JlT)vL11FJ7Q>4!OzL)>-iQfTlYucm!oUVN3x-Y{%UDb7ZGKlGt(|&;wHnEo3m_0 zat!VnhwJyt4IB+(NmRY|bh(50Wi)=u@|#2Nff<37YKZW#tX4r3DYfEo7wJH@}R%>?p&{DLgkweF{g0HQ8&q zT|H=;>`8W`G`DcDxH{^sMM0NpBApnqD7A_OelI|>QN79TpoZEzI%-|%l!+F)c#rs^ z?dT-ck@}n>LFRX*6WyGRXw952Yf zR^xco%TEfab;Z?+*(9t<0O;!jJtUNlEZ-7j>>iqF)uyP8M6J z2RE)hOJq_uHqH^hZny6UVC=+zb&(kjB$c%D--5JCcA}^@yHJMiDNi2#5LQ&=&n{9F z_d8_OfN_v`Tu0CG0lH6A3vENXTqWdC^a3bs;*7w3mik5$6OrGg1{j)^Uf-7Af!=S3 zp<)nc9v@3uT_y8Xf@jHTRnAvdUkXQeXRGbBFz!jz!}be7*)M_BV_#}vI$P5Bokx_& zRPy3)W?Ewt^Gf`nE3xb83C~pcU#<2#)9Vgln*^dn9$F6$au?mP?~6Q)+L63U+hq$$ zjPB(F+@3uUL5Pobs4={3YnC~pL?q8R#c*Q-2AqpoM?;w9=!08YC}<#rJujctTXb?# zJ2wPiw@1!4_?`CM+WX$Uv5(>#cj+08ZW`$1oOOE3{+`O`gC7Xya8AQC=uedypp%9j z^viKx8J1G`85OAy~G3>aGjrmpQTX_1KArnguXwPEV(b>$mH7P>WY4E z+v1YR*L*?=Gi!+~)1UMbLX1ec-2I#tO52F^^ULHyP;{;)xCB9jBZhl#EF?eby*>Oc z`g0&dp?Rn>MXxvf#oyU4uT<22T`0d&`;Yv;Kj-@^>FN>R&&-~;5ZQtMtKMqZ0{*$- z=f;OcT+-%gU9Id{}uovFJN6=Cr?i zRn&I&>EJA1{X^e7)joyt4`!u!?xpvCv8Mkv_q3mUhzyI2%9Dr=jlRZSugy?Rq}X>*pmZh_ZafZittzL37^QaDsfu_*r10uL$9A4zWA&K zXeTCDke^DA`S06@=&w5o|6{^*eX}6(>e=s|y(i~>b5BYgiu>OwD*rAS_WAH>Ea=wb z_76qP)0>0KU%##&)~vYuUzC=psz*l$_Vz|cM?bys2@idGrJQ6S^6&ch8ne6LoP_BI zTh7p+=$ot4-z*5hgG3cx&hd#||>|N6^pE?F98dr}F7rfA{y1x6fO$5hl$c zRZ>U;`UUr~_BG8N`~LmA^sQg}Tk3H-zqY^A=lyF~Os3>}PxJiW&wX{Zh%ebsc-Qbc z2l`a-(c`SM()7B3kRc(b{Ay(-JCX0Sq}LP28-p@$f2&d4O4YLtE1*Fu^H~ZhOK=L| z#xGwJR=Uprw+v6=|Er|JwdwVA)~Qg?q`Ez?ae;4E^$%K7=A7azsk|fD7AhT*^i>9R zyF($vrZA(0j^vTDei;BtP4AuURaFiwQ0;jzKScg+)V);+y8HzQ zyUOjl7`|0_XpK7EI5nuruAkjEctZJC@RXpA>&48U)wP6bibs3l)m{}(Yx^4tYr{|E z+6?Xm^0o(`}D8ufv4J^u_v^+c%-S6_r?oa9ed6q+RhBkc4L_9O|WuQj^bLFC?K*7Ph2_Fc_d z3pJ_eLwoOY_T<%$NjT5FS7!pw4_u7y-F*mAbZ8QveRVM_@#>Y?LrBe_tVIu3M%VST zmF~~<1}bmv@{#cd0H{Ia>29Kh>6tf2?)ZVB)gz+(;O48x3JGiShpEISNEX?vhN?-~FySO|V}AJ5HP2v-H^VRc7GI;`)BfV=;g7#$;WWY_9f8q7k_&}r zQ?T#37^%_f3pj2X78D(Wn;*Sq7x`spoa^RW@Fwls68sf!O4DH^Bo{1GP2NEP_jFoh ze(5_U6RcWkSjrA_c_f_nIONIKPBE>S>v55~m&SB~o{Etc(VAPGAcYm8#!4e8oduok zW1X98^ajr^JiRT8ei9hV3=h`?lrzEky#gUUthb6Mxpj4%J)e_6sxuua!>gW6S`G&1 zCA(F|h^Bp&6ufk=iYYy8|q$U4u^j$&h?3^&O|Y6hRZ~&-gPb!uMoB603Fv~;wK%b zuKk5)C0)-fxm2!+)$_q`PLL~H=&QD8#JKFuuPuw?||1wADAiO#P{kA!Mw!OI~ zKF104NLWe+oBfQ401%Z2XXg2I{k6_7``L#$%Xgj>HNS1NW?DnU(Dir3TWQ?+HHAYH z{pps{Gfn>%BA?VH$i`DX3#Pn!ba}FM*mD^d`=!c)B6VgP=j+++hbs3kwf=OJejCE< za+g&moqF~!{!*{MfO~_q%H@yg&aiRKJne@*34OI6MVq_%S-A9+jlA>vxF%}@|02rLC;dKaP8rJ(O*HOS>aaIXA@NnU)llFIfQG1maivw^ zCKcLnr?N%Vxc}Ak+k>rvwt|}dNTu9ApM*;fqUv{4_DVYk^PJoigTpD@f2IY3dK>Ye z{o;Nh4_m*cgTZRa&{}_w4?Z5kzM-!U@4i%7eG)D_Q9hDuJ6F22xfSm3ax_>d**$SK zWg9lYXP39_KN8G4-xMxB-QbX4JYVO3czeGS>S8cmf)8v%u(ZjT&-<)wWqerkO;RlL zq9Uh)`v69Amq3Yw-PvtP{WZyF0B8JK$Cx3{C2;neiDmqkM``#A+2=mIwd)u5HW(<` z?dk7}ls22W4iQ=Ff~gG4_h5gzG$jC0g2Ac{hMzBhWZapOHzfMzMt(@vVF2Gu3pP9vAau})Xe#s22X z`PpX33XWZHyxlMb6soL#Wcc4XV6wUI6nYxb|2FV>;PcVk_B9qO)4~$XSdy2X0ZDXY zXzt`331#HuTC22B3eI($@JwYUGpO(!U?{FhNCeb9k_w5%mVn-kpR`Cf7K4?CEtAjI zYxEy+y2$U>mRLnUoJe-yAb-@q?|sm?8f}}VWMDz2BDleA=3B|yDEr4O)c2^KoAc;f z*Xm!>4#to9vx!g(`{ErPakj2)#;B&`okT6hY2s%+?94K1FFvX0vY~vs zn5<bvQb-hfgg@8FVW#iRZIc?HyA4?;W0e*&({a;~Rz6UNd zl3D}O^@>Ad@_1AZW7Jms3W$EgZ(T``g+`sz{;vQ9r4}k8#;<+d64k7Yig+SLaB?KZ zYgAyz$z%)>%8J2{0%Xbljs-Eh`!WT(%VB{l2Z+GQAz-p4s;@Sp#H3=9C7b-C@KkXc zSxDRDCCwC)c;cyFxbQK#UM*|59yO<6Q^7;j>nTwtX+*R$H9k`-i{a)mV*I{p#kqF{ zW!^nD0-ILq)AsP{$ozroTJy|`76BZ%AskV!Jn3d z1x!~0F{@9KVu|gRn<2DB@Kv{Pk5XzBJ|`-OnD{1OqO=?|G>rF|;k~Ocx%-p_t$tT* z4cAwx=8H?*v$+SmE{YU{x5@arz2;TF@MDAf5E2~`h!l2YTmoxJJ6dR$7sr#US>Rj| zC4x`gdc9#wF%+PLZBY%85yt0pkbUVPkZjZf$5M~qp}{%mKD3P6N-yKMb0;f?mj zYFCIn3fPjtVP%sS2XFAZQOZpPlf=G~_zrxT#0(+X@v)=$Zk6Gkb|1ww2BST`2S${w zI{^@770xhiz@KHv%CLU$SfDBZ==8zW7}X$LIjx#~m?1^dWx@>w>ITDUoc&dT{Sa6E z?mZlNzRchitqa3|BLNh1;M@C5+U&O))Nh204lt3Bt}9ryKXE0`T$niV@3Sanr;Hr` zSw!QVg^u!ll)%~Nm*UsiQkqmVtO2j692$de_R&dI>O&Rw_f5UuMoF%JRGjiqmb-`L z@D2R9%4&)}P_O6k8THX5JTt=Ur`#LI{bT5#!C|Ha!ZmcbXPJ5#Ne>PB;_H$|Eu%Zj zorp@QA5&2j$zNP%8x8vcvH(GpuquE8p4?Q%XCN`lVC`YhVI#(tas+Y;RE)iGp4_uC zHZ3UclIFOMOgZLrw~i;j*%f(d^;=9k6D?wSCM$b2ky@vKK(b`3`(Z~4xf;^k6f}FD z*Bet&?#NsXdnlBS984bap-NzroQU_WpDH+kQm}`*xG5{MHlfm+J}#&>p3k+7&m2+P zwqC)JQwh5@khIVD^S!POe2vn5zDF^iX!(zp2sg}hT{c<<3zU01q)_YrZ7=nL!G*si z?P)LeySW%o_ygiDe=u3ccjWVG)(v;!$B6uvvQ7|($cueQ(xitXb$vff^bqoqCe=~; zNoX5w*DAYL_x^o~=O=9rG?V>!nlBfbPBWj!OnEKGADJqqmw-gIb8g_A=tYNVB~PDM znmN;trUTbD!8{KwuLgl0QRT$ZF;?EID-P5dpWSeI+jJe`vlV{q~K)q3at zmT;SrAPbg_KZza&l?XZOSDT@@L;J)xQcSGg?o0g4(kFkI610Ma87)RQdWOp;u(Zk! zjnJ^T@a9A}jA(7wPd3*0`vDgjy=f7}{-S#gqMxFDNjkW-Qdgg2TWm~z1{%*{ym)wc&z6jbIFZu{s zdf+1~iEecuSSjtskc-NXlkz^SP2`aq$sM*8iC;Z^;?e~#wF@6+obc*lmZ+phTMKS_ z2{Eesgi3r`l|GZ}&U%OalJKL)gXd;I7Jo|g>Z!xK7FWbtimT8hRX-{aVg+sSdj2T2 zYAE5&>=MN7(@!~3YsSsOwkN4oj0~;*q3GvUGwtSM8H|G=zGN>Vue{`a*VC|7GK)nV z?ASC52T={Hmg|7 z`__vl|3Rg5-t(10-ziY;5t$g;*CRib3UulCPR|NyN@_YrQJE~&nW+En_{tYHLe!>c zIe^@gvV z#*`ep@cXC2v8t6$h{{Bvsd7Y)n6G80?&yrDT>h1BoZSwm1HLlHxy3nLXKmKV`o z_fHHstLon%35}{8KMAF`V`nwF=o$j{*KU%}oT0>FdZC_VVkPKLX}bPvdCFwGwopJ> zM%UlGOe;%~KIK)O+S0eI*vZcA9&vjHbPF7ocU^83zAC6_L*;M@wR*?w63k>~ooBnj z0h(`_cEM zZoSCCM$i+B7jBQlmecV$pNi69$5n+Vq6Ad|EIp_xbK(C`e-*oOJSyz}6rHD|`?3i+ z$4W;$cIQ>0PO|@@3N;ACQK2GZA140QR;Y?sktOd)g7lr(0Z?CpkS}@9=LC)}eH?eK zt-h$GP*vA`e&H`Y?Wu0fOt91NIbj|T_S&bicW?&mWt{brV~T&mxa}S4^9zax+hP-S zy}aPtV}3i@Vtv2l1^-!HaE&aKZSF%#sf>N3Vw0JdDutCUGaUR`mrTak&*3er--3AN zNGk;{a;IDN7Q8H9bW0s726}Ak^Ag zH>n7o5t+QUUv_DtOMfPJgCemke>dtJFkawlRcoTAZ}Ktgp^85H=)BsamsZ%-FwVB2 z?gz%Tu6{w}UQBxLaUz_56xNSYEB_x^UjY<*B z&aN2wI(-K4SME_T#WInRqFjaWkgHx&3e+$Watii2Ff0swS#;UvMy$T|rGSl=16YoS z97wGqRKQgs#=;aC!Pd{E=xMW-v)h-VlDCJ3N-FybowLTD!>1;OXq{DH^qOX>?Ll2} zGo24Hd;Ipe=d1#Dg2zTH7A2u*LpW=6;5e#;!kZj{#+1gNOqCI6^x~0|z^E7WUWOHn zwU%>EB&5__Kt(N{;gOQ?-6+U7_*Q59Cot0r17ssBVCz(6vIx2u4x23=5QDFfDvmrZ z!?GK=7p65Ia5XOay3v=Ye1AP9#B>m38jQv@fM2P0RQ8*zYy$a31$ap~tIQ}C>o8i8 z%q3tDL+xzWkA|LvGVL}{0`kaBX^@E*nw}ZsqE>r4370Bn-d6!8;+HxD6Lo8xfl-3{ z;olNfxr~_C1*Y=MX7BOP3l%-A23&Mva5FBU%@rFVePSZ8`|!RGCplcsnb-?JX8ih6 zl7|(8qUk2-NRG$D%2nns#Ku)>9T7pbMawgEiV_pRbP@7XC3|rVWY|j`sAVu4a)zm# z=Q^{Csc;(DK|?oISqnrDl%XOD6F+PFoYn2_E{6niA(!hYXoMm~@=CCYmEL ztoTok;xeArKh@n3!U+Y~u@% zJIM%u5Dw+1&W0Ae2n8mL^^Bc%6 z-#CnV;wl+mzh;r0V@8k=M++WMR*KO9Sy|^U&`=M#XO)mcGO<#^oPy{B(?x!irh&G= zrx^zTPc(5R9LL}(a3r~Kn9E5=@Kj1yFr26GZ23lkT#7#;KztzO{=y2J&}B}FT#)I% z=FQ_=cliv*k&gPKcG)CV)2KO@N;M$hvrKV5EQS6!BZg^4+eS(AnbEGQBW=@|jk*S- zrT9ZS3QIvFvhedkVk!%8l*kyv%chE7YM8PGhDue-Cdvi-qW8!cCvCkfF5MW#gd(rO zGq!-m6rRSMwr)v#PtaY~!J-*E~ z(otp78rS`J*v!I3fD2cc-WF_L4hJo6 z_1d%BJ=B2dhD5T_<-&MXyR2QXRfK^>O31tRB)1B!Wn>v!Kk1s8XxG$WqXU3rsje+q&l2@ zW$iExB?>l))qVtH@mN#sEL*4Wes5a!V53O0FCp#w9bDv1*ds24UExRgs)>^DBEznJ zPh_@h!tiO!0UX?zBTUPq_5~#?6a_pEL$y%aO-`T+-@^i^1=o_e)I{m(NuFFQUc?OB zXO4dpq!cZL7Oq2#Dl4?j_xGcO5ObA_Zg%5jeV=M-imZq%MC(Pz3EB9HGde-19xw~PWBV)p*dz@&lV~lL{PI=M z4I9DtS6NVL1)3&tz?CRHXM_$GTyq))ZZ`ERuu#b!36WPdBMpMN=wb)CE1==m4~vm! zTXB9`t8d=}6ZOInCj3hyh*TKGGD5${?~J12#hH^$o7ASGf;dbJIHBIQ7w`szJbid&6YLzw8pkJ#d5 z!9n`f!W6zz;@%|DOUg(TB|aLeBzM&5-IbM85-F)P9UE@YsfX-psT}t8rH?b7P}`WMJgcgk@uJNjVt76YCYG$`Pt0qu;Ix*_!e&3l^+aWYRj4>RR-LMg11h^`&a`4#vGR{92&8+(m{*ES zc;-fakgwuUQ*Bme^|*EgruBSpZ@1a?70lMg<0At;37$WtK1W84~rBo8^lm(JpJZS z>8eH8u!EQlT;piVQ}Wf#5Y&273$510EB(*RmCT&Odp^Q6uErCsEWJ!u43fX|ou&Xc zYMnm5$|CBBmy7QDN>*8-tJvbMS2jXd8m=pK+7tkkI$2da3(8us@OagV8g%xaE_%r@ zKJE*>&a@;5y!#Uv$(@6HKH@ZS3_#hseI z{E8)ne&;kumw8u>Gx(z8vZ0f2&rmc%;zoa#)}vzOsQ4t-t~l;O2h~qcMT6T=ZNfm7 zaxNp*-iKixBETPf*{P_r|IZR5#nW08T^M@?*br0q3V1P! z&pUCyU0Q{cze3rfjichDSUa%hO5Hdhzr3ua9rPDvi-Zz^a@$m`%9}#7mk<Ru(I z5TiB>2X>Bl4z`Lx?|HTdPPVN)u zK7W2Z2>Rsr^!g74?}Kx!L#;j^PdDFWYEMVc+riuAamdtrFPlVf;#apk$)oS(6|p*+@GfY&V4}={#NBds`DGUPvEl^!2jnqTmPe_%i--PQ9;1_ zPvrI$C}36OqB@7UM6dH{^sW!Bd#u}RtwV~r{&h~S{!dpgpXZh9_4S9vRm|4T&DGUZ z^I13bREgfiHSeQdJ%RUw%R^AWZp@29`I^}ry?=rbpVfEnj*)ttJM~{zK5SyD*V^yz z*3P)Ks_SR#4w86$N$qqmUi%Q5`!#)SEMxy>;r{$|wf=N;HVg_qaiRS>OX^)`r-vwj z_~$lM|Ks?sGdIioc89@@D6_;KRt;9&3pULJ_3vfch+v%#|Nm`$R{PibT$JyN=u=QrhWL6YfLndfdxPdc ziMG;@~&tN^O>@FHH7J^i%y`ex+R^+dmb0PwMq-2RaAs@RKEVQYpi$`}Dwwxrk$ z;u1nUneDOtAB$5Hiay$Wwr40l$;k}*@R6|PFhxOs#2$>z32`$8!|$|JatC>VyQ*@m zs-$2$JyKu(H9#kTjgS=Y7zitT?K@!rqk%onB@6(=fak3!`%+CJ_JixM&bQ{7K>3;! z+*I7TgTsvX({k>mK>3NfWB+6R86rGhB92=bC)ACkc_ic2!Hyt{5@JX7E*OBsJK|ch$BDfk*|K72m`UfWS>+A9vTbAxWd%|yI zzX7FpYB^))POvG+FMBmNv`9ROrDm& zy1)}X9Fd`b?Z5tJiMk^c&cg~4iEe6|Lgv`E`R@g*GuzdiNku`B z)l^BuOi*7HO-R$qmj4GgR*yC5gJaXw?c&SuA?yh|KVq|r!?+fask@24p=9aY@l$fV zubhZWADIkiR3SIc)M`K2D<^3&8g6Oo8s`Mfs@dPv3^{LX+>>aMuBQjf!or>-dxNFO z>9_&$TUIpbHA8Tb9&!0MWj!x!htctI?JM)_4WVH?av3+`-i=IPd3=_zMK^u0woOEY z{66mZxm7@zbwZD>SAEf#FDG+HBLGkYq`(TK?Wh;*_S~@juDDToQsF||T*r7K%jjIp z?jDj!W4bzBs)d2r;uzuJJ_Dqu$oRhOfz4rf7WHd^AWAH}UxJD&ms0C5DTiED48!zD zLIHe=&7g34hZi@3)w%j=Bx-$oiX+x>B2ERW| zd?t*MlEVhW_S{k$*I5j;;t4lhlRLoNEc{8fO;Z^GcH1T@qs#T2k9}~evb$@Dd(rfJ zub1;5|tH&0n53;hNR@3Ctq$;jQ==gWKRVt8#s@Ck~gwwux5U^m_`}!iN#k z!f_-Jdwz@FWuZFVB-H$<-cW#Z1d)QGwsIpr`BtM9>u&%0M4zS<9(+oz_l|0ku(d%Xw6qaO zItN29&ua~do%O(tBzk8xk?QEpr#KUDhFN?exn?-hKkTBYg(i#cY3t!y;r5G~O9es86!13ry3?EUd z8RD0Vy-TfkfttFB(QO?NQYHAED_G{+*O30nfJ-!n$UYX{sLD|v_CZMbgJTP^yWD*A z=ARK5%A%X_a^*lq^APo*UTi&NVsj4-xANb@Pd@QhDhhWINPL4dB#-b4C-7O=1aIZZ z=C=*1puKZfLM*&!>cJJE9_mhAEf_X-1N;b6k^V z8HWdNWvx#U8Nmo?d?)JP~ZR|g#YvdaDH(1^O-ownA z@jas6*<>Kh9*g|^8)*D+bF*es6cPjd?0wGRsOMHNd5VpTR;edkag--tRS{e&gi|S6 zqZd(0KB)IrNj@QDRdtP9G%a0lS-hlme^tDxWkgVPaNZ-7QA2jD2U~k%ZTg~ydrI~x zj(f@)Ed74U7WLMn$5MU=9bM94KNm!ORk5091v+(E+1kymRlGyX)ec;+4QX9mvQ4UK zU$HKTgHG$x+O|)-Z#8<>HEef6n>DO=LNc|ifAu{oO0<9a|eBkM)m+iT{M0o6$-;}g_ulE9~|9Ax6wA_0l z^6zfsvvNk#gx>C%U&E_chjv64pYm=`|6X|?dl{m9?0FtP8K-~SfZKh4fhNi`sRruIQUUXg;NWTJDL`#=qu@AJg zQvV{Muy7}&DrT^0mBjX0;xYRi%A?A#iheBVn}=aq{mKhbEDZ1TWnL$4D|bF$h!)cin^+gI!?0c-JCeOFs`?l+ zN1>JflE=O?+W*2Gsb(=qt-KViS!f5{Ymb?@{2ED<>u_UHW4_H(roC!+vzap-AS+A@ zt?q^UW!-D9@@wRdtGGNMhc6SIQt;Px zD;Fh3NU`)K&}CoDmQj*0l{H)kON2Irs4S!HeXX2&z$mQ4iUhO6p_(0|2<|as1`8%R9z-Hj^RY+$L z{(Wqip0O_4!{&e~bZlJw@zj`pbMA~-$GL!BmV)O?m|LhVuI9#+TbOh;9kLInH7egW z)bP%5qO|Ygk9XxzOIEkQ3Z_f^;bH{)ip|H8j^#|N)~@p7Jvkpqdn;IZ?pKw+`G3mo z26NA^AFcod%U-9H2THEE1k0hNet`;45^1#OEeT?+XM1sU9XuwH8{`V#=qR%Pc#q-n znZz8=iyWU4J3q#8y|qr@$rXm$%+FZ4k74kcL=rTJ0oDsZ86qtfERV+H7_L7W#junA zj1%iV#?gC8V)7M5Ui&tj6^sX%(7-Kpt4PF7$MSnF*>~`KoL{?WU(35Yxbv5FE;f~( z_iwkqpLOyKhIF!Qooo_rWk1a+3~ghxgW4+va2WTKScYI$R;r>O{LjSUk8z@2k|ca& z@dOEyl&yckq>2n_!jrgibMY1=0hUFftP3JIXT;HuapG^WiQ+iy3z9d!I0PtCf3L%f zrq_r)ALDr6UgLPZBnh@Z?*2_b;wfW0as}@#)*eejmNU;m;@by_Ptm@@ntUmc!}Uew zrR4gCx#Id^8<4XElHb16_O8+6e(z_0MDdynhz<2k<5x)R)9aq8k0irIwihBl*Q>@)X@0fFePgzN zdK!TBKRr!d1_I#XpPuID(`YK^26BHIcZU>I=n_bXu8(otUXu79H>uojhyOxp8-GCz za8?lNGB46``Y*mVn1ex=*Kzc3hw^6y)dV|~Q8UT6lpqlkiVRppFu+=S&;R?a|NYLk z2@=b9xLh26OU4V8?K;_y&NsfK?u6Jc;(2ER&Ng}ZJvjc}b!FNOcAovCB%jm&D9Nr1 z?&tJBN)q}ox?<2&9MDbp9>?Z2hQntPP0%0?&@4>c{OMPv)SApTku|G;s96|VH7~Mq zN^Jc&XYd$D1%e;dIXko1Kk#D~1Ed#(%Fc_FoD!=v5nunCg35H9$+HOr>nJr}DXJ!m zsM>J>xBK(o@(@)QL6fA=^Xt+ZMFd>LWrtk*pAKa!A_B;vR%;Gr{Jc(u>R53UoVOMAL9hQO1~^5JKZnfB}f6ri()}XsL6r|^BHmaW1KAY zzqiUGjgFEOd}N8&CF4bg_RLg;IRacoi3D%41j>>Cs-n)nZd66rqq)Krt$aBh_Z}5= zvF4l}yo5`?&Nc=g_wKenmiThKYI{|7PdW*^{!!V1&GMHwZoVBONjyHX7y=XtKsZQdguITx8wFfb`D04Zi;FCrDiB#F9S}!p{31sDRuuYWK?LHA z*x!Z5A9y22*!^DaAxXeT7E6#I0T?d~J)93|`%fxze_BGy_6IFNV!DN98CV1C-c7Cm z#4N$M7KNyZ@^LD=3wTPL*KgcN%dy#Bzg+=lK&o51FMCCm=U(~=hUVZ<_Iau-@q-yl zS>i?*<{#wc@BRa>Is3;rk`A7tF!rpQI1+9aQaoi*098RK+Pp}_DX|#n;oECz3Q5L+ z;UNmZSrXId)@5Fv=4L@m^Z#l5J~N9W&k27vlx;sdY)lMVvh!v+2;zBX0Zx7`T?u*J zI$Zm{5y&_0@Bcdh`}^+z%svC*@4o{u_Xmko`i;5190i|$n^J=R)qwG<7gokHyiIbDZM36W@c%O3wH7@^Yb3O;jqGH%1*-am3%=d{+ALE$4B(eF5q6n15 zaS!?9Wpb@$D9oWmQDg&Lc%O5b#8}fhti8{l#y9BV|`ydR6y-09XM6 zpiybXjGih7vHwKn`A;lZgRKg;dF|^%wWllFX!Ye<`DK$XwPBBKZjC{}rJ?I&)6Ib) z!j*1xBwJT}EZY`o@KQ0FvaNVVT2Y*x$}n-Ti@PK-Us2ru0h|b|<>2qnAEj~6C4r!8 zYfkR}eH4neAOd@)@I5$5@)gu5-C7pf*>8L=3=#P4zbLL6z7{1lw&IAqSy&w+*x?}i zrTBJdOc>|=UR(tJ2{fXY+`M;+V4ud-z1|$deG2J^>|br;+M%^?+G>sG;D!;=?bSTO zu}NUpy55w=Rke$ea57H&HN7C7`rfi2zKjPrI(Exf@6y~jb=no*C^HX(iWYR9$TEpe z$!uv5rxT$ntEUQ4Hq$ILLm=ABWUDy90~8TbVHu^HMyI@kNsS5QS@||%> z@#4z&o0!Jl0*HV|q0cFk})YVA>P zI#BWbmhu~_jC2*gHr{;P4KJ&AzSQ(|Z25Tq@bb~F-Fe4UFKs!MKIU+rU{kx+^DfUzw z`>sK5KdX=w?JZ%gVMhVkhNc#dq0BZ90GDoPR*i`KDskyW+~Sk__?h&+q8CCa_o2H_ z@1L5w_}$^G0tG~Dy-@gCk&xBvxP8~LTW%8%eC94tru+Eq`4t!-D^JzsTcSljBsh-R zh-UWO3x*>>*#L%vzs~D8(k2vXS_B*uT5tV0ttMBE8ugmq6Aofa?NG{eaPB=z<@?kD z8sY5-iuQ#ME_qA9iZgEVmgD?EGJ`sSThB_o=zJfn~`kP>8p97$_hH=Ei>;(D5XMDf8uhtOlSh;VmH?>kMffuURT83Zu5qSXU(CH z8~@%tmnQ1{IGv*goHaj>X6t1JF*L&JhXOZ6Dz1o^pX024NH%|T7H?$mg||dmeIAC& zHmWXxIIM6}%79*p!%#MD@hX7DI6sc~VEPVLZJPFH3fm0ZhVv?gq{sw%p|bPc9Zp*7h98ctCM37LF@Stt{srS z!*;8{q#736XduGXW0o?7X3MhAdxK5?5(Tyv_`1v_mrgFIOcSV#M2Ipx>^gjLlx7PE z1ez@av-?$7>?Tkg6rftKpxmcZK(`zVE(>yltEqBCSIO(%lsg(Vt23>W~1oyv&ZtpKmg>#2X5Z3 zD-JHV_6vKmh2j>Puf9Kv&jx_(lUxKA=*%5lJ6L=m(K2|gL@-J~29Gl{a6r$hwO#>o z5VV*aAY`x2Vn7)nxgq2hOa^QE6csqAmk$J7tmcQ8Uh?;S|udRc$qQ0>Y z{KUc_6_Ajh#N^h}VXuElo23!q$-_7__PZ5V#5}e0IdlexhZ2p`FgnxtDZdfU*duRl zyCM?dIC8GdQ>e_DQgWP{38^i8H}JVD9)_W;I-gJB=m zeuS4=l+0^=a_SfREr-7WA)XFk0$Gr4m7$Jf``aInKHa#QUFFad+dY5!7qtN&7JS`G z$J7fmvR@5cpP+AkeuYTm@ha9QYw6_laGQ?lM|0x@o{;)8_fwL8ue(e$ z@P>0f5o%!{dEtj2vG<>V?}BgvE*94nAwXF;G$nYTr~kr6zQ`+N1LnuEZJxwJDe%nT zTS)Lh-pIwAPNA{90Pet?YEtHQ4oQZl$VcB1JuAsfK84WfvhI7pTz{X<6dpqJ{beh` z?FiB1d5@3KsWg*;@3#!B{t%+ar=D)1)6+NyXWlupXjtbirmx)~Xd!X05%4|u=1s`- zd;cfvCz4lw0XU$U@%ZTtR7(k{7PtHYWcaGI6c8T2`gGgdBX#hb@n?&vLyAxv!@qg$ zio9W#-+6iyL1PkEX4jlEwpd0MrlcHKUBl7>Wh@jEgLWHRP*A$lcD z^&`^$V*WmU%8MK1Q>4o6zCV}%wc97vVKd_$uzONAwJMZ3t@JcHL7&BnAD)wDy85;9L`5t*#U}NkJfNzAk44qr5Y&F-?;CUd zDv6tnfLqeIvraPzx*FMA@A)C3;YfO39-xSklDHhWN0*)s0fRw1+&_vUJgsiNPTBYMF)qCX^StF9IWzjJZFCz zL?RFO=U}J7E4Jp9!&)$qGWy;s8?~cwZ&xK8Q(O?)^~{KLdvL7F!_NzIrIbHsxS;A2 z>tY-C-FRg$y!#Ui|NKmn_3SO#ldAe0w7jsGOomhX7TDgN1>BNF_78<9q@f4k)^DjwEbr zKz6`1ZySbW;*Y3%VF9_+L87w<>^A)>fh{EYe#|qNcLrNqwTsQG0%UIaoYCquox^yU zeal|OHNNb9puWUC+bCA?XM4dd-W-PY(teln zyry)Ja9UR&i>h9o1(xE~W`J?7e=_w$#0^5^GoV&mqi_&UE$u0ick6eIbP#arH$U84 zwZ|p^{n1*s@kZ{^jn1HOAnQRPu)LDx7tFVkmX&F9oPGAiJD>P=j;P=@uM;6mIuWg= z(9S43d>RqW-lXDso;0H=z%YH&7P}K>p)F}yjU8jd(}D(U1fJ|r5<2R%x2)mX&w4`l z*&zom8g~{*=IHY0^hj`TY%-SCD&?zG#rf;{$Z4PKSsMq>c-MvtV@jI384Jx0FQg$9 z^b8?FzQJJ3ZFu?-hxt%Lqze@`6p>LP3PXEo1|i4yft|fevtf!yk?Yi(l~-P*hYkbb zs8HK0Y0jjcm;#OU-VaYLGbBY9@^mrlsmF95$u9O|7fgL}r{^5rxO*%6odL~Yy=$@9 zOxQ6&AVE^GTGWUJ%H!l8=%7c@MC7$`8#yln#;cI4L4)slI)1n=(EgG4w zy-H==cbFyy^K~J+f6_^mvBKP~a zsxQotus`(=5>X+&iJk?P&TOVG*Goe11rx}1pF@PPRJgB3hgpI6R7}5xMZ+rNyOSlz zZHzk!LhWi$mRvP&n zpO%-6dg*`3sb-%Um5hG~smGyl>70!o`QF5{qGTwOwZeb#cS>a*9U-0Zx_&T^#A?2$Pa0-CQ0X35(`!vqZ}0+~sInu3GBKkfjpf znIG;?LJRTquqiSV>(*5ZAI2a{2fIDLS??&{AN0J-_Bc`&CeLPpCq~)9?)m(e!Stx0 z>0$zFYjH)?dcW9d^yIC^Ek`(w)kA7i&-oUsfg?7hwC5u8 zH9sE(?OKt?t_ZU55c9Wwz9`zI7PJinfvpJIC4u`QL8Jvc1vXF9Sys7!I~rMMds)uk z@^rwNh(=5zWKG(vp@_Xww9ArnR!5)69=*n%kaOP-N16-Iz3y)tia~q!z0=pt9qebX zK|2*|jAB|0MG;X59cm}G>tQc#xPjF*WzU(3OVuowE}O>i0s_aW!k@H^<;Q_>%w>MV~hijrmoP zDy~(eV6=0-O9a{euKOo@ieDwnfP za3jmfC_n$j0z&M!^^$wRaK1)%@6`Fk${dYB+d`Kkb+Zv zK%>)zI-}bY)S=+tZU-zW|5}57d$SED>a~<9)Qf10(`DdnQ(h|OkFVn2>}Vo>I z#c_=VzEjzhLcy1F&ff#gfrgfACkCiUl5w)q1{sQOc#jp@%2gC77o}d^X!iB=$>(da zVPf}=yKh97oEXNvMSU(82*^n^BYJRZnRUNIu;4=&z~9FJe(b*+a0DAMPV!5|9pIA{ zRU$st!M<1~nix31e_IC_y|`_HTjdQ!Sk1B2ExpuH55wPtKJIl%yJq&$UX9EXy{kfD z_lO4-GaP({mojfbV*2g>houhr>NX|b=u=A+93{@4vHwF6f`wFZ`FKE_NP-%xD5{F| zt0kIkSBB zelr{6>FE6TPVHz&$Fko!Bb6NnYby)Va;o}FJ95yK?@G6sLB5vt!kN{?`^Fvj85ZgA z+G%-zXgU_b!$W-0a_rxW*^189(q=jiw!kUVRo&oNo=nAHV&;Tn3-w-PDwX?B&=)h? zz8o0Yk~9Z@+ufSqc(YKQU7B~G<*pytOJKFeh5wTV<4hO+kp^!4Wj?!q^Yc(xCG5ro z<#N{$7>(UrL(QrT_Ue09jFl8^ii8!lqooBUONKoV zq&{d_Feg7xSN*&c*E%2?>?ubc&u(XEbhl(O!pH}rysuiLtD4E!jVRlbr4B56Yo`;H z8|U;Wb#?QQ;jHnJ1b$`&FGF|(JQ=Njz7x;GCDY1N1Ub&7%OeW8ThqzqD@}@a!zVzu z5u#iukss;9av+MYOOfE@h|dm{`LqELH}@#~!8zGv0Yd$MYlge)p^>2ojJ@5$3g^FG zKtvqiIJng=p9*b}g$RpFybLE!*Qp~(nL64~^2yLAR|6%X;wG&XX${vAu}o}Sc)spX zQW&f(=8F+ScpUS~hJmR@SPz0dyKO_glxe$ugkE=CSRh`QI0zN%zo-_SXL^Ef7_ir+ zx1q>i9t?_ygBSLQRD;Q4j`c%R92pI0cBE7YC(bbQ{aJ95db#IPs=|2;fm1DikU5u( zpPpk#i`n#rOQKCl`<=AIpj&pYUZB?x^4CP4)wAvOYBo$6*nAeIFhUe#PY(F&fIk3< z{7hDWWs_q^xASKYd06mVxMWo^{4^Ohl2o%qQBgnR%V5kHacvGf>@s4|lN-6e;pLw8 zRo@4`H&cy(aR!;!famTBRP&v<0s&*lSV`0AnVs08V0df8y%0xbywI-yRC$_b{-Nlx zDg-sJ85MUnv_E83U;)rh=egZ@po5kmhn$4EqIm z>Dm-qn~ezRec;G%TrfPR8YmHuD|cEtOa?XI`zZPG{LM1$l*-j*UZuI)t};%_Qj!3f zfmIb+6d)S+1U|&m#C>7|$b1xRfJ}#SDyo-ohX{_nNQW`>EvD7+VV*Qh&?SP&Er>`4Hwm4fG0mJAy_A0L>TEeW3_v8rD$GobqoHqBF(gQalD2%dt zqhm<7WWTFZGJVqyTff4nI%8S%aw=6Ruvs3X(T;PZi;jB0py;v3AylNw60#x_s8M4| zJr|Xre%rL^1#Pw*gCtDxYNWIKxuG>yOtJDv9f$6XtuoSNEY$JTlVFt1=T|oYc}9^< zLCcNcHJ%s}K69R)asNSr)rX2}f><>xuB;EiIft4l38&KMnxHmZQB%Z?TA`@6tW*Zf z%j?^iXbbeIQAswG&^7hb5Yb)cHEjlmlg!!rmcdB@`z6{|H_ucOcX9BD1wL?}YFk;R z8I4tiYI`At0Gt#rL;8Ckfyr`(t_U`2PqUXHk$cKB9)8crkH)4uL{rN1sa5ed!7HUX z1}fRpk-35OY6^C~$%JI0o4R3~anq>@@4DY6cN({SEg0VMbB?Nlm)}LWUHP;_aGI8I z!Ce~!Ta(>I-YcX@2byKVxlbD?Pbuc0Qc6zvK{V-EPh8ytD%ArT=c;)-88ZxW+k7~* zw{(*Fe2Q-->HI8|FGm+xhKE|cOE?J-Qhub)d1M`D05B=ah zG)e?ZB&gHTs(MP<;cnm{Z6*<($(qZ~ z_C=nFO|-u0TT<qsC0>N70%~()jqdro@TttG)M3+|w#4+YVvlPxPd&im~0+)_>&Wt*=z{{UYtjm5_ zIs`@gur_A)y;n5UAwf!gvHJapMTp64`;I8TpjT$ONr!-fCI)bFAU5NbdxyI8;7Y>m zZje5P6m>EGLcLwU%Qn{vc8;N{mp-nXB%dB&#K!u%piN{(*Q-bjrj?DZqLBH`LXO@z z|CPqYJxFmLB~u+ZGSn8?nh2Z0x~u-0piXSdwU2q=HY@~zL9ZDU=MpqT{-$h{r9ZZ` zJqvYAAS?p%F>%e!}?52)uxm;i3%fKbNn`HFN9c15{+iY%s;~{@2fu|^{7bT#P!G2L45KE%%fD*?)EZVL! zBbsPnaC!uhl(FTTWQM1CAAavi6$Ha-B7u`C5s;pX*2hXKF#|qj*9{trj5O5Lf+n1; zX!oN-Nk#**$pExdbSUH);>5H0m(Xt|x8*5gsq!6WbQ-&~!Zm zSZ%Z37eer&XVQ z4e~`1zzhLl50NUc!GV1M7Pi9w#$r{G!MgGGO0~7np&7Rw(c4L;D4?45FR77(<{LX} zSs(*SgcP`Hc;CASq*$49IF%x%#oTd3Iks`>gpBwuX7)p5%P(bnFmjnS4neJW%QbhP zmGT$$0{hK+M))J@8L=xJiCqou`mc;s1DHEq)Yw~Dw|xV@HoBDB)H}!`V8=6^2lpEEvQ7zHV`~J*0)tG9Bd#csF zuD53|1f&%Qk;VyZOE@B%PF>JuZ+>$61B!9l0Z|-=bYM6Tg#fJFjuVon#0Rt~EyJsT zN>Pm2?z0x$swms%q<9&!nEsZ>t%wk`VA&-FZCH;keVUF?qrG_apZd1d*6k|lz$?l8 zghnK*N>)K-VIopX3tAjouMbBj&3BXJ@TvIn0B1bm6K&E{gMu3 z8443KqQq0G)WGqg(>E;zSL>@EyBV)Rnw%=UGv*0Jw%;6ry8~EcCuk=^KV_NeT|>** z18S@uppPpxdE*;SO&05o#p0c-B=K!5DIZ4>kQb(*atNkve)Zri zmf$bCJ*8r2LVYAP;lsW76W_2@hkQ;2n2(6xeqpK5Z`527&i??#AjN~^0MqgR-Kg-f+W^bgaE-4iFhusbI}1vCShzZuK`RM+JFBZj+OD_#l3#bIf1vIX zbsAi5Q6Tv??!L&%G650Ia}D6}us|P_#_dBBBTOBs^H?uBDDz}r_$k#W<;A1C(|Lh0rmkj zouH~Z-9;~lXR*X?A6j493mOx^=X9fcRWqA?vdHj^xUo8cux zbj7d@oki1-RYDYqp;RkBA}9*QPQ--`^wHZ!Igfdx)J&utFFM>}BPC{t837VlB`8E} zcwQ#LT#UjZbID3Yhha?#8p^|$FhFIQr3p4~IHt8llZ0vli>b`!txC9{%R;Q7QH}S} zJ6puK(uFWw4Pd`PquQD7i`o2@lb*ZGkOViWh;$+;cYNcG7d~?G)i7XJg;VOM-M*ir zL#dpHM&%dFUQEB%(aw;ZEG`>M!rC>=Fa=_b8j#di5Hw6k8$58Qwve+(?oIQnmSzeW zt$}DGl@zl?lnZfZf z$*=ptGLnjzLYKq@`O-$plB((^#$fjmVJIhLtcbueol+?>u^Fom`rm+WaOfexWH)R+f zq>t2APuseH_8o7H)l|#JOi`6gGwC|ZHc8Z5S4z^GG5#BZovDSiE-fR%oGHx#Ma<2X zX(~orJ9#sEiisRu(3G*D}}0L z#EdjzFsO0N*;>XY9t%3wOkuQ!E=qd1nl9u8*3H%ymOkAGqBpEc65>rKf*`|4>;4OK z8b$k;(zF;L4dUYQ?FxvHXwD2;g)(*nZSl~ciHkz~)>-&l%G1{@MH1k>vOJT&zK5@E zKWt&UvzQ_UI%GI8XB05NE^CaTdMc-psz?&?7Tc`ICXgl8ir7^HET{eGzsj$iZ-2pbB?22s~nm(&n~%KZcR&-_fZ8ZUL$L7GL2HG1+z?qG&{fPSZ0m# zc{@eB@?3>nvr1kahn&v%yIi_ZR?7}+7?Hx5YEBHd4bjNbr-ad7UED|7jrDLpOLH7T z!6@}}BIRfsF!tHn$pW>5SKY!obGY2jOPx%ReYn)RB}n3_V3HXG`yW zF5}3;@jdI4%RR^oao|DZVGXaCFTzGqFxzFx=frH5%iS8bIM@i4aBT-ID8me0m?&)3 zK(qmP()>-Dg4Y&x-dp&f3W08QZI6^Gyru7b?*u4p8hl|(O0AQyNvhG*Gf}DnD=I1I zuX1viBZ^9dBJ0`KsjB`zhUf|d8jY%B5lk8eoDAh@Sm0yso9w=@%7Q&Q$r(%f26cy7 zKsY94U5ddE8eB&2-vZaeOi`SX1GT?c{c6R)D9luu<}?87z)du1xg0+GAELf8ERJZ| z7ALs7yF+lv;O?%$-JN96;0*5W1a}=IxCeKF1Q~)uf)o5r&bjx#AH9F9y-K=v&o|w> ztE=XeY&C26&n2SkY)0%oPdW%fPkBM~q;n8zm5;04vM}nWDZ;qIWGjyvs4GJa_KFgk$$j3_l)a>0875jq_p+m?a8v02s;hYDxNk*=Rbx4 zM!8O&xaHH6L?pYG@9NlGZKpO;a?wsJZ+=_-LMorc8*<;Tmt#E;YgzB}&sug%%%RYv9xW{>dxUuMqd(;E z1AF|l&ZeJk+*$(5uKZtDP<8r^{iI|zExw+EKSc{eo+Vs`r`9HOnf6>$BYFYHxhx~F zUZ)^y=Qz(?XlRjP)gv^M)Mff|PK1>Nkh;ik2P7_|CIL7bf3IV*og_t?)!OeBrX;j^ zdi&wuZe!v`t9(;Xk%cw)Ty_mx!o}?9Vns??vWw(Oj@b?Kxx+ci(6wtT$cfoU@8CJ} zeE$c|he{BtxkC`?bf^9MpK!S;La;=zxbw@V~KEO}Tz`~PSfa%u)$ zMy#TvVS>uEzty`IST+30V(6(imFY2b_@dM?m%k}IB)WN94~F=7Ioj0Su2Vag`9B*h z{&eaA*PZb(IpwyeUp%Y7!&_0=yf1c<7O~(O=oj=@0NW_1A%9;zyT31ae6z4wT$}S5 zpr@Oyw+S%U63!r`*o|=3@4eha;hCp`M4%J+mj9|Ca0Eo0q>fubyLn==WOAH}9wfQ* z09Hh9=h(D-3xlSr{J1YjwI0+?w$NEi8wJzD{xne}N<`F*kUOIfttK(VMtFgt)x8?i zsXksVSOB!%%V}5A7!sn5v^{sd^QU;aIKmzfrV+q%8qXdYMDxiWlR~Yu%dAXubZ%+T zX#Jeq^x5hQCSQAN8&%dFtNv@&pBb|(mI{oplLsA93OJhNYL=$zV55XzR>=#s$nkTG z_9pq|2u0-|23D*!2H}a;v_87#p!7qt5XXc49{B%$sVZ9Pya}|XhQD-Moo(1R>!Jctl!K>DXkRs#YEyIjh-!y##CV5=;r%_+{Q3THHX(zj1F)v-YYs zD&R&tHc!z?HMY_uaCdCY|41{yYuaKBr!m!K^7>Pu21dQ2l>W=Ys6NYZ4}HAiil6uU z6BO*1?OShZOL)ukqSC|utlV=JR-Gw)`RX+RFg}YDnR7dm#WN{FV&`m z>)gog6d~DgCVf-Oxe-)0sP=k&Q{gz(0rh5bUpESJA8o!SFLTAdhSk4o56Xu2iGMck zL;t!~V01HSwDEa~t46)&&=cDU5?jytmz$uV`?7a0;CAG&Fd7GWQ3!eRX`8RQdNj~C z{kC52L+;t~3NCn3K55MUGy?vnbbPlZm8Y-Wg2-dct4AFe_8aI5W}(}ynpmBH?DlRb z0E-{%0R?}2HUv$NQ~A7wx^+$Nmvy`QYY(JZ4#s55Mba-u4_%Xj{OTK&K+uVBP4!-679K%*{o+y+?1_ zS^9ERjRS}`TwK|B*8zxVUaWKRN0(g(b;)d!WSiwG~U$I~vPmOt%YYILygwk@#{axGoIOVsDg`5J!6a+o-RmiA=~ zq6w2RCS9sN*pl|}9pXznWPWL!{^8dph&pM^iNG2f334s~Wr+%|spva2VAl%uB`~9Y z(hwj`@55eDUt0&D)Z(BAs3OX;Q|gjl0b{OOg#qt}lupqma7%9y(I*!kA<%TsF=d%g z{kz4HCPrq|jN51D~;yX;ekM8xpH9cwJOL zco9%nzjq0D+1w0N4UZe~8s?dRbmqhk?D<0StuKqr=ywfSW9%-^-i09B=BXK(k*hJ| zLQC3@ta>5+N`Nb1&_X6`s8wEggu8w35a_}2EqjDl#%>nkK-*(^sWYv(e~Dk#-U3vh zOS#b5M>fB7cGWaQYA`0WbqHh$baV*(S3Id#B3i}Bte>8)j;lpF|%?rWd#1XG@J<9X>{aT#(RgN;WP;N6Qeib>jCZ*5J4DkU zVN83tU>L%}ifD7mckJH?>_Uxf23AIo!xhl1Ia4-pe{Tj>GfrLuE8#OQa4%E5fXtlg zaHe&=nHRJS49&o%t)vTJH0yf<0QROL(4soqY!;DL%J!1>7}5+(ip{(TNX+fA|;zWV`9vDIuh|1@(Ds0O)+_t*kVh!JxFU^dS6oOfa&k zkwc*5NK0#Pu$i8bnT8xRuB3*2oNyL=qlSs) zfq^oMbIcTL7j2t1!aMwK5Mr3}&HA$6i)mN)))^LyKnM3fA+7Sw1Qf`Lqy?{*au@iJ&F3eqJ*|i{A3AB$^7md?&Y1keI@MSyeD0xb-#vg0b;E}t17u3 zJ**)n+Acb5O|6_8J%_wfAA8lDujEmCo~+1x*}{xi2kXr*Wb@ z4}sks5yhZ@eov^j8O{NAGUW<6%Eqw=F;@1ump!9S>Wn>uh8vEu#!UP(JH_)Bel^12 zdU)xtPiu8fazDBQOmk>;Vd{sDC~)<+0v!299*^tQZ!tCHDS_jJ+wWp}7KeRVb z&2{nHILQTSm+O|~Xy&bQtC`xOGp^VLd>% z=&ucJ5n6Sq6)!920J*)ZVQd)fQbF?VRQsK{wF~+mJ$FTHa$OiuMlt8PluZw7fZpG( zkpT58W-f+N8&5yiAoJ*x}QH|f{usL~rN zr4&qhp`_iHfHUgKXeP>z1VRAzdQQP(jDcAY5{Otnkh7M5plA9U-rV2~nK|i%HZ}jd zSr~0yESS@gTTyDFgJCaSG4BDkF&5EdpYFiOC~Don8N0)JaFSa8`{Q^ra~_ZCPDCGg zt^AUoLP(%-1RP;n0u)vgm-)h-WKaN82lv`^(kGC55Qn`f*;{nwqz8jMLbGJ{)8<*aWlVI#&S9L2zU&V8i2zAANQn2??f{fBNB^NC1;rco-8l32udt z)a(r=YqL|vbp3eT`Rlp~P6Fq*v1fngre3hoXzYoyLh~lURTi1g8;t*iKOwdRdvm^q zRF{&XW4?Q(DMvH*zEVme7%n6Z@0hfBjs;76MqW&UI~1wPmUW0uIp{4i`K{2k5PIb^ z+-%Own@JSTi6^1Ra}i+$O6+P?2q-&*72J160x_W`1~lF;(fPqa~% zq8n#4seb1IFe}JTBd;N1nab+XN`R6IbSBJs{s%t7`T2PIL}F%wSb6k1iCD=S)u%{V z`Wa?eZmnjLL}C`@cxiNR;VC+#F5Lqhyt2hhQ1sP>(6GYlHo($3^aHzPdAKAcw{|&A zRMt^wp}a~ONk1*EsERTOtf=n}%GM$V4sXg#8OW$A76M9&oi&k?(@q)2Nj)xU%ZrEg zC>OQl*kh}RMqkMmH89Z<9awxb$Gp>SCoOXrYsRdMCKh+ODHxcqvkG`}4ONs$WZ}xc z8q-rQYU2tdk}&({j+{BF0m|JR57=#sWV|SOwIW4gk6CzC`q9zeo+7fDvkS&l(jsOp zBmJ^zEJpo!Y0Pa|iFdepbx9kus!SafvZ}T;F0vG`iB^jyCb%pP7||!K4jA30EFD>& zces^1hI}dUcFCD6X)73`v&=Ixs8w~j_GxaV#Dkl(?l1 zF(K@w{F4?7edofk*Sg=I8sl!fIgpEC`lc(*!0li%K(8 zhC3&P`r85*R(91*NQBHwZYuRffI?jQ08y0Y?;-D! z5?Jei;}>&KU5es)Q8%$WBN)e3S#eQuSacj>l`$EFR6=uC5O^vj;{Xjl4h}IfoNE{~ zlB!1a;5b#L%!nzh%a$oRr#(3poi1i-Mpi#-oMI0qsAOv_peZBSpx#${lQP&sybD+pP*zGui3c~FQP|f=DJ)l z^!0^ziZw=)+eF2L-QOW@-o#Z$D1%C{4QWR{yCSP=0%qC0UG2b8W#*^rQq!wY`t!wS zl^|4y{u5&}r7IEB_=jI;Ri5o*r|g-2L0y`=EVi9(?%{?K=gV2Mztqw+3(%78YzdV` zp70lO6#Y2r)$Qo)QPigtmJrd(Syrtqx-@68MZbRw#oQwM%qLZ`@l!1A_Cv{he(O7% z)=LuW&h85WtwV3MHBa*o+5S6{RTNFe?&v)}5j9CnAe)UMHt?0K%@@85dpq|`__94% zLt~^5Mth5b*+;K3R%dqx=$^kH@xQ(O`ZV7B>(?6TBJViv=kisZ#jjEJ+(SJsV|y zQ7n`NpS1qrf5@pe94*)PABm9Xh6N#j?
We=6mPMDn;$|hB-T{86Ox!?L!DW zvg5~qiE9V&LxnQdLOJV3Gnd(YCnmMqiLq}#TWbSg%bTX~L_##bVLY!|IdSquz|Wzz zblK}s{fWzCpSe`t3fOfcF`@7O*}2@YT#0%|?6>Y#5f@=J!_c@s!U5mbq!)u03lK2H6cvCeB+Jk(Uzr}?Fm zjat=$`q}DTJJbHXZY6m>1fnEr5>Zs3Z8WT+fSvq)5```%Yvi*BEhErYR>i&`CX1w5 z1J~BDr42-q-B66vxKtF`@SO^6o~2Z=ru7}Wb#G$EB=o=J_tA1&Gpmi|y);{D`39ME z4mt;avZuDi<cD)My8jjrUy>ai>aO!Eu2^T_LgZ zh#zJ;eX}*3a59r~N|&AEZ=DBDMwqL!tfFFuGCyZfIR!5I$aFfc^bK(Q@zbhzVUUr} z(e!HFcm91NvJN?@1aNsAu||@yniE~bcZMTS{eP!$+HoFvDC1EW%;W*(6GKc&wuFYH4VZm zytv#bBZ|;fb1VchZ{_1iZjs&yx{=R#T(EWSTCX&ouB`e%ur5jaCn|0}e5gP9E`bcL zS@6f16KV5_<0i=YsLer4;9G45=aaL@8wD!oGAXN?=EVupjKI&4EX~pyutg>DQ`(&F zW+D|b0Iug&xNxZRwV!O3<_FC#%?izKx?navK%PK`osyOUml6(oM592T*;zpbfN){@ ze@C}Ox;(pS5h^VqmLw($7B?me7dRqxC{{;e7(z2hvl~%;Fu2E1{lW4QmjJs7*i>F{ z4QxWaxddjPBnSZ@TS+k5c=7u%IJ4L=^9~#U2#$}L35kphAN?@8rU#0qb{kHjeNHG> zn1LH|EsUXhxaKgQj{C5cQ8hV)8)p&wKL-Z^#bp+~K8txmdg2hdGI7*#%$cc3wJ9T_M>kObwBKzkxTgT@f7QbEFcl9*oXcI37t=wB##H6z6nh4rMM zhy%Ip?-|snY?iUYG4dLkDB%o#Bs^;~2&vB6h|E+It!I{%!`^%T{fFzUoU3O;6;VQ2 zB<;kJ_#wWu<5{bm1GDBVE5l#!$F4>#j3#amxjFV9ud}Qy{)>oA+#Pa@+C2S##BbvM zkXsrr-i~{0aNHtcKYj>3?a!>0+&}n#k+^?Ixls;-c|t@o^t{NTvU5I>A!j?CXTu1u z$YOfdx{}j#o+FM=aIs1y*d&LM$CAOLC~31vo}6U9OS00nrk*y~5K^GqO@H~J1ni(K z8gPg1Po&Pdf8>G6>z$~0t# zLm6ozk*m_ZKq0u#zB26Lw6qz#DBNNRolO8DmcByyVIHUucPh5F>YqdCz3Kfms7cQa z6=X0$KWyCcWH>y*#7UdLkR*MEMiK_X<#!mViaVx-7{Ce-_a=CN9&t($D?A64L7&)z z(M!&uYiCcn0H>k&N4CG|*&}%2gN(OAxL4ZB>`?r2V%TX7anzBco_OLBOHH9X`6N}; z4}EUTdGTR9zhxV2oUyAhnmgS%Y4k+)Ize4uDVhIeaEqq3Zt1vS;CQfqA-6Oe5gLA; zTkz9fmX;ZYS^)(TSYaotus~&~WdBb_Q#=kTgGh`rAHSa{=^aS0hdmA5epFrV!1+Hz ztysri-k)&sH-oKi_h2??M|V4OCTHROCiV|u$40SIj38t05Dl_|{e}G`GD?#XXk_G3ZIqRYJq9;U^G^$c zSz;@UjwBzBXKgUKwb?lFIO_nT)CsFTs{}N-Avb{xd(=JzdIZpWW9xmI7Xx_V@!m9# zB=cNs8W)0m0_ri^ammnNmFMjGlRea|del?Yta7^$_pBXiJnq0cPn`Gv8J=wDVo^wW zaCnzkiD3UT;Kde$P*|bJ%0J}afHzqTA~C|mh|PA)jt&0L5RIrgjDV62%69sP{2QVf zpa@oWxS^~8!&LPnt7U>L^a^$&i>h)ejtzEjEJjNt8Lb{Sk8JAj$ST+CdY1*xfDZrp z1)YpqaDKNhE^nh9dr+y5y0`xwJ`3i&bM=`K6%~owKi5?`vrD@?Zg{q*|GEF+!_1#k z4Z|G2AaCNyjhd|ey47zFSKIXn4!|UR%TohlKdqPZ$IEE|PGQj6HU*)S~fLkQ=VKUe$~urfX?fWWDK zeia$5Lnz;CLZUEV#OMgvemtZj_Cq$wmuGV!O^uJx`r*@D}P;(?3W=QK!U}q3SxPe z1uC(D#YLQ2*cgssfX(?qn@Vo_K-$LlMak+NZVBZR8GQ6yclrU=6;B=C7x$6$(uc4~ zZiZ zQ)GBE}&-Ra1Kz;ofuiIgfiW(6^O*qDiVlU*J=Zc z!H|w?WH0-OZsg4HNN(hj8X6qwsD#1+ehfh3XoCb`)}68INl4R_g=ZMqh=pZ*G!%=< zm~4uXuOYG03!SWEev7QB^;hbziPwaaK`DbVSbMAuHy|8irp+iSPsP@hVxi5DW1t~y zABzU<$JH>%=xD@%Y?MK`v?(XD!&h#KQZle*prZ+QdKr1d2X^ylM?Vzo{Z!f_x7)wu zMHP+#gpCON@d(6zB_EK9jX1=Ri7Bl}I$@MI3~1Z!7x>1#?8EVi`sTs%iK67e^VPu>!nY3Pcfg)|dvZx^wDb#0Y@GZN zmbk~x6li5YnN!z4Me?qDEP%h!37Ca@ED)c8i7Y^#fgQX|g&7)BM#I1zh(jRurxijb z{&*~kOiU%2SJq^g#2Z{?7wQ#UMX==+9DVZJuzyK=oTPt~cR;v*bK(6}^b^Y5eW?f1-2Idr=3G0RKPEQ9 z4X*hS$sW3S7ELHwBN4e#!8*Y4#sNs;Q$7wF$so-iW;`OfNch*yx?LQmT+4N zYKxm8h_I6>hBvs=&fhDzOw-8T(J&hZ)Xn8kJU|fMF-JYGWMt1?8o(g&Q+t?1V)43L zxL>nt6b33i$SW!e?Ybd4mOCWPu09w>*n(j1?9V(!LWl?xRyu4yXcl@(Lc#)mChK3-(hg0G<6V$ z{s}MT`oqw#Q>G2DTp%lIw>&8*91Tb9a=jS?07l2T8J@j zQ8^C~Q{z6*6|=FH*bt6yZaD>JS{mwXS?&;96Nq}(aNJ4}c;|ueW#zCL7xuhcs{@9@ zx}IL*p15!k<;YL!pY!PmN5%RKu#ZtUB(y&#qk|dnaTuT;Fyp)jJdTVZ68nn?A`>6J z>>wIQ;XstaoVmE5L7kq4&5(nxD@_43ZfnX0_DQDL-MK&y1LB~{)CY0n0B`F+1Rh4={SR^K_eP@?{K zx!uxp@|AHb1@|7hc?I{Pz@*wb}K5G_?fiJWZ!pyBa=)C&YvG9i3(p=H{48npYO!q z&VTCv5qp88KK6+}OzLk3J^Z%g8h!mZ4C;M(Y*F9taryFeD`@s|p48c4bA@fyL`qk3Gv8r^?(PT2d@_%t@p3~ zPknDNaV%(v%-)aU8L-d0Ujm+=w%;JzUlz}$-mb>PUtXtYO}7GH3*Gwu-kg5ve);Yu zje?X>e3V((_k7D1cXR&c`*3=={d~RXw)NVcIlJ|GyXe*jyoYu%ck2y!TAS22d;QhE zpR?Tk{KrlFX=6kE^>L))ORh=a)$~SR!0oi%t(j9hSKo>_OHYD0@Zs?A&+F@Q`=5y~ zK`(dvKlR@No>ZHp5juh%%JjJUwA=jeuaM2Y9M761s6U){THr@uYoc{{gLMG5M> z?tXrIJr(SG-eaPA8=Ez4Rq{$cLN!WQID3s_xtXud?J8>yFf{EK7Y}?(>%lbF#b^!7 zoWg>mQI0^XL#ZAR8S6<#0*mQ;iR2ruqh}dkJD;P%gWxugh5DZE^8b>dzaWLl2RT*e zAKER5fU8AZ-IDGPqFhv3J@cX41&nQ zlf#ka4gZ|ZasXtq@TI!=!xkRC!DPd8%iE52ao>DofA4v?)7Mj*)sWlr+a{kSk-1+d zwtpJXZqyIp)xz#XKDKY>s%eycGvh;A%w4I-2pN?~?5yCGNR%%Ln!PtW(^oZqwo9*H zrP@Gqzumc~>wbkTmZlvw3Tq7d%BNh#f!D%)q!=#88$1dY)%S06a6#XXadGXwjld@w zAH(Xz)#xK;A9uzGNaX|VoX~RTXyZ`d8oCuL>O2w#?c}(toGv)&ks`E>bUq zuxj>0i_fTU-9IsKv#uL~uVstKi++hrS6_z7@S+p^UeW7~>MjIK7{GhrdY z&=oM*X$l(ms}uif{LJVtIJ#KLNn!TU@L;LiqJ>*jdPx`O9)li*Z;@ENMkG&vWn1%i zT&{nZz_%EOYmm;8F6E7Mpqq|GxfdnNsi6Kj6Dch>3~ z8LsE98@M#4&0Y`@YQmNnCA{U{&RN(<{Kn5yxX3?ToVt$_3{VEfD!{U%Y-`}Z7sqjn zbal6_F2{O*z#JYEW#NK=HWyV;9k}ga#jGZ~ZcLFReIVDN?z-h>RlL2nrru9iPqo0| zHq++i6_%DkV$9XBgff7lnO$4e7wjzh>WYzRvAgXS>BG=?C`SkAX38qgpxFJ6d&TqF zsT>?&|AzF+pc&xx!v|6ydG9cDBAFodId{e31##jQ4nZQ(W=iNl+H_u@r*Q zZxNWyZAXjENZk^Hj=@f(;l?O8HPv}*G+p)uPUt|0PFj4Uw z7j3slf29)4{u0hhrL~J?hqh2B2OL{e3UT$DRO~v(fBZpB5pFq|TAsP$l?6uKLCw;D zW|EdOCdQ5}sbXf0@b&!88$x(8$#}2Z(EIB>L8m&P{I{+FIU`u)J6P<#1Re=*ld9Q8 z^PX{C@0Q*XlXqS+X-q{lBza)iUUtK>RX{N-d6SEhckUnTt*y})Y0!5CCqKpni z4$-!PUlf$n;BLin;=_vx3yuJtn0A}ET{5O5;(1rnGA(;i-kz6}2n;aEvMqEX9_aRH zKbhyxi0ka{a6=WE*M@F;&cBKVO$Zo$Mz_b($OGrA`&~@{r`!Xpp6qQlq?lwwz4PCK z!`NYs)>?bhCA~m*k7}97xwV|J29c~}D<)JwD2tOYl;t&G7w@h_wX5DvpC?#Tx{@OQ(Cpnjvw@P71&kw^Cw8fLX7%N^+0kTF-@c6eoMaa)||V&SjEeA>9A z?u6;)R_dmSy<1%s>@v`VH)|9xAuf4wsn#!pD|ZC+q0^7D&YUjPq#v{~V5P_-q+VZ2 z-!;X6nyL%Yl6Ie=H6@IW=P(PL*6NFSL*0`=ND7}u%w@ktRtTo_SV|~>N6?bZRHUo>_3@&g@r4x_dtMMG^IKaTc_?+((?g}VQQP4H9pzz zlVAvNe%B4XX|?|-EolggS0-5EvV0rOkyRDhh@gThcAaIurIS(ye#N49=qU@9G!9in@`q-d9mET@)HCb!6; z*_R4bN6!fC~u1~9!WrK6%q=8F#onwKV3E0@_g@eb78us<(q#5yF z1H|cpIrcB#WtB7XzRS9M6ggJBZdQH`A?Q9sbYBZ{p>jcu3gSY{AM(enn6I>v-g7#J zHuWu(abmoz^^)EW`+cC3SVI?LVULNlPVsY4{9v|yr-vk7iBI8y;YzvxXUh$)#8<{% zgi4DEE=keS7Jc2;G;-o}$`Uh7N0Ip>-5~9ppGxZi1U96oz}@81ZG8echFr@cy{pXr zJEo1a6hXwPzt~^QJ9=C8g=JjmB|Zn*K55i>J0la6ARIYb76yanViAsr@-ey&Vh9Bd zGyGJgQQEq*u8twfgTgalzQN?q3TLKK2Wd1wiazL812?Njn_&7BSH+RmU$(z(yHW# zmr`tQdl!~<-TRk*A(}6sqZ)3GKoXs?3Q=ig0{E6@``PBd^j;!n;C7BDj+b8W#x4{2 zkWRVq$2A{J(}Rj{MoRryBW7m10rk%aY(N>`q#15td4|#j&?c{>>Zb}q$HmkwNou9;TX7MTf-d)VB5)- zPjik2+_Lx6Y#8&DJ3POV8w>NrjC#AA?_4y7*utty7sf@gMQz}#32jf-^Bayl)$^N^ zE#KMi?Mz6f7Q}uh2ae3%92mh#nSSG|et@g|y(T|cL?Fl`*o1KSN8mH*BLB}wltatB z*mE&_Oe~_5_pK~qk$vlD4yyLsKQJ1M!I=5)u9tE~*vc9vGg|UH*K22158B?4PK^*? z{O6!DGx}1Kf*P2ppL2z`O;KQeix(3Y5$RTp9^bM;vwqc>g)}G3TpszD9DjnhcbxAp zS#w{sy)v#XUod8n?dk;rb9nKVPr_qO*sD_3#Q7^6w)G!MAwSD8z0^3L=BosI_0#lu zp6r6Vs$6g>jPszC63SNh2K5`)^%K|COyDgkLX>Q z7GKK`s}z+B!LKp6j0(s0%IN{Go*Z{nIH7-*y{kR?x>2)89~7C#>V`^L?0NuY!2B`sOr4VSPDPZ6ITuhYw5LsV=}!;7sx201%8KnT5m#9 z*L$L4Anlrb--p*Mgt_@vm6OXEr30J2?XAAGI^K7F{oa0+yI)mq#r@$XtP6enYieUP zwAMAL5oVr?zY(Kq^coKp?eTJ1-!09TEce(mL&}MH-}oV^fPrfR5Z*gR?`1AX5x`fF z96uB-CrT==|5~F!&4FC6G6(}Xq9fE?G8`E=QAip|$WDCh4$ZzT8UNLYO^VG545^um)(ZueUEVy&L)!$LDsIX*9&-`44`da&iX8TXHv0-Aj1EIUY}(?A)B_^ z6{Ql#98!|h>^XzrZpo*K! zyYZhEyJrt&&a))nbNF$o`wcxm83@U%p`qEa{2m=#124J*6MnZq)9l62Vh<_xn#(`* zrT#P{sv{YO2(rvbN&Bce;H~E61t{nsq4I@|RPz@|R z$IdZ$%^etdC1?Qf3S!z2O0}Ljxp#t{)rv%owPR_C7~wq^8rxm_N1|sK8Wf&@o{jUy zS0SO#LClk0uh0D%hlA20VCv{iM%bD5J#u6s=8>3)*u$u1(F$3oNbssVu<0PJ$vxV0 z-k{@$nisjTvp)uMCbL7r$Rz(-LWHtQEM#ZlA)kGA|N1Fsb{RK|d1oIi?*Z(jI3Vse z@}lc^P;xxjd7s9d=P__XW7v{GfU;7Xt^$`Q)>rS6C5$S+X(Y_>0#JUaXD@J&7si|| z*#3T%=dZwYVpPre0@wgEW6rdFB}YDF;msboPFt9QbpBJ{>mopITBPGl$d$MKU0{Ye zhqrY)aws;205^}$M*g+K1{GS8qLtiBhtp&B(ZIr=mBm&`Kfc{;7NxlhOz zw_B^*tqY9oW?z3aEND3t1OpB$`9LErE`^W_=MQrpz=Y~71AzMXDfWV|fiYoTE`7T@ z00PG*_uXe5@L{dJT1v6SF5GfSlY4T^4}*@m1ZY%+`qK70fk76NUeTzx2Hgrz(2AHF z9tmN}@qhEeCUs)Q2g|_f9>52hd^ooFDD&wFa#};)!tK?&JiX9Gm@6y>A&hhu*+#~3 zaRjH5N#+-TbovoHc{=36y~{D{)`X?^Gi<~a*N%Cs+UF#UeLkRaCiTJZVdPLyocw0u!Wqa z5cEb;_Qkc-qV=zIjW`38yZ*u**3I_H5?L%g;9h*Cp+L6h*Z@-==7*CwXkBL| zA23E4zF^LSm#vbWV{2&Ez^c({BXM;I`D1bMw;>}pd{w?G>RzcM=wn13R*|ER{ZLPr z0OcFvr9=K|P*2-qJfWUKb#qMr^K=23a*@JpA=1Gfsyy<5G1lQDzeu73*(rQ%)xEm= zf1Q`UJpz)Fp($6in3nH;15t*tqpjNwG84If)+FLn)bd<&mBZO})rNnEKEO_HW6sg# zFF~TzpfH<5&9did0ad9fVm5B^$51Nul;PLLcx!yGWR{E`B~Pg@dq%KqC{%XdGM03YEg?0RR+51sC$S}D^e;UaGK2iUeGx^sq8q_yMYXmZ<0={%YXuTdfojNfcoVT>$w_oN zd(XrGdJk&sQ4pCg`FgFFYE2xILk7j?WfW!Ip*HStqgK0{B17Hb$upfmem4o7MQL>n z$optgI!#~0{6o0X8VNZEzVcV>uT$){V2hV@5E@Af=V?egtfPqe3NC{L@b~mk=I-Af zmQRws4xY=t>J#>SCmAs>%>`rFtf^kqf8AXwE%Jr~coUfReq~MB(=k3Ne*MT*Kl!%bjRvnu-xpUo?0kB>bK-jdF={nU+U{<|JE(Q#P6JzOJ2AP4Zi(}tx;T{7<+jZNtH$K~e zv1-1+F>qp6=f!)OnECLfFNy@#Os+&dfv z-lu$&`J?!g>27dvNiX}m%F;ycp@6FbVhQoJ!5@wEFi_`XH1)A(aA;blw;%HfQiXd}g%|R&FUVM#Mz(NlAn|*2y(m@pu@f2CPVItg zGR+jPtMfu^RX%*i1AghoE!}$TJ>)N_weZov7!hDdZ5!LF``E;JP_w>`65g#1=tul+R)TP* zG@E`lR^hExADg-brzRY5?mN4@ok<&V%~_u=%-zM0(EYu46MH*zb92*|AgI|f`*K+! z_;&ig?|++K{eOC$b(e71R!14VV_wkvlizMfHz9XqK-KkVPm(p^VlTJanNoq^-`P%U zyD?u0NqT=z|JQ`zWc?Tae0~I(IlKe78n9R{WNN`D@V#Km zKrAzD)>U%E*dz_R`x}{+e?!+3$;i8qxZoj6t4cL(d`_}&7|aj#Gx$h*LW0z*#{`qA z6zRU1S!d7rs#8S)bvY~Q6&1|JN=^-k%p8hn-W`WDxe&ukilZMNKDnR^RIMD1a~V;8 z2poLQp1`!xGRY=In6iZTB!#1pD)z{zxb?pOGx0{1Rn0@zkTvs{VV5rE&$@S2r-1|a zWa<`%?BIY3X$|QAvG!KMaWp}fsAS6mi$=`M%xEz)Gg>fWW|l3qn3dWoS32>o*?9@76VfC)&%uU z-hE7}+i4r6HgyUPJlI)I&GMIZ4WxMtf&}heqVSjU!XhH>--An24~p8|jG8m+*s@4a z+%4_cMJNR3rrPuB<3W9e0wJoEmQ6T2qxo2pWS)9!tGzs7cVs?EeqSj>F7B44zT^gW z*w1Fr728J-yuIiN=5MoO6vFL%1zqGX>Ip&-)TKpIPswMiyq6Rtg2m$+xGfR0Kkv>7wnsB0jObG5l?kmKd z_qQRN7pMByzuFz=3-GEVyLpD#PDP$ClxE}>M<&EVinkMTiTpc|)zh%ySijElF1l9A z7Qnr}Qh&05j^ck{9-<@(-H6$hpsET!pz_VL85S@k?&oh3&dr$Z~iU<3SmlJ#uF+W^p1nb|JJ0ST)?emria4Z#NWd zJ^77RWHM?Z%o3hEHCNWGJ@ymuI-@udDG3M?W3^}Y{G*q2V2kckmd$7g z=fRG#-^#KkYegVg3Xd6{KIlwDBV`?b+5WJ!vk`LMXdMMKROz%{)|ZwtPkcdVQlAbW z5+r{dD7moSFGYDbZd;JL;{gIy#ynOePQnUW#F%z0*!W@PH)HCIP+-nv)63{o!zSs2 zajob{`?+|y+|=?T;bg~qC|md4*|Eqq=ax~S-EQ5dJ)9WmH#ZB@1Vmo5WtECVk?cG# z5=j6 zTHhGoZnJA_5mT~&O=oaEkHA#@T}ozJWJ-l1zo&m&n}~?gU@#GETXH~#Ol7Zri{}wrZD>SEfMb|kqmWR49K15Bp53uWtx)PR(x-*>K=QjLE@wfhnvFEewnJR7yKDphU z)_=1kEbh!nJER@4DEHkqP;Hrtc^%w#2uUAmAS=fmUUMsQgl#O3>#U0{9;`f-TX3aR z^ct~BUyG@6F_`x=h&mvAvl_~)W0|y;`+I3?nB}ah#bj=|JP>8Q@E*A_x$R|8F(^PN zuA2wyL^1ZOWeTWekanYeFT2=8(Bzm9i>H(hT)TfUT^KuM^?kgbP-dGun`!Q3=6DZW zb7$9EI6XIEd}Q`IIoq$LA9#?xk@I#eCNOk-=!x^xyWO#!Wnphlon%F(HTmosNOqj) z4@EBo;sBxYTr+5&f5Oq-|1Bs(zjN7Lu%nwB-?W(B?=p~|jq~J$o|~F$0EApb{yyJ) ze($e*g)HoUNQf)`gHz$gV|(QFbHPZ3fA7NO@RqKpaq*)1v^3PBplY%k;`p?+z|W@` z+C@gLsXeo}Rt+D#2+f8Y6C`t;yy`@RUp<2AeD1bx$On{85Ctz9~MtEvllpX1y~`K+JaZtZ(z z)Z5cEo@#=A*jJUucA%Qvyf6Qx+~?UKhN$eqNd4WvQViw*XDY~=apl<; z)nH8T!p86RY2pz~DmeP<`QwhLUxz>!iCCePQ*I6>K+B8;BeMi8MIu+Y%gDhd#3cLQ zoC&A_8Bsc?U9r>pp#<)Z6apBJ`(dak=@5BY=5K1>U>V>5I-4O}l^8akGi~pT9OpJF zM7)*=n35fa$HHihIO!H`W350JYn?&pu4YVrJa1Ge*r868R;tnQ>nFb+Jd2AAN98}) zscyXLU|F&Kpj!EG)WH!pu5M{`XZunc?K@MuLlV4DIs;r^izt3=8{=e->GO;SrDsri z3CDG8F~JKB_g;t)<_fi0#Mr8v6JCPuq6dU;@x@ZT@~`QdNRb@bb77ElM~ZWUbbX`{ z)pZ6+*=clWDyYA!rYP#ZKPq2HGi~9Q^l87IfXp}&Da7< zIcnegcR$65UoxT5cMR_u1acWdn{KP}F`wgkxz*!r-R(6;J5k2oNbml0{QilVod38T`SlMAMDDM@8ji z$it~C)lw)q`>Ie3m6u#ncSeb+`q*EctaNc4_D)bKDLj(;Y1n2Pd}M))!kcj>I)3Kv zb#wPXVo2A`V$n0ZgYo5E<}nhghFvm(ESF^uGhlGz`}gA)b~VJu%AAmsas_I-SjY?; z$5LJVuAMXqyp>RkdB2SSVu>{_3#?vxnk&-G>KnF(5sH!SkdU(EnCERB`wHcY|cO{)~DN9lG5y-iNX?oR&n?}M>r|$ z8o2p*#Db15_M{oai?-=i8798ZabFUvxmFYLaICpJJ?DpcfrC!1DAl`>>H7&mVkNm@ ztJp0@5NvO|oqC}j#&QN@^rNo7!-aA}i+F`XrP@(XUnHo^JC=)2E1<2T=o`oX9~1u9@t?ot7jAI{32k02~5S);!$ zgGp_D)GDJPKApT<=fII*bUaHla;NM~GG|Hf02(Vf{{Sdf*I+@x7n@$-B}-_oo7zy{ zu#f%Q!zh8piLLF|W{`bNmlgh0Yu9aakxUUy%a*F*zd4t7lQZn1>neszH2NY!&A$xs zMz)tuO|3fTk7m*ly&2Y_2W_lc9OTa~viC#CGgR0#rzBANY_RedL+L9EcZ%0Mn>3b0 z{?8ZZT!wxx17m_+FFUtW{l-b<7_R1}pyk@>-~W=!M;4pTJm%iSN?o3+_vOT4D9CfY zbx%l-@*3~w`loH{+Td-HwVGO2#+8|%EF(lWIL1BG$SD?#zcN=A7>Q%E?o4+92V0>8pVCTS$faH zcggb-C1SiBGIhU!m_80A?FGuv3f`s!V@8xQ#oT%`_jSh3da%TQgJ_>`8|+RGnGAhi z4DGu;pKn$_-|DT4n~xO)44 zR=5f@=VJPNU7h-Pcu45>yFT7D)6DU?eE{cmtNp&Xaz0jbuP9Tqi)`@m{M_E{e}CS7 zlVjNJ>-h*0-1Jke1VC0B`jvskF4fLAI^TL04PS0knm?OsQ2jq2^q*@4g@@c;9X$m1 ziToZfyZvs*1pRKV{ol^SE7AmT+6>AIj+Sy*_ythE9}0Zjj2VCU`@L+aJAZ{>9d2De zE)*z9|L1B=`}yMz@MKZ=yJ{*=@p61t1C908h9l~NIH~@uv-;y=)qTg_qN2EmteXQg zNr#BGu2;K={RUQEDW?GHzEdRIkH$LtK zze*ZrAr~p`&>jGb1c!oDgUk4!(?D!f6KC6b>q>>ZwFysZk+udc>s)PY=zR0x&9my|7Z|>6NvshHMHtA*t5QP5yRO9Q*^V-?mY^{xF zbu)=B<&B4fvEJUbL(4^*Cze5JSsb4M9E>~M13c3`e?X7y{Y~o7Eq`zSRuVimuRwXB z8BlKA%)Xw=z!MqNOw*pwsHy8n9$njD)eElZ1Vrhy-elk@TVF^npEi@(h={A#me4cW zCQdX9gpNHn%5I9sD#!jlqd=LonNOsM~JCuD|82YpKTCC2=ONc$AMdcu%lXb0b|_#2oth3YbbTEQ$` zI;nJ}C~;fmAyhFEPMK7=S+;ZBs|zY9RO5JR;TA?4^G?u48+Y;F9#Xv8*p09M4UtaZ zX^O`45nhl%aRd6kTQtQHI$JcEaa>vKFOe#!u5yp_@XfVM@$e~G%ic<;5)wz4L-*W8 zl@RSnmLd!6?bEob(loeitFO2lRjVa? z5>6uWl;SZU#x>zFWZ#H`7eV5*a(TZh~bYqLdt#8Wlvnv{P__7P&g)pa77@#9GJ6s?UgHXR{ zY4g;vt19IYPoRr7y3%Lnso-NyP22KBETVpB^QoUAdGPJ6O0#`i{`i8wr|!wVrVO+! zr=~?VpF!83b9Ru@hU--;E34{N>rqd~D*kS_S!7~&TyN%3=W$KKkS;|!{6(kI{gh9q z^6nd-PHuw)X7nhWM@OBLREb_;Eg1BkrAzeIrv8ILS*9t$M2FE}s|1(PDw@__y&l&n zmr?QjPB6%HfPvvR_yh;!tRBn#rbh=VTC4$~IGQ$lzi46WEGm^&L!G&7i5@dGI2dy< z7z(q&hfu0Ts*JO<|H05VZc|VA61~`QOQUM+mJjeFl9lFC_f5G242odjC>wP0>`-%F z@Zg(A`R+V0PfAIMw9)ws`p_ViZYwlJp-G80QK3mH4cr>G1;bVd7^JXLkW8cuz^x*A z*+Kdg_}-C)h6ZI!#7dS~J;%nS-=TEZ(8s3mIP%x~Bn0Z|bjh>fV6wS0B>HSWv5{2Z z2nskxd9p$ifFcRpas~&IK5 zBD7b~viwepB6N`~37;_DsIV-bNan?}&2V(hf?s7MF9|jfJdhRbE_ERA;r6{0MPMkD zIXH6}_hZuvufq5qRR)!j9+EsQAyK=+pK>5@7@Zh3CkHjH@!jBb_WoV4%l{MHpfpXG zkB|`#ss*!bZyM|=DmqiiuIV62+;e|K9=ceNfKT`bwXikd#}~`$yZ?If6Yw*Askcqx zcijH_Eth!F(-~rw2c|NJk%OOywRa5X6R{T0Mq&g4Qr&u6jhjMKBim!%oq(es|K7eL$zP z&j_fVvUgurMDtx~>(^nNN|miqoEIu>V4*kf8Df$ZkTxQT4w5MXh${#a2t28tFy2ol z@i759C|)aZKVM5VWlM0Ar*i%vEEDsPJIK@HfBCCbo!y{SiK_5Dd5E=2C%ot8UTerW z*x+}!kS*^IiZdYYqXuX5-zhkZ6HkoRCV>mj7A@3?frSou&*MzcQ!f)@7aH9{y$8@- zFSXfP)oMQQRixgECO~xR5hR_18c2l>#7*){$Y0fUa8Zuxu;sRT7hQBZ<&S&lq1fBU~J#8#?`qTj_IW z6b89RmGBKEO$U%-e0Y>)Oa9eo5Q!M!@7De_&5Y76LAD$wAa}7Ywyt!wKnwbs!B-Bm zU+u=K?o499i6yB?krIB#a#&z||H!3_&sc<;Opv6Ka;%IE>vXW|jyApKQPTdT;jg(# zDVBzP^gqnuKFlyOU}sKTLps(ct#K)rsmFAQOP7#d8sV=kpAB}UFO3|NW*YL$ceq2xqg8U-rQ>Ud5>w=>!L=My<3jtf6I&?>Si+8 zYmCDDXn-dWJi(`Q=4Ae%ZZEXceR(A|KcjSbKXrF0s?Ffr4^OR==!P)Z7sshbF<+D1jBN%h2PK)8XrL z1Un6qiE9ss0cIr!AZBxH8)_GC{_5pet*1Ec6G;oNG&k)zmcUHM>m0Eb z4pkxxvERa>b>`f6X#s?DPnw0&aKtY&rrqLdRL)FuUFAj3$;lw^GYKwKJL1{455p9X zWUF+GfV{%RtmKl|YcrE;QVe#9T*Vf;Ht8g_eKY=TJ+*|pfi-9|;kr=CJ2XL)kEngO zjax<#o!a|J3PqVZr7U}$e)whhFI@*7TZu~~9)a&PH3bYA{iWIb!IlSso7$;n)<*pn zDn%8#l9mOF2@rI&euho|?QIc)E8MPFt7VHX4xL9*$N>Z$GI1S$7hDuH^T;gP%y)i7HC z#Ppobl*EIFJ&N8DAB)p?2hMft00K46we+nM$2g*6irVI=JB`D3EGCJoGsfu(NNx`gUO zXoGT&4?A}AMDisCtc7+4>+B3Kan5!yA(dlFG6oxK)C)U(DLPj_JM6o)qrOLYsnrQ# z*P1eaOG6o(jP~g%=PC}H3%OOWz85r{*|yhch=NEP9tbC_O582uTrR9MeWvtQRq9G? z@tySaRy}=*hxIV9aonzcoqQ#a_lM)ll8pRoi2|vPm}p^AGp1(He};0H2J8zu#q$b>$ANKGC)tM4wbIKJ;r zO?kwmO;S+YFxCU4EE^kmn-l1wrZFO_Qy#O&qKcKe!>qhaK1nQFl*Ct@hbv8pR)TK{ z{j8LP10{DmOh8@Zs$PQA!NiDCpasu-~$ib)n+55vLrEE(P5k|_# zAiP5BPc5_}V>>9iz{+O{4dUf^ann9e#I<8xwrl zuy(U0(&aqd4Kn4zPgu0aby}$uC>LAzdE}rh3rEx<9t%f;PWX?7^zZZfM}n+*Em=V? z{FbcCd2WM7J0i-NaxGzrl&V!b36!b~y9vo;l43MpC|QbNQ@2SjRvY6L(}g+Rha!JB zv<@NhNNp}B^2jX$4Y=iYWKoz^HCMNo*F|w0p_fAwCg+nal%b?{#8HS5LDo01A>Wxi zLe04q^iR!P?lyLB-xm zbwBV}=tCv;HMr~#n^4kj?SX5QWJ9ewtge+1!$_``^sV0uanvH-`*8|?pizgGwHZ@| z;*`cG42g~8a0jX_qMI_0$x83!;cEJj78bP0VWQUP@TuX=0?>#Fl3Z?5ldaf1$LGHl zaF1&k518oCp6;Ch3Xx(jn4sVZkt z#vHdX28WiY5n}nI#$#OL*MP|jqxzuH3#~Y~{z)Tn08IGT zyF-G7@{Bhtf4_oPhhcmjTZI}iq-XkQCpQl#!zR^iOix&^ZgQPkOc&*lT8fcq7K?;T zRdwE$WO^Oz6^GtMeBV*nN}{Wd8N=gJ%_GO*n#wq?!%jV!tC2QfqGE{&uRR7`grjx} zJ%BSmTJJHekuzXYTunA?G$>wj(rZJZ1Kx`z6OV6}*^A3XNeerGBj&2ZXG%A}L*f`r zH<7C&_Ft%~0poIw8t~Q2urU5?E7Nu|D%WTP#|gF3Mn?;08`db}gsfARxsHue4IdH{ z&*Ki1!*bta#;Zb)S@tOM7$+$oG0Lx2N*4|vF7lAt6qn$ZQl~hEl2UgS{3f*+w#YL+ z$UI1B~`^RMTKGy1>apPbpE*M3l5&aRn~66l?Kqf;4gX z){B&I_(1AEu=zffdX0G68Lj*Nm8G@2^yb|t^3ohia1QKn)X^Xz?}yE@c*+0~I(DjB zD&$*>TR1k91SY3uij?OLgRp*hyEM98$g5ZI&)BG*FH`oncqrb%SEKggs!!|ut8Zky zLR1ygDzK-$@qi^77~Ul*+^YN)ievMQPoHBGJU^`e@aRyhsPp6-|H-sPv-8{h+L&Sd z;M%wf49vk~F)$f4bX&nXnG@hiO;7)huoi_WB$IllJmJ*h7hA$9(05xxWX*|QpWlhD z+|<=5gbunFZA>{Hi*K&z>gG-(%3m|nJ;Yn@Y@Q9+wi63eymnFGRK3Owa*!8t&Y#X) zZIBJV^b2J{VIS26z|dE;D)13Qr<3b9ROHniAkVm>rEl^05sdm zFPssfj=XTlyK<;MDM<(jYw@`kw((zEP)g*jzO>+zVoDQ1iB(qjR?>W(KsB(t*`qh$ z>BXViPWsw)XfDrh<88SzKe|cZDG@YNe@BSY$|d}7UfwEuh`s=0LZ^dqraby)Nm~p7 z6!r(Zg5BML%DAvK5Ukq{B^L<_PsO%PWaft}z6HPE=F2q%m#k1w1Mg8y!_c7|zX(Gr zrVDk+Bub}ZS0*u&S#sZ`QY51m!l7H8M+L!+m@^n9pNoqG#aFZcW>#Y&HLlbaq2I0| zmd|xUJ4<5!t%63p$I^bm6dJZ_PA5;i<{=5m$`z%Hi7HG&0k#>b2HQB)+6Ti0#TH;t z0rHcS(}k*!nXgl0Ezl?dy|yx$La?K}mS0HBMc&dVxKV;}f*_pG%>kroGU>wAPY5!Z z!leqRW`HmI3Yo%xY9$?^ll~~9n=8RtT0_pFX(m7{%anOYS*S%6Gmtb=PY_3{XA5Ij zatDsu{>C&{3c)P;71lG#2CIF)gD{HB)G2RxVbs7L$gJTBZS;2*L8LexjYSrpTbhkp zm4+fFOqYydf*9F|%o3UeZu&O1CGKtqK?Kn;-VAVql)xV7)5?!NIeE{k5WxnU(qxb> zJY0jWI3;zAt}xa3#vR56>z*Z%E?lI0y#?doWqNF86 zGf6TBNYG6Z8`q*T(@|g`!?|+&cQHE%q`Y*H@ug)Ra{rUVp9PtJae3*&=#D=TN{h|Me*IH`7ZjD$yFCBwncVbm59MXo^kUSCgP(>Xdt9=) z_*P}fMy?B&$>95w`QZqkDMkog(LloU(Sn;SP&}(zh4KZzK1l=!zk+G45eXaRS53TLEReKMfeU zcWe+}mZ3ztTdoEQB(jQ}DKtzcXL%A?ZK!UYu>Vj-4#wW8%1O2D^c*GftjcxD2okW@ zXN`~XRzXKVjK~WFvfsZDs`tzo3eGJg{+<(NTOH|ug3kmMupB?3&n>VAb5U?sgYE^^ zcPsN<$#+`s(tXbMFQe5&bA;Q{BbBoo7&C3V4*WAe(pHfUhToguiGKMD{1%zu@%%cd zJi-3rT;|%4#JHY3tW~mi-9RGH7a8LvjyX0E(7oDgsjc|q_n?COBKlM1wkMlQFRT~B5z<5yG@s@F^rIZP26sPN?dEdx8MiMr!t&`zvBk#UB+;8d2& zi80ziFcUXC4Y%P#?w3n-RefOF)uW%;iTl2r-W8@5U{=Gq%IF@Ua&YCt`kbEi-C!y%#btiqJk;&3XP&#HwemBP;({z42f^LP$c+y(cIgW3AaCuyId@iKlL{zly0-C=a zQB$u|ZXm1^SXG&@7vSfpCn!VtIC6;)ZWfDLBvG9xV^mC@xUm}Nh2&>& ziA7jCM5A7ucQn;s^68pDRdd>Qnm=>PXLQSsZ7N#r_^$0W5e4FDi;xmp%zQ(02GoCJ zI?~bfEv%%FQ$2;yq5?z-z`&uUr5W^!DVQfSpNs0k%`SX_heTyv)Cdqeuu3G>Pntks z)(0J*4gXwAZU&v)xalh|%*#&S+mgw<|0S3lojenztHyD0>J!~h}u zpNNP)KOVcE9yjj{j3Hh&)O*W~!$PAPVKzHS-_c)u}`ls^Bjv&Ja&-2VTt#-yuO5dA`X=Ju}+B~3oKaNkV+ zF#LF?k-ZjG9sGCE&EfjX`GFnK|KTJr^*!(UKJgdAKB$S(fqP{TZgthdX4T}V?$x3Z zaq8G-T4a{HK?g>q2K$ui&)4%;2eF+zFoQ$QO99TcqtPFC zopM-2=#K#cB0uF98#?|jb%kzsJ%&mP{RN;R2*ca=4LeqCo>@3eDvo?B7`kdIv5IlC zb)Gbi=%myutdLSFOdn>Bc)zZwG5okb=kkBQW3sOy`nh12&a0fi)Tq1*4_EjhWQ#?c zMGN@HDya+6xNuY;qcZ*>tHl(Cz5sh0fLp&>8!?>kyAmE$qN{7<)r)?#57 zccLL-4sPFuB1wPw`=!6QCEOeW3`4*X?ldToQ4Xh$4BiA={-G(91+tG7v&NtJN=+KO z*a`O_^aGS}^>_E_Z>kTC0y?BO9nnZa{JG@=M=y-Nqk3fH6~0<*cUhs6G>tx}8}BY*qTS6}Y^dyir8obf&0XV(8Xn zo{#UGVv9NT`a^1&+IYm?e6bB{y!MFiqAT`K3Q}ZiZiDAvw`YPg$i$e1Vk{4pd3J+7 zoNwR5WAbA5;Yr+fshTtOt5n|ta2%xL9jy|(bcQJRcb5OO(+YaAILE?1CVn0{mTQ4o zl5=&%deR&evT+kHDQ`+cwB`5o2qC*AmV3!kb>xVM zM+m42gR{?F-2b@Fvf>< z^zy})v1<^20yW77@O?Y*oViq5$>1{L;*T?zE#~s$8miNHVs&bl*P`ANXdeZPkkI^z z^3!c)8kFHoUaiQ+J5H%`k=&ddpC=?*@w3(~RO{mC%NF*X8ojEqDc1Nl5IjJ)ZAZYI zS5iGjgnF9-!hx{?ly+Q{0lcghki@=-y|sL4xIArPPdej&y00BsbAz?lp=;8EDITMrC{l0P(7%KA|ci;4z87bVj2F zyBdmr-GaTYj4w-9ebqoPeO91Fd&A(S+Q2Lv9OenP;2$MdQt#bmc}M!;33oP$TJ}kQ1odvG z0p{Djhb+#}KB2_q%EASjX$xE>B~%G6FC1DC5))^dyr^mIDXO5d`_j&ocgVR`aZM;m z5i9yH(ce?@TuM-Z02eBH1C%pU^KO7#=N}$`&NFi8mNHkOB9#86mj_fOZ%Gp0Xb=>g zCpxyi25smNF!M)%63^tVEX(e)ymOZg&(9-jf29%S-hfb} ztJ(#Ol6OOd_tCo4RB&Ew_&Tn~WB3VK);GJlP$`=L!qL1Qa&Rw^=6uT|AtfKn>sdF} z`@VLb?HV73n*nx2b0DtNgD;eW0aF*ERMqBf$ZC=;k2%C&D2dTw?#_t#SagnvcJ3CR z9A_ADN?URsGV_r7apQldlfOp;bS{2`Zs|_Gg+Q=k8{InQ&bHX>r4OQoZt=2gg)<)+ zVneMj7ivK1)&o4Cbmy>;pz_DIQ2sFP3NdFTCJGC&zrUcW9m;g0oGF=Vp^Vauf6qY9 zoEnqiY=-}dM53&H8vTn7ZbW83*J_GkB>+nFuZrWo4_~tdcbUx7#+H|XMqO>vk`rtm z#=RYE8HTz8Y+1M&5$yh72AvUiodOJ_zb34(Mzig5P>VbuY^X&VkOq{Vi>$^?mV>+a z-z4S`$-nwAKgF-I3{!-uHzsT;=3J$*q2>m}HK3UFWi-C%@3-Fci~y>jf|r~Re>>Ca z!0jcbB#qu-R;d*~f~|`d!TEi+)PUml0zU-O+3-a8sxwmMA9IkgR^5C;XAK5)0VjMl zTwmhbCL8gPn*Z|rE6_ZAP)!(wLKEgW;#4l}kmL)ncfzC-;t7Rc#jCqIyZ`E=xoGra zFMjbu=oduGFD0Z!EC}_P`u76#kGj~)09(1w52N|kdtzt|iXel{ZjwaN7N{*9;YH|a z8YpgvSWG?2I$$;YYkh52hllud)=adpQWl-FICIv1sxY(qf|aC@m?|r(NO5zVi@Ab1 zV2eBZ2Xb$n%u)`@W7OefpqT!M3~rK6NfJOexiaYJ9!OzIq-*3au~NtDP6#zz@K=xw z>T)s*CcGd%DK^4a7ml&mlw#9^j5EmKa){(krUwynnWOh3vI5|G!6)U9RTXqIG$zyJ z%*G1aG}l!P+ZEn^4O>myKmc1DzkChb7QajYTU`Oe47=|^F!he(Zjhg(mZG4GBDdHA z1cXm{=t`qhL5KeG?pc-DCuY=<)U|5rde^Wb+O zy=cAwYbSj=2sOf>k8NH9%DP0j!3RNd2u+BX4roZocqFP{o~9!rAu2r&AKS*?GhzaK z`hX~&_Y7P_tOIQ2e(2JOy)8q;R60OE@9v+iFn1cjyE&$_J{_0|g<9@&v+(@4AbiM3DI6++qqroDOO+fBNK8Iw)% z6vYH|FCAz+=W-if>LN?zB&*#QK~5dVG~;~nj}zKlx}?4} zS$)riH|&MV!)7``89FeRrbRAtMzg>_c(i4nZN57K3Hj=_L6zqTi5Ev@(eZX;6a3^46CL8`84s88o=w zMbd&vc!;70?`@AQg#kF9Cx_-j;Lg_R|I2XKX+#|_2xQp`(NFHZA=e$1+e!HiDJa)~ zfzRT-m$G$2HEgffc=Z^ftS1KtIZ|9wqz0c*58DFLzLMmUXi~ezcZXX0i2O2*NAjN) zpcEoi@=DF6!>ACG`jEvK{+B)W2T4`E!$9vdoiRM_4Q$@Ge_T+KqZxc5zWAG*cE1g3 z6YL?c5PM>?nPPrIH<#$xg+X%x0&B0n%OkwUcJXnWq-5#AC*8s}1%n;GSs}oQqSPOU z7$wK=;Po{SKZQg3%Qc|m*Nv&P1&?_mwB#LTLusl?JAY@?=6)bA(fOA-q{IN|G7?ic z*kUm*!rWwbATu54T?lYzVO)6G>HdBaYe>SotF>yKf|FV6 zc3gF4Ji3~!Z1}B7m}+9u+c-^E{GEZg%ZT`!I(rhymvzKG!OWJ&?XDpM!9FEQSmc>h zI8NBb{6lblh4A@tL{|VYi3ZUnOrb-Pt@P|wm3N}-#a&5uWo=_aEL(n2#)O2SXR}7$9nr$noCe-)|4LW7$NE{sIq-I%GY*uCDz%)ka z;eu_q+ojyCWLhJlP$KurGpWf0#E{pVv7gZ@d0G&XJS2D`7TYd_Bn?|T;Xkc4VBvq# zbX$JCVo0C-`h-bg2#Ej`$%3u%E{Ntf&a2zntXFFB3Cv^JYfntG(v;83(vW(3&s1I$ zEK)*dwO8WUHK)j*YHLOms#j;M_OGEvYEWlP*9q-=tO@gXIW>%X!&?;e09Lmth$EEP zd{X-=cz@<%uU8nPe4vR3EPTXya}Rk$4P`$-;>4H|0UEO(uEmi19+4%|`vkVIP|wkn zEPU>Wta)%Z{VPF&-k;gM5;mXNJHoo3dC7Cv?=bn!>o4x;+{Uk=y?Hz@kB#`TmqdC} zCBF2*(Mul;VNtg4?KV$}NBzn|)S9RnMdm-q@DGc3cC@~B}F#+34L4s zvm?9CX#O}{IF|G$RU>uUMx;eenByD% zmoOfP&@sjblti8QO51J%BVn9};`VcIbKfKsa=#YMfJx1P@ikFjyFqc;mg)7^hhm-L za@^XrUz~SJFadU}`}UGiE`DJ!!62@R_0o%bzsBT)q1)=1z!pQ?S%LJq%W3!7sPNM7 zI7*9XfzQM~034#z&*cREzl!TB^_c+|K%YSIHuL^Je|QRf9??Q6z7@%kIBxW@~=C| z?&T3dt&E@j$kk)9BXy;bxz^W5_WV3_5IdvNRwnux)He_Rvwu@1XMy;Yox4(PCVEq_LKg&7qq|$Y(TSP0Zip$dn;N-WeyO5MQ;xSzEBUC6 z_3OPot6aKkty+FH;^8?f&8Wk5-hNaguv{1VKSl+2+T7I2THFv}l>Ua0@H95s%WC85 zZ6>QQEp(wo?{UQ<vne95rX)HHtcNxGpTtkRw>$eekj@;XL^92!EdXyCF`z0XJ{SF|h@ zO&q>A&(;MeotcY1<(FX1>)~su5k(@!9L;E1rnDu$(UrXiN*7k&Mu(+g9=0vl3hr%) zQ3GjCC*B-}h{L_}>{aCeCCfH5nK~tH?DBFv*l4-Wely+adhQVd%sNJQTSzt4WqM+v z(qE=M0iEe0>5QqW-UgDbUIy_y@fIY1@V}u#j`3vL*80*l9-T19U*}bj98Z_aa|bC= zMA7Omh|sRB#%DK5i+Wa)B?ivPg+=7Y83S{x*CrgD&>ou_dq?m!W&%Bihj^M2 z>Ic%U)-xcJ@yIL~zAVGx z<4>cKxCIfKx>|KdYj#Cj>vxrP7UWgsKMAl^8k;m%f3~X^V^qjNVBD(6V{`^7(ZC!2 zyE!p#TX~r(2Wqy*`C!k_$uz2|mx!k;w{O4QdzkUBuL;GNCUT*U$0Oo)&u%Bi4;tI0u3Dtmicsn$sOFFoc^?dn z{g;qc^J+rlNWIPb!P_GU?=lFw+%!K^DqO^A&nUzXa!ko^7ioESLk?GMC^ z{dIxwxNtR;t%UEy1)xHwsXpYbl0WA`ELF}XFu|!aiY(1GUK&+6)Es38w%!ImEiBf^ z&iDACj09fpPE)43-%bxBiRG5R;4QvVUIFnW5d@BvC~ih^n4H78hAcMdU|Nbz&0fkK zM+N;&-qBa)VNW%&=l2yB`o+k)uUVQ;ZO^}Xnsk$S#`D6W{g$SV;2E5DU#7gC$>zri5 zn7v*p*N(tE>izNfB#^A?Wc*CYR?v%0w2Cyy1GU2q-IH22!%4Eh(sX#tBJhG7!dIwR zPjI!B5xAo%5%zo}H4Z>YknIs_Jer^L`>rp7t@9R?!`Dr6KS) zSs_koNI)j(ABPk)x_Kun`Q~2esXDg)&oE21cd5R zOgW4C?S5Q%D~y|mMWS#33iAS`_`$=uGGFgU&%f{~J5;V5gVUnVvKwti4!`<`YKxZ< zeOdF5ikDK%8(SP-Ck5=;UAxDm$MFtg7-uz{B0Hu54^iInbV{Nj>vDT;mUPhWFNldmB?1XAWS|BMoR ze|#0zvc8l|Z@-pT^Q|SnAF!!1%r9k%TmwhQjcTKvwb>HH3p(m4lPKCTkBE?_H>^ky z{=$G{^k17FZa#8YI$!TMjtoC84nEu84>ykdN?&vATC$XRItnxdU7QWgInT&+lsGWA z5V%C5=oFRO8bEfxIb-h1h^JqzW6plRq01_G+R=K!sAlo`Uho~?Xf_h3%Hb`>%8g6< zuBCTdnEe(e@R=wZEC}b%$!Z*Y81XUUv@GAVu0Ui^lG^wf)kxnu^>+?qUdp|*X4t0M z&5o5clv6#cAUY)K_#e6%r}Z2~BWOqX=MT$^yTPH|@CG$?Z9);}lPk0envtVRD6zm; zX*XS61?jV}#lpXOIEi$rDhrJdJwD_2L8Fp)t%D9gPG1s`>C4hWKvKSSrssB*Q&{X` zt%>^`bbWlE6VrapFS56vI>VQSI>TE^$R3ux8t-_w!o-sI-#fc>Y_LM0A(wJ5Q!`p^mKVL|z19aeM@*lJ zwQ1~mr|<-1rN@t4G8(F-d7xQ?9&OyVTqG}_}@V%#`S5P`5u>_MG3oG4x-l| zQ8eX-VtbBzT%J|RtlsyKf5K@FUT)rDPsq7Wu^2n9(pnP_g_!S!KxSXO6z~QxQ9PLi z{;h7}_MMZ`(G}7=AQR=}FXT2JBMIVW8}wT9ahW!KD^yD)j^H;{E2j4CLr*dYZ2c$k zR{XF+5Q6H5Lg098DkWF&REPSS&Pk<5Sd~*Nh-|@R-L4M_5bfkQwe)W$}0RoKkT9mg!%%6iTjE4Yo!#HC{qY?u;YwU(Xu6 zSlBAxn7Z)ui-cW8B=%x1LW^2Yzeh>=X>g^3R$sNSyI-%$nXkn5*ai8++W$cc0Ui?r^fpW7c=_%Q&tlH~k?94wm+}?Q6 z9ke{UsFX0}IQI?*F{lv1VBd9NC@S&9yze9qgtEWClcDEH=i2u{1O+FMVii7KVw~m` zkU--0!TR3+5f=y$->t{iLTRI4K}{gOd_@hI_4Ww<9?>ZvevXNVMxOX>CpKVJ1F=`F z^9l`9Iy*iLfl{eijCb_)fQ{(j{SrTWAJGFv={8sZPBuzhOAHn5=)YZ{Twa@r{3iOjkIW+q=wZ(uG>Cs{D8L&ub>Rj9l!6^v5Ac%Bhs z8VC^)jZkSjHs#9Z0lxh~WNV`$JNNwv@23HM*ZuOXrp@&E z^hUW=$F(3DG&OK|i{~WPxSXKEKR_MKELKb214VAVKmcwuzTg6}AG@g%ujOvZpgw|-LFwBS) z=OO>!^sA#y@;Rs!7(sM#n62L~B6q?!V~6bf?V3!Vna#(H-N~sp*cesTZ}3YJ!67gl zqmf2O{e0Jf|50L0ZNwV4Wio{sN2EIsO^dq>nRY)3YGRp&_a_ap>KD5XD2uxdnbPjI zt+6?$)E}@qYyLD~rH=@y-wzxFn-#n4ubFNsvvQjW<)4l{wr#)cM*41pdcf#kX5F1{ zo6=sq2u!yv0(q2j^}rM6awoU4Ox!<}f;U?i_U33h@{` z|Iv=}Yq~1y4ky?42R4a4GtZ5SG*`{Fn=FT+7>AQvhuNbuT?CYj)q*P}gfN4HrsM2a zMjlb9(0Vx?4gn(A@WgSs;WXA^tonP&LDTxJU=7fzRuDPynzH7_?jKcBTvlY5w4r#! z%go#fMFS>eR|gjm7OOFse#VD|>jTUOr1eYE`e@-V$CS6*5M~!)dZWfvxmc7|2UT*+ z!AIF-;(=3v4tp2)d1qWs_y^-YYe?V9>bU}*cN;-hCQU@4R|Jg=p;WPg#C=#Yo3T5s z_8ei5Q+Kt1lGK7qL>T<0N^89K16KJZTLU&uhl3mZ$l+U8l(~TnK9rdC0Bq<2`QAks z`sg+FR;x`%jIuEvB?ML@>0~HaN!};>!dB0_7=M#Wck3Mxyx20RJJ>-7aY098`M2Zg z>V({90`1-M2eite&3kdx`uIIbTja&8AL%C8*;GpM(Ea>dzQO(;R<+iCe-*(Vcd>49rw z-j;e1SQzmwZeUhCr|BJcPTVf-QX$3GpjER!d&m_%xhUUl!zCl_(nYN{t7A_`gB?eU zv3I58G_pzlsVs_{<$Z|~w)0KJN;R4vBhJ0C$#b2_3Q#>MMTcAkvAO*r7{&mu7XGp{ zOM9sE@V3835;0*FXd3gwSZ|pu56!~v&>6_T&c88dI`mo{4lHW#&omaC_R3~p`tIJp$3UOhE zLG`&x4uO1A`!DZY;&em*#up6lZl;3W)FeA8ZOaFe`e?Z<1dxK-+2c|~4EV;@Q@U~d z_2_2rnC5kc4}$cIw1{`tpJ=P)FU^xQ(Vi{ku6Mm2Cju_MrO}XxekP|}J;*v57A{DL(gVTOWp9@$FC&om za(5&b%C)?1(a9~%%U9o?&1Dxc5biy2>fb_nKS5;|o@4#1%hU(PR;<++j;$~;N1^v8 zC&lPh-$)QxdWYgqDtT zx`&;Ud!(}|m}`6_dE??(@;m3lW)LOM6GbECPU{7b3ie-Sq@Hd1@X1Yz7@!wq*V_J6 zuxc|r#P}zc^Bz{DJp6E#@oi_d>+A$e?^9veMd~`nCsE8kM#E8}=KV*S7^{$>iG)2m z#p*D(PcNY7-Wd@M5_1`x9-L8fL@2tEtwLzsqIW_lE0(K3C@RHrL}<0ZszNBEkz+-O zkI>ncVzG?9BfwITV@8+`tu+vp76O`x*td*eu_F{tWNA2-(#YB)g!jH;lX0QRqLFdg zjsVCW*UZq!?l~g>WZcw1v^?+66p*M=;x>kN7nuR3=w9wVhUi|h9;TjB!ZrpNXkmKi zs~%wFLfY$$Ji;KN^*pZa0D8D^Wzl-L97n*9e2;(z2H}7nZhjzI&*UnFKuD-*yesi9 z$rYy~kt!n`SK?yAwA093PfM6EFzAoWCCs4@Q^pOLljVNu2T$jERZiEv<7sFay$`PD zEGRQPHDKW5JvI8F{7bUTC@DX`wguUoRtbLpwbX0%S?Zwd_&zjP*a{V#jot(KoQ?jM zT--$M07BF>Sr1Zr3UsygK)BQJIgL-t=YRX2gX<`S9SB{+G+6g|MVLUp)OCj00Sl4v z^#(817q6XsS@Qb`*|KDQD|u=dE~K+kkQStTzRCfFd_G7Ia(hJPjRU4&x8*MPj~b!? zy6OirMQJun59xQ&Q|`pma~qVv(+X>BNCH)r)f_T%7j49}0F`Br_)9k(M0(XfAW{k! z?U91X?LpFl$?-J(m1QGh z|6ZFaW-s(+EO8wZ_up`lagnGIdI}H&17nHqzC@69e!3o}d>88>hWwPb7N+$PnHh$B zTah-V^OV;%M*O7HdK zBU-SV_IyhE(rM@r+JlbD=G$~iYej+65rr9s>K;%Z(?sb%hQm&_)5DO?y>OKd=nfFU zzUJd#%RkpZ1rJt^LV`gn`E&M5H(B%Kc>_5PkD8Wt!aQEw1w6glY%M&fbWOa(xwo4i$9Ep?h72+t_8lX_WjD{*w0Qs)!cN~-jBo`qHNay>=8SbgQ+|?*v*9bUN^L2`z>#5XOfrBgcyf33E%^4mDB#=#Sf9!EVE>;7M5cXgkrb4 z<=xBc70)cUp`_>OI7#$l(&j*iq_#G)dDiAYOTsBY@Y(n)bYkSmc>@=cnMi?K^wu|+ ze;R|?2T#6~39v8p6WXn;7L*QXXx*#*POu4`NSmrCujln#NY)~z^XA^hoM@BTno>f| zUe^Jg0nVT=E7?KNHH|XfA~DRvOyiu;uYkr}wqF+)`x!E9>}qG=$hS0jdxP8$Yg1O$ zZ_!sppj$L33J#gV6iF#;#p->(d`&41+ixumjU@T4uH(|s^dc%HsJ_b;i)kt?g$=$} z(WC2E^d|Z)@eaVooO+@kbF(^|jp^<0QW}MpBoA>Q&C<7Tqo@E#QQuta9|zvo@P``g z&aJe!!f=*a@otS>Gs&?-j19s3YfA9lZ{S1OYP%O5lF)rkMQ&T=#w zlhxNq5+)IEsHO8|RbhhsHsZ-7m6CS#$$8dbO`F}%B^OWC`E!wh*z>AlX*vHT_x0sY zQQgX(Of^I8py$=e-Ln6RYT{2Tg#_zbX?nsBIy@;p*`s9=<_WB~%(HyDrJb+n3lE+o zmIOzHlIiAOPU9#i0#iC-;TyBOLCNf-Ej`&%eLgkS^mVDe3G=V|B$ZT?0q`BM-JO}( z*najOq`izrtEvY078984k~K=aA=>gce<-fvy)lfF9k*RY2+CZ9HvC`2yXB=vM&_R* zS>;a8_~s^Dbo372<0!{>y{<#vCPHhUR+jn@>KN6o#gOZseHS=FBStWEfa3TKGe9E_ zFJnnIa;7u0e=6cSlC5eaQ~!1?Yb)b=jlLu#KP^htHn+%P!JH_1V+ElRLcS z|Ef>vI%FmZwz2WXz#U?ygOjrnMc{Vr;bVqrdtZ$! zz_2b!@wG;1-iP1- z093(?PT=8yR*|a9 z*b&<(_6a+PalOrx2!q#72L(kYQ*a82lLUCrvkFh;y1VFIWEN zPig#|EnQ>MUnMYXY*dXv6MDtRK@@t%$H4%HGbyes(y&_#b)I6?VpE2?IjgWa>>IUKnB9eSon{=YhO(cozL$|UFtSh{vRhl+Xv}yunLz zp)l|?l2V8RwFD)8GGUk;2v4Om8YsKHKIpK;sDp&m^8((Bheso-2&!w`g1%W=WHntj zzfA#%R#;n_8|kr%v>9YwUP~S9LA=u;q z(++L{dotJDQKuss+4af125R)h!~1B*dTq)bnL#$N1ldk@^xYzjfZ^@QhZ^y+ z<9@@Pwr|r&D(%1()oT$JxfkZx0psSOcLwX9b-SdI=w(wEBi*_n?%UZc^rJ@@dbj^W zTM5JR3pqK}VhFZvf?yQqv&_yh^dN<|pkRqnAo>;JUq`Pki-&jLm~?upMHC7K$Z+B7 zh1E)Z&_Zs-x8G}LC99m4;B?3$tLb%+&d-YrN1;{f)h#$v3OV(FU@kqT)l(Ctq0fae z?VQ{exd3S6ABa#NN9Lu|17Iz#m75B4Y3VK$jDB`80yTn3ZT1RPR-CM6?bRjZ08e*~ zNoT8Iu@|da4524WGemIfQ)BAp3N^FbRSHXkI&97huehwE#vEB|&D{EgQGL_DaV<@{ z)c}SbH^O$hCnLwsrX^J|4MzTB`t<;2iH(QJg?;B%R`u*mMeO|MGM&|o?it?|*@KZ& zXVZd_Q%<(+a@j`J0qBJz?y6Zz*H*S&O4oG!1HJTu37H;PAsb-pmvu!R$<%c)Id6Gw z<){Tm)?4%K?~Rke>)#s|CSU`*(wMISmqK@l{}irMx~C%?sMG5rF(0?Yq|hW<)4etO zLWAvMCt7x9L&Kq+Z3_bi)NtOw8O7`GQ~E@O=2(H*;!0m3Wzb}n)7Zi4%35LxZ6KUF zoXdSNC^MpruPZkFoblM>E~qvlc%bExMk60sT<$0Qk|p_ha8Ktw`X&4DFLGYJe0^-jzGA-D z+SQ-bk1>ba`q(piE%_%`c7d47ohT#$uI1&qzc2oMn)R`1?TY!Ij{8X!&|A0liZ9y| zXU8(9oUJUy3MXa7>n+sanP?%pdC0|=0n^iE2m1}iG{Pu&LMmwt=3rUD&Cxul(h9mGP8@- z2OYxjyW|uPq;hZFiPf)Qi)ZB$6_&e+(>#=;N>eNSmu1vjn zJUSWF=FFX~OnvTtzW20DDK{e9I8r+}GPg`!>Ax?`9?^H-IUhGuW_C*PJC{gN2;!?E zRTqkdor-xEJO46)e|B2&d5Y6)oI+O&ryl-^IMcaqXD8;vM7FvRB<&+V^i&ARjNZY6 zc+H!UI;O={N;+c@&+wD^W4rWAmu6PpSpo%AZ;=y~<)l1cR=!s5vj`SMyIH`3du%lTuw?u7@gtRAxV^ z>tcom1ou&LC5S_M97ooiYN~1MQlP0v2%V@^#hP_}e{%>oTQ3L~1;g879%qiDHVh6@ zL9@ZSjO7a}is)aO(fbJ2C@EpHzR!kyVN9`V`=|IOTUB`_h#DQzjg578cI7BP#&_pi zApdWf!?fAWB21Ffl(@*=-Q&Iw4=o6R^IR;;N@F3asTZ#oBw2Mf6{k#4DiCsnudsp~ zYF9$H-grg!^mq5%tP+=~Ow0VP=FsP!{Zvitv;CZ&pF_anxXG;w4zy`S^G>$%r*F?S z#@MgY#y*SxPjKzvv;5IU&vT={0zS`PgM;7nL%+ZaVhFv|3?~B97_yCveSFz7 z@ecWZEy@Wx1>fp##y?_pZo{WUC<8>)X~48(WEC9+-tEPDhp4?P4|l&fNOk_B+_#O? z5R*J)_n(RR?TdN*5AWY&++Jj65WeO!n zK0aoJFPa+0cDMn?_?2o0iLGjwFWOh4Q#6{v5zRy|p&FxXi<%w7X#Yx330v%8O&m?^ zL7*45@8SP$vtZcjC2;%)sxe9psU7kE8e&%AmwGu8NuFv3gDpq_mi6@|lI;@A7ObR6 zv??Q7-xGsqZ>rqM{YEeQxm7TIj&3p`-XRfjU|Gt>U<@DFzT=uGYb>~YC~MWonkY;E ze~SaT*$!nrH76&MkmryH&UTzd_r&+_uyHiu9iZ>NTmnt(3Aqnox}NHU-^|u!&1E~z zhqAyGkBegFNNrJEyEo`Pp#1Kb(9;dBg~fk5Ac8`BKT5V8^5F~ff4iMi9o}=El{6pn zd5HvPOwvt;Y+fQ+ZO8avw(QU}gB^4yjgtVo;@9ty31awe2MmE%DbYl|%?yTYgZg}7 z#&58@ku#U0d@y<`dUk7%8Iowm>!50c#w{*K{EI4Y2`~v!ph4sr9GK(?L%vH|kL_M8 zLd{hVRE^PU$mfW$SL+?Xy4RT5^Ii3j%XG+w4?geJXBR2qb$|jMY!N(^V>lR#IQG3s z?}2cI`;?&YcU6ZF{H8-9@$;of2Jz#kIPm!3H6%0X^4}*NTzEl(+yd6)Fi%ZwtVgdo zq4l{{rUIa!j%KUO22o!lciPHO!q_gSHBodUC}C07|KzkKItV%T8827i)tN+RIHQ^B z6;|UnGK|^d@3H#~blbH4VrVWnstSG+SkY*W8mz$Ilg;Xx-c$4$z)v{^k9(jY>-S@p zY}bU;w8<9auaGku;4`pO0r^Bq61oAipS2+3rZe!UFp*)9O%Rd}MFjeZ47l@pne+uJMJalD+#1TMkp0h|QXaxqV!y@;7|HZ~gh=qXsOzFa>n1b;!<#_yXuwx>snWRmI@e`NnfWTr0 z39~g43x209au!LXR2T{-$?QKL>06(1Gc$diNfJltFSB}6sORvJo{*)<@qXG%pl*ArR!-ouAkcu)wEm>I|IMoL- z*#6*rx5BX~S*`IPD6=u~p&=*}i5a+7M*YE<9Zo;zycbczKEV?ZUiO|UEB+vRc>Siz za3@@W25EurAP)^cUfG}*b4t=(ZoM!!Zc?5+zWa}|?%DVQr2DVWDGIw%y+8DAha(Ex zXSez%Zd>l{w;GzX0Xlro>60bwD7EP=roYQebuwvswhD~NF?T_8k%-sYIu3m8%{IB! zg@89twa}p&rFKJ&zttz$S0K%3UWu_w`m-LlnuVv~uc6~AsQ#R+=O#if&y$o4OAlU1 zM`4G{!SX-@N$8`I{ZdZb`mI5N4uRQBsYCl0JAL*GDdTMyh5pR1^qtYKv^?sPtY+Y^ zEOO}nylwlSk*pj6mes>#C?O3+L{0Raiww+M)x`^*cCW<4%#y*rJh-yZtopsXzgKIp zf>Z05V~w^$Hq_4B10)Q!<^Idt%#<_A!_uYlK7e(Ve-7juY( z<#vcH_9^DY8tvCPESK<|Rtn#xsY&hIjNT-c%Y>pmpKiv!Bekh{3dfhUcix3Fj-G>c z-|Az>L4pc%{mI4tw#=5pOGL$=RygaEY?hN3-t4D4P_AK7P68QS11(wRXI8kT>ywML z%~__)nQI>MRag72Xqu@G0%0`cEm;wig6>TmElFb!Q50Q)I%uVD{}}=`Uy(Bu4rfe04E@y_tpL#EY zDDKQDfmc56!MER=qhTbCN2Gx=2g~^hVaz%sRh~Z3d2e?_qI`nc8uVEuq!+yQ(Y6dA zwW42zj^~R*u|bT^E3$cb4^;>UNpw1;nZ)4!yV{cVQhecY(;WfPv1lXCM3^=vcPZ6^ zMv;uBe6Y2T|A6fA!1<>|WH`tkjg2d4NdBH)nixuFzjMK1k(5f9&`@xy39S_@!Lz+W zJsG^ijyY;`MKF#t%lYK+_oboDAQWe+i^)QjEC!zAASw#7&wrd)vr`fjz>R@9X=&l5 z-bWPKZRhiEunRJ6go#rZ57?xJ6f3mz?3Z72DnDxjk z=O$SAt|CMnYOLla{HmI)gpW83jOqULS}pnK0q&p^gGUH|)tH()(vg2Pn5yHTdZ83a z?5P;3C1epu2zsue$7ngh70H9ME*o(o89}H_u*RKM>rM#QxGWSa%n&1_-}4TavlH~0 zbxXZJnn2rHNZ_2t7z@LStHdz5RzIN<%m$w?J`6aO^r)wtWli-Qee@W;?#Oa3D9zMW z0mI~EaYTn+FebYV2VNi9@91YeHOv5B<=F4&Vml?xnDUKx`u)F=kV^#BoM89wGMV14Uz-@?2<`Ubr&2z|mqwO!38ra(Gr+GH}oRdLXqkDR$3-0ve=? z2nm^w4MALFMo}_DYVonHxB{e`O!*9dF$Jw@1@_5aw;V(~bje$uH zH0K>$VwcP6@f^%r)P>3Db@x^DON?s*?1M^U;}zHbj)gqiG^v?A6vl!|=_ZAb3QNz= zmakR{u0B^VT4_PeXizeC8bkf)AKRow`$Tf5^S>A=7KKR_G=!CYFK{Rqw{7RdkIco~LSj*D12D@LF;kPm*YF$2Z%X z@}2lbLaK=yKjml+jP@ivJ!`3zt}Bgu`Ca%7GF!>K@cMnd>KY7D+-qDV1cC=@f=dEI z{~6KAEU#`M(8;XGIG)D~B}E$PWW>iOF(^$Fej|%Oxn?AzTNwSvqbI6rWrCgfz3n#@ z-{U4NC1s3?6QYcgq)=jzC;enrJSV%ub8x{t;~+KVf+QK41xkjT^lIq)SL{T|M4aF8 zoQ?&}!3FX-tKOojm;Y9+MQ5McGD*EQl7+2BRim6kJ;Qs$gLDris#|6+36Oy)M%Quc%M4^|)Q-HoCi=R{| z8|A#3C<_!h;J{zP6hQ1rRuN51=$0MgRVuu8jnRlS|D+KZVJ}l8>N#&t|Eo5tD3JOs zP`LH)pVD|z7ab%zg%0(*&~TyG7EymiDp`z!cza#?`)8Uk%paA<{onso!9a3@+(n;> zAr46O(EY10AaTaABqN;klO2ViMn!P&cvrEZPBy_lcUjGLoNa|Q-JEGIgJgt@Ig_!! z!T~$zL`4}*OnA42C=gP;5eJR*HF#PGWmKeu7*3z9yNEo!j1j4+bY4sV5-LrBJ{yB- zpGsG@L8lM^6?p!qkaXBr2MHw?JlUXi(MDQP7?X~pF+s>pPWE6#{x&X z(Zi}R%;Nw|A>QCfcPG3!AIg@P6a!o=mO*cK%jbGV`~hXg=tJspBqTpzMm<-pMc&*? zE2*zWD7xMx_f=+fD1pbNk|N$L#m3yz*?9mWC-PT07IB+RVYwK+(J`^A4!BFmnOe4Q zIgbuu;Kdt3r+Kr0eDP5;-2jz?dcb6v%IXl==;h=FB5`QKql209fs>o)?C)O;Ng;-f zy(_x)0QOfF-JLE03$NO|FeS}sEqz1Cd`1*J@nbS|wB9HDQzS@B@RJS1bSePJS7leT z=_Llt%W7G}F*-liAa^`DK|wV_nXRJDRZu;~NiI8qw8gWu7mD#_T}-fv01G!!dhpa| zZm*0;lFw?;i9%`-^otIoGV_fWXC-9at`Ca5(}9U{z#;zxv_c8B6XH`Xw*OKMm59OF;9N(ZIydk}_`$q?%Y_8kgw&UNSH(z!5^Z4J?rVYC6lS_TUpuUU zlO>9)a|uj^Q&~tdI^ei5Ip$;*64C{@HFDPo5Y(K}xRzqk1xx|uGWc;;_ga8tDh$#Y z{L4bsIgmp@PC(TGvs#Z6K%wx>W-k(Q3b;B?HhnqSfh3r_TkS9GX$zE2$6|u*3|~_< zkHKJqb)CA?^w;c_$>5(Yx(74UWdQR{tm$n5ie!TgzrVsF7XYvR4*(V_7s6~ZD3WA) z^zuSx_@B&Sp$jltrha3R)i^OB9FgXXs<}!t6A-Orb_w1Ftf+b}WW#JxtX_rprMh%Z zB9pl!=2dV_M`TJ67`TP_uhHA659hWrnR|X^2{ZQmdKH;R@+Sk%<#A25RrA&n0}QG# zEH!Sk@iBgNp%i*jv4Bf%g6EW#f2EuUbJF`{`oy5sVrq3$Mn+7`>D7hNT ziSbD;ItZoee*$_LcfY<58T60clX#+D&35HbwQGLn@(Er*vjCSPb?j7}u{M<8&edZaLgx(VPoNleV7c zKX)eNyR80DP-O2{IB8eX)J-qY4zq}MNI%-GD4;XHbU$=_@Ir(%#9>CpM1Cwu@x;r4 zHV;4GeLyx{UzJt&j-1rv?>^w=G&QL{hRDFxzk0Wg)9`%g&o|)jrs}ORlesoC*wTg9 z;(}!HO>J4IbR0Bx_D_-WBl>D&W^BDjhnX|a@a9C(W3shh3Ekc~qUqv4w$kNWP!VBo zgmn18!#7-EGVI~^n?wtqSI9b9(sDO{PFVlYSlvH`#t#Qzv>tJh(_OE~bhgy{)Kdyk zEquoX*q&w_`$9XU;ruk3k*Q~3y7?|m-<>z1`3PKe)H5#0M7q8`j?0CzKE+?mn*>Bv zr37CEsX-cO<}9iEb5y#WN2%k~dtC@AW>V8c!cCBq7vk;0x`DL%fRNu) z!~CW)%fwC6$fFR4mzYAfr;;v{)r=e4!V@pwmesCV53E3p)mZ}htN@-=tVI;_}3HpqT2P;x*9?CiP_dX3XC9HIwx(`jTBXD<6A#J$qFMjlBO#2XV`GaD+j$QtCMR zowSG7{Y`Tq?CvVY3!+574w~M{?-ttw{6Y7yZ(Q&GjCrtv| zXU)k;DBV&+l70bA1`3sKM^(dlwx{P`dPHHa^u^jJ&a%Z?-T!NWFLk-Vmr}N&l z$Mk^oleb+{=4@4hKn8iOk|0c@F^V&Osudp<^HNT8<7;v6wVLVDscXVu6-}W=jM&+l z1VI~avo0665FNn6T4&dGVYy*Yzu>Qr#ce0uOvA7~<;+9wJpEsbv^MEKR#|Pp{1cH< z>3kn5JK!gMj0|U`OOvcRlPjJKju1_QEGLs2p2fV%l`V+YQ=UF?Sm(wTRHAdsoJgy4 zXS>i{AI=ZD&zvt)>BMr8l?;*iv@Nteb)^YVBif|<0&p!O%MWxx8nG@_lU8jz-g3*F zFLgDTBh7b+HdRgNuL}FrK>UKO^8<^WnzuN9CRv~%##FUD7zJ^jwnYo~y$$357J2OX zXt%IDI4e~`CKl*c*1;_#7Ex4O0H(xhR%556BpgauYOGlfrXZT6`-16;o4#*ys|XOH z0)Q2uYOoxR@6JjjGj1{_y36?;LQPrupkb^MA41)-cdtPuL<6v(1gmK|oZ8)y$dtW9{Bxq`AA}R5K4ff95_{y+8%r z0cA6Ty*4Fe&|-Bnh$FTwnzxN79f<(}UR2OQPi4p89-%lBDFup2h7Lk`46IgyhCNkT z6XR19>_8|e>t%wcP(qyh4fS;@c%{}+F-ia!xZm*(#!WkjM?xiP!{%q1SQ|0?Aq0kt zbY>k)jPZLoLl%9%j~}yO9a~b@$DnRE9gDgDr+7_wCVgrge{n1E??}qm6wU8G2Drlq zp>qNY_o+sdGxw?UWdS4fF0yd2SL$Df3dkeMhW@iXHoFTFhcaQ7{d$l9urtv~HWcPE z2?cSpwBkRU0;x|8RC%B_Y06>ak09*CZT8|Cq;qgT1PFw@6uTh73o7Df#BVP0fgmO@ z5iKeOisRu^_(RkPi&6K!U;_`6^sFc83VJudJph+gCws~3gppna$Pt%+yxX8mxE9M)h*9z<+nK4 zvgnhN2c%-55>08}ww2WEIUp(XV!XhlwJHDXJ}z#leR!V-s3voOl9i-EgG`ATJXf-d zia9yK&zQ@DTP&&QFZ$0Q3R6&3SgGJiBd8|gD)SWlD$V}#l($^yHo^Vf?L9x}Y&LeF z2o(Bgk{zyz*Dh(@R%B3lNK&U%xlfv>4@hJ9@8tqZWIuE)uFd|?<*G>q3;gP$X#U?g zFL02x1je%k5QYHg2}|uagZM&%n>T6YbxTz&raPiwRF4v;{DX*!BUEV?|4IuAPnA1A z)V+ws!NXnT&qrE(;MY6Px1+!;l6K?KMC?mPx25^Rkmo0`XjdIr_hMol*KV3#T5O0! z0uRxCWG`kFh5ZS9%*c+=Sxw3DqbAe+_z;xG>2*N2RQh^6v-*v?c%1mD&6!F`;kzSMdemCVR{I^ziAqWCdx2D5@*^7s6&b<6 zWF4Y_bkW$q7Vhy%;pKhG529340zZ3kv$Ohl2XB}RklT;V%$&TIqSY<2=C!GU!wye} z!ov+O8;7S)3X-m;w~Ddy&HDA0;w1^~l+_Q2g~}Y2jn>@O1MD)df9MPEYU)q@k(?h2 zYQ-PUwwrR>6di3x9=)f8_f`L*XJLzN+4np1-44+G;x;6HyuN?FU48Vcv~c*zUv|O> z$G7QzTg}h88s2!PZzgwhxt7?XaC<7BpKi)*MJF>}s(B9ueg>`&q<)C18JOT3+F>z# zx36Qw^8Vf9Gk|IHM|$aaW=Q66 z_i|l1dZoAZ)$pfhzAqf*)HdW#vFW}wPCXgY0Z*4#5kZpHl_;Kl)&7-V@#u5~TEEsc z#7UjGEw7Hec{aN4cCzVub&AT2FUHQI1Xq3~IW)1_SgW#wueN@B*Kbr2aW()Qysitk zAL&n37Imzckw3rVb&zy>Cfq)Hp6*i(8m_&{+e~wnqQ1JL`ZjeSc)WDF^QhgX-u?+a zHT6M@dsn%PYHG82*zpKsd}aLFoH3%4*=^-KL0xM(On5X4bPDS?nOI@xGOICcJ@w?0 zEvY7`eKc*?xr`qmxdP7ZQzS?(RFId$Wp4*r3`4~q+NKdmqq(!k`~l5tqGn#_8Wf(v zcK_P14)OwVwGEe%39l8FPYLWRn9UI}t5N713C&3BDEiDa*YdGex3*^rRL5s#dxq@a zPcm3gGwE}=4X?!=I;Iiu>Zqm--W(8b#4b@<0+!va0GoFuz+uI!%0x)plhPLG7dq~8 zGH7To#~b=gHwH+~Z2pD)zpjel&rg=6VX>2}K~r*UI^p%9W~KPtK%2B^Xh^TRn6ABf^}@zAi;k&cx&W%=e$apQkA(a{DGj;bQt%hMG0(4zcBgBT69^ z-6N-w<@HOe;7l7Z9x~vqKIY4kn8+bANP=2B+5t%#W;k1$vgqj>m&a|X5<5jXcPIs$ z&{Jtl%ZymQK~$o6{xI~#H>m~svjjM-e|*KGTv0Rx{<}6PQYN04AQXg+!E1(6geW=3 zzaG`K$vSbI@jFwVK#>8CYURpbb!i%2np(z)GSS2oF#3u-pSujWrhmasQx$H;Y&7@$B5t+ zy9S0_`-RS?c{0q@S6~O~oB{kOc7SeoOF-@OG8talNel47%4w^)J<+kadqAMLEZH!Q z(oFAK(YPUwA5>4hSr))CE>CU+`3Qv45_FQqrFZ+UBi8BU&!fdfpeS(rkW1VNGvd>- z`9sFbF+K)Jfgzb3Q2lIb1KR$2?fIP#`UQmhZbZzeG(u`SV0fUQPUb zUx;)u6C?*Ug6oj#)PDf5<^;;wQ{8a~@7UPCR}n0Y^1i*3eR($qZ?$Y;dkE}Ax2Psa zEo85bkKXihA=!!Lv}axO3^BWhN8Xc`+_JGA)z`G7he;K^G49BL{q@Jc3&R zB;%&XLcO$C0oh*Q6B0J?bis$!YoS{l${>!)CufGb^=5Q(qERyWvC|MyJG^qS<#><>@#tbOqW3qKZ zm`u;qThZ;Mu-bl5Yf+(9?i0%p4fmRGv1%47ZXDHWqE;BNAI!l-vPL(NAv9+BPl_Ax%@n9Y z$sMv_=QE}^F$s15*DS~77f8daQEO6+}Qwk`0hFPocm*7wx+7O`sv=Csjljp92AiJ7^f`# zz2(MDYcR3RE9UHe+O2#kWpP<*KijcD8!@{l$;ggI?hi;!wiM|_v)Ap+bT1Y$Nk1I* zR3%}?XnMelscdXlm=|h%rdbLN_-IF|9Q)%9foe+WQoKW6kIN;EVb>?H zIaNejbRr!wWG^~W!gdmlDudWx%n5AfCe%8>w@K~K-IUBeT9P_ucxDVwyp0jREWr{T z$j8F`bWQ4XJ@4xKojiC^R)K0ZcLC!OH8|%c5XbXpR}1NKCjHKz+$Y4-e}XKV1y1Gp z`A;fKDBCf~@g61rmAR?w9K3#+rnQZ*IF8~6gCH|a@=xs-+%NvjMNYxD z{?jqOWqJxFspccSRWiJ7X$HGZxpWlN@*K0R)#KK@6vaE5S-hras;0YQ|B+cEb!)fR zRh~W3FB4A}UibKU^b`Gm5DvdX1pR-`-E@n`o3j<<^R4B>mJ`=%D&is=^js3$4~DN_ zX2q|H9qxF)?C4(^k$D}nJ-f#JX=0=)?*+zW!Ie@lyKnKFLgD>EwwEC5r@Ejd*J$(g zBR;-po(A@-2O$yVjjG=lGQqGH{emA0HeD|$cU$PgKJotdt17tUrJ|OoIs!<=IVd@) zY>**~x$^Af2&4Ngcn$y6{&>i_pLyc(sqZG~CUw|+aKkVk6||xxb2XTg_p%>&_+Sm2 zsFAFEpZ#Ih@g^OY9uW6V3(&zpP5OMq__$uxS*I2F8?v-j_GrR-_OrH=8TA_@b?Seh zfWpIue%dqdgpj_wMWH+5u)a7=1U_Tm3b*BLhfO#58*`-j}kceEXNdNG~rY^r<`$N64CYu{=c z;)t{FQ8ss@Rz9Ypb-r2sJ$8*n{s-^pW#!wt47gPQg*HU1 zL>fh(!`%QqmQfl-umag89>ibyOB7a5q6cLJ)JLNc>}!|A)64}%wX?bb_jqI*j!<4* zu_Po+I|1p}Q@M)mIH)z`2!s4w*;N?H1LAX-D7tXV0ykx(mk>$Tvmo~ACr-hpcJWj8 ziL3Q@fa};dTJCP}B9{MNypB(x8;3Wt9P^`oq+r~&Z=@jpU$w{rC4YKo0YHO_0yL;7 zK!b|oJ$xoN!v9-IZcTl32K<>%Cs&TUmM2$!ra_)*_SEyO0=1tMJ9<$vZVuj%Q`${? zKC^wHK8obWlc;TY{tWQVm)6zoFJf7OXWl={nq#CJbcb~qWInSs?#;@5$W`)(_di>L zn`Hz83rN&8IING5UzLv$is``i7ji(bgUD<>*jR%E7`DRlu^273QmY~=XWod(%?fI) zw;P#VrgiD0S(tD&2*g;90k(n>i7qzx8AeM2WzD~p1bG-`I(L$Fd`yYdM_7#URNoif zsVLoT+~LI#%iUSllAQk;T-RWS#Au^|jQ>%CF3!bzQ?!25IP?Sc-!tq1@mfA&L5W2| zHYY!G+nM>@3F?}PQ2Bv=&#-RBw(Z{dAN<&O$rNLbmCIIByxI;DQdwjqO zTBIri^RIl-Dr9_`yEDarHfZ&;HfNwu)ofmipQaj*ie!dT9_p4=@9P|U*&ahrs#m%u^z(=P+e)TMqpl5sr zZ-%J3Ll;V#u zu-J9&rDqjAh~l5LT>lbJ@cf>8wWl#2G_~fupofc{|>dUIatvN@oByp|Lc*#9gP*@OFWlvw1MQ# z6S)0ODrUYj=TP)k<6;_#Q>HscL%%tA_NFg@6J{H`mK3&lETPSjoln^uR!{Kb{TzlE<8>ywBhaOCvC){_@=Xfet zG8l5z1qRe#lO;YMLH2D!K}M^_Qhc;^^)#N=dn3EB3MG5aU%Q*LYXc^@ugEs4AeF*v z4{Y@fC2=_;wKWm-r40f|DYmwUChuC~j9u~-N?UcmDrogiB1UO64WkY`9EB$SitJ|A zFh!1M(w_a@z*QC(Q$}D(!^=ZHOTN#1Ou6i~CF-O>bR}!uvhOS9A~?=K%-K*6xiOO` zSr@zaBskQ5koSQ{t_oDp`T%bH<0Z~DdrBARQNo#@?X|qq5&WvAw#jyB$TN8RHAi8| zYsQY4z!SRtImqZBwHn`d^0*Ux4dSBUCwk*(c4*fN6aV+oe-{1J*Mok#9kqbg7d^OW zpQ8RO4(vXB>1nz%uD&JiY1-6&IX7EDNn44x4mj}LO+GaYE!T22uH)Y3MLAV^<@}0{ zaeoZH&Vos?jQxE?WgUORu1xHXpa=}RBXxwLoijx5!`Fqyf+BL+mg`3znug2RkDza> zh=ZH@OBb^?mdsy|6equ>Lav4xPE{tCZUpJ=(-STq#dw%idsnr-A!f|}HCjjci}6P} zn~|Q_C`xM>DD({&Q~$R%*IInIv7#nHL+}e%J=(d3z&J@bd2h4uMy|l#=okcZs5{bw zLFnB}B9?3io4uBUIp`gOP?b=GDki{st#Vk5=8IMG6XnYZXqG9S zv!wL<4I6<({cSw{YI?5GvVY~nR4Rp9j{Ye~o9&m= zAWCE46a-`UDGa^rS}=|f!EM5huW7)J=WfF0J|1P4?$ouMvRta@lN|Q=LeO6Qqmm%= zxm)*hJB-cG`sWqvj=spx0o{^+=2N7321K&lS&Dzrpg=>9tGNSsYsa_e9sp<-j1)wc6M(EDMN^9$RFvIGivQTMFF|qkSs$w+B>=KHf-a$n$cHhZvHO}mL5c17 z9qP>2D)~v3cZD&c=z}+n4D_^SJ4Cc=HZULw?|_KbY?r7W zU8f}E&bUPSE{D@A*ho+o#+i6qw}p_u(K|EcOyUlvl-Fi6AX>aUE^^#@wAU&(+h+clNnQ z)J)9=k-*h21Q4QyAP{3!Kb3NxVI5SRHjv_>cgnC8EFgVfuZcW9Czhh94m6clo*k;U-I;y5mt0Re)oY!?>h~7=C@s7-aj?wW96On zJd4=K5eoipF;I7OtsxI2+Q$>HdUpyI;F_YcA6(i2E=sQfnzfN^DKe4nJ!+z6*TDh@ ztg}=Ox>Y%C4n$mYRQ6U?KRSS!Q7bkb@BXK@2P=>JhTZ<{A@HRvSOLD2Gc5+V@tr9O zEb*PI75t>49T+=#vmAMy)4(x<;lYSg3`V~41`Y`$Uz7u2o*ew5e!qoutv}?*_8r^v z9mQbiy>>;&{i2!3yESM8OJ3(H+lc=Ec(Z$*QbcF^`_JT1ISkcM{x7e-U@hv^mBvu5 zTkS2{?3_r%b8rMKu<{GV!`L10^@W{iF|&RV@t}H3T0BH4uoNO)D-H$o!D`Ly(XFJ{ z-&m**%e#kkQbejD1y(78h_aMTQT80UdYjqosirgtJA3YUgX90rb5i@Q@ak{P6BHFo`$!+LeFX6-R;VH!QW##1rqCcBSj>%n_;Pts>P=)qwK zjpkM7G{xPJ4`H#)t+wly-XtWQ&45|`fUThrsNB=15N!^dwa80!7?fP ztt;cDfy<;j1}X1D{16D;5<`TVyT z>fJ15iPY~qFiNiQnw((%VS}x!h#8SmN1NaE>S|~w8PnWT*BVOT*x`)E-+Ai3UJ9Sb zw5ven&M$#+4aN6+`(pDqa6u=x)RCkvWkk;0=(f+r?(AD4OLB`5KTFkJ_cNL$C5qq| zqlslR8Y-oSP5+HL%o+8Yz0DGMLm*rMuCVI*FAE(>tGP-Ey^(bOPyL(IfxjWnCkk3P=Xm%)z*CwXP&-z9pXr zp1Evaed2-*ovE~n*-H9e`?Yef+B9BWNS?$u{W+vM%BSN#yR#zaWe^sunCP$gSgN&6 zbze&!2zUBIe*Ue~Yu%;z4X`qtd`A5+9=`^xQO{KrJ67w!VhoPo$?1RTFz_3sosQ2< zyHP=D?$@YE=to@2$uVQ88oaM5zhQ?OoPbb$CnrM@vDyCK2?2_zt=Qj_><7 zRldR{BZTXnw>38K;E9$kj)!aSEOS7F#GLGUmjrKANHRJMcv;x*y!T?qr%)t_qRSm%5(2mR#Vf=~&V|h)!9d5`Rk(#o3=b zGoUE#=GUr`W*4cc4!a!Tm>xd|4~ZR&T8e^-92kg)Ge}9MLO~)GR{(P74Hl`|MUt`8T!orN_(1(jG+yx3o;qZPQ1}L(WTHSekWHPILekT&rC9v5aaee z0s9M%SoD6W1K6psyoQOsfX;DvwJadl`HTQU&6rMb9@N&5hNm%v2W52t8>(T_crSv` z3nE1$yuwG>ra$Cs8RTAaZ*Zp$@2=t3+6^Jhp4QU^8!qOFPfl+Tll*~pU$}xcc0a9v_s|M z)le03FUe2k9|qEUJ!! zpeP*+iZ^z^v^|V4g!!1L7&gmBBw(wNU)t(}oql0NiCJu=^m<*3C3>^ezH?zOd^uv7 z&1%#~;|dr7$3{qul>=ZG5?6+W#jD;$;K%FG@b zZ^;~LSWlf_D$?*GCfWOim5vRb#i;$p>t;hCg0=*wvNSui`pEk*@w?ev=bSh0N3Itm zgDXKa0#yaqORV-y&1<_81ap$b88%y}EAkILYE$=9JFNtBL786^j<0`}S`#IeR~uXc#JRn9Za zX>GyReasIr#Ku-lgqv1_={h5Gg}OBb(gPx)^S1i+ z167jw>0<>%x;ozbQ?r!zcY67|$7)hb^f$xxWLMKnDD^bw>GFFCiuN>Et#ZNDZSv64 z#Tcb}0aqL(1pRQ)d$hYem`v#8_ULzXm0zX*NbFHmkNPN6 zIV+}Z2nrwE%8a&k<$P+z=dkNoSSjGk_ddfI-wllS2a-B<9hVHv!pO(R;_iwuF7va(a%NIff33@wOH>n^#kmXCs8 z9Ou%v42lIy;ARkB5q?69iLG8c95J|ZL~|e-C|n^+9@c9Efzk|Xr_I~!o#$e3u500o zD^@Da)o&(eCGey8f89&RNnuanO9ef1>Pv5fvrpWY4s-rFFY6NuHhpLSzu)Z3|GWCp znoUwNqeVOXDFBr$z}@se8RCkLHwThG5|{^!5GyGIaO!1PXQ3;HT;_@32=0;jzwrVL<9AWP=KVULe?xtop&ha-1JqvrO z^pTj&3062)UaM&{&f%1VmW3TS{TM}b&$`#d?v(W3C3fJa5S@JJuvvmE#Wq|&LNZjQ zW}F#QnE0R+LCiL-HR7memqdDreN~JEn5@u69|{z{uR`&j`~=QZ!*FBY(mLnR2E2i} z@^>!!<2YN&NE)I12Z87)rCd z`7=IU$+Oj5OV~wa9EURLArl2rdO?ikRI~Bk5rL3L>*%hI%rOXc*1d~DyJuZ_w)oX0 z_R`j4vFww|UlW(P!=E~Nn&RU)>xJ!53E_{j66I#U{ic~I_Rtp@ABzEqJLr+K$m^(Q zlrj7wL?K;e@m+X3TGUMK`k}ma(%kVZ>q6+0rANeUg$6yMM+@8H>cI)Ul2P7O*aM769lesR zon^Jqa&Us|oIt&TMee^`gL&pzA>#Ye17fyDttv;odFIDm;`{LXVp$6B4*CdD?2lF0 zfxW@NG%0pvpVnIB&}M~M0a&sic8L$<0XDLq0GoIez-CS zOMJd{S1e18-iZ?75!?H|Lbk0{iaVb9w+~L<=v%%rN|?tSeaML8G~<>|0}Q;N6j=i@ zrzvXJN9M$@oey(z7=_hC>CF;)1*3ebuo3G2AfbUC0XouP?lPr7-4kPUE2O+N6y7qC zxJ6cAXd1OT9f|jnt}jrWc>{Ei`P6n^??7i^*LwRbrAh0VC<@ULXej5Cc3kCzmlr73 z8~!>-glanpaDLIa;l6)x*__i=-T3dSmRkLl6XDd1#*UnlVR&kSmsW-1wA9wRQhX@( zC_x%XLsMBwWK*gHxeagu5<*DGD`t}11Tp9D2};InBQSNGcuo|A6$0K31R2?AT~i~% zZHX;#yqG-2b^W{T|#lt2_e zU<7!|l+%PW5{O%;Ta=IbFN%?D(im?G3sNFTLIvMSa=&BA5+dgLX+>?ZVTZymEpwoi zZnsJ#O(#eYK)@V33lo1WSrgx7da9ge(NCQ{|C#@cOk}!6!QKPHP7Ae~6laEN28UqU zY~W8882J}Q$}fv(eLY&ZeLEyEcl$OH-hTG5D1k$fYM`+B(xc>vag~-O<3a(<8p-`I z{O!yxAagv&F(8v?b)^NamgAn6pgMCq$x^pVev;JJPB9>#cuRlsWtZ<2gD3e_kp|w0 z%llRO@4}sV7?}c!L4VTaNw?%Y`>mKl0}jd9s&cAQhYnh2FRV_FXWd!cnQOBU?jy63T~e1u=2yx}7pEG3XpeNNEUWJ#=KGjIin+h? zXiU}Y!4>(0t@9A$=w6;1RCM(~TyjrFYG0lk7|$qEp8LGoSaOftb;~h&<@r7;=>e|c zu<3}M_z)A#zc9Avo&0xKuI8j`l3z%2VJv%_S><}F8hK+5bbTR;yz=dn>G$4Sxr|%e zfN<8cILLSq$JtnR3@hlL=PrE|;Zs)40Jp|J&(0jFM1UpDb|V+(li$R;RCMub6IHI& z!R=dqFNHS$SP#2(?KxFt(W^FsWbfpXv;S^7I1YVf$_6G6HZ|ZMDDw+{Xl$cjm5!-O znKXTOK#$MM74B#Sn^t0}T)z=|%uejErc{_-9W-d!!4}=j(KoB{*|!fgsqvXwndzpi zd{IeSV)d@lXZ2?4r(bA+%T7;DLtEp|oLkY33YJ2R6YsOdPMaL_FX97*gJqcaKI^7HDhmE4-)Xq`BvThm`f5#GXn+$*$Nu&AGygMf_7#44 za0ZxSF98lP*`{t>>n&NL=_!E`zV(mdw|;TVeckwg?C%#~qZt<=u_9GhGVnA%C1tC5 z^WbMJAh%0XUxGLkIOXzRj8)bTik6T#_^B^=_vPmAzSggkx{`Tf@u#jQ^7CYhvw^LB z)l*c+;&AS)12r@)t`X#G`yw~n+O9e95KW@OV89BGCZv?KmHD%!n*N5#uh z&nw4n_1V-+r9s5C3YXAI_O|EOUUB*M_jlSW@q-?+iMyBofWJXM2`7!#Q7HUpVSEL@ z_)bYjzcT-RwU_H<6iri<6^0z7-n$ap^*!U(g9EHiIXCaHVK@?LKzLJEN?gUfu_bPz zW-4_g<-}D7HmUk!ywO5b!*uN!m|Dpc8*RmO8sVNc16Ti}xjIj{WMr;7>Ne zf7hm{kJt2LqW8~5!hMzZ5C8XkhC=XEUYPffYn25{@MHgEYlc4n!;eLHW<;&rO-EV9_Q_o{fVcj^v3n?@3?-`F;g&WYEF&E;}8c?g5bpM6Be#i~^DHdE~58XK=g2YkHYhrcjT= zeJ{wKvF=b~ue{EF56W*fuqeXx+v;GtcqzXEZT2^NlAT!zmEx&Qo!9hL8OQZori@V? z2CR|y**fpP-!njq#b6bR59LloGH+bD7~V1+_km{UlVlU1L?MRx$({7VuEkP^_`h!2SpA>aG?d1wR)=2Rgp z1h{=sxax!3>e+1{$0~JjeQ`X?kxlC~{v73)G!4l)S2={38rnIu%OY2NhD*3rw24oT za@4+=uBc8|(1$XQN#UsbQk;X4Ar|>%$Tsd^3mfH*UXn)K&CC*)ZeOCbs`cMpP$0ivwk!B)@ z&h-}!y<{IX zH)@yZpr`C->7I$ai&a>q*$!c?mBU@XH=z$*50 zL-?Z%9z|xYcuSpd>`RZCerBuF9sT^YKCX6nJ2)uZCUowR0+fNI7Lk++kh-dZ%416Xc{sjfNWG4DpHE8Ne|Z} zLD?>#0>yV_ibZ&6kFu%hm+A1n@h#yovYx=gf_DHPc+f|rot~s4?F$Ui%PXVB;YA!IX#_U8#~O^l!D7K>13_r{LNg|1^I=^iA-O?b z&wn;u9TC_%|L7=TFl=;?5raF_=V5g*$|z2k`Tgo|pJ@tO2_fOT&Hs2?-u?)gpHE$O zlu9=Avb?reG_|@Y#m|sP9(FC0mthy~v^q@#sq=a?2M_=2v6{LM ztJh|w6k*Pe5Mq z`j+7+i&ZJPD9_Bw2aLkov8RXNmo-VD+(#dNedo@t%-Q9-#K9tq!-t=py{X{@>qP6i9+86wi;1`lfe-dPz#q-bCuD}5Myq|VY3`V97`(r^JOwq52 zs+X+Z?ob(;)?D4Mp+$#kJ{UZnTp0Z7xI=FIFOg>4a>1k~E~ir|dMsK;q?-L~O(D82 z>Q=q6#Xc~Mor9#m@+?s@ueM?K5MOffw&v6_J=O_9Bn!76GKXS|H(vgZ*psG{iE3V2AM}rJb$eK=>j63?ur4mc(*v&VKlQzpkXe+z(9KKn8 zaQzcr&zslHNkIj*CppSe4?R`e24~eM80FyIcc&w5!iQJlHPxEeWyNnYK4dhs*h zjOAem8jPv8#_t{<+?+7hT+8x1H^)?RLrjCJ2w9BcRdjWX6s9xjKp;?X)dl2oX^gs5 zQ?9!vyjzUwF~vvvUflB!PF4ZE^1R@K{_Q=X{sp*_vSiXx^P)s@G8#!gZEO2Cd46!5 zLSofgWrAtDt8nt?{+-i{&+0}ny#meIK~;0jHe+aYrB>mDz|3IzgbP5L9wJwdEUwgI zoJbZhW;(Ef!WCPMU~F0`0#S_R%v459=Kx7Qr*dMNb(ma%Tmdshk3oHQ(6JDZgH{5n z5>f<=`K48~EAB;%U}Xu(0@(cVs6qSPw*w#QKY};YDkrK!z0RV3`9tLZGd|>2Cd|#V zIPweNSwrce@1IGTwb^s?%mC?Q#1TF8*;p80tmEZ#3+iV441mQG=Y;*|8D+X@^a=5Rirz;9-C(098oVEle!=c5B`tz)l zgQ$YWOtoCUD;;(L5?XUnnVzx*OaT?XHK_x0SDW9Pl?L`wv&H}S*!Tylgu6^9gf?4e zkWMpO*1`9N?HY>$66xHlsAFj`&zd+-ENCon9}eJ^TRSm5-+5ay|BT?`GhFQe664PZ zw$&?E$OC4kmi~WcCUf5(I$GB&>J+d$5-Af|L-ixYjTmYYTxac6fKT+1m6a3h3CxaL zOp|DPfa$ZWlb~U8E^=C?be(RR4jpA9m~=tTFnJZh0MHx;cm|4=IPA*FPiFuJ!l;bi zqn$2ftwhrZ8JbpclRqfNkP4wghBTx;8}PO14CaqdKs7)m5^H?SSj0QG^w=xGx|0 zez>zbHmZbV7i%~RIr1}gYw(q9Szc*4CkdPr1Og-ZK?fM5=NTYyKd{Yz1e0Sa+s}GNntBjU?$;!lPM4Blj8oglMO%k1a3m3v>gds!7aq$DfN5 zW5rU3^%vH(-{&4gkP+{^Dj0{we)eKsMhKbGem`A~#m$beGZd8QO11@S!i4Pm5G2IA zueMHc_j0$Y_>cAs?ups(ZU?W$marrtKc@|KazWnyG$8_w+AVIB zI%|%_0`qHP6J`iw1E$#g&pzA2B8x}bhkq^w7g3_aU1q_#%zW-ZRC@MyZs*3SYtRYt ze)cwK+wCqIl2dDP8odQ+tNsbeX|9N$su3QWY5|>#UsYW0*9cEcZ2~)#cqN)D0v2jm zr>0tnZ2cCi_3Q)GWr|DO6RiB&{Hcok?#BEjc=|Y3yPek!u5I*mQzPAOaFJWO@_uJ^ zx53P{>^yr1{?3z~lZTqADv`g!1&h~_Hg~h)cZr*n89{drP;S0_mfId@1yW6hQ zL*|GJ*+Q2TLwmjHX~wG~1A+7tu`BLc(=12GZyhtsujb!|vs*XEnkDL%bBiwHHS;Az zJ)^FMZC%>Fx!qg}XS%!)E%$D{xT%okdHkrre?qm~F7{ol+qoZD7EkUnn_Q>R_uW54 zw7vSmj2-=N$T(8)lx5v>H#-=4T!OzR?pk5>8!?VT&s^B$6s%ZPYK@e1z6s509k+R7 zSc4z6&vW(8=fAP{70Ukp;E<9294dUso7{7*ZIMxH%wu!wYsO>Wip-TXl4O=8*F!|RQ*wavGP z-(_oQv7bG=-cmrBgO@5c;q9PY*^uEReE!#d(;)PlTI~T>6*k!knt~QPItT1oUCm6$dYgDd0E2QN@yf zQP1v+9WC_QUckx;4EW@Fl_(C~+9g{Gt73XJKVKKn{wiH%OAeJt#~AK*(U&WxQOn;; zXwgGfSS;04UW+$~2zW4#R1`cyr8X12`{&3wCQKA-&2Q*_9Zza`Vq(jfAdh@3L&KI4g9%m%lPH^GTSHMqMxl$<2a$@XMS1CHDt*WL zmQxq{3E?pqOBPHS-`u|PAEXUb5%B)!R$|3-s-gEjA(n9qzeDGIO;z)KiQkbvYTZ}m zJgZ92@(rLoyfhc_ZZfAA71TbDxiKZa$9%u^Q1?Qk$dQZdTes?JLGYS8phwtE1DWC^ z-F|Rn#0cF|D8mD)8Eke&)i3ZTtB5a3!P*T63vaG#Zi<(i4mt~igXd_j&84r z0s~!D@?fd|Lx3P$h++~MSmP@}N)($yN@O7^ArSnKWiPxm$jC$5L`Ov_B7_U1OicD9 zkdhP=-~m-2$tXXP6on-Cm+;sF?QKLu_tpo2_C)^*7O;fGaH@nd+~^OTjvFSUfR3wV zf08;7k8&)24YE!x00U$vc}!&>XQHjF)xmsnxInj8cN!9r1nuL9-&(<7i{Dx<_c~G& zXADW?E76$tf2)|CR+sn+J$ZQ%?HfGF5bqm2?G~*&1mb0h=g>P9St&Y_e?%{pb97>0 zG}aQRCS4^pSSt5PSlcR_nKwJFgf|!ol-7clk#!&DBsxo@rkyU81~CpU|7Q7evBo&k z-QG+wMA1^n&4bS}gt_FJHafNmGfBrrbK+khuu&`{(VbWr^0w}Uun3v1=7^v=t!RS8 zmlo8F<<=x_J24lU3eB+{NHApac$M#~& z*5tl#toiAzA$WMqlICv#GJormCShZ0x6&v5+13LfTMcV5==U2pv(+WB@Mg1Ls$CJ| zvlX6}1J_7$Yb_T8uZ~pDCFI*rlvb!E0x>5xzCZGQJiN<%#dW;UwL2s7Ez&yfuXu%k z<7D(5eYX1@Eb{47&DF~zsLda_4x7pWfyd275zp4Rjv9oqM3Z44()>${`*XFBAZF&u7AnNr zXPvXXuO2T9ald-MW3|Prrgl;OXeuc#7AisAlNC4Gr3p8|pnl~=#QmltA=XdS`$1W> z+B>0-Gk_&=ZvW)^aY$>#Yi+yf0J6QC=scGY%HU_S^|QA7jthl2xQ+^ab{LyOC6#O1J&a^{cXZ2xquU-|lQ!_c zscXXDfpXnGzFozQ54G8dk8b8W8V+;AMO!*Qma;)0!rdBn^8ds3?0Na>m_B%|?y!3I zm~6Q~ED|B_HZ_WtaV}jE^3TtU!u1BpC1=BjVJNL}`5mTE9X7u@@~ap85K#SVRuy%5 z6a}q3J>>lsyn>KVTC)sBWJM@O36XkvcH|+_NJA}n4DrcnUx_9S+)-G`W+J60#gTyU zqus}Y*Xv6P4=zQ#aUtg#SBNURDJLB8pLb|>THUJpZ1TvFEiuZ{u4T#|Z@JEWI3ilZ zDaU{QTf8qWl`pJidum{(#hp_oa&sGRn@&moN|cdEQ1K}S2?&e+5rxX?sIh97Vn4x& zzz7{ghg1Yv%yI5fPWRDhZF#pmqdrlZp_E3)YL+GXNWBp39T901QN8%gC=VH4sRih# zHSRBLRe5Y>i%31>^p-T$v{?gKd@?aM5zo-&8#;VaPb~YE7}ZITahp969y${VdSO(~ zgV+1venxn;RuT`c4>R(uH8UNeL13SK&5bugoh(vM#**#q#S2#<_fl``aQe_U`1Kc{ z&!`6pPTvgUGB#c(Nb87O67S8`Yje_u$-H$39j~-1>Fs~jLv9eK4}qJ^!V2u<8Q)=$ z*EMsaO4HSm>r74c(YZA*!z#`D%HK8CtL4#l1@CH+8_F}r6Ga=MTTN{-){zgo2w8wg z@W`)9sm)3*UT`<}F(9?iGQ4WOOsPDMy5q#A^%skr8N4!8BT7_czj)zWb@9TK`{G4y z^@W`dHNEzpS^L!svV5G#X=(3lCDtc72?rJFN^DU3Pw@i-!N?L>9VB|~(&3v*?3Q%E z(PR;om|a2R!$p+MA%I^ znK4Zi_!TV!Xfb3&uuK^wWsO!|kDnl|_0^WR+bOA!`d#ZNtl(0vFrGNrkl5;_Ikg3z z{YFEh7Dcp#v|Wc1Bqw4`LT0H_Ng4U8G*a}@@BSP|NDhS2b8xE9cD!L47Qousz>2iA z0y>ouv~^76Pb^b5w>=6$wn>Gcz4GDfVL8FRmq!5++p5b>+S(8Zo7zrZr_7gTyp3qA z!-T)Ndcg-G^!L!2WzmjjE4%;|XG}BPU5Uk&zZp_MIiH<(+LLM9l|{KsVe1R0e$_C| zFhZWKbdD&YwwSb&Nc{e*e}m6=;jdb+gJ9%Xo~sZc#6x=rP&KFMN>H3S!kCQUXGZ?^ zdxXhp;aKoIWO4-*pm?xjNsliWQKo8covj+;m99$bTBV9LrAm^U1Q!;hfW-f4jlX@l zc+C%^-ZMNV0P--3DoTMz>nX*ZUZ!9u8DJO?`G)uiguYVR*cpWDlva;dz_WV zn=u$;I_f?bIz#R#-D^YOuAxQ>X_&14&#Dr1c(&%_2t|4WX=e{2urSUl@y+1zRJ{eRF| ztF9DQY0|mVNHdUPE`N`Zs$u8;xq)AkZq8cIUDS3Ca{EVzVSDgWnAI-*3P4`8pKC>0 zA}~Xma2YFYPlO>jBI})Ii9B&Puc~}!m3Y{Sns1gJ5oE_#2Ym`P$0pA1C%8A|uAv6! znynuP-#ub3JKl|Se2eh^o!c^Z6uf+x>sf<{UdK=j2+Wll?KtL+|HE~&7@MB_&t&<~ z-MLhiRygivnIp0JAIZ&PH7Q};rmsiMa<dN z<94fmZAe5xaYOs|^V`D|s=rNC_rtuOfNkKLQ8xcBpj$Ra#wd3YL}g1`g>BV!(~^8u z(2iXLTk4bdw3M+IoxW@C2br|IO5!K+Sn>_PgJ&*7WO4ggg*;7+73)L~r4h7vX$+_) zLe-)tN9mv@`^a^qUvTi~$*ARp>X%Y#KAZkojXq1~oVgwdipF~rx}?P4JQkHy>p*x)Xp#E`^Kitj|Dyrqd^j!A)8A$7tY zU+d;{Je|dUS^I}Mep4M76n76KOHxS+RP5>niahm*F;$Edy@m2#=NVv;y?(AZVkLj7 zLA(+UZ1y>pts&=S1bjKrsfP7RZ!~|Ri+l}vh!@UtYPU&>7l-IL(s3;ibl%(o0~z2z zn!AnDrULnwV?}OqkAbp*pV^A2UJe~7lrkM{NYg(Y21}(oWPm!{v$ zygT@_{b22SN1}n$vEJPKeLY~|3#bo*(~i4&zV<|Ql zK7VJ~3K?MPKn6CI7gSE^Cq^Ij#MXM66w3;xz14W54$@RK~5zb>B>r(sARD{R8 zSZ2$5;Q^pr8OxaHvQ`D`tL{+%z~=|bi6q8|M2LR?inRT&h?;Q8ut#&BBV}8}ce}5r zvxfhrMvE)~S=Cn4<%hxrP1q52WqKZOMJnPGojzDlMgqN4r(fp7*<^)wERCbZeDa_1 z-u3%m5ssOfdpku`K0T6tWKfnMf4=bbXs>V2zbU{$WZVSnt#pC~wp@<&Iy6H6!`1x` zR3eG&|6eeb2mDTd00T&?-UKtP`~W|f*#KK$9KdC@ok+6d?MD1lYP3V;@>Tr9Xj#k#hNP5U`xS#j^;{APp zoa1)yb!KL-HJjP9;<{{h)h3RQq;mFruNnV?gBE17$-@>mp&08T>Xp!SjvKBp_fC0N zZIa|ziYoHWvARewf*lTCz6~+5i9^kLpcqiHocaR(Teq~)V&@3mW2udC+hcLK?doDx zlnceXAS(2QJ|pa!@C8MR^66m_>=I+ILavpSDC!ujrQkn-p`g4ddQym^#g0^hP`!N} zROrJ(0IbEw<^*>qlPiJ>li-GNALDOHKr-W%4Dbo7PwLuN1|S%xqRXRzFgOsR<)XkP za6(lJ;zY%*Nmitz%>)*tT#`bN46C;4nGAi;7`jFu>ywm)0QZHrZa?_%q#$k4&n)cc zc9#eUv+OHx%;v*`QeT4Z+cZv^Zp>9DNyfP@4*-x6Q7ig-%D z+LRcD31#kyL5}50?3$npGLvEfw5-?i^G@w-fo4j-O+13t^njq;C2aJE6=|v;J&V4N zjKd^yERlQzVj9x+wO;BxPNNM!qErtB-`W~KN|z-sBVZ`6`V97^F#cLR<<^%Mg=p0H z{CacJ?YD)!4CRdCeY=gHM)6~QDbM8kCQRJ3)1ehd{L8iR=C#Y`%hz;LKLnP^WJIfV zXT*JjEb03=6N5Jrc&SE3s>wJ|daYwmAZdXc+r5R>qK6PdDq=bUMLVF&sDh&i8IcMr_LbJem8^y<8FHp%OQ) zE9tP_ldA7;n$)j;Fa5*X1C+|H*Uj?^1^cQ(Z`>XY>&N&+XHvS4G6pTpOUg7Z?~Kez zt`_QM3wLyFe_IQLC#z0=l>Ud>XR>O$uTx3OeU4Iim9T2)=w{2Qs=PC-F(Ih6qX>C) zoyVFYPH<+~agz)mucLOOeE%0$FV4xyz~nxbj}@KI6~q1PTCnWn%`ih!W<@3DXhoLX z ze~QV?;{l~E61pQJ_J8|;Ilp?Fd|duwNn5bG9VE7`3YmIshos!Pd#&v;-Su2QUSMps zYu){Go~UsS64XEFSvt4!%uqggA)jwxE}edElj?t5y9oW`NaYK&DWJ!hyk-b8GVDno zyrchQ%<)@P)^tE^BW{k?3fx^VLeVfV3p23k(h%=Xp%dL?sShN(3g&)u_3qa!yFwDdrQ>p=D{#rXhee_AV!0COxtX$ce*D)dPo4SQ<1&?Dwn3ZY%DQW%I zo%B<^)+&RfP->0J47{z{8^X?!IoFdn8SwW~B}Vb*B?%ti>N7moBQq)AxOFJ1w;eVQ z31eU0405c9*)ML=!G#O?#q1Ei@}lz*zfJpcHKQ1x$hTI|EXYA+N*?;Af~wQc{iLi- zIuQ!O|8KP&W@|(~&{aR_Eqoec87PbDkcXsk&=_AXZym0!3URLzG#*v)b3O_FaQXJ| z=Gy;@@(SC2k$$|UU(_d69k-R8=!_KILk#&5yy5oGX0y=QdS!2ikiU#kW!M$hzj4tq ze^wmA@vIQFZ6(u(+=Egt>r}Z@^NI62nW7TCkLZ(N>&p-q(r?! zUogJZpfJU%M=g#?Q)esJd(PGKcbJ=d|NUp{GghoQUwJTE?J|>?CrD1GRjy>jdr>aY zJp21=aG8WhWeo4W387SIohJG;O_rW1l>0v(SQBway?pDDU<+#E{(3@pqSd6}h!>Ka zgdY?0^adjib$D6z9f}|y;av0#t?Tg$93bMF95Eg@1`{aBZt0LoIk1kuG2ZW5k;~CD zq}^?gdlJ-ikMmnfha_E8OX4rMwX4?%gQ7dlE=&04`a)Nj;?-i; z^kX`#<6G`r<;sH4U>hwvt{AE}NG>IMzosNa^nNfA&1)wXf;7M%J>47FlV`kzCPPE% zGQ3Q>G%*UHyfnEzhVae9BFT!5#h#faa(m3Y6xfyQC2$6Y5`*G*1TmrC7X#(mR)YU9 zGF1|V%R5%{WX42r*Ukr;w5`%5m#`svj4j*XNV4f2VAuRHBkDCh{Zz`#HYm{C72Y&kNQjl}SKN2TKd=N@~n!8Mwyg|E* zgY{Oq(1c@;>ocSbS-EgaV2V$@?x$8>K)lRo@ufO;_&TCj92XY|$Vuh9r4|q_ec|06MU3 zm5Dj5+PrZO+89YO-Yb zj^Fs!GF_x)bu@=(@(PbAosG6+nvr?}WFi`~G|EUIeo`kBKcNie;+8H%n63EuT5?qH zQv$Q1W9fl)^CiVZU4}k&04~EWPC;>Ze^c>F^%RoxSZXi<(+f4J--q%)EG4c3&gWmd zOAVZL$^YP(?z@Z_=3`bcrJkNDY!z4sMgXG_eQ#EC?%71|Toh zfYvIFH$dxUuEMaWZIXzY{thO9?O;t%_YUnZbM~cBp&cmN= z2_8Z5ytHb%Gd|K6N#Q9xE_PvY$Roy}C6OF`E1cPUxr>2j(a+FOFp~(*S z_SiUTXqjPMLH^D%4<0Q=F$LY;Qt)ure4KwLjTR{Y&FI9RyZ*$WHMZ$XTIX!~<~RrV z;V*`gMZ2)#Yx6X_7ldB%CySj+!pBkiAL|xL%tGD_y|G-|y6|k;{TCB%fl3tONwV}; z2nzdhRMNvQL3!j3N{S}fk&M$cmEmWEAoQy9nElTZ-bP~wo$uJwpANsFJ4(aNtFy!6 z_RP_3FBESPe^d6XEAz2c%C5VF6~vokTdxq9O#u4}b22A8?`L}E!Pd2$CS>LhJOQuQ zov$B3MPU&pnB z8QD?+ro26|HPrc2wDEqp$<_-l2S=JUaeGqGbpLMk=UOYspPlQ!DJAzw=AYM`Z8ZbO zB83JTy@wi+q32n_KXxVNP^m`NsR0@N9>dLn2CX|qVRgcYUk+Vcy<(IaY+Anc9g>#{^JZ*h>ziYUchP2BSG!^eZQMHxOW)e>yB z4fy;t67YQ&6)tAZu9wq!v=GsDxz|!_hy6yN@z2mdebYiyLNMKS5NN;t+(hb%URyzo zn|VqGril5OSY8{Cm)%V-^gb$~HTP=w9FH`+VGaLOrG8U*9Nr<>QUMhjHzULPu~3d1SA1MsY}(+J#|V3AWNMuiH{QhB1<6~)&Bv<;8U@x zuvNM$&xqrRoDqc5bA|_pG?D{DJO>hKTQwDnfJg7fRLunZ5m_+VP9;oygqD|;8-l$B zdlu9a319VSQfj7R#Z;Z0XZD5^BnioPTV{&Fq9h1ERyb=Io+~9u%-Gjj;RF?eo#NhJ zi85|R6i1b@a+!pNGY80K1MV2{i3uqxChT@A>ik0ZNTwz-4Jsx95=&}vNqqF-zj|9{ zc@Ff?SH&ga(O=e&GNtL}=^1`7*zfY`mu`nsZhiLJROJG+8@bC8Fit|tqvuu)j*B3= zzbDjT%xs1GQF2T`~q}($$wR^0&xvJP+@BJ3}Y_#kvA6 zO%5cq)OU78-^eB$WIm`5(Eq7xF z;%}Q){Vr9F)5V^Qf-P3WVL%xnSQFt$d)hlVFsK9uM+3t}lybl%O{}~(6kUNT-@PxD>$|X9?AlvE6;!}; zS)!Cc8i@nUT`HmK$uU_Z6I}to)_jA@o-g5~Md5^PjF*aNxIQa5s)A5+;aS0aEkK1p z!Pbbq?-Ovq$m1x%;H(g-@p_bD4QdTh&TP#oz_1z&QR?A}AVo0iZHys3Q?Y&7NjkVSQRaYGCl}zAf0`wICm}VQMC`p*)4Pe!Ja$_Y_={;xmP@{qS04P6~QINz^ zZA7Quiles>_ys_GU3`B+DwiIo-AWBi?#LX_cIm8qEAr){EOjEySYPM_whSteW{iRG86XZ$>byiNk=^Tb~D9 z@OQ7o!JB4BZ8d>Zmxk;4A$qoUHG?3y2l!AunwEcOtci2N9;%`wmToKUH={8+jMh=vYLv%$*4_CD`A9y?g-iqiKjf}8|5LpYAkh%z6GQwoNV1?^u zX{nbNq!AQIol|>alArzM+9B{))0Z$< zlQdBZ7;}u-JSp$KQ5)_LyCBaQW3f|u1|15mi!?gwo;~FYyu7CsZaMlQ;qsyZ64mu& z05xH9*nRp!;p<4;|2|4KONadJi3jb|JwCbB6I#wSqL?k2@O0(55YE+@^7Mr_Zd6mo zQzo+V*u~#}a!zddG9Nr&P#9Zu^e_noDaKsvkGLEvNzx{oPjrVN9`pAieW?ukUx({nHOVd&t+= z>s>SpK}0L2hLtJK_QMV<#Fq^}qwU9BhpXw@X?#XMJsf{4!(ED#^4xmXMc)mF1=*cq z041JmQkMDcj*lPgzICqs=1M{hCLD619@cR_)or3)2jcDR04dJAc|o~mN!0jw<3x8I52(o}OVj-)=?wfW?DzAEJ@AFU8gCN0 z%X53oF9VGTr`FK2hs=y_p>y`CFJtB!H!P>-@?Ud}%+3C+e9Z;$*KJxl*B4)N=?WeT z5p(t8rE~md{~9ezVU1eR*p8Y4MceRepe|FJmaY#RW;DHtoetjRwp#nkaiubkquEi`--@K~Lw8yzmG_SyF={N6=4 zX-7kS_C|oyO)5$A@|17%IdD?0i4uw|D>;IG-j^fU05%(OMXFbxsjP%-A=?Ur+68Vh zv)_tT#mC4hu{8a(V-ZkgwGf#Zlu^nUOqpUU79^Mh0uNS;^ZH|`(3zPv3xy}ya$zP9 zUY%&eQ6EpL&K0L&Fi}vX@CJSVaEK$UbpSrQIKqqhg*zB+l>mvg>$d?R+ux%Vt4puz z1Dac&vWplH=;KAS>V7{{p&BJ7+CX_Z51kfv%o^n|k+SHu8c3yWl;NUpS6?Rr*zXuy zWsHz1v0NP{0tr#1p#0L4D1mehD(mb@DN((XcE|vVSo_di_}7Upv3qjDfjqsInE@?V z%1L3BtPzW4b2?FU%_zW6QYGBpW9@%|%94=Jj?Ucnu~K;Qt*%SE)d*5yLp1b55d}8F zF7E7L5d{64*zSzaOZv$!L*7GNsl~n=?Ah!#NKN`+dz^0A6p|xzkbPy#EZRrT#iZ}S zgf-Ip?N<7HL^8sYo~0(LU$kkgE#3;k=5K2Zb{QbA(55B_1<}RStul~fF!RIa17NKk zBsWIggo6m+Wte90f58=FT)t`Y8zr22wb;3wtB+7h!8$$8;57Dk0$#J}n?u9~@Wx6UGB?q7=$(-e*VaZ=+@R;MbB}P{GmEMv# zQy$!w0CFxtDO-@$8)lAx0x)P<1{YM0V}NI7p=GDua_+*G$qUtUkU_lE#TzA?hs+R z?^%XvSQzXLne8h9s+iuO*ZyD+kHz8$65V)RWRL^%tr>uFZyRlAr2lQg2~yGY3{el- z;%+7*dmYB>dL;^TmbkK!xJt^zCMR`b1KVsoOIfwS=Dusa3{GAfB=X67Ex!8mwux8@ zrofhqH=rP2!SKrf09k67W*D!VW$3D-BYFutWyi$}TVTr^MI~wr5a$3b5J-kQ#IXSL zc_(X>!Gmt)xurwFAT-qEUWcwaQ1Rw(*{phAu%F&z0#MXq2tcTgkKq9)DS$V($`{n( zSuE~!*xP8RpnFU?XM&)~iCS}sH35p8x~4sx{9$^JT7vIyHfo+i;VFPdmvmj{K>Xb4 zg(B#5F|rq^iI)D`Do+^#VBbZ8)*6gy#*-3#=F^iC#e{Md+JZmP{yM-n6T;F%vU$1r*c+ zdz&f*6qM6`rE+_7fx>ZYC;|r8pn{e%n}U#%$X_!cWlaJnFN@wIl)R3fk_d%QndL9@ zw=Cv6cidm@-ijBa8m}8Ak&{p6OZt@Z(b?3Oa>Tg7QiKcKA;wP1ED01^dyEDQL^3QT zU56xRjr_@^H2-7(^NAJqAC5OJ$WC&H7_)_7yKboEwiQ_$_ZMmL7e@xN)64p(ZCY%% zu1Pj0m?>T-Rz#W|1Gj|~_@B{r9R_8)a>Uxhw;C&N1ru`X@Okd2SdSO{Ny;LolCgPBS|FhEAdrOTfM#cdnRp%f-cN2yFN_R8S=#jjP89FmnTqNk^62iL7?&5QII<1E28Li#W>LhXv@k4T9phDT89O*IwCtX0;TfuA_z=<)=+9rG50u}&Xr!3G`QCpGZ=?D32LyI|h?FWCevR}=fcUQz z(VcC9Lkh=%br(EN>a>nkTbrMqB@P$a@GY?zpFw~O<)dj(2HcMrQY zqi#0bPe;FmgT&b%5#mpR%(prv_cyj5;q>6;+;oi7-o~*%7^R)KyxVaO_}W&qVeAVY-S*c`Ef+s@(oP;e+J0F%$-hrm ztF8I*PGuxf>qtD5_|99)bH&X3to6WF8k%wdK<#MBjAg@bvzD|$d?K&Qctmf{qUg|U_|Gi-(1X~1_H z?ck`~u#hzAk6;MA+~73H9M`Vb^^@W-S(?zMnL@Br{}#fl9a&-Fn>T?o0{A|*i%Ee8 zzM~ByKXET5DuH;KP$p+zxm9oe?B?Fq!!^BtpvxKaO~uUbwKJmbN)oa$yH`@5*jHkS zWX%jbpOF52FAl$Ncq78$U*cJL@{J_`N$*P<#9s@zaA&|sQl+O$4>3z;y8LR-0!>wR z)t5R)yGrIzlDr}E;%QeE*)e!7=(}#Vc|FWAtqnfv<|#IWj#GpfrP`qtdA`&XqJiA< zJ8;V!$uu-X#W25Wc4aFP?BH>+dL0W*ayHUSJQZj_LDs^1^_>MFme_4*Lx9Z5e3Pp9 zhX-}hM6xE;bCF#DWg&B*)+g5`MXr1_D#Dwk&c_;N!@`{RB|*S8tHpdj`=>*~w7ZoQ zdn7Ln2yQd1moo>$XvuRaz$OZ4N`b6!yGZ5ijEL|1uJBUL_<(lh6LNffY+hg%&g zkDF8YlmJp6N^&9|OJXI9bCpD0@xDc>beSsRO>7$-y1xF<@bLh*NF7A9jTvJlRAl@n zVAfJTib-O8+)Y?^76elr$x9ZVBl&Y)f!cRHE_&~NDtGBMtu_R83hvm`aCRF=fu zg0Oo9Gd~4#*-eQrC!_M^R+eeAx<|}yDZ)-Uc-PUoQZS{t0&a^! zMLhJg@@a-G{}o$umi=&F0;rmbUxIKo7GB1=wfrsvtk$*39~AYOGF2%&*>t$NMH}+5 zkk7Y(KridDB*2PBE=ND#G4f|cnlE+r{{A<0xL%neReB90n%gqs9hw#+&|^V4GjJAP zDRA~)0vLosMF6?qU@CXN>&1wXMBDvO9Qrpww_1A@I9E1wUMgi=8AY? zD#~VlGXQW8u)t=lmgdlDP)3%G1HFvkVNJ%qa&2^w(UK+#-(x^G^J9c@HI;xhsuzS! zGvykrH`5h4m`_J=QYsq>EGo5NwtQ65@UtY{mPryy`aX(LnaBB?lz9OElz z>HvcMH8q7!MZ(BWn!Kp|le%j0wuZG%*V(%Y_s2=^DV5J3E|T1|+)`?wAMU`PhI}76 z#bkjZC8J}ooG+;2{?cC@%MCUd=PyW|P0x|?9rxCt1pOsQCkfEY8Krz*<8z^7h!9Hc zQg-~vx-K+ty~lYX_;v{Mph4uD_WH5vTaD25V@&&{2X?zwmZsxtl*X0Ekflck zyYPeLxr-7M2|vO{uwHL8Wz|sFK6kN@dUbs5*eTR^{6c0jjO|lkQS-)pq!S)eTP1i zg!wz~fLCXb2{&_PmE{wT^qA@y1f1w1vs?$bdVXn;Bw=O%1AC-}r6_Eo|qRE<^VN zT#O%ll_sBxLGY9J=W1yIu>tVS#_Dp0X&?faa}7jY&XURUSc!CL`$CD?jZgrDU6NHQ zK|pQ*9B_8JG;w%{z`2Hps7q7xEasU$u1RxHT#pTp(wx+;%7Z#4i1Zh07YFqfps(6| zsB$1Kj447`{khUVU+-!}U2QEruD+p!#yUCQx!fwUQb!3~+4Yorz$Ld#C~d=&XUKUA zFAIV(1}&3y5ch#Zw0ywa~AIhsTWeRM7nKMbfKR43>H z#plZ{06rR%BW_@GZ$vbQeu+>z-ul*>x@J}(0yt`sTVzaVV5maNEDjlC>qsrg1HKuq z^f~0&ZYt39Lh;ZoX>svVhq4hr;G^f+E@|3`uyL8IFVvG;wqudupK9~#6i@80DhSdRFP$zV15zcV})-@^?^Dl zwKxq#bdK|4bzs*rG3&h8cne*QykvH!sLXBvd!Klfs{2U^=@8p?6XNgJYTMp z+h7dX2k0sTeGPn(1)N|kCC{_zx?Z&~g|Zwh+VOaJ15Qv!S$?UdKAI9ZpHi_|aQn|+ zr4q_{oRjonbrpo?Dl(BWTDZ;$13*bwnjRhEl<8WpImTncfe$?10-YK>Z|@UWA*S8Z zZ}E0<&c6MGdtXz1%*B)cU~R0BugerzffWK*4i-P*L&gB?Y-X;(UXyf@#fEf1?rMCY z;PM8CP};d1r^U)Aw&a$Xh- z(kVwku3a+Y3wfT)S^PHp)~t_$9d_q<+7q$;CsAp&O<%F2zoaC8%CeoXox)jKPn(a_QeqsBvz13pJ+#0=f81N$-o=v4No5CvHU$J!`3+CvHRbp1^z`_O`I1aPd=|^+ z!<`3Asq95k7@Hd?U+2h126&Ww(kSf_w)V3JLSO*IHx@MCTs&BmCI&Vz=VwayoMx{Mg$=VQ;u4JZSsG+w-`&Ase@Wdf7p<~sy) zIRpyWH`@JJs?B0x_d5Qtn83*FZr0u$w;hh{D8~x2(GI|H2(8|s2}8pd9McDk^~GaK ztyULScS_>ky;IK#4M&c>Y%clv<|1#^H(Z~+zpt~bf_W;ZXSkW`#UML&0>pRzwxHvj zOW{Bw1w!hvqo8Ey;n5=7tJkxl#uAB*it{Kij9OSJ+QK*Ax=p@?5(Z|=D( z)8`h)-@DA-DBRsnTi3E^Y~rrJ%E~ykys#baTouqK)IWUhCS)S%a_HvoNdlw8%W!yi zr0d)~)!8dJW!w=JE1r@iKKjk#*6n0l;i-Xis{*~J!*5?}6%tEvjEhsx=kY0(E2ZDa za~ksWxye`N#tJ(85xTe-dS5({s1jP>hpu;W$ubU<vsA!#UZ$}N>E^d`aeh8dr_u*|T@7CThRts?MtdgoUyd_Cumm3kF7)j!Ti8#{8 zjn?{^E#am9+E;2Isr_==g^}gh`VboGB?L6vb*y80Xu`wK-7d@Ze#>Jdb|u1i-< z%6BYmP&WEYL9q!p7vs?F6DDZ&Dg?{tnSjH_xLqJV#;}`jMgsJf`>%Eg@b(H}M2t3h zChN>V_Im+PPi{|N&$nfVCPfN%jT1Ej++Z@SD=iCZEH-)@t|%&brn@T&`O@b%prIU9 zc!iBL5h%Noa2+VWpniczubQJP ztwdPXhFCIV7O<|I*J%}Q1v@>nnsS}Sw|#RgyrqA4KRz$9P^=^x95@o}uw^Om(Ly9c z<9R!t0NB()b+s)H6=2gT0&;+h+Ka|mq~4I&LyPEP=vPq{peRWA0_fMlt02T99>~?$ zMOOUlVl`25U1W{oFJCU@umTJ#CTjB^ZF)TO0Fo>4g$zuk*xF$ImS~UT8wLLEElZF( zrC53)lVS-lgboETBYnyWg9-2G*+8ET0iHB}Nc15-ooaqo*RN{);}`KRYAYJ?df z9gZoOD7epD9)m?)K5@$30OB`}M@=es_DmEO;J)>48(~UMsG-kII%R{ww0Rc!5~jMt9u@{ULlJS|y#xs^n{;vW68pbHehRv> zil7V&+M0+&0qZ_Fvh3%yIuuq>Z>L%1syNV3NCX{+AQcodfBn^~c5EC@Ts~dQd+<_- z+Jt{y!SG~1jWO56p-5TcPba88_%bBo{#FaH2M*-UyV3_(QE&yC%K@OgBHq0;Q2mW% znWyY{mknrOjSLx#4=l@jI+*KGy_D=0SdHU`p8X#tqCD5lY%gS`h7a0glJaW|sSQso z+eM53Jvvsc8BxzEV@NgKTRI?potoSaz z>wZcz=#ArZ83I?>FA}~+RBIJQlsq#5DSHtsjZ;;^brE{<+|O4igPO_m1EZcvFMW+x z810^Z4o~^Qs9{kUf(zxMlndCQGIV%3VE>-Z=2vxRN;w%i$Z+_`HSnX}=Ra#nCdlAcrf`zNC21RFAwZTqbbbGrj>Z=ueM6%)FfRCcV0w z-KiGrUGBc0{7GhFo_~^s`qfg;_s=v5w42XulKu}qNAyVZ?(YKRFB*TAU;36X74Q_|nZ~Ywg1+@jn7_MFn9$Y^NuzP#6 z6P=Wt{}s+0?^dKggAyPL;^X{vkA@3xeWD6@Ngo>5+Tet+x;$X75rsMmgUKiKsD+1umec};cV@~utF z_ZzxkrTp!u>TYiD#R`PKo!c{=UH-2k^_}-+F{^u3y13iuwg36``jNl3fw;=CXiKEU zbAas)j}8%o$;s#d(_uj}t%)D2kSAm0RkHt(lIySZj4^GF*o4YVvDy`8*Q|ZZo^6E? z3R*?D%Kq6S8b3R9O_8zw-S686K0Cc-_3Tc>nawGi10aNpSf+Tj)26^N(<+RPMXbK_ zO;QEl1G84a!(*Qx^L!>v>&%_e)dSv_Kh0|6av!`T+|hfy60ET_!40)R*}L-C_44$Y z!)@P-9clSPW`T5h+jem}e#o8bECk!$0g~k|JxQ2e#0t&p%h{U|{x+P9-I?CKDM_rznYvjyON!Drl?vAnyiO za&Q|S{d-4oe$eYrTa?Yd&*zcyh~$0L-*_X&pC1MASh$2A`hEU%Z1NngL^K-{d2o>u zvRUg3xUUB2ZWwXi4%EN0GWg!470Km4s+7B-J_7!iBwZK#X_G>^vXPAv_VwR7EOlfk zzySNHL5Z2c9^XY;?NovW4(O@=^ohc=yqae4ut~&N?n&njx_4`hg=vvWKS)aDEu4hm zr9#g$XjBN$$x{fBoW5jiL~sPVyO=LNfUo5%3B`^YL5WWE#dQptoYWM*Z-rbz>VQpi65lZwKAY>_|~7j7988jqUibYkjMgl zC$N`O@wK2IBept%-|_zUz+a`Ix|ji+q0he`SIT%ltptYrJkSZ`5$O2G^G)|i`6-(+ z!XeP141*9yyg3Hve>XDS?Iif`iG%g`WdC1@|88_ZKjiK;7&8_sgAg^2IR*`miXLaz z+Y@Gf_564;LU{8i>JpJ5OqAYaQIw!~kh{j?RP>H~I|RW3Ea?AUSs!NRRSyEP&v*Vj z5Tw!nsASK0kTPCL3Q7@RYlN3^;2%$hCG-Duzbe-zS5+h9{iHDJwN?LB+5cz`{3shx zeR1)dKFkFtIfC ze=G+AIpEIvy1*slv$Rq%6)>H7kj9`fA4dzkBC9)|Vw6(e|7*4*icwY>+6^gY{MH z6Rw?^G6O?in^c+%yCiBDJqv1K&2T_hvH$s^pzF5*Q7^^}fIzj+fFf1cGiZG$^G@=Z zDW$EU63uD4<1;uxo+Qo6iz}l#o1Z z{j!FDFgeQzy#5jO2{9^pHhhx5V3eo@={z(GrssnI6(k7~-Md4{*i&dPBeWiKn>l&ur75PF`f+ zmem-Q|XOlnLG!mvAEJoX?wkF%ofUr0XCAm{X%eZGZe;w69zBn4&oFFC9JHS3k$l|5f`+J?n23$|+#R z_v!vOAvv48;O%B=lD+`OwYr&XjHesa{*&tI&`@7@M<~-LVPpLc$))csPj41iIXpD7 zP}LmY+vzI=Dy*-P250^?1}!&R}SIzWEOREN0y{7LreEPGOXs=8GOJDFx4k2$T2A_6F zk(MVbx}4=v?u$IH{Sr{UpKw|naN9f0H2u~^FWdLse~N*>>BD%rzFW1nx+{8KQt#Snx_G~FlPcLY=kT6dQGZ-_)_NP(A z$Mk+WO+kCL%&EraT4C7Yi-lg+e@BOwACVk*pX!9_&h3Kge)A0Lrc~(frd=45aBUEP z>fGpr>g;Ap2LJB?x0{TaJxCkivtUM8)?MirRyM{ff^qXIH1U^WR)IZn#X3hCOBXRU z1|V6kPKCD#qiYsfE$_a?a5H?u86v6`Myy-nQ?C#}%?Uv5*AS6Fw!>Lfx0RCASp3q< z5VNvc>{!l;h5n58UgSJXjipgmCN`@=9UF*-G824R+C%?BmAo}wl|H9G2WP+z5Oq$f z6bie#5lwt>RRsrhL=yq7_;~p-HnWR3_v5_Rh^Au&wV2!5oAThyKZ-ai-E-pxa8JBD&BfKW6M2( zEBXDg#j%*-m4Fz$TdgU_Wyv2bMg0~_WPL;_$|U4;?WM#_7XMXYiE+F60mCtMJ+ zj`?zW!X+4RYE}*J-WXm3I#W%G0=0BH>k5NS>uEi035bs4E4{&V<13-hM|$wskORO> zHp)PNSM;x_{ay^>`RCj~jSomc=`sUkTtpdNKu=w+UWIzwh0lm^pzxkOL=NtovNg{5 zNgv$%@e`9=>~TAgWAH(Qi9!@$%b5W4o4A>Gqx|Qq zEH&c@Elb)#CG^vb#8h>L{Kh#l?ILg3i2AzS-0)Jm^Z*W>s%bWZ@uOwC43EP=8{GPe z?d#5(4pyK*I-)*UcYM55C9>y@uDWS8N?_v!Y9N4m4|Ju{M#b}8192ZCy#Y^)C zI-hJ8A_A}(yNB5nr}@iF#58pv%e+SBxr*zV!nUOOuM3=)-605B(t z^7@kJ6JHMW+FT=pLQlZ%v&`V`+IOLN!b;R$34tjP*VE; ze3)v9fFCAVUs-5zqH9J;>2z9VJ~p-+THc3z7&O02S*Nw=u>2gI?@^}y&W&}B!(p%O z+Y-XDwOwky2XtH2Z7bw-xfy#2VFZ8Vs2Xga=|g9-T2oPkx>}R@+!UUL236fyTkB4i zQEa{MvRb*Z-C%e)v2p@xOtD>}_)_J^AJd1;EXlByj4;patj7YIE?ks0@D)}O{cn;_ zZ8zdG!DhH`+soogM6ENje3HMp(hf$s6l&wO?DvfhGRLmkGTx@^3s}pQKp}jWp_^lEKbVLNax|QmGqsWN(@(x38nD-^{%|`Q%t0 zQl|SO`gqW)7Hl=FN4kZ%_$g*syI)V6_rDE2F!tPfu;f^RLWc)0SczD=eSap1}P(k=k)A3zuW# zb=$Hb-LlJ7#^_-9^t>zUZ-* zYj-NeMbfw6aAbCzf$;^VCA8B(v8V}ZBba0tyBI^-V zmsL6{b{c_}sF@ER4Dk}LXchF?3p0Z>k%N;zG-vf|XCh%XV9j|$Mq@|*F4J8I$`DZe z?zzW84lG7>3P3$ORO@{56`Lu2<@BRRPBEwg%`9sir%VUu#8D!)M|aFZ-9p9y301v% zNc{I(3mgWHH-q(zINL1nK{-m>IreiLVK^r_5};z|mQ86OOzkbI)(kz?fL4q(u2h&F z5}dThkobCqH4cLX04W#VfL1Vh4;He%9nH;4h=hYZs~yetrFS8qCk|6l2&$-$qzq_n znqaJAawPcY2vzYdT>lKKatuK#KnfdRdpRGUrh{;{DkTsHYoOe@%NXf7jgzK>)4;U# z644~vk(QH&89wMXe_1ibBOLoi%J(V!c10?m7B`3%Kd3~#jS><1;Pq_?vJfh)VdD6T zeoigvA9DB^L&Tbzga8r3t}V)#`WOf`d8hBGvP#Y53mp{N6lLMt;x7#34{F?~lQKqd zAw6-bFq(12lK#f&l3kkS+#~3%HF4o^DvB-z_Bw?b5j_Q^7y&&6MO!&lhu!^Bu-}Ny zRUidyN_(g>Z&AJXC{+JN zV{BL&rz#~Uaw*=c`I$ow593y>Q#chVqLK2fWvREQP2YRXi6xo2uIuuc-Uo=N2s*(KF%V?(XhVytqSgw@Y#N7I%tEad(G{ zySo*4cZcHA;?{o4d(QWRoZZ>T>?GW5l9}frfN1?(YGMY{zLyvvs!r>KaqQ*u3G;Y) zDn```Q5hHw5hGIh(VDw5ANWeLK5LGSissRyw!x2F_0;Y_K`wb}SSaNk%wx1{{ zdO?deH_QYz4oy*k)HWhM=V>GYpkt;~u?CjG&%V;|kG3uO?RH~|uqNyN6nHEIu!xaj z{)S!p`elGBOh|3?$Bg!+?S6^&pGK^v1$C;?yC&F}ot1L`6m~%*k1>2Bw`hgS_@yV}lk420*f(9yU*vB0hr==82xo4_R15#noY{{K6O-^)Q#qpf^!GqLbrA^IRSs>4W`k5v0hJT`l>T>ir>cLQDuh?8 zHf1ZPWCQ*yhFj6sn!|$%A!kl%Y&q*0+(b+1j||xKT$Bg10-`7b0*d&2)P(zZX%aTK zkqMgs-cF966*0}0Beu8ME4KL~k3o^QxhF=i8kTpi*j9##X)M4b^Vwb{CQ>w)h}qx+ zlgv~hnAeP41;Ik>`qv~_L?RQL|sb3{h zc1wzMf-NX%bTltt_p;TlG2P|++o7F zk|lx(=23FE@I}7)q_EqnPlLpkXK7j-mTX_R#6BcR#sp17v=ul?`<)OWu#YI8XEBV4 zKQBd6#x%H2(4}+I^V*1CM?9Gk>nkZ>0*G&c3$2b57**`DH$iPfXbR}LeRy$9+^`iA z(?fOp>wBe;8FP=2{dd&tFbCy#=EdCOkrv73mzUL}FO7dQJ-^Zy6O$Ru-*eWUEJj8W zYfya?GQf-VX%xv*9JgF+WNx(nE0gK)uTb${5`Z9m68630c=L?t&3Nrr z?NKI^7G&e&cEMu*V*yn=LpYt4_{vKCeII)5Hsro9c3=j)kt+gLG%O&qny)XWQ+tj9 zf|YnKU=9qX2i>jIHyXY#S81P%)ad`)c0MyCFD9+Zh|o}0XLHC1*C4lL4l-|L? zy0k58@?;$Wt0m(!-1yyjC(1QNQGRp>Kvn7GZoHP!xP(TVH=cx(84dgxXDjvb1R)jC z&H(rm#bU2yrYXsWZC5(LVV`PAo#*FdF_}U!qEd!0S@@OQd7GbCtF!B!J+0wpw|5U9X&8dp3eLhPYX0j;j5pJ6EZ=-PTw7V(9hsaE;!a=#7wMztgX| zrA*@rX5=_irhOFO_XTy|pyv$`Re)s>xoRdP4l3YP?(RUonR2c~cLY?5W`Yxk12v8@ zIhvMv55>!(-Kdpl8aJ6knv#)$l6_s|TnFvJV?%Zyepa=|+hk~N3+3snyb>Lk ze>jCD%QT@ml=d_}sI&8Dlv2u{_m<)Wg+zi%u-a~SP89W|cNj#smQDBD=9jsDWasQN z#FWn8Y>StCf+rF!`2*WQsKETr-1nOz6734|Fb~fzDr_lwmAymiEV~` z(X7UVlcqY!aW9H@`3ThK(E_;3F`kk3R|RC1EHLF|Z!v*Fb`3_?%5D((lvAq-qa|AE z@KCaJLG7oPysmV{Hs|m4owvsWuyCjFcL0cVmv*Lu=V!u9FtZ`|eT4;< zS@BAy@XP{GW*-uWA_2g&=IyU!B$`jUwBI2AM1%rh85QM3+wsz~C>NTA`XOTBp;3US z;LCP=s9lD4&8fD9L`36KmnO(i2=M;(UaJU3M&2lYUA)Ni&Q{nChxS*#N{T{iN7|(^ z(*yA2W`WS6CwYK;%{^V}5q$jF5BLTr;3yTP;)?&D+VgX-6QnZmeqqN~QHi_sd5+m!I-@P^-Fn1NLGE zen(|lX|FU0h<4*8XHhQSVax!pMuZNO1MN{n+^o2s1wPlRB*2*oqf=e>(*U4($3_M0 z={105B4Y&{LC-TdBc8|u1Sm&d0nl1pS?V980K6K*_SKo-CN!JmjXF!Bq4?t@T^QH} z5Y6NP;H_otaHD14&O&PKvUv&Mt*Zb_UjVp#2HGged(masdvT@q_W*Dnd~LwJNfgUf z?%?$fjrY#CZUr2<&N4idA2&agt2PNM6j2NS$Na~zo<;GlN5IP%=hv|rxJF;)$GgS~ z&dIdDy+i%=0#R^%DuwYbC4w`e&vPb)iGWJ)j9kqkV%LQWjAkEQwIVL1s{lMePzd*E z{~oXZ%zR8ZOofBOo~XSPQ{BmwC*WQUeq;pt-4z%g@0@beKp3;Ye#Or&4qVxh+Bka` z@f`I_jrq6V?|_5eEWYq1M39o1%N&4-(=2Tes}j#fAsRZ2$@UK6{KFFkMJEI>iao1c;m`tD za_^b6=^FuNGv`cSo20r#OdF%W)&sn5Ujb4&Kr8Q%bVdL`XZWNOQVUpJKhFVP0_PO! zHJAW3S`^i+wRs=H&r;y%z6=gY34v4P3smNR43z6At;F16Q^2mv>=|TX+b(`o@y*!%xgj>YT{-WwE9UYeLOVE5Hnj!yA7d5GS3p zwWlS_)~Tj+eEI1!|C6$auXt+YKHXa1?{y&^<==4QRwKH>jMqHBhy07ax-iT|3zO++ z!`rh|sC^#PRHj?8VZ@gj?V)kYGbyAUmI_N%;RzLkB$jIa`xp&zOoVxNJnhe7k8u?7LPY)J4 zi-%cbbXKld+nDzsxNz4XXxdtT)1r=f@g>l@4=^V)u#?#sJMKp z!H@R>T}Q;*Xmf-cVo-6j4n|?y#LubC?^7BV0T6p}*e7>qcx@*i|2PKiiIb+aTj#^4 zCE#L9-Tz!@l>z*Q4jz7@<& zBEzb*CANPNY;lw6{@GU>FJSOTfIDNZB76uS1bTq*wLd7^kv401 zK5q?Ncl0dSE(^KRI^Q+FCZc}T^tcg5$I95un zj6KghAMmK*8|AFciD!q}bh7qF`L+DvWQ*M%i$haxy%Ob5(qA;5<`>_(o@N-s_50R_ zh^E}FHqj5nHS11DhHbauozPWRT~2QwoWIm);&w_NsJ%*oa@vC2mT#_(x6ib{8OnP# zeu277mg9*%8QZdhoKXymKHDSdUbE@Di2>7qw4xQ!m_8Hg$5PY~)>|~VEN)PYi+D|V z+mMsYjB>>tS~d{=`NFQn;y%(J{ZM|=cPLYM8h@aLnsd#iw9O8a0jAd@ z4FQbi2+2hJ^K9`9^7{~~_7es@XBsM1N)`E zV)vuTd`3q~#@xevi#03+lob1c?&XwJF!OQllarxz)CI)=eT*T9=Abx9fTkt`K&{0E zLe#-H5V^;uWG3a0(^~T$4*oq$y~sI1!~P(jWo4OZ5@|84&hor8PSVbukL6 zQ}uuKA`S=nhr*-Zc6|G}l3^U%cp0exrZ8|ld5m6Tn6Fix$^bUooePkm*SCLR{z;>8 zN~4H^$!;{1hPqH_g)`EwaWk|y5Fo#l+v4m}H?K?!A><(SC`n)q2XI=v)@p-;8?!^c znH5d)0P|jk7Y!cZlo@S4D+9%64e*3EXyEoAnv~y#H z5#aGhDvT(db-nvxg#+)Y66HPO%b z!jvx|+zdLmdxeLZ^Xj_PFvwr$}G-^-Wp*jdkAn{1{)^z(i3h-17V9Voe#oN_Owq!GjxSX8`uROf@W zZ52RDU{0Ie0fxzh9MK&Y6kpR75T(Gwe)~{=V?zR&?HuP3oTWZRMqEW3|MJsr9-7Lm zy7;eAwY7MBV|S#X3H9jXTBcedfi zzj5;8Y@7sQlKHiYcb(5}t_@YbFN3%P=34|%T~a`e8fzR6i=#n z8pkk_3^=&n4Kr<_pZQ5}dPAK7;m3RB6G=v@J2NMroz9FTS6SYllcJ z%*}A3FAjuXEB-UC$OhM_Ze9e3MR7yT_I}v-@;_9OPR0zag4IY|MpQ1S*Kb=-H;)w8 z>3=-1kCwk5dabWI6YhkK*POEWwVq{I7)@zX#0i#R__g{ZfBiiG=7ufYHtqgXow!{% zjF$TOp2RPWdpKD_L`O40WPWhKT+ zF?TvM;8NjTS)4vQ0{CZ!lwYFlDJ2aG4PywS!SJd@syGz7+-s8Iozj``?+ldaQiMBu zs1>So;s@O234eiDpJ0F{@dtVpq4|3;g{8^l(nv|2Fz%y9{& zWQBAFeEhNu7DYRE9MnCGw_xfpP_k!6UW{ zL=+jAIu+|_lB&U0$)#8ne=q@sXFNzGHm*#=g_snvM`?;9wA%hieZL~NOs(FiYSfL8 z6mXSmkuxeRV2^g0mu!Kq?^BzP+jpJq`69c(mDdpYcN6&yy`x?-5)yrV3R3gSveGJaO=%rX=M6`H-xFy3YmlU}($`XvE=kTk2sQXmhZE0Blkd)+q4T!&X~t!E!3b{yzR zT`djZBSpljBJ}K+1Q;sQj+c7va)2e@hbxT?w)puE9A{bLv@1Vz7!KSw?ffD2->N^a&&HRxp3Jr*fK=O%Vi^6sD|kfhOg2mF>rPS_Kz*ax6QOJ_H1VY)Qbz zi61__+ZfOsvy+x+_=eA#vc^#%!^-BIlRa{I1)E-%I|c#UGujtZ3ScHJqMth+!>%G+ z5B>odxvZcp;0c&kWv)-VPO+H(5c(!asTVTnVq0sNM`}g$?7pk6&&6GPI2MS7*$K?) z#=xq20|+*!H^H_xGmp}W=AfXeQKdEK;`X1f0~p?GwwSJ6nE4L{WedMRl^FpHuh;GC zqNqPpypw6|xwrw+@7;IBwGo&=l8`$yRF1dO2_tdx;nLVCG^59jQH<3MtUn`}aKh1CyeaWMIa##1pi? zV*e^%ptm!@FN{M?2}Zew7?lKLjcZYd24!5(vg-56gnu5nwPA+TA1CH_ES<*>4z7)m z{95F-Y5$Uzld$58qr$xl&tMEdr+m|O|CW~67IXr3EwN7S&3gk&L8jgx9vRAv2nTee z(FbSMF602)yS~k_1Pl!&);9UYZv}@CLHF#VT)&TgVklvj_f5EQs*%$%-@z42SBgmO zM&WvtAwhdX6=e;?Zoich|&N*Dft zgSYt?m3I##W}l1xj(!Gzr%bVcIt25Nr(XGuE6}UyABGsq%d40#l$aDlJ5nvPP!AP= ze)i;!prP^7JFrL!&G_jE?onOFZ%6qs`C2x;8%|~VR@~d0X&Y7rqpVvtF9uPXUb>U7 zp;~h}p4kvKzN_c&USjOOP?0LlWjX_K{O{|!jw7{}=Gwt0Sl;)#;03Kzq9Y8QE_!Fi zF8sW_o2eH1<1)T(C|M1!a2TO>zOOGQa}WAwh_;{140@VgxOam-kI15l_IX*A$c!u+ z7FxE;%*2&J;Hs-p#)evPW&De?a;Jj1BJ6_qoRr25;nVHY+j8x>{Ja>zy)t)oi}20= z_p=l~mnV!}VzrW_GD&ZS9Bf;+k z<0ypJGcXsk-MVzlG#O%e@v{OC9a#>0PyK~R@DO~w9{2;5MQ)#A#afon$^DgwoA8A< zYx=+Um^`}ZQD2{IUJ&<|{Mvn1e02FxN8!Wou>vpbOXBl}Gf>h&yMwkn4`7{Lmw8Lw zUhI%q_VkQ57Zv#FZ<;?8efMB*e_S%1Xja?yJLCQXH?r(T6EqaGoQn6`v98c+WOH(9 z{hZcs!7_t1hX%kTwHOK%`Y|hn*W}-QDOIx>y|5U5gmOX13Y^d)Wd?{ZFFs4KZLU{;lN+Mhb}bC)G2>5V2WsSstgnMxq7v`;Z1!<`Wt znVidV+ogNx^J?vk5l7&Bbzv&AGzz{&(Tq!pHe4DG#AUh_}MK$i~%YkuhMQ-UsM)ni4h z59<|r{@3!r)0IL!>bleYT}r%{`Gw+@syj3-L{fMWxrh{jIwZf9;>YHqnb@Lc^r;QP zfT4)nUTE7ocf*Z=h2@fo|6U-oMdvlv!$zxv!{uZ4$CN?h-Y8_b`TE7oqr@}%KA}#o=83RL74bAKMwA~^;5`z|d`D%) z&tycbMVsYh#Vd5+$j8UWOq7X;{Bb{sLt=W9gHVX`J*f|6w4xW`azlmdpg*jAz{{;0 z7v~E!;C6z>fItvN(KpG3$kQq&HYPf{t%I}C9K!fnzBy< zy7+W-k29&<*e4twUaHoeC5P%DHHiwuDIF7M#1WH+c1@gb&J1!W;pi$WnGG187mDL^>tTCP4;8eR;0{y|FBd1|$whY&lZm#Jp0z z;r{GLPb!P2Nk>COSVRZI0#DRZQqE+yD9G2%m`AC1K!J=+^}NuUHf9JNiqIeUil`70 zG~_U;%NB=iR=PP7$Yos{=1i38sQj79p+2J*xnYLw91!xZRlm6f`cuyhBOI$Dd{!xR z!>gc>2GHFC@wuI-)kP@+;7v59F`N{~;$PQ)nQ|AECQ+@#x9OnJFup;LP(Vqo*iiPt z@h|koGjs8MuJ=RE74`d)e)o>4k~=)2qB1aOy0 zln1fX+Z@oPL z3+hmZWAUGf!j*;C>zj*yjwIBzsW_KclN0FsT?{+(3V&W6GIIfagtds%{G|#zhdhmZ zz!H_t^9C_|{I&$9E~HZSL1l}}RPmqhI&G)ZXUm2CmXD%>rndQ&E$}0U1dnu7sdP!FI zkG%jfUBimxvhe%*cT@4(`zG90A2%8vEw;-4%8JF#-pjeKE0|w5FdE3owLDX`ywj=A zO-+5c!@I(IN-b6T{CgD&q2YSQRO&F_ZoIl-??&-(cXL!RjN9EryG%qsNk7qC>r&t_ zzwO5UaJL|a62U^iWt+AyYEHuWXnjuNfPknk7`g2$H0KYr$!w9J$J$bcPGNcd7ao$S z=b`R6?r^k=&pzrt^fl8;t?~0y!_8mr5us1=-zc}^NpsNdtnU#uSeE733cH`5LVP6* zyUG_e0wYdOLjWLYBl}Aqd86owqf65aBTAYtqZOpwOE*IwtLiS>U5U1N8_})KE5ZqF zUv{_Vbdd66kw3oB{#e4I#md&S&fzF~v+JL~_|x}YF{I?7NzVfjjeH~ZM2T$qw!5xo zD{=Z>W#bp3#!X+(9-;;@dFL<0g)>a`Jkqnm0%pxT1H3ZGJHJ!CfahQ8u{~-R<{EjZ zC+1*LA=b&iw$-9tAJt$^-&Wcn?@m}=s9{c323b`D_$BMoA@5qxQw^M9PJQDURj$xX z&y^3G<{DaWR{Tg`<~8a4R&tlxpCfDkW?jv#-9NEC22^c6#+8R(2wId9I}MtaO%us` zJZbE?A=7*!1q&Ld2^<&$&d??!(h*}5ltcV5dRR~q7MA#m`U@%3fF$xt9 z0T~(EA!5K!!QNKWBRv-N4qmn$opQ>>a7U{=E_|n9bUzqmD{(08I7hYW9SIv!qm4S% zYS#7ZU+mN$N>#W`Mj*cIAhxSWFShqE$1^I(Br)YoS_>m#gn^{TquEfZMdU?;{MM#S7cMf1jQf`2VMsC5l@uA_+Te6HO9RHMO8I3 zj~EkSdP0@{RMJ5PhG};DP&kFU_?;s$qViZ$(dYOw;X5OY0%haj(>d2$M?P$Om z=TsT6EaGOT9^cnUw%t8oJH`Ga9mPKwjb+-08EMSC3~n8uSKq>CH&fGj6rK_76T%+*MlK7R7L8)%I!xV>lJ}!a&w`Pud zmn)FL%<_Di^(z2&VVQdry8S5$U8o(&N9LG;0GEed*-#L@WOjQE0!4+|R1)#36nJbw zP&$f(D;7%}w^$%@KhDLCEW37G3q%~2aC3pO)LYY?ljz&mSD@m2J>cVIg8Lf z)rHymE4Jh=Z;bQu}8t~|^?WCg6kEN-WM!%Gpz zr(RACbH~ZbRh(7k`h%2Ca=t1ESv(~JFmsa$Mxo*=P;43*HUN47?#~+dl3jeE%sUI+ zD!nfdD>yr#jDOJtqd;MIKUfqjm#({j*Kd-<;2VWMo+ONl94?Afh=^JgUv6$Q1S!o| z^5|%iSDUK}<7)X^PfSCuEkU4pa@g@4dRVMPW}R;GpwEr096# zq^s8!;-sQ@lH;%>aKTwjE@RgL#E|M!$qLAsXb0Dfhk6unD0<2HG?D1$NDQ3;5-f?kW2rGh7n@Ppa9Z=ijNyv&bOFBVVGcWNvslj zm=l=i0>O&no*^;{e_dXuRg7c}=%Ukx$78Nc2@CWyjW|VQvx+2!gS>z;R~afQ$=tOO zga8Kupx^x${ym!|wb$`>HjvJwmi28ohJ=Ktt z4(D(MVL_HK1~a6^!4`~Z$V&&CkI~>j*vu*w@S5cf!qCDiD`O6Pd|}2*G18Xf4Mbf~ zr~dB85lSv}2Q9`n#v^4U;nnI9+}%ZlunELi;6;-Y6yN6Yg_c-mmXEUi<>5e1HaD?ea5h%FysRy5T4}eqH&v{ETw9!8uFgTj7`bkE{j;`s zlV9l}-?4V@yO~RNp?GoXcZWUbd*;~;t79OKrc zF#FUor}?yKz=5`!p|>2HR9(I7@)SR}xSQc$d$8KBf!3a*`}JXU-&HjhTP(O0)O=Ch(uarcE9 z#ZW77sSF$%0oJ7CqW(tz(;y+A3Q zF5eWP>ROdztf5~CisI0=#V}1D2ShGiDaP3PwFFUjSxn9T0ZXmz)am$<)vFv)Qh4^b z`)L);;f@pLL~Nw>J5DF*{Mc-*sy+gq5Ld;GWllt4QvH=oHTT;_Zq_*(7 z$>fcnE3OQw#&+!~4ftnz6H-x{-soSV6qh9khMxDnN7dV{@v7?=U*SRw9we3dy=4wq ztp)JDCo3kmc+b9tX+96|nqR(I!b`oNeF+9@tq_DNpp)iXJ?tVI&t4ATLO}k@rWm=M zX&=^Ugm4cG=x&WK=^y&c-ey^ryXM79^v`4U4GHOt<0ff0;CatfL!|M+4Ytnq%s4V2 z&`BCgZxm9I1KHQ~1&q?f5CVuPfp^7Gv0Qxsd7=_e4|V z?f3J|`1DMcv&36wlb=hsNPpa87fcE|h~LV$Dw3<{kfxQdIq?pZx(nDN1&lf2=H~H4 zD2$dza%wj2*AAARuH_i#wFJ;TGoUL>uRIZ>TRG9REl^4|AL4!KW8r)lmsl1nrcM?j<=bx?Kp^v7=HSB10Yi683LVd;#)R z@XR&im-1N}BiJO4ESCF*aYj}9hOxjhPBUoJ3q2SYx?Tum8FSee+p}xk@lLU+_>;EU zthoc)uDP$6l!Lw2nk2_OzPtd1m?KZ*!nU~eFaS%ipCoIHK{Vx&e&890i*Z@M2 zX>1n;BqZf)RwVRH;0uzR$DZGg!maAd2sx0{;#V|pPO-&>!-9DL5pWSYJ==8lEp+y( zdH~mCu|5R3z;-n-#A?k|ASlktFmXtlkI3?#;ps!a|Q1EsnxM(ns39ofdr?My8t_~Y*e zA1VkzLV#tSeD!H12bpV(4ic6IvWBR^s5gi%*4wTFLu(lrTKgXPeB=wX@nwoktDNDA z?>5p$!sCd#VAZQduXyhRtqZU{1rLkf2)P!^P#yjVFnzpdi@IY4MD4h&I^kf&FwXGu z$wn5*<^B+4C;>H6$Wcb~a;te`q}fIXilG0L9oux_4bo{$ZVsW>ZH^Pe2I@kOUG{k#^xNs49?lYQ;^F#cb+Z zuUSl)lO>Csy?+yhut}`T@&-iR!W9 z6DKAETXsb9#eHS-12;mM{~8d@jrHP+_?+>qw6UCa_4DbQ z=twl()H(!(t%sYQqLzVkM?}f=3r<7kN=?Sh@`S@)chb6I*0L&5H~1%TBXdqWq;Bbk zbtQQB$i%H1?uIpBNzstWTf@C#>+s3ZklGDvzmBs5;lar_Ve@BgFOWYJN*Z_~=*QT$ z`E!$&rzsPk?ANNp-k#_AqtKO+Zqd+ zwAoJ+8w4c7m0i>M7U~GU4u5PQSh%3nyTkTS%#UfcL}1ByFf?UQd3~W?h1=S|@jU_? zCp;Ktu*%OikIt!GRtqq&M0S57VCgd*+alN~t2|k}r*E4euPgce=t&(nD>vTtiOzTQ zOkX0Y`|uDqrR1w;EwcAtU)~1xGo$7+??j{fH{sxEwq>KJU*LemrwHR;3_;G7Hc zw5`AP-7YtCZV>{m<=$WX+sz?0COT+T^ApnVe$)31L97c8oc#4jf4L)L`+QL!_DTRb zzwaAxVhjy_=>RVA0#1$)70d(fb+Axx#vY)-hF!(9U7_CEitS5lk9g`L85*|DJ~synZjD~ z<#ZXF&Uaasz1HH@J<5A{W2rH=fm1idFS;2Y`~F4{-knG#e9TV$8+ag(hPXAJ8go|q zaWeH%-nu*3Xzo+O$M?t4B~yQj-E+JSSTh*Rp60UY51!`QvIPy>SrdG$1>I6U3JKlQ z{gS5&lmAm3-*5gj=ef9&=yTF7^QZW?an7IOFAQCVU)l|qa%xIh$j7v5K05f_xkFW* zWqilgq29Pp{k5z*?JXkr*A$os)(Fv^zvE1KzU;C$+cGX2Z;-4nime-0uGupU9Ir`@ zn~Vr|doEmS3<~zX#VQgxnB$|UR}UY9SG{}VE}ook@HM>wnWmx+OQ_v}bM-eXyjI3F z8>WG{*Fue0ir+s4ZCdv?GJvUjT`RQC3X3H&U|(n~*=`oDdMC@0^zI3j_voTzSmzR% zd>~E$^&flfs(4xdy>cGnJY+GVH$?y={!u!etNZzy|A-0k$7Dam)hZEpv^wkQDrA#I zEnQr3Fw9ia1k$d0B|sS+bi5WcB0hpRENJaf>Uu_6XuDp8Txk6XXqAN!mg40;z6|W! z!V&(A>E~Aq^9hYGr_2^(Jh*htgDHr9O&NGuRuM}?Su-QK`=`|!v>{L52Xqd)G&&SC z&ChT_5Or2pRnSmVo&gN$n7ry7G|*t9tYvptM=N!fpjpRGcXZ@79Uii*ovh)seo_OY za?|Y}?2C0-w+hBBHMJ|yM}pHyJJm!;iYukz3RP=COhGzLO(}!DVr1rW;NTH#Ods5g zoh-aE-C3sq;~o5uDvOO6+M%wPqH$qLY@e+bl|?a7%B`Hp?Vj z;7$z7v1Zol`d>DwksCR!-l>>0C4 zpXA4HH15DYKg1j$rqtCouF=xjfO-vcbT0jU+0d6CnYU=LR`3DLbqq){(|UE4rtIfQehc{^D$3G8GjPk z*Bg3ewwXvlmIemJ-qI1UkUHCpfR12TK+bn_^CYE+@6{d(sJthou1jyN{jA6ucJgp_cQH=s0SbQm-_ z=p@TiDnx~b{R0esJC^O?Ck$Ty;93}_!9P~5Hp&D33uJT%w4Lf;fSb=ZkodM78d88#pD2Oa!>ZT;))U4SIOLQ+O@D-nct(i&Uv;{MwAp{u27# zfEsaKhnb&cL~>x*e_g;Fk@S*O91N|bk=vC>3$3Pwo3)dRmo7dw7MQ4K7tfH^#R*TH zD;)DtMM4!E=kv^q3fGl9NXvT+e4t6|=vV;|Yn(7hLekjGw_0RB@eWFp=+e<~@qX?W zXv^vaM&^{rsw`(q7Gr@*s1S~Fqo`VsHSxM(oXxSbt!57bAIiid?OstXRyH1G6lA#) zdPJZ^uH7tOE7uH1qdq2nID~5hBdvX#Eqv{*+PtB{>J{&gdwnB)6qA$Nc0?1HW(X_D?}{u}4h9-DhlEOQd%hp1m#0+a94jT@w-f(k&@0 zAq1(hdVhn`*Ye85$QKj|xLG9<0PC>r@2xJ!qNhz@g(%OZ`rO@-r3-4gYA$N$G5&A+YIWXpiInn~Sw$nwIX> zE|(tVt)bGJp>cL|x^UT-Imi9=P5Co>p&W9a3!GdE+DZB0=&ui~FuRs9;ZbE=foYAb zB%iuB+pvxOrZMW6SL9;SxL6lox?Q&CyfSruenR1?tzwfiS)Y3v-8$Fx+TatD9`(F} zwFsB>{`GWW|JBvf!TqWa8e{NZbeEN^^RK7S?!`=kj<@X2wUt|ul~@MrNx`oh+ou!E zeb3Y)hFOB2c#Nr|(=BgCr_aY<=?!KgF6{3ve#hU}d`;m(-?i_6JYng)$ff8M+Q!?; zk@oQJr0T5d8F3KNcJtnuP{f0R(?|BHJijNr)L*q1O1XRD+e+G`jP=}TVOjrDzrL@_ z&`I_&U@utl#5x*F(WuWZALp&EY< z_B`+0>}b2WAWS~osvKu?Tx-3A=43^_$o{%iTG`U06pAo9?u0qf`pWIztzW3-&=QV} z<@=*Wob3&>=hj*1&jFOla=Yin&|w`MdPS;x|f{I?Co*tt}4 z=KS;QuPOUgEfw~m5z?S8jEPp2Mv=seXeYt*eC_*sQ{^YKk79bL>jK-1!)GnhTmgbj z750J0+AlX%FMEd`-yG-*Cd-Z`Ue$fCt@p8@p%ZO2u6+HEmJT8( zrU9)LR-NB(i~hk7cA3)M>W0>shfc3QKumF|;~Bj8beE89*mrS`4-YyHT)cjZ-n;at zS>L6gwmZj$;vhhyxVe%zi4&{*xVRIm`omMrJxoE)yVsv;y^rnr?kj4cz62I>)(^Py zHT~8s6E4?)TKxK}{<1(dum`eEy=t}DJtx|?e^eGhLB=Dn<_Cy5c60;ur?AFsqEr7M)%s5FQLP)d4j9ho9a5Odvti9?!gH`Zl($_At_7I@T z319=ToXARzXu9jtP{XcIp>QNOvlzlH1fday=+!R_UPZ*nC5+ig{+y3sZ>;Jlgh@P} z>}!Nsg^DGCl0H$W9E+s~3VboLNx$>PfGQwBQ>|{`fDCv>nZ`ETNMZ!7D36M*p1eu z+r(kQ&?wQJ@o-DX=VJ6UtG374%9o0Dk>5Kk1(fm$=mfDgM%@%kHu9q_kV~MPfKyZF zb!?p#s60f}7p@SI@?ta0#Unx;nKw90xo-No3%+i;d;!7H3c?WB7}6{s6qQp*U$fBP z`sx28RLl;jiDC)Viw7i0{J>&)XPj-RgMLw*{A;no9nc;{T&o(med!Ps#S^JUC7mf% zhE-?_V+eeiF)o@cfco&*$4bXD(MzxM6f~>G8_>Dh9P$hs)R z?hgEkwMcyXls(0$YAJ7EyHHIqQq@x5=BMb1^iH|8u}x^eTy(Eyx|BCY;e=Xe zgld!3#{qiXAC~MXpfp1ExG31_AGlx(d>LsWZ55z1hVy5IfrAR5@Ar6-`!jQwDUN_s zk0O%Rz+~P-MAY2?rja%@+>!h_R6YGbTwKUQRFMja$;otGOTI11l_p$n3DI3?Bb)3H zpuK6`g^0SYT2JV|J6|5LeYFatgL%e()ApAqmlA|dAd==!)^~-gSdyGd0=!$P6kJsj zP57=$`M^;}#cx_^-~21}MP0#26^lg!NgWFy7rky%s&P{4H9-m}>=fghhtnfGDxRa# zd_l1X7Nm{CpMLS83qF2jmX*l;0fG%@X!cKq@Rars<^7^rznw{S11v+gEy@h={W1?r zOkeep?h<~xvj}tV7v=;Z_e{-ou)l&sN`S2i+^zK8m&zHW{RdT7{!qgv!H)#pwv%N9 zq$l*IC6hlo*!_A~2pWE8F0H5kK4YFh+Fu4a@DF{}O-YS1Y+6}}iiJd#Ml0vg3l9z8 zJuI=x&L;St4&&+PL*ED`A~pUy;Wu6tNA|wN=;ULcwY}pmEUIo48Gg`LR<G>#&D}n zLg~JkD8g}8WY$?Jmf$(twm+>zaA$vS+G+-SXW1t?HXD=dI~;W`6kqa8Rm>J&azJ(F zuw*Q3E<44xKb5h@wzm}3+);(pM7(Uh!K(OMW%b)Z*<4Ag&lJ-<BW!2DIM@L~`cHvtjh{L9e&b_0Jy(w(+|6l4+ty?1m(hOR zdQ@^mTC=?)#w4&Z4_AG#z4TUpSSOoA<`lJC&^uZsFvAvD6WFdSDSLpB`QfS1X3(op zG;}ldsd&hV{13g=B%33fDq0{xNYSsUmI{x1Z#?z^$?qE>U7``4s~b--ooyQTkorp2 z&>S`{7tvo+P)BzKpnmF2801MR3tjnqQI0n7JBQId4C1*7PsG^@z*2X z_s#wmt3GI!;w?uT=lsuZb#@?;N;&q@*3(bJH6-Kk^Mh0dSvDHq*Br9+=@)6g;DOHx zWcsN(elCqcN1umH@5KHTzLed(9#58#eqSVI@S2Fd)y*NJ*k)!HY5zF)dhB;DDB|VS zCj38=t~xHN=j|dT-7F!((zPJnAl*o=bc1wCBc0M9pwv=Q3(~oCcYTo*P^7!N-s|uE z=Q5wU&z+e&GwjSf&pGGzBmB1zNfQgAEdyuc;z0-N$Tvmnb4=u4)ou*Apy72mi%1{J$CEV6bEN?r3!Q z#@ZIgT>MFeL_WEwm&47#kw85O40`WZ}$hr8e9m-TJF5tzuS4*Vg+L;8Exo z>t$K$U$!vgbjB&{D8>6E4e@^bh!x`86vF1wTBMUE`q)UWVU)!j(1CJ0QR9mvtB4$e zS$msUQ}Bz!63fsxq-^vmmpdY-0jb7;_#DS#o@op8cZz9?qOVeIi~~Izoke?yOH7*` zvBHCKL61XYIs5P4UG2^BD|?6YytPOtj~&sik&tES-_kXM{hwB`K2*^mPlL!2E}Oxbxa zH+6zhV~cOnka^G`FY3=Z2OIJvZ4nHXit(_>D0m1fxs7&lUbVo@dO{8l+GkHQETa7p zY2t@!6zG)RF@#Ub@^zW?xuG)Y&(wa)yhn~rtVfps@~Dqj-O|LebIIjUQJ}h=kXOy2 znJMnG^%22J&l7^c_P-M1brF-^dV?<`8zJL}6VyL!fOLAR*m07Qa0`PLU^qQVRFnn6)3t>`gNFuJo}QQ zS5z!erx~DsrJ2x`Nv-B2+$F8sYj;r7fHz><2STr<74+J*Y@4c{hyMoKBoA;U^es#0 z;U)1zICXdF%nNK$$OrL}282pdfUV*7G#{~P>yT~WcFZ4RUwk1MA&I$1*5+ZKQm6eQ zZG{C5h9op?9@#h(TD|*2ASasn3g|#qZ4Etz;_Bb(83vVg_E9f{8N-C?f3$=I_aN$o z@FFh%h7mK&rIuj{7ez_tau1M@%mF_1tSlRXg`tZYOsxHgemBJmZ<;K&pQ$(&?M@Uh zaHGR{s3iCi2WYe#449_wK+BaE^vR?804xCNXZ{i_1YrmnuJ|^< zHgo_{$AuSv`B#RRZ!WvsI^9tn2QXs)S@#my%Pha<0@qeb@JU&c$c@Vo{<7!Fu9lkSI@A&2Y(KSOc& zxEjWLj-qQ4fGk>VWM-@^Eg;kl@=}PF7;Rui*Mfqw^J)@QFEtll(=Js^!wB|Q_{1V4 zpLW-UCcdkKvcR=?s>5+p`ap+@@IY<&y~A1R6#Xs0nnkL^sZ+qLAIaot7^D1GxU_k) zozxY@H-iuSO@qN>e&->WJPs2ivQ(VWGF4sCB8mD1KQNfxb%@gP>aHNbBu>7;&GGc4 z#guj!nEqTbgLZtr_BTDTbA0K5TOvhUnjm~GB-bc zson0@vG~Wm(f*%PVY_5}>5wZh3vJQzA+UjNV(@Ej5CAvSau`w1>0hw?v{4vG!;k^X z<#A~2y|D&aB%Zp(sQ$h9?8Geiz%$zLc%otO(r;wePn0Gw1o_bS6Uz_w&r^fk`&ENC z3*SbfqNWh7dA$8U2ca(Dpx=|$`16@}E~8Z|H7M;1Sz6Oy)rn%=&yV(5^N1Xv9Ssks zIlkBVv9V9KxTe24sB-h!IF8GeM|IMiM_b|lJ;lN=&Y?xyg(GG{`2oJhySD^NZAI*9 z3$0h%3jQj3Y&J!s?sk4xPKPe+DwF3AeAZ=u=0?4rto`RyIv(Qw{`Yc6bnicR=lz+w zjv~&0`r|I+drb)~6F;NZ*%JSmdLF$&t*xwkd^DIH4f=Dic^7-_`w%O3Ie+i59obXy z$S~rk<#)I}^+q^gfy`}vx$476T$439#0e{oPv^)CL>Ma?>$2|s~F1W}*!KM&b7|(I>OTc>R z&-`scEpV&LOy0b_{d_zUZQHmz*CPFEBhgUbmdEN%J@ zw$~P7y|ReFT0xeY_rMw5`UgVXiXM~B?=|%7Nw%e>VgVBH5(S=JzYjOW+w-0R_R#c~X1t%= zUYS$uhwiZgK@NucajdM52uzq5)^R?zUZvws5m6%JmVv3h?+HH3#Qy)=)S|>Ngzo;A z@DdrEEDZH1kN_EsI+2X?-&K&46qbN*8D1j)Iwo#=6ia<}>ba6;xpDZZ*aXjg`Yjeb zq^fG4FVS~C$<#?_kVS4B$2q#C2{j-7(x=|xKdI&4E=z5fAt$AU6^#k*)0vMLbDO_2 zqYN9?9nhQXp)HS+Iq`1{W6(bZJ8ymNB_>6Y0NL9Vk`Gb8mYy-GqCiFzktQM?+mEF5 zm4Ue6>FK~4C)#X)BMh2Ceu}2Wz8=z<2FwNuE;rHF4ZiUdgWvPxb4A*vvfG-DqbxtO zv}A$K6yju7ohC^?eI6a=GCSF5>DkM2XCxy#N3#5;+|t7t?;Cti)8t?qT4U^6*1O=M zenDb6LtP1y@uCpcH8$CwwRBuMgwds`}Pmy&|l34aiQ_tku{}#D;6Y9H<{+Ct?}g% zNzn>rp;r7_Xi?0{vjt8@xbg~a8^c_9Y0a;2$cgJrU!qn=;cF#TXcZ^9pcjMFid4HT z7kDH3eu|a0nrlb2Ml3X}IiT14rZ^)WfHP84{JVfG{qxT;E~=7Qg*o)}guceks_zqw zR6=0A7R`4jKeIqSRs?F;Vi5UxSQUl*%m?5-8$I<<51^z+paQ#J^Ed@2_kZyUYy%V` zHIMG_ur(Xb9ndxFi^?PPHk|LcL21o~aRn=;yf}PYSKUeif+As(=gmVu3vkVdF>Fmy zvNAp#ALny( zWYqmM9OdSi#{qop3*8{msQX1sKa(DgLM7o$gq}CeAZ;2@m}T>wkcl^GuMK(YdtW`Aixz8w9aZAerTQWI zu!SQDS#<*2ZMCwcBTGE&8aPM-h_DRwN`vjJr!lE}lgldksVU@hy|jsCc%UOBS{gKi z*1XqqJpjBwMGPX_x&Nq*qa=-@4P_VO!O*um0`O$4qZ#lf`~hP5X{q^)zF01yaZ zP%ws}z{aGrQbHu(f!oI3Umpl+&=;#pJpjF3-$fs$2VHmOPJ(L{TfHll5K4P;2iy)I zA3cm=9bxUEwEh`zQclISS z6-2W#PY>5fidCg06iL7};wTV66^{O^GQ=pY-wne|ohApYziITtVAGr%nDmuNq3D(G zziDyDRsOT-6$A~@hTswymy7WLXbox*@*-OimO@Dgn^iePj00LO20?GECYNpf3BoI| zPgX$BAM8^nNcrJjT>WN~HU^kU(Q*!A5Y$@W<97MM@v0mK>xA4B+Q8tTUR9AJYiTH? zW~ae&`j`~oi>qz-%JHBzA0U=bTIakNdXEj3%p(=jmB~ZzE#Xxzyjb8R8P)Az{ z5+(oPp<2*y_)bp|^qMD&yKSR5HT&|2$06#NEkHf;*kIgzK*2;AnXtYpBeJD~7d~BlBJFril`)eDqbk$V$xRRTq;l&O9_J z-DjnDgx_)e=2{;;4xl%G$_5o$L8y9`)8ie*?n%##og8G%(tDy6|3hd%f7}Udso6trI!IM_WbU%XO%{t z_i~kY8SYSFuVnzGrSjw-P-yzT@=nr6x00>3|7m(Py?jLU(~9oZId03|Wz?^dVdx|~ z6qP3GOSyZXgkj|!Qh;Hl!KBlZ^Y65B*jL00@5}WY#TK?BR+`bd-jMD8EKnPZnH*X# zvgR+Z?H;gy!lfSgjkPArM^V4y%=axf)Lr{B*Z38c>WGw1j%bzyuw5(8u4Z2cZ*l7U zIiS#?tH^3O_C4>OGRrk`C60AfBMd6TVDqYxex@Uyr5e*>h;RmxpZ9dr`3WTx9;E=LV=5eu z%sZ36iacf%<+mDFB=U3r-`zpr?$PEQ!|T1N0Va{3wDIE}rI$QGlh&n|0+H&_()B{I zMIa_dWp>;A<89*Ou4gv#nM$t99m2LGMd{Wu>^d;DWQ9giWKx7PLG&nck-UGU+OE?v ztlHjeoWKgZrz=r(;x>CNc}bQgjO6^=QDpHOF#0y5-t4m%wV|4Qif!p(9H5@-`(a(i}Xbu)z2)akzWaFbwG|x5Rg7 zyYp*oBF74Iuw1JZGg7R;umFZZQYIahL6Q~0##WkZIQT#~ba_UssMS2^^E%BEjp&Po z2Jyxh3-wH#C<{m9%go`%t-Z_`SptIs82grQ1kv=4&p$HXfMqwW1dvmtIH8#Wf;7@~*@g%tbtD9Z z>lbR(`=;a_d}rvk06s4+iZ_sAam&%rud&8h!Z9&tB1ypvJ}o?_e|i;u7;kBP*eslW6@o~j4ROY&qYQAtlsuN)k7IbYXx zLe32~uj-X^(o6aepPn5cU@-v7Xo^469UAW6n5Ji^axTQ6BQ!)tc2ZcoXV6%;hYJK$ z3*xtP(x-&sd5%~8a6-$>(;Jke_?4_g+FbS$*mP4>qtJk5Q6T#GZXzkBRUhJr; zhHd{)u(p&LrZ6-15*JZCgx|?82MkX0IK_x8%r24}J?D^~4Lrt_o`%h%uW`F3AQ4Xw zX-yZ;WA^Y|i|_pm6&N9c$O_WbS3UamXbCs$H%N75(8MYxS)r%LI6r;Bh!SuW#84Dv zRoU@e>-CcQtE2}2>#G6rh<@7UDD?D^EBBIB557|}FooaC z^;)EUXa~FjRJ5lI-3payU7GDi;TXtgN;KtbncYJ6z(hdG>qW~#(DuYpK@UT6z&{76 z+tDPKl!X0+1ci_oU~z?VS!U{}da)^|Yh;uZ2KAU;R6)WG0j(4?HiL0=3lWG@>$m|7 zgX*-69$ui=LB4-TDaj3zJW_`04(e_?-nB5_qyHgB-0naubw;MVFx_E;rl!pmt zq@x%Sk8#%DIZkGd3m!Z!+%oM5fryA{;m}9%Wl=0YedOES-aP%fBajzxS6%RaRJG)Y$4dT;qdqVEowxNXX#G;sN!=YF-w;kbAF` zlEH_NM_eR)%>lwTDRH@N;n5R^DX;em1XQwuJSviDQ_CuTbmL>|r@mtacOt2U*qi7r zh3oQ9f%HGK?;#~sG7G)}M4#8N5Y3o7%O9o#a1qm*il$MO=XqlntudNlvX(< zHpMGNSBpD`&P+B6$8}R3=+N!mj-P(>3pQc%t*)zhs~;i)a5E=*iM5aR?i?@NuM_JE z=QRyY!}319g@wh;8b@@0ZPi=FGx-1wz;&N^%pfC=6yRCw#qe-DMYV}npmyDyY`PTA zl*AhLsi9QXciJPEe3j^=Kkpr$ZOF9Ir)hnw@-tiSx+l=%_cg~eM(4oDK2`3q?KM7f zPL!KwZT}^~ZVtu_4HqRVWuo>zVoe!_@ZOJ&j$ zSRG7uQlHbtdAaG(g}<@$sX7o2BaWwk*7RzH&1Prkyvf@_WzhXN7d2~dI670f$5^l} z#u@)Etv%wg@G|=(_}NyRnOf>HlV)=6E67R0&&(txH0swv3nlOF1Yt5w&NAn4 zx)Iybck0Nstd{B_+7mrZs>}NI_^gfAC4&TyA4rqpAqdbnf3=!Qw7c35X1cg~q7<2q ztVbMjqQ~uLs6T%Cck&e&@17}7;PftYjzk~-V9Z;uQti8C zyMXM(p&-gvqCCaf|KTde$bCFue45iV_JXn7yuVO_1t<_kO?cRr#m{Uj^h@-t3Duc9 zqMcF0p^{%FOs6iTN%kF_hJ%cb5)lkL;0SqNM@>P=M~LmKGKUhmEu8tV=Y5qfncH}Q zbC_b6(u7)2lG4eT6zh4Fj#{?$El@%W{(0{G+Y&8eV;_^xTIYy#cK-WK?DI@^e&94- zwrIjxIIUV@_x3&(Z!OXN)AjIDs=A--dU3E51Sw`Wr-t9yMc z(>iVz#Z%#b(;7=V-w;J?J@#ctoZrUZ$@*?_P^fKYG+FR{v1wF!y3E|?1**vN4N6gg zQM`9|BZ0_XSz=)xi#Z#uY-U>o*j&1|SNQ2P8GSgX=?uL61o&CMUEV z=i(3Te+@gktYw3_>=d}y_CqN5f7r<17niIQJ5VkS_Di`m$%_4+Hk}BrUNO$nioQHr zx&OJ|>!Dj=TDgMYbKtle%bi(8iiRs#H@a@Cjhm-kfgO z#VlAwt74UHXV=dKkE}GXM(F*!O}=@wlxmUM>M%n*aJI9QDy68mLZ>}ye4Pn+<~SKq6f5$<6~r#4Woo?@`LC5W zAl2C_SVVrm(g7sf?}6n0N*9o96%{H140?7k3xA7eYsCc$y7~3!9do{8mDk<&iJd-@ z08*{5gvHG-TEA$=Odq{}r%rx(w3%w5h)&#M?=4tDQn-4U4daU8g!0C@3wrqVlp5fr z11I|;p!x3C9?IM&E+OUa-k!?b>8*?z{W~RKf9oBkG9^i z4sgC{+{QvLJz&Ooo{>xgj?2)1jdjr9W<#+e07ZYZs4QQ`oJH804McL2#5_STvtWRo z_C1Mr)^o7iVyI0rBeWt>_4ry$CBV@JM$XMr;=n={Z#j2s~;`5 zLU<@T|EyvY*J~MNI*%ijr@K;BF<)YSyVP@iWM(;zCZu-9v8y|N|vx}Q@&q5%t0CS}Ylt8VR5oKbg1q&s7s^oIR3 zlLV%G+U(Yr4Do}yu&!cufMbd|+orM?sHuzeL7i3iy z9|rdW!1*VK-2qrQovW>$=lYu+2AhPJHdw*{XiTcFM;#owxk4etAsuFuj^Y534vj*ob&pQn`_L~l5A#2B{W!4N$rr%9klR> z3rKV z;3cDMD}4y-eQvh?R$E=FljIvYNjuX$Qb3fgPOpvaRe>2v#akKseAs=P`jK&_dyoDm zlqyY*v1I{8*HwZ8!nSt8>)J5HO|WS%wYN(z^iG%cU%o`>n_4=j1HhFC5JD$PUSg|^ z3N_b}4`~72KIJG8+6$Bxu{@*TDxA1V2KowO$PHnyN3(XroG3|V7n;^62Xe?2zh}_>@L!Q##z_mG$)LxJLnk#0l5O^B$ zdL!@Pl#G<@+i7x03K;iaWv{cJQ`Qo-`SCyaP_YwvnfdK4Ci6Z7&`$gANC{Fc;}Fkm zxuey$Ny+S-eL zg`XCj*I8I7F7Y3MXHnu4jNwRp*CELCZYlnvp`AX!sT0HWt?mt0_p2v6A+e$|YOSe1f`GyYpz;-V=QaxFr0~!KccjOY}{| z{N`P~`});G^>vZzHJhdLSE8bkO0!3ym3>e3XO@oYccs^%`2A2=wFj9VJSCQR{EChxH`}J+X!TlNf}c(skc^ zObW}xbK2z>a@iT5yKKMCEci2I$tYMJ6E<2=w`ie%Ru1QnGBTTcM=-4${=!5q`_+rK zGxak=DO1e5ExK0GA^&hM?2WIXwT<*apQ{y3heX2*sv_E?=e3%*UG>U2*|P%TC`mrg zPBOVhJnIHj=!bP(cBEq)&6g*g^OH5Nl9hE`wpn+T_04`-t!f@1Em5nQ@}r_>C#Rd= zrzCEnzMTFBCT#(@=tGx*2S!_WTb7BPS{XJZ2)s0#Vvm5E^|meL`FlDjVl^?x!8mud z66_^zf5Wx4Y8cR3VfeFd_3tmggtJ7qnzv)~A8QHc8@IUAy6yUm&l726YoFC z%+I{R4(Sbzm#Xl)v*t#?zF3p1C3ZsOgM@X_r)_#fX@_}&?3 z7zGe0*H9J!J$Tcv(D+gMTILjy(NF0fmyqdU3 zr<;jS1MLTU5f;{*Bq@~~MNg$dCunV|uoh=+s?IdFdRJ3FvZg(JvU*>HR%YP>X^alo z{iM@Y_+2<~3y8Cga=jP7YaoA&pz{z%s>3L!PP4`^#_xhi&j2M9wv!}IUFJb#Z2it0 z2;tPJ))>%#?=lkx+}k_-+Rx&rk#7Fy8<-0USoN|1t>Xq-r^01Mfk3T{0qn_Rse>qR znq!?`_6m8tu>1eJc}BQK-KMGTXumYhk=7HwxT9^teS^7GogiG@LVT_f2j^xXnE%ZV z%@)731|0f>rXb6IHCoQBzlp8clhTizuHx_L)%#bap6B4Kg~z`R$%F;z$5k?014yj% zH?f+Rr~oT3b4)+(suqA7ZexVN3lyv=WT%O_ur)7BA-$z0y*_j zfSq^0Lyn^p?F-7GRGh7jycTRt;7R~&B~rUGLY2pP(dwonBHX@39|0lnbwn*!LO}Ok zP~gd{BAxt52@SM(V3v%`0<%N`pwF8#EPVo^y=hNRc}C(uYMW)-J_py73B6WlgmeUg zqH8?v#uHbm&<8@XW5Zrgs;ra{==M(iI9o|f9Tg(2G6J1Bw29T+B%I8hBV^Ou(Hb)G*EL$)E0Y4zE7KiH63xKRI7Y*L8UUKmhu;hF-n*8d_tQ5_JHzy zS_JcsF1_{;;P9V<-%2Kgq5Lo2Fk~)^s5?OonjZRT`J85EramGgIU}C|-`lXDP5Pl# zoTqahLiORhqe%FmEdy4TE<{YKhcZLj8+#-b!vE-q@q?WiSU@F`dXqiO0VrW%GV2B$ zA|lld3_UxmC6-BHEdGWNe}Sr07XsJ=8Uh*%5Ax#L8i@CxEYMFq^x~v4t>US5Iy11g zwW?I7K>$_MTUKkVT^lnjxpW|S(?OXLIudV@Hy(knMu2dKYgp~d5UVN+L#L|I;7O%g zaG<~7U@bFqsw1E#HS7@xtFEVkv?`A6DvR!p7h$t>v2u&ww_;(O?{J2=-f)lWWK8M# zG__`-wF*wY?y6L7G2i8>}NGo|8Ay~Qon z2EH;D+hDNi$`fpqhtOOgz{#(?zQrXX`Zr3!eq^T`6FBF$hYQ@E?APm3 ztT(lm8wmuqwvH^G)@aK`9)GPq_4T=^GdloJUmVoieIgpD>br?3i z!#9HvYQvIO_MR6*6kWHCMx(f>PU#0P-k+g%4pfc=h~ZQ0`vyJyFojpr{nEb_ubD3v zy+}zO8jzv8S~7Jerq<8C_O3Sxx?aJ5-tYbWaMIcFeB%8!;Bj3&=rg%AUi{=>$Q$av zRZqK@G*3@1&%b_Sm{$cos|Q`1nwmb#FB;3ctgGOI#b`En2~9emSF+%XS8kb$0`(r7 z6z9Od*#3R!;w;98d;d`V+ttA2vA{;FtBPOiht5wcPdqV;=d|Eq#=1*)ea>3ezp(ud zS(3VwzXMJVtS%}a*7%;4QWo7=Jx|>)nTH|F+jVGla{b*cW?qK*9LdlVFNwE%0j#8B z5~_-BulQtWn7?t%3oI$rc~n%iE*pV~##E`?&vcb$P+)V+++*+OXUL!4 zX6VrDIG)NPm)YOt&sKf%HF}N({@JRLll`LqN6#tiV_eD`uQUD;W%pl0{&n4vvF(CM zCZ1QTMq3f6uC1@?`-iuN*+_YQ3n(9 zg#%|$`x~O$eV+r>r@hrm^^{ILC1<*z*D=dRPkt@4ytn&K*1035gHgWohnLjbYgdSP zn)Smgk;^B%#2im_uwum;G61oZ}V0D<8M4H}>-*PnY?&Z{t<=%b6^GUNrLq;PL8{hwDe@2a6X1xPcU1@RvQH{NImpJgD`W%T%FoTAtua z&mK_T%A+Yy@LjF0VBk#QADle3_D9rGgUMv1p;f6rwk)(f;pVc=gd-|ts7T@@-Y+#S zNQ6*W{IDEfq<@WYtA_!eY1?QpPq18KFfLMk<2m>1V8?0OvIaUyI|mq#*mMArBjJ@o zVj&LFYm(Or`vj6!NKvpS10)X(z?ELm!X%7hK4146$9(4BM#A0`8d`1Asx*lq^NIZ{xFK_V?f{hKHYSc9p>$2UJD!E|cJ1K%GSvOA% zHT3}AaCk`v=!GC}I>@+?5;dBdMMX~c0c74XcA|~S;#hv){X=f@6K^CQRu~N7(N;2rKLd>;Xb``pMz6r4A?x#z2+9 z`IglfLzCnRI~6<9{NEc=3yYaMK$2HNY?v~NP!t8|q(3j}ESDY<-+L=6r2-@4(jz&1 zf8Jo=f{Sd`5MChA7>LtVz}${0`RWc0+toHP8&&EZ`)fIkpIR|_rH2wamL=wlniw$# zlbWIzNrE!LUbLu}De~xsWc#5< zNV=Dntn3$ju#G}`{-a4On0@?9A6U^2MadZ7j~CSzgsfzX7*b?g(i{fsi0_XRz^Shc zQ1$J#(ycHl^w|8CvS`ijg{m1G)CP#G>dUdkG^X9tLE@+U7#h<&>EMD($SkdcB0*k0 zE<{SE6_8fLbn;9tq4wL$qNVaXa3B;|Nm3z5k`hVZBM`8{XoUeI4b5_7#3(=FrVLlZ zH{nG+NWNV_xrA6N%_W5t(K-(iB*~zsTh$EnU?|$?3OYy%|I!bZpXUaI@Pt&9;P!3i zNReH%D8U}IN#TxP#ws+%-;)JcB@HmWxBcKv^C>T*h>AAqf(kcHCK9Y2yp0jMsEo{a zQCos7ku-V)k(A+lm7bC`3W(aJUs4$t6XPH$ec#5gSp0%&Yis>@^OEv{3+eXpYuB_F z>G(EMt^Ea+6w9b^%I}~J#q_T@NEF|nF&69!sAwYqJv|=%k>mQK!OCXn&NYmynWO}NvO_z@>KD0&k_|H%VNg|XsF8zB&Z>hOycIp8xM zfYhBCPrB8b4`8DPvBC5$#Gjn%b7r{s<0w`g4*CwckR*Ji-(zlTW#{On`fAqlV?O17 zdhfnH7@y`-+C1{(%V-RscT^wt4JhF4?u3p7SEK1W1|-b523Z?Pk?se267<7vmtU$? z(7#Msc-MoEV=T^})W`E7Nl0SSpP-M(A}{KYQ$z-T)JN*S9iQaifwXQf?e!+HwN!dW zPxdmy=xeOnh9*0jOK~_L>uAFT>qWl{(ydM^#RJCw)MhWA1>?|G_`3`Fa2r%BY|!C) zRL7C&gZ)hQJQKbpa=yLjiiOY*f1wxsgvXuKMa_UCgYs)d7Yi4%hDM}!y^&-8t`P|3s9M z0f$Z7oD12KiqZ7MDOc4{`cj)fs(!%hu+;mkvR_wif5OC+(kR_epA_nUSAe>f!MwYu zG+}Yn`w(W~lU2wx&3d#A`ezD-uZ#D^IxY0bYLNAw18zeQr3~9+( z02v&c+NC-B;{hjs53gM=_)?JGuBEuZCcFT6QhFMAGB`a;7)h2mq)^WL4ET8y+`&cq zG)AtZp>|<|RKHe4B~?Z!6pFA|#O&g9saeNR^YP?(MTobO+k|1;sDxzI=@5!P1t@yr zwV^*gDJV{mBa1kR1gkZj@&-e_w>cy`9nU@n>*KRo~&+kcP2(_`6~8CpBof~L z9{jHKm-jo7b4Re)y45Mgp{F2?{~rx`;S^}$HpaN8utJvelp!kLGz0Jhw`{y4<**Xp zZ&N?_L*hbGOG;S!rP|BtJ&8c{DNp}ZRQu4R{qXWo1A1PSenR#DCD~wFoxlB-rKl6vlYSB zs3kQkXw-Z&D|$ZiyeoSs_^717YRw>~qG6+vKBX*JjVe={gG&7`$M(CSzE7mc`o$M& zRMJ$&@A0rAH9?>(wI*PsE4V~4#ix`|)8DTQO%l9cDQvv&n8-v5lUg$zkHEzJ&@Lw_M`4L6`k7Nw2G*_5hOl%YOtMJ%gHk4IR<`VaPtjG- zdWDXZf+bJn*zZM_H~sc&O88UD6S1V$w9-k4PR~bF-+|#!{LF1YJyl`=P){vrMT*~Q zxgb73gt@%<6Q~x7kJB%vu#?kTvlF)3vPKN{E$&}epe=@isj#~3iUI=qn7vNo)c76i^-P^QGZv%vpO6aomb0#nV-c>|+(9u*1D zU7gzbHYzN=w1dLOKnhT-qkR)JMn~xImp0K8@=DEs)k@Q7BSb9BJ^VvUR^lYrD|#v^ z<~3pI5~C5qpA;eV7;Fn(bo5Blu zteh0D>9$#GR2j{GdSb8NL;yEH;WS((CihM zqq>QLt>g(3iA#0KOHfOq?kP`0$niN|vU^)0mWk%PX_g+KEyjX-+y=&9?W^*WY)v2g z4-ICGO#hpE0Gi>yef~w9x|MUAFLr19lrT~J$^P}>T%_UO74wY_FX)nBkX!5Canh2##ilf;KCMrtiM3jN_&TZk{1-{b`PNU{{?*Oiy)RQx#I( z$EEu2fYGbszi`w0jNH;@k@P5u9oLxhcel65G3>$a{j-4V(7^!QgQYS(jIA=^*Ku{j zc_FFpg8nT_|7<}CL*nCxI{m@(oyqSFnvVM`@3A}=krePT62ft5`(u&w&pPj_Mmd7*};n{^YW&sD5AAwKBW8-{$zqkG&j!BGG}* zy(%$nv6*;(wqFeY=wNVqg~+DeNX*fvK9PS;>d<_h;a4GlW!Tb+KELTp^H2WeIKQ&G zJB}(;F!z=rh6K77mV z&BtXnFC`7cC9|=t@@`Rkn|K|>V%jCXw?-dr{kxV@^Y3A(_16wd8ei5`J=>f?T6ec) zw_^s=-eyq&ae^B16ahmb*zwNCH@+5T6g}YgD=Liy0n|CN(E{qSOtSNb8#sl(ZRq~d ze>-zuSNUK;gDr?wPQ(WciFi4n%!(SIP2 zyH3UJ^P3<}MG6`Ckqr2lH2`h8NqNWsw^tf{A9qvQOH@e3*q2DrcgD@C(E-$jvT*^~ z398XDiJCmo#*+$=J^{gW`aS{gbmmBX3%NM8rgV-0kpwNeJ`r_AroLhuR*F8j4FjlP zvVAjpdVA}vPtVg^xOWH9>d3t$rv91yrb!YykCKK{xU2NJzw~2}utjQ1w-|Tk5tj`) z)cYHUd`1)-p^SU~5Oh{M4M&D4VrZ7fI|D`j?Y6{upPomFaIc<6`J&knSDO25;^K0E zS=Y}PceE-v5JujDee7GmbmO~QA z_r(M<$g_^5ZODJcJ`Y$YMexpUzq^pty9{QO0c6;CX1AO@`fShtSOF4xF;kZteRMy4 z`-lklmeXKBI4Oz_KSQZoI+jO z=;$e!PNabPN zl|6kyb*D5z0#E8CTm302-dnm}Z!OK|SuhFCgf;6$`yKu!j4tp^?Jq^RWt!*FEe^U+ z6jwl)_!p^TbcW-qtG}Th!xhsi@;Umo#_+oS{IS;#|M4+yIqI;!P1|ZYA2({!!VH+MIb=Mh5gYe=% zAN3r?e2f^I87yMM)|w#In(RvZrv>mG7E)fUM#zJs|KXo=`7Gw+KlwaMZMk$nl+^me z29`eCCRU5hA7#*Y_SiMj;eT46?>Qlny%Qso`=t78h48ozS`ZNJEW)}UfWh5OL>Ev| z04w#A4huqp^!MXIIDB<^s%eiRxSt|}5h*-q+T}L{f+KLk5+OAy%1d0;9gGrk^Bgn!c@c=!MXfy)NUC8iILX6a^ER|K?TD~}`=s!Tj zV8kto)_dmoRT}Glez0?c!ggKbzH20j)TxuvQX?{#s!Pvte%} zX>dvianv$dt8$bGMAs1TFlrQ=xs!e~u+l`-E-;Xl+hDnm0#5v9BeY_WRcRb+i{5*h z0rP0NjL;+=o(MHxP-gnREQ5I&B7 z2mx9J>wHYVk$*vbVcj8dfXBrR+J@T+clLMbAh2`kg zhqRT9M3O&=r2P3T$0WVOCN9G)BE%D#U^h>Hr<+N?Kyov8~;O|8+MPM*O1UH|tj zMThyt?pbqwjK$JvuM<0*ZF z7X`=-?%%#!P4qHVvDVn1{rl>gRO*uqdc@m<88@1?KsV5helB z9LJK2Us>}imO7~ZbzY?Sd-G!kL!@1kQ6w_@}00k3DC2}sQcuV+X!Wb8dUYYzGF z`M%3HIJ+oS(%2umm8VhWu+1fC(QiNo@3rU;9@+}#ZoU;80=CBAiLNd|R`aafooKSx z{ArZCIZZq-`I$dwKY!$V+my)3R(&iGw*Rx_w*+Fo{|0g+RAr0OG6_n(Y%AQ7_%8EH zh4m8CvhwH+_vJ1(!uIwv>8hNCDC6LI~q)=vG28 zH3GCwK{)PuSs~{Lw`Xb;^7k?ZN+I)4_&w`a8VvLqG4ApLdF|o4Nb&W9NFxp<7^Y3d3 z0fyoOfvpE02wIm83@|=xrLwkI#;Q8mH)fev>@_-YTfO5_-#bbY&W9$}z&D*Exg7z` zHHfbe6h8#syR+ApWzL5y1G1D`!Rk%=ekvv|uZ^;bQwT??>Q7Pv)Wg0=Z@}T$E|HoW z4JP7|eLCl*Yh_D~zBo#}!n(Bsu|~u7T`ehAwC)XgKCxz93J`b3nb3d2Zwtt?C)~LMd1tKFf?~%b$Ay{!rn7eU>t@~mngf?f!VJ}B3fdu*XFkVyftET;KXg%D z!@}rImCUS^B&2=`XLKXy5eFWk5}=t_)ts_$dguiCVa4gaUmlQs>tZk?QPv6?&mDGgEu?WQjnp6U|2lE`j4YXd zJ%7W5sRo5~Yd7MIhO?_{kQm9nc9Dt=vgn>rVLPk{#Ap)Zw5%^be8QgR2KE4h$hwzp z@ElA)Jv4;<*wk8S++yo@fjD}w;oF`*WSZ1?tgzI^9Zog|0rLXR12_lqR}hOG`k9f9tL9)-|?vG>!GHuy?i%9C&=dniU>|?;#>u_vGK@QuK3_DbM`?@D`+yc09E_=N^$#`$DD6=r3s}9x z-l(QE4Dewq@d{A~Z~R?BTeYD2nlI5U$+VY|BI<<|qRRIPX92TX5|5qdIbam`z6aTN zv4OZPLUKeoBQzc$g0r$elJl_27T>L4ON2>MQ$`y!y!wP*V=w4~{bJBzge1E{JpA7R zb)be;3~vmZ1X~qRWY{keNB~;41gjQZ7nxFE>`S*cot1@ga8d+%G3XE@*Sw3fM~1`+ zGgoRTj^JA;H-)u5H#CnJWtYuT`Dg(}`-G_+!q=Sz(O~RN&50;RQz|XNI&kVhB*^ z74$dY4%#<3h3gF6mi6U%8D=_%ST5W^oV7CZDxwMC7WUYX4@sivLPY`2+P?&gOR*8h z(yLVf64=$kwnP?#A@8PA=PwINIhMl6BB4GRXKE$)fgez3!ukq!m?-T>g)_}tUftP zwyY&*@OU8vQn-8RxvdX8oG@Jm6bwcdq$+n8yO~HSs6PYC)YCkJUSUx-vqIoiYBv1v z&-jU=JcZ~<{nY`O)cRoPjYKs{RNg0_?BA7~CtYKCUkCzjsamST>I?=Z+}dtt#Ba~P z)P$YuPfqCky>R%tMG7(yHz_~=J+Udwr#rm*TVmK7Wo@}bc|_-o`G$Ybxp8gA%YIFu zR?JB3mkyrmY~Qks(>^oii;lay#Dj|<;U?quyn~F((!_T4KC;C(z6vs)pS}~PM)=+- z<~pEycD(Tyi9gu&QMkHLX=;B1_7kCjcbdzcZOW-{_ujoB6VH#mW~X``<6nDEG%aRs z7yZkg)x`nU^_STWcIWx`K9Ob7^{wfBt9L691HM?gSC zq*tYd4#{`8_df5%``-8e?elCnoSpgYoY_4)o88UK$hB{JVGWR$lBs-tO7yxyJHq zQ{t)ewMWL@^$^gMZwaBPF?9~hE5SV;c@a%_hHaJ$J|VIHqDRdO^>$8rMO3`CXDJwj*Hp=@bxf zo#Ay!u{VtZSJ=A+qOFc?4u!jl8sX+ew?F|aLJ5{}qAi>7De=@^kYE1-Kd#diVvVhK zVh&fqd-kBL8@>V{BfB_uDlR56%Q2%HN~X|fz^+6Y)Ejh~x?Jikl8z&0v1txA;$#Bj zs6>}5IrvMb;~4cX^MlZ~afN=4kUShDmk+Qs`=E>lhdTPY!Xvv^(vbyH7Klm*1A9un zq%L*E+XdXjU*9THNZ(u}O9Z)^aT4*U`G^uwainpsDB@~)^uhRB2s+<^&z=No`{UhQ z2wn(-4rmq|XZ$d_8pJ|B%kTPp#tgjDL!?#NOw12strm&g6EXE88rpCJ;}{5EeaJ#L z%MXjEG!3tKR`uQqyc1NxQr(j?8T#&6m=Uz#fJQiZoV$$LM06no?D{~bz2t&k!p*>F zAnuZ8WdGHqP~{jFdiE;9Vu>*JjgNW>Ecm-1i|>A_l#!Nzw|nNd?}qTk)E0=upKzd? zx41mO4YYX8&$5BlwT>4IFGz;l?bVf5NI>C<&HBj?fnAyL_+_Fx3ShmBX*$Y2V@@xj zl6tXK)QB~W!{IirMrGTi`j4=|cvi<1uFbSJvVLG9+BVBvp@4azR?C2QAJs`cy9TT% zIGDqPB^7o;mmSu(C|r@GIafwGMF-!}t|e zDb3C!_9~LCnufC#RhovZ$^$Z zTT1t8`BlSgDvD=j*3J38F)L;w)#{Wjqig_0EI?rZQ1B(o zv^tU`0~IT4f><_!xK_oC)nUPgkwx=)g#^41cmhe0R9%@INnzGbq4063Y)m1$cQDto zShX6=$1q4tm3dLs6RqzerY7-H6}aOlrrLBVer}?$&mqAzCa!g&xWggtwr1SiihtNJ z!&KVU$5lGM!?X{nuC`aHISw;SQ_(yg*0C6-J-cx|#yYW}KwRBz?OCyU}FWSQ~W6Ik{PN3^&2b0(AJ|A{loFf)(rzsP8=cjJ!j*+ zK2ObZ9m^{9W<$_S@%2`-XPto}MP!61b<3OhTGtl$q87s$Oqnoczhc{LE$eBhYpZ>y zc-+PG<`W>)Tx6KAJJWYVzQuamz+TtJp4grokXUCM$o#RSh}J$SbSwa;>=#SFgd=Zq z%A(%9kj`S1A6Rz2mt|2PYf<-Ba8uJ{zg^vA;GpQbmnkMTU{SRFIuB{x)bgh>+ck?- z&GqGMrsw;6Q%uE-A6@XB8BWR8hrcOJj~h()_>F1JHZHDA_PUCT8MeQ*c#Oy^vNC(q zpz_InknMe5Rmdb>ijygm0M(tq%)C6bC#P}cD-%}2U*=9{K+Mb_YOxRwlPKM~t<*EB zx8H}>yR*?0bQrZjSn{hclcd!SV9@vLRI6j9I&LQxlW)@5vjo?PMBj@{p=MsX9*lda zWG^OU`R3^4xLuj)M9I7^5$>sqKli%CTv&Sz5&h;dEmtF5*E101R9d>wgiUnp*-rY1cir`-OhY0pDjlwnI7svhOm?zqevUG}5@y z9@}}KhQ?b-m1Z{BSxp(3tbseULg?GKJA}~vLWmb{+G!Duz?n*b_^%?1KZ}mVQ>Efy zD_Jmz5;S($zHsV^FeF6aKU@wY?EF@vy)mDG@)-!gYW^Q$fbL41ECWF7ab88?o0b*S zXW%Jv8wm=@4QIfG1Q;n4|+2-*SQu}n_@rAz@z@t%PwO@|1yRUY)S zAesP$5;W1Zc^p>LqUHb;rY0IColwyyvpdeLh< zeL(j$(AY3GCf&4UPWvPY` z;e^+oNPagO%u#@3et4Y3`vO>u>DIA9mbZzcnuY6u<9*W}NE^)+*|-|kwE-c--6^a0 zy`gEAUD*_6NTheaPz;F$5Wj#V`#L&x`$ZY4tv^B-JVk?-W6xtEavfa3(qsl4r#vk_ z9s(bcE|ZYj2D>1YzUROgOz^uz3BZzR*Lgf}O@^k8Xgby_!cAhszKin5DFuv#cp#PL zb71oIKR<@=AiVHbbrzhA`<)S0$dxgx{A(hy^Cl&{)NqELO zwty!L!|C$&6>E16MHa@r;WDz<{sdt@VnUDIy3%+z9tS=t=oyDt>93YQmY?gHlcbWI zRx6QS_)bi~A(_l8R%At?u6EmS(P+<^!1LRVNd$;k*WUAVO=K~XPiZShVT12cHEq{D zI>V${aB)8B1%*@pgnpWM2 z*KpVW8L{cyMpKozoIOie0`;b*Th)7iU#i^-y+g6^{Ll;_F-@g@gv*u1mr(N2$P(u|Lk<;QBQ_<6k zke{iu!-SLgMc(SosoN&hep%a9P!)t)$Li!N5}||G6b!wD6T_&fJ8rjccgTv-MKGth ziOPBzbdUuxKlEF>1cd9;G!+dV;o9%sGJZIbH5>Ko79Dd(o?8G~#%?3OJbxgHOqbftv9Hy^=iZp@mNPi$1!Yqt zJ|vze3@oZkK`%IJw{xvrE% z?eW8r(QXO&Z2;F94JGMlr{=3Orz8K3$DMI@T#5CN@jHc zmuOEpBXpY}KEAEhbQq;V7Uj7{8m$oOS}0MFH%$Iv0`N=CR8 zi7iP_Tr*V>)sp@+V+x5o=2{d2CF2x;oXYxUrT%E)zD5OQZ8##r3*S+7LGz0!;Mw?Y zU|EQExJpdms7L2dT{mHl%*FfNY&>4oNC`M%cr0tiO6&-y@{m-#eXh`eS#^o7qmsLZ zHigBz!X||Iqm$D>9?VF5xrVmAb{ij}kt)Ib?ASwOP-ryon)h4T;%X<1kowvl*}1ZEg`=(|i8L9okfJAJ=gsmwDTKHW6c}{8CtfAwN+p-ho_jp>U9O>cJJ_C?!dXoINYB%wz*6TIO458u z>{z&BVZa&!_*%sKvXIOBz7IyRk}=ZSX*!xM7xqYOe#?`=JO-%Gr*E6WHv{mZ7!|a8 z?@7p7FMFHp-r|*cJ$DQQk8Dvkt`Igbpm>FT35;A55*-w}3A7sRx>1H&oG)J=Hvy!d z*93+9W`!;jN~B#ex>ieH0eBBIaSx3hE^d>t8s!zvqqS%_0*t$voA6p%h8pBN1|Om! z5TSqG5@}`E6KQ)#pWcZpSURQa@DQw_?d7i`qIJl;@{wM38Sq*~a7KXVMbbkZw6q~B ztJM$J7gSVb{g_C(T&YMzWVsS2m1zOp@%u$PZ@Ll&m&Y zbY)*htK=dkM&Hg@p?QJ&LV9|*2|iTNf<^S0b1m`vGMx;KWm)T_5A11we)v^G;TzM# zuAEb_LmX!F6yIy&r4e)PkXV$caWOL3YILeaE`leh){^xZFJB@>FU3<}F`5e4xY4uE zmX%S^RmfBv$?l>`G47z!HpB&59>qpDN)?-^o8*}dco)vDI$nv)l}h79_ibypKp%_X zyQc?HKgzUWL*qpcr(=L~Iv<*q6ZW z&CVdOTWY(=gvSWf4`<9saL8|`J=OGUvzoZ9s6r`PTx^n}@F25$i5c3=`!mkh@ z5H)+g$PTq`tiXe*eVB%aw4al}`mLZCj4hgK-1J^2GT~8hzw>eW`AR9VS+ZLpU!fNOEaMd5y4P+ zn+XSYZ-g+o8oQgtjGb9Oaokywz86;yeBa*t0i#$Ah~8 zr+2rept38dv(-c>wznyCcjV4YkJj;sMAO-76te&|{A^k742@!5fQIgFVvn)lE8%;0 zpl5sVqpTxmirhvFN@50!p3T~XAIw5SPf(kUM_c75CVMzd(^y71zDcFB&L}MVNgnj9 z7@D}-)QH(HSufcggk#P&7x9l*2?JZ*8!_7^&~A}AYWTMM%;_O2Di5=F?bCo9=E#4C z9-0?4oUVsi=yVS~-d>-<6bY^pClg`LZUy5rV}7E>&yQo2sr{bBnbTRq%xKKvUZPyc;ZJh8;DetBSSw83$EIh2zsRw1M+2uXZ?G&AqO@6| zW6apoX@6$S5g=IN(aY|VvxBCiTiS#>KlZlWuo0&RaOl+&O89i>-a(M>E_3dWGlDOK z;~7n1lzqG2*z({GKx^fBA>Y%mRh#MBnmYnm^iT2`_~A70v0GcAurR(u5fF_&0S@;laCS;)9s6y^+J&17?iH zaV7SbNmI}|C7hjgeX|04mMDVF@HfM#C&5panc<(Bx|o}ert{z@{Za1NEwv-!;KTic z!`EH&!6zl;@Z(wXnN#$e0J+99%rXAiF1g&Se@Mvl^_m@z!N~=!94yD~#F+!O`o7=+ zX4d`9OhzBE$gd{e52yO=>k%gM71*B=@MBfeqou5wvnNT%QE#w|C+_f+yz6#W49i$< zv-EhmljEAEYIv1aBkv*n;aT^*VB^WsftZb=rOEZ!F$lr_1UgNG$M*6j+}@7aj8&#_(2KObAA5Mv8--=b zTbG;nKC4zPYf8qdVbG}ZS2ozf(*taSz>;7r#&(k#ql(F!aXHk|?m88$>4Y*J_Ws;X z?>yA{INqE`e&{?j-`gy>OP*eXA)7dk+L?h`wqc<%^OSkp+oA#Ru9BvWk|U<=?(N%i z*uba3$H#1WQLpVLq@zOS$@ivR4!7zbN@4P#7ERya@)@U_hftCDSJw2zsp?Q{O=q|Y z4J15{b77?I4ES}>PK35U{BYj78uzrRU1VvG`2qI0>FlgJ?UWpQ)O5NB58~&+%IRql z5}9{ZqJEU(g330?KzdquU@8z15fNz6dD|RxA@Ks&I<`JA8<-DF5b9;?;w|XvZe!~L z^|tl#adflyzG3a|X6I;s@xs};2`R3hsW9E)xZ#TmM9hV-#4?WRjdWM?Tjd#bNW3pn3MYBr0i(eqrcE82P8 zWweH3(T#{~o1kI&nmFHdn&5MgUDg{^ezn^+Ob%4cSW9mJ$2r%*zR0QkYv2j7K>pu4 zV7jP-e|`G+lq#LZ9X7 zN8e_PqF>7BR zsH2;myO%4>$I;#GMu4k}c$^j)pfBZv?ADz|o%(gQW_`9XjVY>1&J>n}M3lY6^T1t~ zCS7)Zn67?p`|?>BMMj$%=7Z_Z@_uWh^Q%wTFt0UwNp|Hol1@0!H2sD*O{Mr{WG4sBpbW#ha97z07#~;8Me$MxdI>Q%-Jq zBibQ_(O-RJ_Wn=5Z(PE=g;uzgRi)obm*1cB*)O%~P47tyb^XUib#MFeAny>IBsYCN z^q#Xng|rn;VnEl#LCepdRvz|ZUnNbMG;JzVi(BLH3%$`U0W>@J3QO^JJzLfGL>VO@ zt6N3v0`YMH3j#u#oP{px)yB1(rm7ZuHDn2OuKg_Sa{j92=q_P>O zqD0K`O|?N*uY{-P4XtUo?Z)ErW;zs}BG?PW`Y7$aYu-4iIQ0T%y`qqvYC!5BvoJH2|An7ICw$%TNg?;rRZ=N8qxFVF+WyykiQ zrBqqada-PGAX>mzv+ec!0_wKrA7nZmHyqm={2vTGXCJ+~a9Y8nxUv#2GxXlijgHaE zL2;9Cw!e%?!r|?w_tzk39J|8QV;D1BTBgEF+6625=NR#In~QW82Lvhr|6g6_63})2 z93KA|316o4YPJbcAr5w_fDm%%0=Cb7H`!`E*nMwjbFJcgvumi#eAk9C^bWNPWywoQ zVGnXR#xVCZb~v;1;wl_-?b3+)A$e%Mk;Hw@z@ig7lZH#ttW4YUHn*d1e;xOMw8-KF z+$4D{D}HyybT!_PcJ2$QWpc6PYP;Xb5i_5>^gwgfXd?x{c&NJiRAi$Lk-GAY@xkFtX z?HzpnT_n3u6zMHMob!D7H>h}y3s64p9{A0x0K5zc;a? z#YMEg9>?AqnBd%SwGsah4(QK$(Zv}P&2LhD`JXud!T4)#b#caVKDYWikrCqk-C_TK zGp&EZUNp<+)0Mx|WugnP|2ld3C)PzQrY{}bur(D}RKPc9<;m!9Cr1z@PR&m-s31hmcV%JM+$U5(EkHUUu5P0 diff --git a/assets/3d_printing_files/go2_stand.STEP b/assets/3d_printing_files/go2_stand.STEP deleted file mode 100644 index 68122f9..0000000 --- a/assets/3d_printing_files/go2_stand.STEP +++ /dev/null @@ -1,46768 +0,0 @@ -ISO-10303-21; -HEADER; -FILE_DESCRIPTION (( 'STEP AP203' ), - '1' ); -FILE_NAME ('MID360+֧6.24.STEP', - '2025-06-24T06:25:27', - ( 'pjoffice' ), - ( '' ), - 'SwSTEP 2.0', - 'SolidWorks 2025', - '' ); -FILE_SCHEMA (( 'CONFIG_CONTROL_DESIGN' )); -ENDSEC; - -DATA; -#1 = ORIENTED_EDGE ( 'NONE', *, *, #2845, .F. ) ; -#2 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#3 = CARTESIAN_POINT ( 'NONE', ( 41.50181681594300898, 120.8598905339968184, 87.87266037630595861 ) ) ; -#4 = EDGE_CURVE ( 'NONE', #8671, #36222, #15537, .T. ) ; -#5 = CARTESIAN_POINT ( 'NONE', ( -20.00010960551400530, 118.5861297300807138, 87.28009461489128284 ) ) ; -#6 = CARTESIAN_POINT ( 'NONE', ( -15.66647089846898488, 184.8876660487106847, 102.6891680080509133 ) ) ; -#7 = EDGE_LOOP ( 'NONE', ( #6417, #29162, #21440, #27963, #9046 ) ) ; -#8 = VERTEX_POINT ( 'NONE', #20221 ) ; -#9 = CIRCLE ( 'NONE', #26783, 6.499999999827354102 ) ; -#10 = CARTESIAN_POINT ( 'NONE', ( -25.67545716422647573, 209.7076544165666689, 75.74092205266403255 ) ) ; -#11 = CIRCLE ( 'NONE', #3896, 2.500000000063874239 ) ; -#12 = CARTESIAN_POINT ( 'NONE', ( 2.303546409809000384, 189.9846911846000239, 103.9762804151000211 ) ) ; -#13 = LINE ( 'NONE', #34144, #24756 ) ; -#14 = AXIS2_PLACEMENT_3D ( 'NONE', #12949, #31961, #16196 ) ; -#15 = ORIENTED_EDGE ( 'NONE', *, *, #13893, .T. ) ; -#16 = DIRECTION ( 'NONE', ( -1.287855998059750215E-14, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#17 = ORIENTED_EDGE ( 'NONE', *, *, #29026, .F. ) ; -#18 = CARTESIAN_POINT ( 'NONE', ( -20.51978786315646630, 209.7094320854081104, 73.57086927696296641 ) ) ; -#19 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282898364, 148.0700263536679984, 93.85134194391106632 ) ) ; -#20 = CARTESIAN_POINT ( 'NONE', ( -16.17402367319390066, 152.6351915047822558, 181.6236851348978973 ) ) ; -#21 = LINE ( 'NONE', #3875, #3676 ) ; -#22 = VERTEX_POINT ( 'NONE', #3332 ) ; -#23 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265227786, -0.1368326740407717901 ) ) ; -#24 = DIRECTION ( 'NONE', ( -0.7933533411653069800, 0.5930537057989943017, 0.1373964268091564522 ) ) ; -#25 = CARTESIAN_POINT ( 'NONE', ( -25.99976593112455348, 118.8155677978001705, 90.28348901843737906 ) ) ; -#26 = ORIENTED_EDGE ( 'NONE', *, *, #5435, .F. ) ; -#27 = EDGE_CURVE ( 'NONE', #8778, #14326, #3469, .T. ) ; -#28 = CARTESIAN_POINT ( 'NONE', ( -22.49823373578395191, 173.8377602238623751, 102.8790334322490878 ) ) ; -#29 = LINE ( 'NONE', #9440, #37171 ) ; -#30 = CARTESIAN_POINT ( 'NONE', ( -20.49970531958899400, 151.8550384256017480, 95.23695349276246702 ) ) ; -#31 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22396, #12985, #12777, #35225 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33 = DIRECTION ( 'NONE', ( 0.5422127811705124145, 0.2959572644767380356, 0.7863934114289006239 ) ) ; -#32 = DIRECTION ( 'NONE', ( 0.0005884949961155384228, -0.2249510543439099397, 0.9743698870671255730 ) ) ; -#34 = AXIS2_PLACEMENT_3D ( 'NONE', #28971, #25924, #37761 ) ; -#35 = EDGE_CURVE ( 'NONE', #16264, #22006, #22569, .T. ) ; -#36 = AXIS2_PLACEMENT_3D ( 'NONE', #24915, #12607, #9558 ) ; -#37 = ORIENTED_EDGE ( 'NONE', *, *, #39919, .T. ) ; -#38 = VECTOR ( 'NONE', #35966, 1000.000000000000000 ) ; -#39 = CIRCLE ( 'NONE', #17646, 1.650000000000002798 ) ; -#40 = EDGE_CURVE ( 'NONE', #23346, #30982, #3734, .T. ) ; -#41 = EDGE_LOOP ( 'NONE', ( #36460, #3149, #28592, #26769 ) ) ; -#42 = EDGE_CURVE ( 'NONE', #36951, #18050, #10855, .T. ) ; -#43 = VERTEX_POINT ( 'NONE', #673 ) ; -#44 = EDGE_CURVE ( 'NONE', #1155, #29199, #10034, .T. ) ; -#45 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; -#46 = DIRECTION ( 'NONE', ( -0.6772915400549289755, -0.7357147339628467009, 0.000000000000000000 ) ) ; -#47 = CARTESIAN_POINT ( 'NONE', ( -45.16400980236513618, 70.91888486856629470, 322.7789803297500839 ) ) ; -#48 = ORIENTED_EDGE ( 'NONE', *, *, #32583, .F. ) ; -#49 = CARTESIAN_POINT ( 'NONE', ( -19.99814303586761710, 191.9760241014712960, 101.9334704393890405 ) ) ; -#50 = ORIENTED_EDGE ( 'NONE', *, *, #21680, .F. ) ; -#51 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567900 ) ) ; -#52 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13175, #12763, #37700, #31787, #31577, #3945 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.005577396964778614727, 0.006726925734499736992, 0.007876454504220859257 ), - .UNSPECIFIED. ) ; -#53 = CYLINDRICAL_SURFACE ( 'NONE', #24949, 2.000000000000014655 ) ; -#54 = ORIENTED_EDGE ( 'NONE', *, *, #11868, .F. ) ; -#55 = CARTESIAN_POINT ( 'NONE', ( -19.99828015742506793, 192.0076529467379771, 106.9671611953735777 ) ) ; -#56 = CARTESIAN_POINT ( 'NONE', ( 20.50141158344984404, 191.9758728513155575, 106.4093071483684696 ) ) ; -#57 = PLANE ( 'NONE', #21814 ) ; -#58 = CARTESIAN_POINT ( 'NONE', ( 13.46852558400658850, 153.7328115929476269, 98.21571663388800744 ) ) ; -#59 = EDGE_LOOP ( 'NONE', ( #31590, #21771, #20752, #12795 ) ) ; -#60 = CARTESIAN_POINT ( 'NONE', ( 3.063400437118999786, 190.7419505334999883, 106.7647335544999976 ) ) ; -#61 = AXIS2_PLACEMENT_3D ( 'NONE', #26719, #29184, #10775 ) ; -#62 = EDGE_CURVE ( 'NONE', #26666, #11241, #38827, .T. ) ; -#63 = AXIS2_PLACEMENT_3D ( 'NONE', #25666, #25869, #19886 ) ; -#64 = CARTESIAN_POINT ( 'NONE', ( -45.39754466565177182, 131.1270945138005573, 90.46656737203734622 ) ) ; -#65 = CARTESIAN_POINT ( 'NONE', ( 36.18256164553691434, 191.4809836520348085, 103.8379386387424432 ) ) ; -#66 = LINE ( 'NONE', #3323, #4540 ) ; -#67 = AXIS2_PLACEMENT_3D ( 'NONE', #38158, #23026, #10163 ) ; -#68 = ORIENTED_EDGE ( 'NONE', *, *, #307, .F. ) ; -#69 = AXIS2_PLACEMENT_3D ( 'NONE', #8559, #8969, #5060 ) ; -#70 = DIRECTION ( 'NONE', ( 0.0005884949961251572477, -0.2249510543439052768, 0.9743698870671265722 ) ) ; -#71 = DIRECTION ( 'NONE', ( -0.0006039748319391886151, -1.387778780781439522E-14, -0.9999998176071844824 ) ) ; -#72 = VERTEX_POINT ( 'NONE', #38092 ) ; -#73 = ADVANCED_FACE ( 'NONE', ( #10849 ), #25042, .T. ) ; -#74 = CARTESIAN_POINT ( 'NONE', ( 16.59040448417249891, 121.5622698803751121, 177.2309519810485767 ) ) ; -#75 = VERTEX_POINT ( 'NONE', #13165 ) ; -#77 = CARTESIAN_POINT ( 'NONE', ( 35.91265183286542850, 191.6406926546981424, 103.8749735105696033 ) ) ; -#76 = CARTESIAN_POINT ( 'NONE', ( 36.14467970416134790, 192.0930395166764413, 104.3839062667640150 ) ) ; -#78 = ORIENTED_EDGE ( 'NONE', *, *, #16278, .T. ) ; -#79 = ADVANCED_FACE ( 'NONE', ( #35746 ), #31361, .F. ) ; -#80 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971522104 ) ) ; -#81 = VERTEX_POINT ( 'NONE', #19267 ) ; -#82 = CARTESIAN_POINT ( 'NONE', ( 15.59122047669174549, 126.7497335477701910, 179.2034385373662531 ) ) ; -#83 = ADVANCED_FACE ( 'NONE', ( #29652 ), #25240, .F. ) ; -#84 = CARTESIAN_POINT ( 'NONE', ( -30.44899458943609005, 184.9287475678549981, 105.4443921870966250 ) ) ; -#85 = CARTESIAN_POINT ( 'NONE', ( 6.034202834021533235, 137.3564637335765610, 91.35735362699509210 ) ) ; -#86 = ORIENTED_EDGE ( 'NONE', *, *, #40303, .T. ) ; -#87 = AXIS2_PLACEMENT_3D ( 'NONE', #27595, #15294, #40024 ) ; -#88 = EDGE_CURVE ( 'NONE', #10727, #39550, #14097, .T. ) ; -#89 = VERTEX_POINT ( 'NONE', #9485 ) ; -#90 = EDGE_CURVE ( 'NONE', #21775, #20721, #2367, .T. ) ; -#91 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971537369 ) ) ; -#92 = CARTESIAN_POINT ( 'NONE', ( 41.20424435709291089, 166.0101408972543595, 183.1539072767900791 ) ) ; -#93 = CARTESIAN_POINT ( 'NONE', ( -14.62254490296892406, 128.1170529630574606, 179.5121082275731794 ) ) ; -#94 = EDGE_LOOP ( 'NONE', ( #19904, #14870, #20319, #19242 ) ) ; -#95 = ORIENTED_EDGE ( 'NONE', *, *, #10616, .T. ) ; -#96 = CARTESIAN_POINT ( 'NONE', ( -5.671191585905537735, 123.8351953472891864, 91.20138000056049066 ) ) ; -#97 = CARTESIAN_POINT ( 'NONE', ( 20.48673967653602901, 211.0896571907997554, 75.54495990469186495 ) ) ; -#98 = CARTESIAN_POINT ( 'NONE', ( 15.92170649585048281, 184.2627309268899580, 102.1837104338655848 ) ) ; -#99 = ORIENTED_EDGE ( 'NONE', *, *, #11923, .T. ) ; -#100 = ORIENTED_EDGE ( 'NONE', *, *, #32571, .T. ) ; -#101 = CARTESIAN_POINT ( 'NONE', ( 22.50136996952335267, 157.6320572232312998, 99.11047108320519783 ) ) ; -#102 = CARTESIAN_POINT ( 'NONE', ( -37.26202794485465120, 111.6171511925439148, 151.2319588935870058 ) ) ; -#103 = DIRECTION ( 'NONE', ( -0.0006039748319387582953, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#104 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #39047, #23329 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#105 = ORIENTED_EDGE ( 'NONE', *, *, #19721, .F. ) ; -#106 = CARTESIAN_POINT ( 'NONE', ( -36.67432554227874419, 115.9022888061950880, 89.74328836332526294 ) ) ; -#107 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#108 = CARTESIAN_POINT ( 'NONE', ( -5.668235839012205624, 187.2935674832718007, 105.4622348357629136 ) ) ; -#109 = CARTESIAN_POINT ( 'NONE', ( 31.81423252379520505, 154.4985393321093454, 201.1972645548150354 ) ) ; -#110 = DIRECTION ( 'NONE', ( 0.7933533411653070910, -0.5930537057989940797, -0.1373964268091563690 ) ) ; -#111 = ORIENTED_EDGE ( 'NONE', *, *, #24435, .F. ) ; -#112 = CARTESIAN_POINT ( 'NONE', ( -38.04444379205944671, 118.4867705051282627, 87.71485106921780073 ) ) ; -#113 = CARTESIAN_POINT ( 'NONE', ( 38.53174385238651922, 78.67361070814361312, 289.9170220609951230 ) ) ; -#114 = CARTESIAN_POINT ( 'NONE', ( -37.82318234731999951, 118.8138069173000133, 87.38894521921000091 ) ) ; -#115 = CARTESIAN_POINT ( 'NONE', ( 36.55562030122000294, 115.8243310143000144, 89.83301026034000358 ) ) ; -#116 = CIRCLE ( 'NONE', #14483, 6.499999999988752997 ) ; -#117 = AXIS2_PLACEMENT_3D ( 'NONE', #18312, #14872, #30813 ) ; -#118 = CARTESIAN_POINT ( 'NONE', ( -29.41044142705827014, 181.8648675259495633, 101.6574994283702296 ) ) ; -#119 = EDGE_LOOP ( 'NONE', ( #38155, #24800, #1408, #26406, #5637, #19732 ) ) ; -#120 = CARTESIAN_POINT ( 'NONE', ( -45.48423345424451014, 77.14301703112153064, 297.5860163668562564 ) ) ; -#121 = EDGE_CURVE ( 'NONE', #19053, #25286, #32870, .T. ) ; -#122 = ORIENTED_EDGE ( 'NONE', *, *, #5340, .T. ) ; -#123 = EDGE_CURVE ( 'NONE', #11575, #21267, #882, .T. ) ; -#124 = EDGE_CURVE ( 'NONE', #1239, #14482, #30688, .T. ) ; -#125 = CARTESIAN_POINT ( 'NONE', ( -38.20440139773999988, 118.7296188347000054, 90.14784475465999947 ) ) ; -#126 = EDGE_CURVE ( 'NONE', #8868, #31885, #31773, .T. ) ; -#127 = VERTEX_POINT ( 'NONE', #36587 ) ; -#128 = FACE_OUTER_BOUND ( 'NONE', #13493, .T. ) ; -#129 = EDGE_CURVE ( 'NONE', #26891, #35621, #22863, .T. ) ; -#130 = CARTESIAN_POINT ( 'NONE', ( -31.19629630738960913, 110.6131156702000027, 90.28662662050363963 ) ) ; -#131 = CARTESIAN_POINT ( 'NONE', ( -33.38621112099523458, 163.6246645812861971, 189.1270109278173095 ) ) ; -#132 = CARTESIAN_POINT ( 'NONE', ( -22.34218834335725390, 158.3009385975264536, 96.21306774085992686 ) ) ; -#133 = VERTEX_POINT ( 'NONE', #17959 ) ; -#134 = FACE_OUTER_BOUND ( 'NONE', #39381, .T. ) ; -#135 = ORIENTED_EDGE ( 'NONE', *, *, #31023, .F. ) ; -#136 = ORIENTED_EDGE ( 'NONE', *, *, #21942, .F. ) ; -#137 = EDGE_LOOP ( 'NONE', ( #21578, #37363, #29502, #27008 ) ) ; -#138 = EDGE_CURVE ( 'NONE', #36900, #25308, #19809, .T. ) ; -#139 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#140 = DIRECTION ( 'NONE', ( -0.0005884949961178167653, 0.2249510557410934197, -0.9743698867445601541 ) ) ; -#141 = ORIENTED_EDGE ( 'NONE', *, *, #24667, .F. ) ; -#142 = CARTESIAN_POINT ( 'NONE', ( 19.98041095528421707, 209.2225623532448253, 73.04692467823424806 ) ) ; -#143 = CIRCLE ( 'NONE', #21702, 2.000000000000011546 ) ; -#144 = ORIENTED_EDGE ( 'NONE', *, *, #19370, .T. ) ; -#145 = PLANE ( 'NONE', #32036 ) ; -#146 = VECTOR ( 'NONE', #7172, 1000.000000000000114 ) ; -#147 = EDGE_CURVE ( 'NONE', #36039, #25299, #36173, .T. ) ; -#148 = AXIS2_PLACEMENT_3D ( 'NONE', #18417, #9999, #12866 ) ; -#149 = CARTESIAN_POINT ( 'NONE', ( -30.07826481366596738, 134.2402275243734096, 93.74179301315371049 ) ) ; -#150 = CARTESIAN_POINT ( 'NONE', ( -3.632612936599522779, 143.5564359001282071, 95.77751706023541090 ) ) ; -#151 = CARTESIAN_POINT ( 'NONE', ( -30.07174127556133669, 134.7161224726260116, 93.44441010718954033 ) ) ; -#152 = ORIENTED_EDGE ( 'NONE', *, *, #23533, .F. ) ; -#153 = CARTESIAN_POINT ( 'NONE', ( 28.34188046507999914, 125.4821649217000044, 88.94658904128002064 ) ) ; -#154 = DIRECTION ( 'NONE', ( 0.7942820423213359238, 0.5918950211223032998, 0.1370267171630252800 ) ) ; -#155 = DIRECTION ( 'NONE', ( 0.0004161288024547937867, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#156 = CARTESIAN_POINT ( 'NONE', ( 25.49923630764208227, 118.3473981419666785, 87.75233666297712887 ) ) ; -#157 = CARTESIAN_POINT ( 'NONE', ( 4.379475180782625543, 135.5225349930722416, 90.93811872962228904 ) ) ; -#158 = ORIENTED_EDGE ( 'NONE', *, *, #31069, .F. ) ; -#159 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -3.519737327345223780E-16, 0.0006039748319385488274 ) ) ; -#160 = PLANE ( 'NONE', #23809 ) ; -#161 = CARTESIAN_POINT ( 'NONE', ( -15.94429972368852866, 121.8869921648800698, 174.4792395813007886 ) ) ; -#162 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#163 = ORIENTED_EDGE ( 'NONE', *, *, #23583, .F. ) ; -#164 = ORIENTED_EDGE ( 'NONE', *, *, #13285, .T. ) ; -#165 = CARTESIAN_POINT ( 'NONE', ( 38.36929107696393970, 118.9352448211023017, 90.24632071806664158 ) ) ; -#166 = CARTESIAN_POINT ( 'NONE', ( 12.31450649940180142, 135.1704657886633356, 91.19412197989161939 ) ) ; -#167 = CARTESIAN_POINT ( 'NONE', ( 25.78894422189694779, 212.1706022175659712, 73.04292820630129768 ) ) ; -#168 = CARTESIAN_POINT ( 'NONE', ( -25.49895059653205109, 190.9802068742214658, 106.3202087131623585 ) ) ; -#169 = ORIENTED_EDGE ( 'NONE', *, *, #6235, .F. ) ; -#170 = EDGE_CURVE ( 'NONE', #29017, #39184, #16528, .T. ) ; -#171 = EDGE_CURVE ( 'NONE', #3824, #585, #35482, .T. ) ; -#172 = VECTOR ( 'NONE', #30008, 1000.000000000000114 ) ; -#173 = EDGE_CURVE ( 'NONE', #20721, #921, #36791, .T. ) ; -#174 = CARTESIAN_POINT ( 'NONE', ( -12.63885758284349237, 182.0021742443144035, 102.1105035275109572 ) ) ; -#175 = AXIS2_PLACEMENT_3D ( 'NONE', #10239, #35133, #38619 ) ; -#176 = FACE_OUTER_BOUND ( 'NONE', #9445, .T. ) ; -#177 = DIRECTION ( 'NONE', ( -0.7933533175743878729, -0.5930761747309520882, -0.1372995428259456974 ) ) ; -#178 = FACE_OUTER_BOUND ( 'NONE', #34083, .T. ) ; -#179 = ADVANCED_FACE ( 'NONE', ( #39644 ), #21261, .T. ) ; -#180 = DIRECTION ( 'NONE', ( -0.0005884949961184574203, 0.2249510543439044719, -0.9743698870671267942 ) ) ; -#181 = CARTESIAN_POINT ( 'NONE', ( 36.36530821653990131, 191.8372400467440002, 104.3548065722559812 ) ) ; -#182 = CARTESIAN_POINT ( 'NONE', ( 36.51035386448999986, 190.9807345362999911, 106.6672906836000010 ) ) ; -#183 = ORIENTED_EDGE ( 'NONE', *, *, #24382, .T. ) ; -#184 = ORIENTED_EDGE ( 'NONE', *, *, #16639, .T. ) ; -#185 = EDGE_CURVE ( 'NONE', #5998, #16791, #35473, .T. ) ; -#186 = CARTESIAN_POINT ( 'NONE', ( -3.723721742435894377, 136.4323261788989612, 91.15305474119872997 ) ) ; -#187 = CARTESIAN_POINT ( 'NONE', ( 37.96521291183479008, 190.3639829187772250, 106.6578906949923464 ) ) ; -#188 = LINE ( 'NONE', #12660, #32996 ) ; -#189 = VERTEX_POINT ( 'NONE', #23509 ) ; -#190 = CARTESIAN_POINT ( 'NONE', ( 37.73070576671000254, 118.1925768933000001, 87.57314476239000101 ) ) ; -#191 = EDGE_CURVE ( 'NONE', #10943, #662, #35954, .T. ) ; -#192 = CARTESIAN_POINT ( 'NONE', ( -6.036264379394199686, 174.7922271991594414, 102.5762947721396898 ) ) ; -#193 = LINE ( 'NONE', #9610, #25563 ) ; -#194 = CARTESIAN_POINT ( 'NONE', ( -36.32955808867194492, 191.7831307432306289, 104.4004776953238576 ) ) ; -#195 = CONICAL_SURFACE ( 'NONE', #27637, 2.749999999928335992, 0.7853981634201930850 ) ; -#196 = EDGE_LOOP ( 'NONE', ( #3440, #31934, #12454, #39404 ) ) ; -#197 = CARTESIAN_POINT ( 'NONE', ( -23.36033136076990502, 129.9689112135512232, 92.23847830418463900 ) ) ; -#198 = CARTESIAN_POINT ( 'NONE', ( 25.61340328942235089, 212.6007637392172001, 76.04305467133100649 ) ) ; -#199 = PLANE ( 'NONE', #28726 ) ; -#200 = FACE_OUTER_BOUND ( 'NONE', #18567, .T. ) ; -#201 = ORIENTED_EDGE ( 'NONE', *, *, #5666, .F. ) ; -#202 = CARTESIAN_POINT ( 'NONE', ( 12.64191830251873583, 177.0167639429040776, 103.4528965672968326 ) ) ; -#203 = VECTOR ( 'NONE', #4844, 1000.000000000000227 ) ; -#204 = CARTESIAN_POINT ( 'NONE', ( 1.446531013058000026, 188.9112451455999917, 103.4032447082000061 ) ) ; -#205 = DIRECTION ( 'NONE', ( -6.938893903797542002E-15, 0.9743700557921584071, 0.2249510932971567068 ) ) ; -#206 = VERTEX_POINT ( 'NONE', #7964 ) ; -#207 = DIRECTION ( 'NONE', ( -0.6087613186456907188, 0.7729176985478710682, 0.1789074850089337476 ) ) ; -#208 = ORIENTED_EDGE ( 'NONE', *, *, #28907, .F. ) ; -#209 = DIRECTION ( 'NONE', ( -0.7871416011357068587, 0.6167723240884886993, 0.000000000000000000 ) ) ; -#210 = EDGE_CURVE ( 'NONE', #14771, #34948, #20641, .T. ) ; -#211 = EDGE_CURVE ( 'NONE', #5370, #12877, #14316, .T. ) ; -#212 = CARTESIAN_POINT ( 'NONE', ( -12.62960812168191183, 177.0992617944713743, 103.6047656994513204 ) ) ; -#213 = DIRECTION ( 'NONE', ( -0.7075227810178097432, 0.1590644159616022568, -0.6885564798298096090 ) ) ; -#214 = CARTESIAN_POINT ( 'NONE', ( -2.833334676081999959, 208.8581063077000124, 73.25715202902999579 ) ) ; -#215 = CARTESIAN_POINT ( 'NONE', ( -1.997901840931525230, 189.7491732284025261, 105.9548322323222607 ) ) ; -#216 = AXIS2_PLACEMENT_3D ( 'NONE', #15180, #36225, #14975 ) ; -#217 = EDGE_LOOP ( 'NONE', ( #30516, #18788, #9334, #5463 ) ) ; -#218 = FACE_BOUND ( 'NONE', #19523, .T. ) ; -#219 = DIRECTION ( 'NONE', ( -0.7933533416835715224, 0.5930537051408173443, 0.1373964266575322113 ) ) ; -#220 = CARTESIAN_POINT ( 'NONE', ( 42.89008714222951113, 113.2528206432904341, 125.5033208068462329 ) ) ; -#221 = ADVANCED_FACE ( 'NONE', ( #17345 ), #33103, .T. ) ; -#222 = AXIS2_PLACEMENT_3D ( 'NONE', #22583, #28311, #35005 ) ; -#223 = FACE_OUTER_BOUND ( 'NONE', #32828, .T. ) ; -#224 = ORIENTED_EDGE ( 'NONE', *, *, #25103, .T. ) ; -#225 = CONICAL_SURFACE ( 'NONE', #864, 2.503000005669923311, 0.7853981634067779272 ) ; -#226 = ORIENTED_EDGE ( 'NONE', *, *, #37023, .F. ) ; -#227 = DIRECTION ( 'NONE', ( 0.0005884949961236880453, -0.2249510543439056931, 0.9743698870671265722 ) ) ; -#228 = ORIENTED_EDGE ( 'NONE', *, *, #26833, .F. ) ; -#229 = LINE ( 'NONE', #9050, #27668 ) ; -#230 = CARTESIAN_POINT ( 'NONE', ( 15.99992735094624763, 169.9186965180942650, 98.87215626859075712 ) ) ; -#231 = ADVANCED_FACE ( 'NONE', ( #39237 ), #11242, .T. ) ; -#232 = CARTESIAN_POINT ( 'NONE', ( -3.536105410441011010, 136.6754134117661863, 94.28792821396773149 ) ) ; -#233 = DIRECTION ( 'NONE', ( -0.1782640835105696875, -0.3528946327679918782, 0.9185245204640325456 ) ) ; -#234 = CARTESIAN_POINT ( 'NONE', ( -38.02513973112999679, 119.2109743768000101, 87.30192654314001288 ) ) ; -#235 = CARTESIAN_POINT ( 'NONE', ( 25.50040748627628773, 118.8155663766999481, 89.75240507814876878 ) ) ; -#236 = ORIENTED_EDGE ( 'NONE', *, *, #33905, .T. ) ; -#237 = DIRECTION ( 'NONE', ( 0.4298642588094122585, -0.3871440406461976180, -0.8156814395279384788 ) ) ; -#238 = EDGE_LOOP ( 'NONE', ( #19592, #19335, #38778, #3267 ) ) ; -#239 = CARTESIAN_POINT ( 'NONE', ( -82.80843920860921514, 105.1411378422745315, 24.32376295616780482 ) ) ; -#240 = CARTESIAN_POINT ( 'NONE', ( 38.49879497324275235, 78.38483656737932392, 291.5352916277676627 ) ) ; -#241 = ORIENTED_EDGE ( 'NONE', *, *, #17146, .T. ) ; -#242 = CARTESIAN_POINT ( 'NONE', ( -14.99990248618953181, 136.4138140789638953, 91.32664213178384216 ) ) ; -#243 = CARTESIAN_POINT ( 'NONE', ( 1.306454471753598190, 188.7206452512837700, 103.2217284838431794 ) ) ; -#244 = AXIS2_PLACEMENT_3D ( 'NONE', #25224, #25423, #22753 ) ; -#245 = DIRECTION ( 'NONE', ( 0.0005884949961193586092, -0.2249510543439039167, 0.9743698870671270162 ) ) ; -#246 = EDGE_CURVE ( 'NONE', #39374, #22073, #23759, .T. ) ; -#247 = ORIENTED_EDGE ( 'NONE', *, *, #28931, .F. ) ; -#248 = CARTESIAN_POINT ( 'NONE', ( 20.45872449161620210, 118.1119902764347245, 87.71370651214481029 ) ) ; -#249 = LINE ( 'NONE', #22554, #33049 ) ; -#250 = ORIENTED_EDGE ( 'NONE', *, *, #22389, .F. ) ; -#251 = EDGE_CURVE ( 'NONE', #10727, #19810, #20465, .T. ) ; -#252 = CARTESIAN_POINT ( 'NONE', ( 2.563028759935935597, 191.4135359453850072, 104.3558246061316339 ) ) ; -#253 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; -#254 = DIRECTION ( 'NONE', ( 3.538835890992693415E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#255 = ORIENTED_EDGE ( 'NONE', *, *, #14656, .F. ) ; -#256 = EDGE_CURVE ( 'NONE', #35304, #1023, #21922, .T. ) ; -#257 = EDGE_CURVE ( 'NONE', #14938, #3287, #29232, .T. ) ; -#258 = FACE_OUTER_BOUND ( 'NONE', #8621, .T. ) ; -#259 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24376, #25173, #2696, #36821 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.001089237863740169726, 0.001154390576975604810 ), - .UNSPECIFIED. ) ; -#260 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927775713126, 0.0005734119022076485583 ) ) ; -#261 = ORIENTED_EDGE ( 'NONE', *, *, #3575, .F. ) ; -#262 = EDGE_CURVE ( 'NONE', #11101, #410, #18365, .T. ) ; -#263 = CARTESIAN_POINT ( 'NONE', ( 22.49999922077099157, 184.9675253677782791, 102.3424519572667037 ) ) ; -#264 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.271205131337280331E-14, -1.000000000000000000 ) ) ; -#266 = CARTESIAN_POINT ( 'NONE', ( 36.11364262193256280, 191.5260145455536929, 103.8483746271915322 ) ) ; -#265 = CARTESIAN_POINT ( 'NONE', ( -38.93740081958814159, 183.0561992808241882, 105.0172067937131999 ) ) ; -#267 = VERTEX_POINT ( 'NONE', #27817 ) ; -#268 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971581778 ) ) ; -#269 = VECTOR ( 'NONE', #25372, 1000.000000000000000 ) ; -#270 = CARTESIAN_POINT ( 'NONE', ( -23.36013622322097305, 127.9076955631128811, 92.27576111919179880 ) ) ; -#271 = ORIENTED_EDGE ( 'NONE', *, *, #10804, .F. ) ; -#272 = CARTESIAN_POINT ( 'NONE', ( -20.35185535331545736, 209.7097377694403804, 75.73747142885962091 ) ) ; -#273 = CARTESIAN_POINT ( 'NONE', ( 14.17154134345668126, 176.0476639716964939, 102.8539302333655172 ) ) ; -#275 = VERTEX_POINT ( 'NONE', #2664 ) ; -#274 = VECTOR ( 'NONE', #26596, 1000.000000000000227 ) ; -#276 = EDGE_LOOP ( 'NONE', ( #29220, #16061, #26642 ) ) ; -#277 = CARTESIAN_POINT ( 'NONE', ( -22.49964039505865898, 137.3544959182434582, 178.0533373668075399 ) ) ; -#278 = DIRECTION ( 'NONE', ( 0.0002393071182785117587, 0.2252352986010041080, -0.9743043687658491381 ) ) ; -#279 = CARTESIAN_POINT ( 'NONE', ( 2.621271904897064520, 209.6171333383382205, 73.39025471814052537 ) ) ; -#280 = CARTESIAN_POINT ( 'NONE', ( 35.99530537726000290, 191.7686035531999948, 104.0424034760000040 ) ) ; -#281 = EDGE_LOOP ( 'NONE', ( #15248, #10667, #27731, #33068 ) ) ; -#282 = VERTEX_POINT ( 'NONE', #6699 ) ; -#283 = ORIENTED_EDGE ( 'NONE', *, *, #16458, .F. ) ; -#284 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22030, #27973, #40406, #6458, #3390, #29163, #26701, #29361, #38351, #26101 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998142042, 0.3749999999997213340, 0.4374999999997243871, 0.4999999999997274402, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#285 = CARTESIAN_POINT ( 'NONE', ( -13.49823340920320724, 160.0628909777703655, 99.69670533858855777 ) ) ; -#286 = CARTESIAN_POINT ( 'NONE', ( 20.64817629877472172, 129.1121636414192153, 89.44834173347469175 ) ) ; -#287 = CARTESIAN_POINT ( 'NONE', ( -28.26178469267999915, 125.5769036415000102, 89.17499484335999682 ) ) ; -#288 = VERTEX_POINT ( 'NONE', #37784 ) ; -#289 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #3040, #15521, #21864, #1578 ), - ( #11001, #7106, #35490, #7509 ), - ( #19969, #4644, #19577, #4441 ), - ( #38583, #10796, #39193, #35299 ), - ( #26541, #26741, #32854, #35697 ), - ( #7709, #7915, #14063, #32466 ), - ( #20172, #16894, #10400, #32270 ), - ( #29406, #4837, #1372, #29809 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.07039365576733999652, 0.000000000000000000, 0.3333209167664999972, 0.6666601135059000427, 1.000000000000000000, 1.073358129890999990 ), - ( -1.157058506089999943E-06, 0.9997056213035999672 ), - .UNSPECIFIED. ) ; -#290 = FACE_OUTER_BOUND ( 'NONE', #29891, .T. ) ; -#291 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -0.000000000000000000, 0.0006039748319387908213 ) ) ; -#292 = ORIENTED_EDGE ( 'NONE', *, *, #20209, .T. ) ; -#293 = ADVANCED_FACE ( 'NONE', ( #40444 ), #30866, .T. ) ; -#294 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #5334, #17791 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#295 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319383846792 ) ) ; -#296 = ORIENTED_EDGE ( 'NONE', *, *, #22800, .F. ) ; -#297 = CARTESIAN_POINT ( 'NONE', ( -29.43062942139435023, 161.0139814470911688, 187.1134349459278496 ) ) ; -#298 = CIRCLE ( 'NONE', #25167, 51.40509898897000340 ) ; -#299 = ADVANCED_FACE ( 'NONE', ( #28207 ), #9403, .F. ) ; -#300 = CARTESIAN_POINT ( 'NONE', ( -1.042992686386000178, 188.5885128006999878, 106.1192851443999956 ) ) ; -#301 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5638, #8928, #6037, #30385 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#302 = AXIS2_PLACEMENT_3D ( 'NONE', #2191, #27750, #8527 ) ; -#303 = CARTESIAN_POINT ( 'NONE', ( -34.02846521710866057, 93.66177618440443098, 291.5790962755415308 ) ) ; -#304 = EDGE_LOOP ( 'NONE', ( #10614, #37478, #8917, #6655 ) ) ; -#305 = DIRECTION ( 'NONE', ( 0.0005884949961247682359, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#307 = EDGE_CURVE ( 'NONE', #27317, #25168, #40047, .T. ) ; -#306 = CARTESIAN_POINT ( 'NONE', ( 33.24619400733308794, 82.58330910283459048, 291.0120781237818619 ) ) ; -#308 = EDGE_CURVE ( 'NONE', #37286, #37740, #1403, .T. ) ; -#309 = CARTESIAN_POINT ( 'NONE', ( -37.83067437562999658, 118.4147154292000010, 87.61792235453000899 ) ) ; -#310 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; -#311 = ADVANCED_FACE ( 'NONE', ( #2843 ), #10711, .F. ) ; -#312 = EDGE_CURVE ( 'NONE', #12152, #38835, #15709, .T. ) ; -#313 = ORIENTED_EDGE ( 'NONE', *, *, #35780, .T. ) ; -#314 = CARTESIAN_POINT ( 'NONE', ( 15.50029468041032388, 127.6324160061002857, 89.62297635135885798 ) ) ; -#315 = VERTEX_POINT ( 'NONE', #9390 ) ; -#316 = CARTESIAN_POINT ( 'NONE', ( 22.99270477044632344, 214.0899081099834689, 76.04459013870678064 ) ) ; -#317 = CARTESIAN_POINT ( 'NONE', ( 5.675840488321574284, 188.3446150673902650, 103.1322824216947396 ) ) ; -#318 = CARTESIAN_POINT ( 'NONE', ( -38.37514916663999998, 118.5434696222999946, 89.84850653638000040 ) ) ; -#319 = ORIENTED_EDGE ( 'NONE', *, *, #126, .F. ) ; -#320 = ORIENTED_EDGE ( 'NONE', *, *, #18623, .T. ) ; -#321 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971557076 ) ) ; -#322 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265227786, -0.1368326740407717901 ) ) ; -#323 = CARTESIAN_POINT ( 'NONE', ( 25.53747175047978857, 190.9172658757476313, 106.2799836673595024 ) ) ; -#324 = CARTESIAN_POINT ( 'NONE', ( -15.49852918879845554, 137.6306203023815158, 94.00257520767851815 ) ) ; -#325 = CARTESIAN_POINT ( 'NONE', ( 29.05533563819800236, 110.6131156702000027, 90.25023614458406485 ) ) ; -#326 = VERTEX_POINT ( 'NONE', #34307 ) ; -#327 = CIRCLE ( 'NONE', #30403, 4.999999999999990230 ) ; -#328 = VERTEX_POINT ( 'NONE', #8995 ) ; -#329 = ORIENTED_EDGE ( 'NONE', *, *, #7732, .F. ) ; -#330 = CARTESIAN_POINT ( 'NONE', ( -6.036418464817404406, 177.2878155064289558, 101.0168780376782109 ) ) ; -#331 = EDGE_CURVE ( 'NONE', #5120, #21171, #6300, .T. ) ; -#332 = VECTOR ( 'NONE', #39259, 1000.000000000000000 ) ; -#333 = CARTESIAN_POINT ( 'NONE', ( 15.66679300288561727, 160.6640684447974365, 97.07785643563907740 ) ) ; -#334 = AXIS2_PLACEMENT_3D ( 'NONE', #33895, #40031, #15305 ) ; -#335 = ORIENTED_EDGE ( 'NONE', *, *, #16182, .F. ) ; -#336 = CARTESIAN_POINT ( 'NONE', ( -23.36258586059182463, 135.1577092718124504, 91.20172337759686343 ) ) ; -#337 = AXIS2_PLACEMENT_3D ( 'NONE', #2937, #2552, #15427 ) ; -#338 = LINE ( 'NONE', #37553, #10692 ) ; -#339 = ORIENTED_EDGE ( 'NONE', *, *, #26267, .F. ) ; -#340 = CARTESIAN_POINT ( 'NONE', ( 6.035817316619340289, 176.7425654431414443, 103.0192746799617822 ) ) ; -#341 = CARTESIAN_POINT ( 'NONE', ( 39.06393364112003042, 183.1686747597475744, 104.4829110299670418 ) ) ; -#342 = ORIENTED_EDGE ( 'NONE', *, *, #9160, .T. ) ; -#343 = CARTESIAN_POINT ( 'NONE', ( 28.30037992548000148, 125.1369368826999988, 88.52587847348999617 ) ) ; -#344 = ADVANCED_FACE ( 'NONE', ( #12645 ), #31064, .T. ) ; -#345 = DIRECTION ( 'NONE', ( -0.7069397808361403968, 0.6508952239913371463, 0.2767156548817158446 ) ) ; -#346 = CARTESIAN_POINT ( 'NONE', ( -22.18332052414608668, 128.5026941233560649, 175.4939087089999532 ) ) ; -#347 = DIRECTION ( 'NONE', ( -0.0005884949961209497843, 0.2249510543439031118, -0.9743698870671271273 ) ) ; -#348 = CARTESIAN_POINT ( 'NONE', ( 4.504851336039020104, 135.4216444545554339, 90.91475058518872743 ) ) ; -#349 = VERTEX_POINT ( 'NONE', #5911 ) ; -#350 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#351 = ADVANCED_FACE ( 'NONE', ( #3037 ), #25140, .F. ) ; -#352 = DIRECTION ( 'NONE', ( 0.0004270958050665225100, 0.7071067811865940911, 0.7071066522025566403 ) ) ; -#353 = DIRECTION ( 'NONE', ( 0.9999998268367519261, 0.0001323825254113870128, -0.0005734120100192159576 ) ) ; -#354 = EDGE_CURVE ( 'NONE', #36048, #5125, #32620, .T. ) ; -#355 = CARTESIAN_POINT ( 'NONE', ( 12.64386512242256266, 130.3482773188944748, 92.81742853362089818 ) ) ; -#356 = ORIENTED_EDGE ( 'NONE', *, *, #16875, .F. ) ; -#357 = EDGE_LOOP ( 'NONE', ( #38792, #27046, #18775, #35953 ) ) ; -#358 = CARTESIAN_POINT ( 'NONE', ( 16.21976467472907757, 122.6436220881636814, 172.0961230653717564 ) ) ; -#359 = CARTESIAN_POINT ( 'NONE', ( -40.82578792912735821, 120.4063655703290436, 90.55449113282519136 ) ) ; -#360 = AXIS2_PLACEMENT_3D ( 'NONE', #12528, #31160, #8887 ) ; -#361 = CARTESIAN_POINT ( 'NONE', ( 20.95020508879656163, 128.6695385774041256, 92.42488413635012989 ) ) ; -#362 = EDGE_CURVE ( 'NONE', #20220, #18693, #23368, .T. ) ; -#363 = CARTESIAN_POINT ( 'NONE', ( 14.55294048017762698, 182.5605668518259392, 101.7915615195478409 ) ) ; -#364 = VECTOR ( 'NONE', #37833, 1000.000000000000000 ) ; -#365 = AXIS2_PLACEMENT_3D ( 'NONE', #31960, #21952, #16195 ) ; -#366 = CARTESIAN_POINT ( 'NONE', ( -25.50667448668442816, 190.9437958018905022, 106.3169387399151304 ) ) ; -#367 = VERTEX_POINT ( 'NONE', #773 ) ; -#368 = AXIS2_PLACEMENT_3D ( 'NONE', #34656, #38343, #10354 ) ; -#369 = CONICAL_SURFACE ( 'NONE', #17333, 2.502996077826407983, 0.7853981633816121688 ) ; -#370 = CARTESIAN_POINT ( 'NONE', ( -19.70083802979191034, 149.6495827129742793, 180.8771180990181904 ) ) ; -#371 = CARTESIAN_POINT ( 'NONE', ( -15.66646722745994680, 127.6691331963593399, 89.47923018327796285 ) ) ; -#372 = VERTEX_POINT ( 'NONE', #29202 ) ; -#373 = CARTESIAN_POINT ( 'NONE', ( 28.53094770716555217, 124.6122665164779164, 91.48361085109841895 ) ) ; -#374 = FACE_OUTER_BOUND ( 'NONE', #37509, .T. ) ; -#375 = FACE_OUTER_BOUND ( 'NONE', #12336, .T. ) ; -#376 = CARTESIAN_POINT ( 'NONE', ( 36.67803170103999832, 191.3755374097000015, 106.3641529334000069 ) ) ; -#377 = CARTESIAN_POINT ( 'NONE', ( 4.035676232316198764, 143.6517845923164600, 95.38087260498555509 ) ) ; -#378 = CARTESIAN_POINT ( 'NONE', ( 36.67231531969000002, 191.2361342563999926, 106.4435789431999950 ) ) ; -#379 = ORIENTED_EDGE ( 'NONE', *, *, #27117, .F. ) ; -#380 = CARTESIAN_POINT ( 'NONE', ( -5.386563737826397968, 134.9999922083646027, 90.82337864291790197 ) ) ; -#381 = CARTESIAN_POINT ( 'NONE', ( 22.50029346827053089, 158.6816162529845826, 96.78702253161689839 ) ) ; -#382 = CYLINDRICAL_SURFACE ( 'NONE', #31791, 4.999999999999990230 ) ; -#383 = ORIENTED_EDGE ( 'NONE', *, *, #7035, .F. ) ; -#384 = CARTESIAN_POINT ( 'NONE', ( -30.40330716480172057, 177.7873404760022993, 100.7167276284103821 ) ) ; -#385 = AXIS2_PLACEMENT_3D ( 'NONE', #13264, #16710, #38204 ) ; -#386 = ORIENTED_EDGE ( 'NONE', *, *, #6638, .F. ) ; -#387 = VECTOR ( 'NONE', #20369, 1000.000000000000227 ) ; -#388 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#389 = DIRECTION ( 'NONE', ( -0.6188015000093128881, 0.7855473910504855439, 0.000000000000000000 ) ) ; -#390 = EDGE_CURVE ( 'NONE', #4391, #12087, #16705, .T. ) ; -#391 = ORIENTED_EDGE ( 'NONE', *, *, #16628, .T. ) ; -#392 = CIRCLE ( 'NONE', #5623, 2.500000000000002220 ) ; -#393 = FACE_OUTER_BOUND ( 'NONE', #13748, .T. ) ; -#394 = ADVANCED_FACE ( 'NONE', ( #31675 ), #28990, .T. ) ; -#395 = EDGE_CURVE ( 'NONE', #34749, #23829, #38108, .T. ) ; -#396 = CARTESIAN_POINT ( 'NONE', ( -37.29428432633125112, 118.1868522465356364, 122.8630558711557796 ) ) ; -#397 = VECTOR ( 'NONE', #24823, 1000.000000000000114 ) ; -#398 = EDGE_CURVE ( 'NONE', #7038, #1494, #16113, .T. ) ; -#399 = CARTESIAN_POINT ( 'NONE', ( -15.49970617728509481, 174.4013312752846900, 100.4391564138297497 ) ) ; -#400 = CARTESIAN_POINT ( 'NONE', ( 20.50045376188424129, 118.3470799342523350, 87.75520690767631038 ) ) ; -#401 = EDGE_LOOP ( 'NONE', ( #16276, #95, #15037, #35711 ) ) ; -#402 = CARTESIAN_POINT ( 'NONE', ( 9.175045684063999119, 135.1076161457999945, 91.09600681774000464 ) ) ; -#403 = CARTESIAN_POINT ( 'NONE', ( 1.764841773357460175, 189.4098073068830104, 103.8140057643769723 ) ) ; -#404 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510153906202348, 0.9743700737782995391 ) ) ; -#405 = EDGE_CURVE ( 'NONE', #479, #31729, #16501, .T. ) ; -#406 = CARTESIAN_POINT ( 'NONE', ( -36.53787773711000142, 191.3244119832000081, 103.9585308249000093 ) ) ; -#407 = VERTEX_POINT ( 'NONE', #28793 ) ; -#408 = EDGE_LOOP ( 'NONE', ( #679, #32778, #36283, #17693 ) ) ; -#409 = DIRECTION ( 'NONE', ( -0.9914448496661262267, 0.1271494159038595306, 0.02949806952699914747 ) ) ; -#410 = VERTEX_POINT ( 'NONE', #22471 ) ; -#411 = EDGE_CURVE ( 'NONE', #31583, #5720, #1518, .T. ) ; -#412 = CARTESIAN_POINT ( 'NONE', ( -20.18663680212400990, 209.7095168387737942, 73.23727984573439187 ) ) ; -#413 = CARTESIAN_POINT ( 'NONE', ( 20.00050118914248998, 195.5086344217266401, 105.4811071159344920 ) ) ; -#414 = AXIS2_PLACEMENT_3D ( 'NONE', #37315, #24462, #36702 ) ; -#415 = CIRCLE ( 'NONE', #1729, 6.000000000000007994 ) ; -#416 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#417 = CONICAL_SURFACE ( 'NONE', #7597, 9.999999999999664269, 0.7853981633973083909 ) ; -#418 = FACE_OUTER_BOUND ( 'NONE', #23180, .T. ) ; -#419 = CARTESIAN_POINT ( 'NONE', ( -2.570582216233999961, 209.1916834252999990, 73.46146492376000481 ) ) ; -#420 = CARTESIAN_POINT ( 'NONE', ( -36.80923119322000048, 190.7095693884000411, 106.6535541835999936 ) ) ; -#421 = ORIENTED_EDGE ( 'NONE', *, *, #13929, .F. ) ; -#422 = AXIS2_PLACEMENT_3D ( 'NONE', #39753, #38787, #21168 ) ; -#423 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#424 = CARTESIAN_POINT ( 'NONE', ( -20.01841854128525711, 211.0875725380936103, 76.07063535483980843 ) ) ; -#425 = CARTESIAN_POINT ( 'NONE', ( 33.97195405289492953, 127.1809089859550994, 297.5380268206066035 ) ) ; -#426 = VECTOR ( 'NONE', #350, 999.9999999999998863 ) ; -#427 = FACE_OUTER_BOUND ( 'NONE', #39627, .T. ) ; -#428 = ORIENTED_EDGE ( 'NONE', *, *, #14466, .T. ) ; -#429 = ORIENTED_EDGE ( 'NONE', *, *, #6211, .F. ) ; -#430 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927782437076, 0.0005734119022074447283 ) ) ; -#431 = PLANE ( 'NONE', #27250 ) ; -#432 = ORIENTED_EDGE ( 'NONE', *, *, #31159, .F. ) ; -#433 = CARTESIAN_POINT ( 'NONE', ( 43.54015349051805117, 114.1160320780469704, 121.8918845946140124 ) ) ; -#434 = FACE_OUTER_BOUND ( 'NONE', #8446, .T. ) ; -#435 = CARTESIAN_POINT ( 'NONE', ( -38.36175615046000331, 118.8220069778000010, 87.72134297774999823 ) ) ; -#436 = DIRECTION ( 'NONE', ( 0.7730662169443226484, 0.5272861007345267526, 0.3526159273084130130 ) ) ; -#437 = FACE_OUTER_BOUND ( 'NONE', #8419, .T. ) ; -#438 = EDGE_LOOP ( 'NONE', ( #24862, #21064, #20177, #39906 ) ) ; -#439 = CARTESIAN_POINT ( 'NONE', ( 44.64373491923319648, 189.2041368418193201, 103.8203288493235164 ) ) ; -#440 = VECTOR ( 'NONE', #15444, 1000.000000000000114 ) ; -#441 = EDGE_LOOP ( 'NONE', ( #38871, #28206, #5259, #6281 ) ) ; -#442 = EDGE_CURVE ( 'NONE', #28499, #3536, #37467, .T. ) ; -#443 = CARTESIAN_POINT ( 'NONE', ( -18.98889543208580122, 125.5955304196095312, 175.3358149539526778 ) ) ; -#444 = EDGE_CURVE ( 'NONE', #17419, #72, #28596, .T. ) ; -#445 = AXIS2_PLACEMENT_3D ( 'NONE', #8077, #33200, #39549 ) ; -#446 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; -#447 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #19934, #29772, #17470, #23031 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.624050982390370379, 4.624081416319758553 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999228146308, 0.9999999999228146308, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#448 = CIRCLE ( 'NONE', #33069, 2.000000000000011546 ) ; -#449 = CYLINDRICAL_SURFACE ( 'NONE', #28212, 10.00000000000000533 ) ; -#450 = ORIENTED_EDGE ( 'NONE', *, *, #23332, .F. ) ; -#451 = CARTESIAN_POINT ( 'NONE', ( -19.99846415485538031, 193.1625704610679577, 106.8253906829090454 ) ) ; -#452 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #7019, #18804 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#453 = CARTESIAN_POINT ( 'NONE', ( 2.588293688821421856, 189.6472944346019176, 103.4348881448569273 ) ) ; -#454 = CARTESIAN_POINT ( 'NONE', ( 13.47054187644548406, 153.6079216790072621, 98.01583170369502795 ) ) ; -#455 = CIRCLE ( 'NONE', #18704, 6.500001104192627110 ) ; -#456 = VERTEX_POINT ( 'NONE', #13259 ) ; -#457 = LINE ( 'NONE', #28281, #15295 ) ; -#458 = CARTESIAN_POINT ( 'NONE', ( 5.668109638569153397, 183.4506315909706302, 105.0813282954734262 ) ) ; -#459 = ORIENTED_EDGE ( 'NONE', *, *, #2690, .F. ) ; -#460 = CARTESIAN_POINT ( 'NONE', ( 41.39926400812499452, 120.5685452915470108, 90.54227133756512558 ) ) ; -#461 = CARTESIAN_POINT ( 'NONE', ( 36.16642383351802437, 191.4912202370425405, 103.8403116878715764 ) ) ; -#462 = CARTESIAN_POINT ( 'NONE', ( 16.28421033156310216, 151.2599356526419285, 184.6951526137606265 ) ) ; -#463 = ORIENTED_EDGE ( 'NONE', *, *, #38612, .F. ) ; -#464 = CARTESIAN_POINT ( 'NONE', ( 2.711028266378750828, 208.9737166860216462, 73.44859438967698395 ) ) ; -#465 = CARTESIAN_POINT ( 'NONE', ( -4.139449305539524282, 124.8489201536050075, 88.47906534633457909 ) ) ; -#466 = DIRECTION ( 'NONE', ( -0.9999998268368063270, -0.0001323825921995365950, 0.0005734118997056624183 ) ) ; -#467 = ADVANCED_FACE ( 'NONE', ( #32267 ), #13847, .T. ) ; -#468 = VERTEX_POINT ( 'NONE', #35694 ) ; -#469 = VECTOR ( 'NONE', #2521, 1000.000000000000114 ) ; -#470 = DIRECTION ( 'NONE', ( 0.0005884949961247070869, -0.2249510543439059984, 0.9743698870671263501 ) ) ; -#471 = CARTESIAN_POINT ( 'NONE', ( 36.04524237818177568, 209.7096540190999860, 73.53673375003081958 ) ) ; -#472 = AXIS2_PLACEMENT_3D ( 'NONE', #1170, #1783, #13650 ) ; -#474 = CARTESIAN_POINT ( 'NONE', ( 35.59539200389620817, 192.0921221148306302, 103.8968606314943202 ) ) ; -#473 = CARTESIAN_POINT ( 'NONE', ( -38.36106832263448752, 118.8212171802660606, 87.72011982685570786 ) ) ; -#475 = ORIENTED_EDGE ( 'NONE', *, *, #17363, .T. ) ; -#476 = CARTESIAN_POINT ( 'NONE', ( -15.10714331244187214, 129.6097141051087362, 89.58480571958619976 ) ) ; -#477 = CARTESIAN_POINT ( 'NONE', ( 3.166350703034567449, 184.1264558197564156, 102.1599558388959537 ) ) ; -#478 = ORIENTED_EDGE ( 'NONE', *, *, #11877, .F. ) ; -#479 = VERTEX_POINT ( 'NONE', #7506 ) ; -#480 = CARTESIAN_POINT ( 'NONE', ( -13.46986788395000012, 174.3879284816999871, 152.4718672074000381 ) ) ; -#481 = CARTESIAN_POINT ( 'NONE', ( 26.00170599668673788, 118.1131156702000169, 87.24902382708054915 ) ) ; -#482 = PLANE ( 'NONE', #32390 ) ; -#483 = CARTESIAN_POINT ( 'NONE', ( 8.470678213537377488, 151.0674926792860049, 95.03763680969706229 ) ) ; -#484 = CARTESIAN_POINT ( 'NONE', ( -2.300490056545999806, 191.0208375971999999, 106.1810267846999949 ) ) ; -#485 = ORIENTED_EDGE ( 'NONE', *, *, #27419, .F. ) ; -#486 = EDGE_LOOP ( 'NONE', ( #38539, #28194, #8804, #34851 ) ) ; -#487 = ORIENTED_EDGE ( 'NONE', *, *, #24736, .F. ) ; -#488 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971576227 ) ) ; -#489 = EDGE_CURVE ( 'NONE', #22792, #8531, #16957, .T. ) ; -#490 = CARTESIAN_POINT ( 'NONE', ( 20.11108698654291516, 128.1535755644673031, 89.22735858623562422 ) ) ; -#491 = EDGE_CURVE ( 'NONE', #25299, #18476, #6907, .T. ) ; -#492 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386880390 ) ) ; -#493 = EDGE_LOOP ( 'NONE', ( #20538, #32260, #32848, #15873 ) ) ; -#494 = DIRECTION ( 'NONE', ( -0.0005884949961224280940, 0.2249510543439061094, -0.9743698870671263501 ) ) ; -#495 = ORIENTED_EDGE ( 'NONE', *, *, #34696, .F. ) ; -#496 = VECTOR ( 'NONE', #31484, 1000.000000000000114 ) ; -#497 = CARTESIAN_POINT ( 'NONE', ( 36.06588537441000142, 194.9391275604999976, 107.7152975676000040 ) ) ; -#498 = EDGE_LOOP ( 'NONE', ( #36671, #21549, #16809, #24710, #13730, #17370, #35163, #30337, #29356, #27134, #28658, #1797, #27624, #26608, #27772, #16640, #34868, #35558, #34400, #29870, #19344, #31943, #30587 ) ) ; -#499 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#500 = CARTESIAN_POINT ( 'NONE', ( -2.503680010063999983, 189.6842172410000273, 106.3860591883999973 ) ) ; -#501 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; -#502 = ORIENTED_EDGE ( 'NONE', *, *, #7788, .F. ) ; -#503 = CARTESIAN_POINT ( 'NONE', ( 22.78196627740044278, 153.3599009982148118, 97.61084599868732425 ) ) ; -#504 = FACE_OUTER_BOUND ( 'NONE', #32385, .T. ) ; -#505 = DIRECTION ( 'NONE', ( 7.930164461882003851E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; -#506 = CARTESIAN_POINT ( 'NONE', ( 42.83827273200019903, 189.3718331974772582, 106.4258958018896095 ) ) ; -#507 = EDGE_CURVE ( 'NONE', #13220, #26074, #4031, .T. ) ; -#508 = CARTESIAN_POINT ( 'NONE', ( -37.83650503347710270, 190.7637522520328162, 106.4538665319802959 ) ) ; -#509 = EDGE_LOOP ( 'NONE', ( #2105, #12513, #10717, #17166, #22728, #20104 ) ) ; -#510 = DIRECTION ( 'NONE', ( 0.0006039748319375823696, 6.916865751211140412E-15, 0.9999998176071847045 ) ) ; -#511 = CARTESIAN_POINT ( 'NONE', ( -28.25689436368393714, 186.9042180597057836, 103.3333805992548093 ) ) ; -#512 = ORIENTED_EDGE ( 'NONE', *, *, #20286, .T. ) ; -#513 = ORIENTED_EDGE ( 'NONE', *, *, #8641, .F. ) ; -#514 = LINE ( 'NONE', #18919, #29035 ) ; -#515 = ADVANCED_FACE ( 'NONE', ( #35094 ), #8765, .F. ) ; -#516 = VECTOR ( 'NONE', #28278, 1000.000000000000000 ) ; -#517 = CARTESIAN_POINT ( 'NONE', ( 29.20104124293241910, 162.9684951647539322, 100.3384403448970659 ) ) ; -#518 = PLANE ( 'NONE', #29405 ) ; -#519 = CARTESIAN_POINT ( 'NONE', ( -3.777786845789887327, 174.7331624351747905, 102.8264155123936376 ) ) ; -#520 = VERTEX_POINT ( 'NONE', #17505 ) ; -#521 = DIRECTION ( 'NONE', ( -0.0009686424659220778562, 0.2252351993847904188, -0.9743039395844949047 ) ) ; -#522 = VECTOR ( 'NONE', #15662, 1000.000000000000000 ) ; -#523 = ORIENTED_EDGE ( 'NONE', *, *, #12901, .T. ) ; -#524 = ORIENTED_EDGE ( 'NONE', *, *, #17371, .F. ) ; -#525 = ORIENTED_EDGE ( 'NONE', *, *, #30357, .T. ) ; -#526 = CARTESIAN_POINT ( 'NONE', ( 37.28362348802268400, 145.4126454253283214, 281.4614046043920439 ) ) ; -#527 = EDGE_CURVE ( 'NONE', #39304, #31792, #27729, .T. ) ; -#528 = CARTESIAN_POINT ( 'NONE', ( 19.44287702427785547, 124.8277558452613363, 177.7399537498035045 ) ) ; -#529 = VERTEX_POINT ( 'NONE', #10998 ) ; -#530 = CARTESIAN_POINT ( 'NONE', ( 76.10748482112096269, 155.8105762428847925, 98.14442178571833608 ) ) ; -#532 = ADVANCED_FACE ( 'NONE', ( #20584 ), #30204, .T. ) ; -#531 = CARTESIAN_POINT ( 'NONE', ( 21.72426698684031976, 130.1004708904147265, 89.67586055015539159 ) ) ; -#533 = EDGE_CURVE ( 'NONE', #20299, #20347, #26950, .T. ) ; -#534 = EDGE_LOOP ( 'NONE', ( #25263, #15716, #6651, #33569 ) ) ; -#535 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#536 = EDGE_CURVE ( 'NONE', #8692, #10027, #22362, .T. ) ; -#537 = EDGE_CURVE ( 'NONE', #19831, #17075, #39384, .T. ) ; -#538 = DIRECTION ( 'NONE', ( -0.0005884949961193586092, 0.2249510543439039167, -0.9743698870671270162 ) ) ; -#539 = ORIENTED_EDGE ( 'NONE', *, *, #6576, .F. ) ; -#540 = PLANE ( 'NONE', #5303 ) ; -#541 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12398, #28162, #8952, #31212, #30415, #21211, #15081, #33866, #15278, #24700, #24904, #21627, #34067, #6257, #131, #12593, #22227, #22022, #3983, #35251, #32024, #4179 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), - ( 5.594315114139762021E-17, 0.001939686057088096547, 0.002909529085632069686, 0.003879372114176043041, 0.005819058171264075187, 0.007758744228352106899, 0.009698430285440139478, 0.01066827331398415533, 0.01163811634252817293, 0.01357780239961627056, 0.01551748845670436645 ), - .UNSPECIFIED. ) ; -#542 = FACE_OUTER_BOUND ( 'NONE', #30780, .T. ) ; -#543 = CARTESIAN_POINT ( 'NONE', ( 16.00202263909956457, 151.2883905618018048, 97.64994197610543836 ) ) ; -#544 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999901590, 132.9679238121798619, 90.36185680190951075 ) ) ; -#545 = CARTESIAN_POINT ( 'NONE', ( 20.96422822264385033, 158.7934676277431265, 96.30062105744464418 ) ) ; -#546 = ORIENTED_EDGE ( 'NONE', *, *, #2807, .F. ) ; -#547 = LINE ( 'NONE', #31856, #21347 ) ; -#548 = AXIS2_PLACEMENT_3D ( 'NONE', #23737, #20660, #33122 ) ; -#549 = CARTESIAN_POINT ( 'NONE', ( 0.7260690469630617372, 189.0066063905518092, 103.6849890980020206 ) ) ; -#550 = CARTESIAN_POINT ( 'NONE', ( 20.50029379647860495, 189.2267361095769331, 103.8400967508667492 ) ) ; -#551 = AXIS2_PLACEMENT_3D ( 'NONE', #36766, #21651, #5891 ) ; -#552 = CARTESIAN_POINT ( 'NONE', ( -26.00132979581089288, 118.1159538331455252, 87.28348844368876769 ) ) ; -#553 = AXIS2_PLACEMENT_3D ( 'NONE', #5804, #28106, #9484 ) ; -#554 = LINE ( 'NONE', #19154, #5533 ) ; -#555 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923101038, 127.7447309815698873, 89.13696229017300254 ) ) ; -#556 = LINE ( 'NONE', #13642, #33299 ) ; -#557 = CARTESIAN_POINT ( 'NONE', ( 12.63829599803258041, 181.4182578506842560, 104.2633634328516905 ) ) ; -#558 = EDGE_CURVE ( 'NONE', #23378, #27940, #11387, .T. ) ; -#559 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825957230524654, 0.0005734119015252938864 ) ) ; -#560 = ORIENTED_EDGE ( 'NONE', *, *, #39768, .F. ) ; -#561 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20914, #2315, #27676, #5778 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0009062002059386310747, 0.0009636043971113295633 ), - .UNSPECIFIED. ) ; -#562 = CARTESIAN_POINT ( 'NONE', ( -19.00260255556003131, 149.1275189729910267, 180.7566863177478638 ) ) ; -#563 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971575394 ) ) ; -#564 = ORIENTED_EDGE ( 'NONE', *, *, #4497, .F. ) ; -#565 = CARTESIAN_POINT ( 'NONE', ( 21.46292357967359976, 116.1138482125577838, 87.75460328546795097 ) ) ; -#566 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; -#567 = ADVANCED_FACE ( 'NONE', ( #17908 ), #5242, .F. ) ; -#568 = CARTESIAN_POINT ( 'NONE', ( -25.02200516277000375, 130.2733187283999996, 91.28345564459999650 ) ) ; -#569 = CARTESIAN_POINT ( 'NONE', ( 36.06505882652250250, 192.7068426039909923, 106.3467840092589967 ) ) ; -#570 = CARTESIAN_POINT ( 'NONE', ( 3.931141971386352463, 143.6293547669063173, 95.48310455860253398 ) ) ; -#571 = CARTESIAN_POINT ( 'NONE', ( 35.47021744578000124, 192.2039990837999994, 107.0420568499000069 ) ) ; -#572 = VERTEX_POINT ( 'NONE', #8124 ) ; -#574 = AXIS2_PLACEMENT_3D ( 'NONE', #8141, #27180, #13869 ) ; -#573 = LINE ( 'NONE', #37996, #19898 ) ; -#575 = EDGE_CURVE ( 'NONE', #24174, #13536, #14673, .T. ) ; -#576 = CARTESIAN_POINT ( 'NONE', ( 20.04381349576867066, 126.7748930407473722, 91.94483827613792926 ) ) ; -#577 = EDGE_CURVE ( 'NONE', #29516, #37526, #38988, .T. ) ; -#578 = AXIS2_PLACEMENT_3D ( 'NONE', #24274, #40378, #36718 ) ; -#579 = CARTESIAN_POINT ( 'NONE', ( -23.35979081385350398, 130.6186769843367017, 90.16484899944724418 ) ) ; -#580 = ORIENTED_EDGE ( 'NONE', *, *, #14785, .F. ) ; -#581 = CARTESIAN_POINT ( 'NONE', ( -17.34531841520229634, 127.5687170461390565, 172.4105396402263466 ) ) ; -#582 = AXIS2_PLACEMENT_3D ( 'NONE', #18653, #9286, #39940 ) ; -#583 = EDGE_CURVE ( 'NONE', #22996, #1259, #2416, .T. ) ; -#584 = AXIS2_PLACEMENT_3D ( 'NONE', #36881, #14813, #24230 ) ; -#585 = VERTEX_POINT ( 'NONE', #17710 ) ; -#586 = ADVANCED_FACE ( 'NONE', ( #4642 ), #33574, .T. ) ; -#587 = CARTESIAN_POINT ( 'NONE', ( 20.00000279695219874, 118.8155797008581374, 87.25566994753728522 ) ) ; -#588 = CARTESIAN_POINT ( 'NONE', ( -3.169796603587565986, 128.7385212851464757, 89.37646504162516692 ) ) ; -#589 = CARTESIAN_POINT ( 'NONE', ( 38.22623376675434059, 118.8155667128057615, 90.24469678293085906 ) ) ; -#590 = CARTESIAN_POINT ( 'NONE', ( 27.30442999513742919, 110.6131156702000027, 88.75129337409590846 ) ) ; -#591 = DIRECTION ( 'NONE', ( -0.0001358647734255411942, -0.9743700647848254626, -0.2249510133161850278 ) ) ; -#592 = CARTESIAN_POINT ( 'NONE', ( -35.69795641737000125, 111.2706431035999941, 87.53934500879000780 ) ) ; -#593 = CYLINDRICAL_SURFACE ( 'NONE', #15667, 2.000000000000011546 ) ; -#594 = DIRECTION ( 'NONE', ( -0.0005884949961246487568, 0.2249510543439061372, -0.9743698870671263501 ) ) ; -#595 = EDGE_LOOP ( 'NONE', ( #8672, #24429, #20056, #22752 ) ) ; -#596 = CARTESIAN_POINT ( 'NONE', ( 23.72263521211007031, 115.9590670243358232, 152.9217693425221682 ) ) ; -#597 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34553, #4704, #4086, #7164 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#598 = CARTESIAN_POINT ( 'NONE', ( 18.99695336057541795, 148.4229678448664060, 183.7014091461406622 ) ) ; -#599 = CARTESIAN_POINT ( 'NONE', ( 21.25891437287570440, 136.8714408223384567, 91.75249562560091476 ) ) ; -#600 = EDGE_LOOP ( 'NONE', ( #32369, #12113, #22331, #7773, #33819, #36917, #10893, #22939, #13959, #36294, #16984, #37697, #23156, #9020, #9923, #6852, #1017, #26161, #30987, #37503, #17151, #36365, #24213, #3389, #26066, #22005, #27886, #13770, #25460 ) ) ; -#601 = CARTESIAN_POINT ( 'NONE', ( -37.62510914575000953, 190.9293338957000117, 103.6056530092999992 ) ) ; -#602 = ORIENTED_EDGE ( 'NONE', *, *, #7262, .F. ) ; -#603 = CARTESIAN_POINT ( 'NONE', ( 13.81047920904208226, 150.0053730344457676, 180.1700289459587907 ) ) ; -#604 = VERTEX_POINT ( 'NONE', #17097 ) ; -#605 = VECTOR ( 'NONE', #11678, 1000.000000000000227 ) ; -#606 = DIRECTION ( 'NONE', ( -0.0005884949961249829080, 0.2249510543439062205, -0.9743698870671264611 ) ) ; -#607 = VECTOR ( 'NONE', #20837, 1000.000000000000114 ) ; -#608 = AXIS2_PLACEMENT_3D ( 'NONE', #16548, #29043, #35344 ) ; -#609 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20952, #17247, #14219, #11334 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#610 = AXIS2_PLACEMENT_3D ( 'NONE', #5756, #18407, #40091 ) ; -#611 = CARTESIAN_POINT ( 'NONE', ( -16.04896084364859021, 152.7188673256511890, 181.6067879991456664 ) ) ; -#612 = CARTESIAN_POINT ( 'NONE', ( -15.83179463202705861, 160.1070185153170087, 99.53409605412225858 ) ) ; -#613 = CARTESIAN_POINT ( 'NONE', ( 5.995984845311999933, 151.9652147202999970, 28.07991271570000080 ) ) ; -#614 = CARTESIAN_POINT ( 'NONE', ( -2.996716101987999981, 209.7033295502000101, 72.92379390556999397 ) ) ; -#615 = CARTESIAN_POINT ( 'NONE', ( 38.31102854718000117, 118.7287393711000050, 90.10199935446000552 ) ) ; -#616 = ORIENTED_EDGE ( 'NONE', *, *, #10432, .T. ) ; -#617 = EDGE_CURVE ( 'NONE', #349, #13580, #36535, .T. ) ; -#618 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16049, #714, #19708, #10139, #4166, #1114, #32210, #12798 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 4 ), - ( 0.000000000000000000, 0.0003628416619586385971, 0.0007256833239172771942, 0.001451366647834552437 ), - .UNSPECIFIED. ) ; -#619 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989946348, -0.1373964268091547314 ) ) ; -#620 = ADVANCED_FACE ( 'NONE', ( #7707 ), #31317, .T. ) ; -#621 = CARTESIAN_POINT ( 'NONE', ( 19.70892818629356569, 149.4293184409359014, 181.7720440811204412 ) ) ; -#622 = CARTESIAN_POINT ( 'NONE', ( -3.668404234881370574, 185.3449489777972019, 105.0111528741126676 ) ) ; -#623 = EDGE_CURVE ( 'NONE', #30537, #14528, #38910, .T. ) ; -#624 = EDGE_CURVE ( 'NONE', #28651, #36967, #2290, .T. ) ; -#625 = CARTESIAN_POINT ( 'NONE', ( 35.80519753165925323, 112.4664341929300093, 89.99614522430350405 ) ) ; -#626 = VERTEX_POINT ( 'NONE', #40290 ) ; -#627 = ORIENTED_EDGE ( 'NONE', *, *, #36499, .T. ) ; -#628 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #36202, #18194, #20675, #24166, #5118, #1665, #30282 ), - ( #20457, #14554, #8824, #39465, #5747, #36622, #30089 ), - ( #23959, #23750, #11683, #36417, #33134, #8423, #2078 ), - ( #2278, #29887, #14150, #26623, #32929, #4926, #20881 ), - ( #21088, #5329, #17995, #39064, #8206, #33338, #17787 ), - ( #26825, #14760, #27244, #36820, #39675, #39879, #11075 ), - ( #33744, #39271, #11271, #33536, #23540, #30499, #8623 ), - ( #2486, #21299, #17383, #35990, #27457, #11890, #24374 ), - ( #7995, #204, #19001, #9621, #12677, #31490, #15159 ), - ( #15547, #34338, #3064, #25170, #27646, #12474, #28040 ), - ( #18785, #6731, #2873, #15351, #34520, #34728, #403 ), - ( #3264, #21897, #37818, #27846, #24774, #5942, #30700 ), - ( #3457, #12288, #37228, #12, #18397, #34143, #28426 ), - ( #40078, #30900, #40276, #24973, #2695, #6335, #12089 ), - ( #37426, #24575, #28237, #6528, #15931, #9226, #31290 ), - ( #37030, #21698, #6137, #31097, #9422, #15737, #37623 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 3, 4 ), - ( 3.467946620240000122E-12, 0.01041366078304999977, 0.02083069311681999894, 0.04166475778438000210, 0.08333288711950000149, 0.1250010164545999891, 0.1666691457896999906, 0.2500022395825000077, 0.3333353333754000003, 0.4166684271682000174, 0.5000015209610999545, 0.6666677085469000508, 0.8333338961324999739, 0.9999999601867000099 ), - ( 0.1894117542789000019, 0.8184388841219000232, 0.8247291554203299846 ), - .UNSPECIFIED. ) ; -#629 = VERTEX_POINT ( 'NONE', #2880 ) ; -#630 = DIRECTION ( 'NONE', ( 0.0006039748319383109534, 1.233022124494217175E-14, 0.9999998176071845934 ) ) ; -#631 = EDGE_CURVE ( 'NONE', #17579, #24155, #37040, .T. ) ; -#632 = DIRECTION ( 'NONE', ( -2.449021403759176867E-15, 0.9743700557921586292, 0.2249510932971564847 ) ) ; -#633 = ORIENTED_EDGE ( 'NONE', *, *, #16949, .T. ) ; -#634 = CARTESIAN_POINT ( 'NONE', ( 0.5444273898015001834, 211.0000000000005116, 73.55817535311000199 ) ) ; -#635 = EDGE_CURVE ( 'NONE', #16566, #34518, #24587, .T. ) ; -#636 = VECTOR ( 'NONE', #11508, 1000.000000000000227 ) ; -#637 = CARTESIAN_POINT ( 'NONE', ( -32.36931359533516428, 158.3297460257155649, 186.4994859931237841 ) ) ; -#638 = DIRECTION ( 'NONE', ( 1.387778780753341559E-14, -0.9743700557921585181, -0.2249510932971562904 ) ) ; -#639 = CARTESIAN_POINT ( 'NONE', ( -35.62084758004493068, 207.7152267789312816, 77.23343464428440086 ) ) ; -#640 = CARTESIAN_POINT ( 'NONE', ( 114.5937281169188253, 50.54601443099469549, 171.8750556891886276 ) ) ; -#641 = EDGE_LOOP ( 'NONE', ( #33141, #841, #4462, #16740 ) ) ; -#642 = CARTESIAN_POINT ( 'NONE', ( -31.91335489949009130, 137.9985878559502623, 92.04483278691883186 ) ) ; -#643 = AXIS2_PLACEMENT_3D ( 'NONE', #17508, #17713, #30414 ) ; -#644 = AXIS2_PLACEMENT_3D ( 'NONE', #34495, #25543, #6499 ) ; -#645 = VERTEX_POINT ( 'NONE', #5953 ) ; -#646 = CARTESIAN_POINT ( 'NONE', ( 19.98261053240618779, 208.0209216810735882, 76.90620748650613336 ) ) ; -#647 = CONICAL_SURFACE ( 'NONE', #22118, 5.500000000083335117, 0.7853981634365208020 ) ; -#648 = FACE_OUTER_BOUND ( 'NONE', #15019, .T. ) ; -#649 = ADVANCED_FACE ( 'NONE', ( #26764 ), #8358, .F. ) ; -#650 = VERTEX_POINT ( 'NONE', #36561 ) ; -#651 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971542088 ) ) ; -#652 = CARTESIAN_POINT ( 'NONE', ( -22.49999922076347758, 151.9675441756866690, 94.75098345857674076 ) ) ; -#653 = PLANE ( 'NONE', #18143 ) ; -#654 = VERTEX_POINT ( 'NONE', #39210 ) ; -#655 = ORIENTED_EDGE ( 'NONE', *, *, #22684, .F. ) ; -#656 = CARTESIAN_POINT ( 'NONE', ( -23.02059183176825741, 214.0904033191889084, 73.07235108223721909 ) ) ; -#657 = CARTESIAN_POINT ( 'NONE', ( 13.46793942647703801, 157.6314446051065943, 99.11578051374280562 ) ) ; -#658 = ORIENTED_EDGE ( 'NONE', *, *, #19905, .F. ) ; -#659 = CARTESIAN_POINT ( 'NONE', ( -26.01326056281665089, 211.0902258159713085, 76.07393268928584007 ) ) ; -#660 = LINE ( 'NONE', #24831, #1306 ) ; -#661 = CARTESIAN_POINT ( 'NONE', ( -25.87425499709999954, 120.4547996877000031, 90.43191455909000354 ) ) ; -#662 = VERTEX_POINT ( 'NONE', #36142 ) ; -#663 = CARTESIAN_POINT ( 'NONE', ( 13.85666887114530077, 150.2803490827782298, 180.5372210466468061 ) ) ; -#664 = CARTESIAN_POINT ( 'NONE', ( -38.04444379205944671, 118.4867705051282627, 87.71485106921780073 ) ) ; -#665 = CARTESIAN_POINT ( 'NONE', ( 35.84002668644952649, 165.7685787144644678, 188.2286130183017008 ) ) ; -#666 = CONICAL_SURFACE ( 'NONE', #37250, 5.249999999955947239, 0.7853981633862021638 ) ; -#667 = CONICAL_SURFACE ( 'NONE', #25502, 22.50000000000906653, 0.7853981633972855203 ) ; -#668 = ORIENTED_EDGE ( 'NONE', *, *, #4798, .F. ) ; -#669 = CARTESIAN_POINT ( 'NONE', ( 25.50032466477000170, 120.2211198582999998, 89.96472687520000022 ) ) ; -#670 = ADVANCED_FACE ( 'NONE', ( #14702 ), #13874, .T. ) ; -#671 = CIRCLE ( 'NONE', #28105, 2.999999999962116526 ) ; -#672 = CARTESIAN_POINT ( 'NONE', ( -8.473032270639919261, 161.1929806888288397, 98.41182820864784730 ) ) ; -#673 = CARTESIAN_POINT ( 'NONE', ( 23.37116632637657077, 177.1196686977561399, 103.6090577849978445 ) ) ; -#674 = EDGE_CURVE ( 'NONE', #16466, #19730, #8144, .T. ) ; -#675 = EDGE_CURVE ( 'NONE', #38540, #14950, #7938, .T. ) ; -#677 = CARTESIAN_POINT ( 'NONE', ( -9.889664841446476728, 153.3280908470186148, 95.05747415439600445 ) ) ; -#676 = CARTESIAN_POINT ( 'NONE', ( 20.00176513869433137, 118.9456690639568990, 90.18052439326532976 ) ) ; -#678 = FACE_OUTER_BOUND ( 'NONE', #24613, .T. ) ; -#679 = ORIENTED_EDGE ( 'NONE', *, *, #3309, .F. ) ; -#680 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#681 = EDGE_CURVE ( 'NONE', #31532, #35965, #31669, .T. ) ; -#682 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971575672 ) ) ; -#683 = ORIENTED_EDGE ( 'NONE', *, *, #38650, .T. ) ; -#684 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #20340, #5005, #1534, #36078 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.441567807838093351, 5.011884969131253698 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8048507809858624906, 0.8048507809858624906, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#685 = ORIENTED_EDGE ( 'NONE', *, *, #2582, .T. ) ; -#686 = CARTESIAN_POINT ( 'NONE', ( -13.47069009286630603, 153.6544384493914492, 96.33233530911239484 ) ) ; -#687 = EDGE_CURVE ( 'NONE', #38882, #38531, #37490, .T. ) ; -#688 = CARTESIAN_POINT ( 'NONE', ( -46.14362517609952619, 125.4997054666571472, 91.73359335677182003 ) ) ; -#689 = CARTESIAN_POINT ( 'NONE', ( -43.57128771414367918, 121.9172130293124212, 88.19101713714755419 ) ) ; -#690 = ORIENTED_EDGE ( 'NONE', *, *, #38385, .T. ) ; -#691 = EDGE_LOOP ( 'NONE', ( #31999, #16217, #22925, #7696 ) ) ; -#692 = CARTESIAN_POINT ( 'NONE', ( -29.78271044658185218, 126.9386829446179377, 89.49016549083705740 ) ) ; -#693 = DIRECTION ( 'NONE', ( -0.7933533411653341805, -0.5931840316264885837, -0.1368326740407639630 ) ) ; -#694 = CARTESIAN_POINT ( 'NONE', ( 0.1948172102453834542, 3.621363614364748935E-12, 322.5584319246983682 ) ) ; -#695 = EDGE_CURVE ( 'NONE', #10631, #6854, #27713, .T. ) ; -#696 = ORIENTED_EDGE ( 'NONE', *, *, #38303, .T. ) ; -#697 = LINE ( 'NONE', #31592, #13485 ) ; -#698 = CIRCLE ( 'NONE', #1361, 2.000000000000011546 ) ; -#699 = ORIENTED_EDGE ( 'NONE', *, *, #30882, .T. ) ; -#700 = CARTESIAN_POINT ( 'NONE', ( -37.79509714950135901, 117.7323670804173474, 89.71823316337903975 ) ) ; -#701 = AXIS2_PLACEMENT_3D ( 'NONE', #25935, #961, #23055 ) ; -#702 = CARTESIAN_POINT ( 'NONE', ( -28.46737701140906651, 131.0177979894622808, 89.91795673199465000 ) ) ; -#703 = EDGE_LOOP ( 'NONE', ( #2605, #10511, #16063, #38102 ) ) ; -#704 = CARTESIAN_POINT ( 'NONE', ( 20.00176513865781303, 118.9456690639568990, 90.18052439326535819 ) ) ; -#705 = CARTESIAN_POINT ( 'NONE', ( -1.744169957438999941, 188.5358409586000050, 106.4260139966000054 ) ) ; -#706 = CARTESIAN_POINT ( 'NONE', ( 21.72592390767327686, 135.1711755393868941, 93.92543662762206225 ) ) ; -#707 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35200, #38286, #13962, #32763, #19671, #7204, #38890, #1070, #4534, #26040, #22571, #10698, #1690, #35803, #19865, #14178, #13555, #38679 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000370259, 0.1875000000000689726, 0.2187500000000849598, 0.2500000000001009193, 0.5000000000000535127, 0.6250000000000375255, 0.6875000000000295319, 0.7187500000000210942, 0.7500000000000125455, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#708 = EDGE_LOOP ( 'NONE', ( #22990, #9936 ) ) ; -#709 = CARTESIAN_POINT ( 'NONE', ( 2.781572041167127640, 209.6623637130746545, 73.22349110528780614 ) ) ; -#710 = ORIENTED_EDGE ( 'NONE', *, *, #33726, .T. ) ; -#711 = VERTEX_POINT ( 'NONE', #27183 ) ; -#712 = DIRECTION ( 'NONE', ( -0.0005884949961263054178, 0.2249510543439064703, -0.9743698870671262391 ) ) ; -#713 = CARTESIAN_POINT ( 'NONE', ( -13.78572884413053323, 125.0559276006693921, 174.4126573023246465 ) ) ; -#714 = CARTESIAN_POINT ( 'NONE', ( 19.39902400086316092, 126.2415996759917505, 175.5115058955111351 ) ) ; -#715 = CARTESIAN_POINT ( 'NONE', ( 21.71477686248909933, 151.2531533811763325, 202.9610808053989217 ) ) ; -#716 = ORIENTED_EDGE ( 'NONE', *, *, #32049, .F. ) ; -#717 = FACE_OUTER_BOUND ( 'NONE', #37574, .T. ) ; -#718 = ADVANCED_FACE ( 'NONE', ( #26564 ), #17730, .F. ) ; -#719 = CONICAL_SURFACE ( 'NONE', #37390, 2.499999999965141662, 0.7853981634008656565 ) ; -#720 = ADVANCED_FACE ( 'NONE', ( #11020 ), #19842, .F. ) ; -#721 = CARTESIAN_POINT ( 'NONE', ( -36.07808061111000342, 112.9804154865999948, 89.64438889024999924 ) ) ; -#722 = VECTOR ( 'NONE', #9071, 1000.000000000000114 ) ; -#723 = VERTEX_POINT ( 'NONE', #29424 ) ; -#724 = AXIS2_PLACEMENT_3D ( 'NONE', #4283, #32713, #19425 ) ; -#725 = CARTESIAN_POINT ( 'NONE', ( -22.46513725335000089, 140.5903658354843344, 152.9217693939943388 ) ) ; -#726 = VERTEX_POINT ( 'NONE', #1395 ) ; -#727 = DIRECTION ( 'NONE', ( 0.0005884949961257676535, -0.2249510543438813792, 0.9743698870671319012 ) ) ; -#728 = AXIS2_PLACEMENT_3D ( 'NONE', #21683, #34318, #34122 ) ; -#729 = CARTESIAN_POINT ( 'NONE', ( -26.91923286534074933, 123.7406455964028567, 88.23695837583139223 ) ) ; -#730 = CARTESIAN_POINT ( 'NONE', ( 23.36598296845494360, 177.6947003474286930, 100.7482006756413284 ) ) ; -#731 = FACE_BOUND ( 'NONE', #27312, .T. ) ; -#732 = EDGE_LOOP ( 'NONE', ( #34050, #35652, #23725, #5148 ) ) ; -#733 = ORIENTED_EDGE ( 'NONE', *, *, #4734, .T. ) ; -#734 = VERTEX_POINT ( 'NONE', #8562 ) ; -#735 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#736 = CARTESIAN_POINT ( 'NONE', ( 1.875840786765911039, 189.4897504644060575, 105.8774097022063643 ) ) ; -#737 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971542088 ) ) ; -#738 = CARTESIAN_POINT ( 'NONE', ( -25.75976792568999940, 210.3999399800999868, 75.82533471885000154 ) ) ; -#739 = ORIENTED_EDGE ( 'NONE', *, *, #12362, .T. ) ; -#740 = CARTESIAN_POINT ( 'NONE', ( -44.78294139341442559, 188.5432348633073047, 105.7511144607040876 ) ) ; -#741 = CARTESIAN_POINT ( 'NONE', ( 36.18941359597000940, 191.5903931521000061, 103.9682770481999938 ) ) ; -#742 = ORIENTED_EDGE ( 'NONE', *, *, #25799, .F. ) ; -#743 = DIRECTION ( 'NONE', ( 0.0005884949961251158311, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#744 = DIRECTION ( 'NONE', ( -0.0005884949961251545372, 0.2249510543439063315, -0.9743698870671262391 ) ) ; -#745 = ORIENTED_EDGE ( 'NONE', *, *, #12498, .F. ) ; -#746 = LINE ( 'NONE', #38170, #20322 ) ; -#747 = DIRECTION ( 'NONE', ( 0.0005884949949860971558, -0.2249510543438488497, 0.9743698870671402279 ) ) ; -#748 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825867343808962, 0.0005734119035994554754 ) ) ; -#749 = AXIS2_PLACEMENT_3D ( 'NONE', #27685, #25015, #24617 ) ; -#750 = CARTESIAN_POINT ( 'NONE', ( -25.92937993143591413, 117.3625828949747785, 90.28344553495060154 ) ) ; -#751 = CARTESIAN_POINT ( 'NONE', ( 5.695423016759590951, 134.9205841030388626, 90.79835259162844352 ) ) ; -#752 = EDGE_LOOP ( 'NONE', ( #18976, #37690, #34170, #524 ) ) ; -#753 = CARTESIAN_POINT ( 'NONE', ( -14.78542059478467330, 183.3574060367851359, 102.5063981592711571 ) ) ; -#754 = CIRCLE ( 'NONE', #35338, 2.500000000003740563 ) ; -#755 = CARTESIAN_POINT ( 'NONE', ( 1.038435199333894943, 189.0574318112943217, 103.7007315583379210 ) ) ; -#756 = CARTESIAN_POINT ( 'NONE', ( -1.198528310954169340, 138.2140671179444666, 181.3494557296553182 ) ) ; -#757 = ADVANCED_FACE ( 'NONE', ( #33478 ), #30965, .T. ) ; -#758 = CARTESIAN_POINT ( 'NONE', ( 12.63825265581525059, 130.2405143122917366, 92.64486568747496165 ) ) ; -#759 = CARTESIAN_POINT ( 'NONE', ( 5.668109638568658681, 126.1283174451533711, 91.84742690372624452 ) ) ; -#760 = CARTESIAN_POINT ( 'NONE', ( 20.45340480371016767, 105.2139170030256281, 87.75543103923976673 ) ) ; -#761 = CARTESIAN_POINT ( 'NONE', ( -43.16067970895235106, 137.0136042933273472, 338.0369414682852494 ) ) ; -#762 = LINE ( 'NONE', #13252, #15106 ) ; -#763 = EDGE_CURVE ( 'NONE', #12730, #23821, #24372, .T. ) ; -#764 = CARTESIAN_POINT ( 'NONE', ( -20.49851155431899841, 191.4731498523730693, 106.4361349872459641 ) ) ; -#765 = DIRECTION ( 'NONE', ( 5.259792451068736282E-12, 0.9743043966640311249, 0.2252353050503814180 ) ) ; -#766 = ORIENTED_EDGE ( 'NONE', *, *, #14407, .F. ) ; -#767 = ADVANCED_FACE ( 'NONE', ( #36360, #1809 ), #32684, .F. ) ; -#768 = EDGE_CURVE ( 'NONE', #10259, #4372, #17894, .T. ) ; -#769 = EDGE_CURVE ( 'NONE', #17683, #5306, #24325, .T. ) ; -#770 = DIRECTION ( 'NONE', ( -0.0004161288024551938573, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#771 = FACE_OUTER_BOUND ( 'NONE', #3554, .T. ) ; -#772 = EDGE_LOOP ( 'NONE', ( #6568, #9921, #33003 ) ) ; -#773 = CARTESIAN_POINT ( 'NONE', ( 43.53560975226982777, 121.3918131887250524, 90.46069063649885322 ) ) ; -#774 = CARTESIAN_POINT ( 'NONE', ( -25.99205882618559116, 191.8000695062693524, 103.9294257625771110 ) ) ; -#775 = FACE_OUTER_BOUND ( 'NONE', #29670, .T. ) ; -#776 = CARTESIAN_POINT ( 'NONE', ( 36.19056359025920955, 192.0351720573459886, 106.4168301014839955 ) ) ; -#777 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#778 = DIRECTION ( 'NONE', ( -0.0005884949961246307591, 0.2249510543439059429, -0.9743698870671264611 ) ) ; -#779 = ORIENTED_EDGE ( 'NONE', *, *, #37023, .T. ) ; -#780 = ORIENTED_EDGE ( 'NONE', *, *, #13425, .T. ) ; -#781 = CIRCLE ( 'NONE', #30831, 2.000000000000011546 ) ; -#782 = PLANE ( 'NONE', #14722 ) ; -#783 = CIRCLE ( 'NONE', #15190, 47.50000000000481037 ) ; -#784 = CARTESIAN_POINT ( 'NONE', ( 35.91066480312174036, 115.4548871365115161, 87.24609515033561991 ) ) ; -#785 = DIRECTION ( 'NONE', ( -0.0005884949961257719903, 0.2249510543439054711, -0.9743698870671265722 ) ) ; -#786 = ORIENTED_EDGE ( 'NONE', *, *, #24400, .F. ) ; -#787 = DIRECTION ( 'NONE', ( 0.9914448496661263377, 0.1271951663094869900, 0.02930016617724658101 ) ) ; -#788 = ORIENTED_EDGE ( 'NONE', *, *, #5292, .F. ) ; -#789 = FACE_OUTER_BOUND ( 'NONE', #21421, .T. ) ; -#790 = FACE_OUTER_BOUND ( 'NONE', #32863, .T. ) ; -#791 = FACE_OUTER_BOUND ( 'NONE', #38364, .T. ) ; -#792 = LINE ( 'NONE', #16138, #25333 ) ; -#793 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; -#794 = CARTESIAN_POINT ( 'NONE', ( -30.06407215524082943, 177.1126099298436714, 103.6397089757105192 ) ) ; -#795 = CARTESIAN_POINT ( 'NONE', ( 44.93984957629947274, 145.3877245808612031, 285.0133094889154677 ) ) ; -#796 = VERTEX_POINT ( 'NONE', #27783 ) ; -#797 = CARTESIAN_POINT ( 'NONE', ( 15.50147165697079465, 137.9484461010407870, 94.05722786790197176 ) ) ; -#798 = CARTESIAN_POINT ( 'NONE', ( -30.07079256068832152, 177.3114379493538308, 101.0139105263539818 ) ) ; -#799 = CARTESIAN_POINT ( 'NONE', ( 6.034204648359921208, 177.7921235470974466, 100.6958268401488539 ) ) ; -#800 = ORIENTED_EDGE ( 'NONE', *, *, #36871, .F. ) ; -#801 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#802 = VERTEX_POINT ( 'NONE', #17934 ) ; -#803 = ORIENTED_EDGE ( 'NONE', *, *, #23864, .F. ) ; -#804 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#805 = ORIENTED_EDGE ( 'NONE', *, *, #34404, .F. ) ; -#806 = AXIS2_PLACEMENT_3D ( 'NONE', #907, #12794, #34828 ) ; -#807 = EDGE_CURVE ( 'NONE', #5625, #8723, #8793, .T. ) ; -#808 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6625, #35021, #7232, #9723 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.009024888469274735397 ), - .UNSPECIFIED. ) ; -#809 = CARTESIAN_POINT ( 'NONE', ( 13.85658554618334293, 150.4134353313125985, 179.9607612785380581 ) ) ; -#810 = DIRECTION ( 'NONE', ( -0.0005559617639789404386, 0.3907311284894095516, -0.9205046855589108512 ) ) ; -#811 = EDGE_CURVE ( 'NONE', #35987, #5120, #12421, .T. ) ; -#812 = ADVANCED_FACE ( 'NONE', ( #25116 ), #35503, .F. ) ; -#813 = CARTESIAN_POINT ( 'NONE', ( -16.78108589029219644, 152.4450255530118739, 181.9531753362896325 ) ) ; -#814 = EDGE_CURVE ( 'NONE', #4354, #18466, #16429, .T. ) ; -#815 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 0.000000000000000000 ) ) ; -#816 = EDGE_CURVE ( 'NONE', #1746, #24020, #6276, .T. ) ; -#817 = LINE ( 'NONE', #23106, #37997 ) ; -#818 = CARTESIAN_POINT ( 'NONE', ( -2.458395782143000030, 209.7031701907000070, 73.44000010378999832 ) ) ; -#819 = CARTESIAN_POINT ( 'NONE', ( 38.30818804999999827, 118.7293481547999932, 90.10350194488999875 ) ) ; -#820 = ORIENTED_EDGE ( 'NONE', *, *, #31967, .F. ) ; -#821 = CARTESIAN_POINT ( 'NONE', ( -12.63662704360879729, 174.7913534257970696, 102.5800794996181367 ) ) ; -#822 = LINE ( 'NONE', #34545, #16252 ) ; -#823 = DIRECTION ( 'NONE', ( 4.799828776013770619E-10, -0.9743700559000059158, -0.2249510928300180457 ) ) ; -#825 = ORIENTED_EDGE ( 'NONE', *, *, #583, .F. ) ; -#824 = CARTESIAN_POINT ( 'NONE', ( -20.50031106545476689, 193.6217541318450799, 103.8231728181809785 ) ) ; -#826 = ORIENTED_EDGE ( 'NONE', *, *, #22963, .T. ) ; -#827 = ORIENTED_EDGE ( 'NONE', *, *, #12133, .T. ) ; -#828 = CARTESIAN_POINT ( 'NONE', ( 25.86791385122951681, 191.4731423800313337, 104.0134104725774193 ) ) ; -#829 = CARTESIAN_POINT ( 'NONE', ( 21.57097971548348880, 115.4710243950989224, 87.25475596080617890 ) ) ; -#830 = CARTESIAN_POINT ( 'NONE', ( 5.666417568496214585, 124.0425428568022710, 91.06625163005953993 ) ) ; -#831 = AXIS2_PLACEMENT_3D ( 'NONE', #17862, #30364, #91 ) ; -#832 = ORIENTED_EDGE ( 'NONE', *, *, #15867, .F. ) ; -#833 = CYLINDRICAL_SURFACE ( 'NONE', #36116, 5.000000000000007994 ) ; -#834 = AXIS2_PLACEMENT_3D ( 'NONE', #11891, #26826, #8827 ) ; -#835 = CARTESIAN_POINT ( 'NONE', ( -38.36863212317000205, 118.8178900763000030, 90.09766773322999711 ) ) ; -#836 = CARTESIAN_POINT ( 'NONE', ( -38.37945905963000115, 118.8393537648999967, 87.72095146696000256 ) ) ; -#837 = FACE_OUTER_BOUND ( 'NONE', #10537, .T. ) ; -#838 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971557076 ) ) ; -#839 = ORIENTED_EDGE ( 'NONE', *, *, #34963, .F. ) ; -#840 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; -#841 = ORIENTED_EDGE ( 'NONE', *, *, #5013, .T. ) ; -#842 = FACE_OUTER_BOUND ( 'NONE', #38123, .T. ) ; -#843 = FACE_OUTER_BOUND ( 'NONE', #732, .T. ) ; -#844 = VERTEX_POINT ( 'NONE', #15684 ) ; -#845 = CARTESIAN_POINT ( 'NONE', ( -37.62305393521922525, 212.3970732061812896, 73.58122755549422322 ) ) ; -#846 = DIRECTION ( 'NONE', ( 0.0005884949961292186690, -0.2249510543439060262, 0.9743698870671263501 ) ) ; -#847 = DIRECTION ( 'NONE', ( 0.7933535325932937754, -0.5931614258681804364, -0.1369295263402622864 ) ) ; -#848 = EDGE_CURVE ( 'NONE', #38719, #14771, #30439, .T. ) ; -#849 = EDGE_CURVE ( 'NONE', #25128, #21097, #31129, .T. ) ; -#850 = ORIENTED_EDGE ( 'NONE', *, *, #16275, .F. ) ; -#851 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#852 = LINE ( 'NONE', #7191, #10889 ) ; -#853 = VERTEX_POINT ( 'NONE', #15297 ) ; -#854 = EDGE_CURVE ( 'NONE', #25248, #12222, #13478, .T. ) ; -#855 = FACE_OUTER_BOUND ( 'NONE', #40097, .T. ) ; -#856 = PLANE ( 'NONE', #15052 ) ; -#857 = VECTOR ( 'NONE', #17204, 1000.000000000000000 ) ; -#858 = EDGE_CURVE ( 'NONE', #14434, #13079, #8104, .T. ) ; -#859 = ORIENTED_EDGE ( 'NONE', *, *, #24577, .T. ) ; -#860 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25539, #38388, #3827, #9993 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#861 = CONICAL_SURFACE ( 'NONE', #34165, 4.999999999930255790, 0.7853981633830142695 ) ; -#862 = CARTESIAN_POINT ( 'NONE', ( 40.54493956983929337, 220.4002260892000038, 73.03401595479815001 ) ) ; -#863 = EDGE_CURVE ( 'NONE', #23346, #11066, #33681, .T. ) ; -#864 = AXIS2_PLACEMENT_3D ( 'NONE', #14431, #36912, #34036 ) ; -#865 = ORIENTED_EDGE ( 'NONE', *, *, #34601, .T. ) ; -#866 = ORIENTED_EDGE ( 'NONE', *, *, #9089, .F. ) ; -#867 = CARTESIAN_POINT ( 'NONE', ( 26.00511610745047264, 120.0889745669351782, 90.43625461076925376 ) ) ; -#868 = DIRECTION ( 'NONE', ( -0.0005884949961218496721, 0.2249510543439063315, -0.9743698870671264611 ) ) ; -#870 = CARTESIAN_POINT ( 'NONE', ( -8.192072165922381188, 151.6568654278863733, 94.67061599110682835 ) ) ; -#869 = CARTESIAN_POINT ( 'NONE', ( 36.06386299210247870, 192.3813622508035905, 104.3665697773190715 ) ) ; -#871 = ORIENTED_EDGE ( 'NONE', *, *, #33176, .T. ) ; -#872 = DIRECTION ( 'NONE', ( -0.0006540525280306910220, 0.2250342908583061741, -0.9743506248539022252 ) ) ; -#873 = CARTESIAN_POINT ( 'NONE', ( 39.01961099979754266, 175.8196705488005023, 136.1591049921323986 ) ) ; -#874 = EDGE_LOOP ( 'NONE', ( #4772, #37592, #29615, #33870 ) ) ; -#875 = ORIENTED_EDGE ( 'NONE', *, *, #34263, .F. ) ; -#876 = DIRECTION ( 'NONE', ( 0.7066518122933521662, -3.184449828924648418E-15, -0.7075614575303836862 ) ) ; -#877 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23234, #35878, #29974, #27133, #4411, #20553, #5017, #32631, #16869, #17480, #26310, #26714, #35666, #14439 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000590639, 0.3750000000000573985, 0.5000000000000557332, 0.6250000000000540679, 0.6875000000000532907, 0.7500000000000525135, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#878 = LINE ( 'NONE', #28908, #23317 ) ; -#879 = CARTESIAN_POINT ( 'NONE', ( -2.557262702658000375, 190.9632190922000063, 106.4318435757000003 ) ) ; -#880 = EDGE_LOOP ( 'NONE', ( #11826, #12243, #12769, #25971 ) ) ; -#881 = VECTOR ( 'NONE', #29482, 1000.000000000000000 ) ; -#882 = CIRCLE ( 'NONE', #3502, 8.499999999972331466 ) ; -#883 = ORIENTED_EDGE ( 'NONE', *, *, #24759, .F. ) ; -#884 = ORIENTED_EDGE ( 'NONE', *, *, #19167, .T. ) ; -#885 = DIRECTION ( 'NONE', ( 0.0006039748319395907457, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#886 = FACE_OUTER_BOUND ( 'NONE', #18879, .T. ) ; -#887 = AXIS2_PLACEMENT_3D ( 'NONE', #19343, #35459, #38165 ) ; -#888 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#889 = ORIENTED_EDGE ( 'NONE', *, *, #27357, .T. ) ; -#890 = CARTESIAN_POINT ( 'NONE', ( -20.45570291159294030, 122.4774857238997043, 183.8048636542243059 ) ) ; -#891 = ORIENTED_EDGE ( 'NONE', *, *, #13113, .F. ) ; -#893 = ADVANCED_FACE ( 'NONE', ( #5689 ), #36969, .F. ) ; -#892 = CARTESIAN_POINT ( 'NONE', ( -37.13539223219807894, 116.7950545578066794, 89.73131408846597878 ) ) ; -#894 = ADVANCED_FACE ( 'NONE', ( #5884 ), #18339, .T. ) ; -#895 = EDGE_CURVE ( 'NONE', #1429, #37610, #27074, .T. ) ; -#896 = EDGE_LOOP ( 'NONE', ( #16759, #29679, #37111, #39920 ) ) ; -#897 = FACE_OUTER_BOUND ( 'NONE', #16698, .T. ) ; -#898 = EDGE_CURVE ( 'NONE', #7054, #22555, #13333, .T. ) ; -#899 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555688 ) ) ; -#900 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7965, #11047, #11444, #36588 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#901 = VERTEX_POINT ( 'NONE', #28969 ) ; -#902 = CARTESIAN_POINT ( 'NONE', ( -30.24155573443220746, 159.9839851041407996, 186.8751258489507165 ) ) ; -#903 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425149360, 185.2313152530017248, 105.5040075785468048 ) ) ; -#904 = CARTESIAN_POINT ( 'NONE', ( -22.78222448785095011, 163.9594641391059042, 100.5986201911018298 ) ) ; -#905 = ADVANCED_FACE ( 'NONE', ( #9971 ), #16680, .F. ) ; -#906 = VERTEX_POINT ( 'NONE', #38366 ) ; -#907 = CARTESIAN_POINT ( 'NONE', ( 25.50773672857076235, 191.9759150222000130, 101.9060413065578530 ) ) ; -#908 = ORIENTED_EDGE ( 'NONE', *, *, #18787, .T. ) ; -#909 = LINE ( 'NONE', #1111, #34236 ) ; -#910 = CARTESIAN_POINT ( 'NONE', ( -43.16067970895235106, 137.0136042933273472, 338.0369414682852494 ) ) ; -#911 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319356122658 ) ) ; -#912 = EDGE_CURVE ( 'NONE', #16019, #21171, #35273, .T. ) ; -#913 = AXIS2_PLACEMENT_3D ( 'NONE', #25178, #804, #3460 ) ; -#914 = AXIS2_PLACEMENT_3D ( 'NONE', #34086, #27985, #7277 ) ; -#915 = CARTESIAN_POINT ( 'NONE', ( 0.06247583203485999881, 188.8062377635999951, 103.4410994233000025 ) ) ; -#916 = ORIENTED_EDGE ( 'NONE', *, *, #15721, .T. ) ; -#917 = DIRECTION ( 'NONE', ( -0.0006039748319392586546, -1.665208279866278382E-14, -0.9999998176071847045 ) ) ; -#918 = VECTOR ( 'NONE', #35489, 1000.000000000000114 ) ; -#919 = CARTESIAN_POINT ( 'NONE', ( -35.82625367234000890, 112.3689870599999949, 89.91154723993000175 ) ) ; -#920 = ORIENTED_EDGE ( 'NONE', *, *, #5292, .T. ) ; -#921 = VERTEX_POINT ( 'NONE', #19743 ) ; -#922 = CARTESIAN_POINT ( 'NONE', ( 11.82534515883345527, 158.5331529580515735, 96.24604232593732434 ) ) ; -#923 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#924 = CARTESIAN_POINT ( 'NONE', ( 23.69085248748276840, 130.8248087875101362, 90.01295625239652054 ) ) ; -#925 = CARTESIAN_POINT ( 'NONE', ( 3.064236136099508290, 190.8512031035150471, 106.7914583158460573 ) ) ; -#926 = ORIENTED_EDGE ( 'NONE', *, *, #39072, .F. ) ; -#927 = LINE ( 'NONE', #38154, #22617 ) ; -#928 = ORIENTED_EDGE ( 'NONE', *, *, #16160, .F. ) ; -#929 = VERTEX_POINT ( 'NONE', #29180 ) ; -#930 = ORIENTED_EDGE ( 'NONE', *, *, #19926, .F. ) ; -#931 = CARTESIAN_POINT ( 'NONE', ( -6.035163149060575272, 177.6449902918727162, 100.7936898218632393 ) ) ; -#932 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#933 = CARTESIAN_POINT ( 'NONE', ( 19.24557514809682957, 124.8328511027356456, 177.9395134564782381 ) ) ; -#934 = ORIENTED_EDGE ( 'NONE', *, *, #31296, .F. ) ; -#935 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#936 = DIRECTION ( 'NONE', ( 0.7856637144487862434, -0.6186538028643614462, 0.000000000000000000 ) ) ; -#937 = CARTESIAN_POINT ( 'NONE', ( -34.28801115370752228, 89.15625349133107136, 280.9732277762227000 ) ) ; -#938 = CARTESIAN_POINT ( 'NONE', ( -43.86701283492332948, 121.7474466771614914, 90.64158096768842654 ) ) ; -#939 = AXIS2_PLACEMENT_3D ( 'NONE', #35478, #37983, #9983 ) ; -#940 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971545141 ) ) ; -#941 = ORIENTED_EDGE ( 'NONE', *, *, #27660, .F. ) ; -#942 = CARTESIAN_POINT ( 'NONE', ( 28.24084398341999957, 125.5722885917000013, 89.14071976869000480 ) ) ; -#943 = CIRCLE ( 'NONE', #40138, 6.499999999990746957 ) ; -#944 = VECTOR ( 'NONE', #12893, 1000.000000000000114 ) ; -#945 = DIRECTION ( 'NONE', ( -0.6773442687123379935, -0.7356661890032381024, 0.000000000000000000 ) ) ; -#946 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#947 = EDGE_CURVE ( 'NONE', #35304, #20063, #16576, .T. ) ; -#948 = AXIS2_PLACEMENT_3D ( 'NONE', #27763, #31014, #3186 ) ; -#949 = ADVANCED_FACE ( 'NONE', ( #1151 ), #10373, .T. ) ; -#950 = FACE_OUTER_BOUND ( 'NONE', #24854, .T. ) ; -#951 = CARTESIAN_POINT ( 'NONE', ( 3.533886511882771142, 137.1968222802559012, 91.32516919190832994 ) ) ; -#952 = ORIENTED_EDGE ( 'NONE', *, *, #14768, .F. ) ; -#953 = CARTESIAN_POINT ( 'NONE', ( 45.16550232355236005, 181.2351781714976937, 101.8091835899543440 ) ) ; -#954 = CARTESIAN_POINT ( 'NONE', ( 0.7291628089563826354, 189.0068906503063886, 103.6850538576102139 ) ) ; -#955 = CARTESIAN_POINT ( 'NONE', ( -1.692498771449036932, 188.7201307904135774, 106.3023338887167171 ) ) ; -#956 = CARTESIAN_POINT ( 'NONE', ( 3.334663580956577000, 183.4889149388049816, 104.9205407821583123 ) ) ; -#957 = ORIENTED_EDGE ( 'NONE', *, *, #36269, .F. ) ; -#958 = CARTESIAN_POINT ( 'NONE', ( -26.12986736251000153, 191.7563640120999935, 103.7886991103000014 ) ) ; -#959 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8128, #26744, #14271, #35699, #11003, #22874, #17102, #976, #17304, #35301 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000002350897, 0.3750000000003276823, 0.4375000000003435585, 0.5000000000003593792, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#960 = CARTESIAN_POINT ( 'NONE', ( 24.01770307888959621, 118.3486789263952517, 189.6358675532988229 ) ) ; -#961 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#962 = DIRECTION ( 'NONE', ( -0.9914447019871281963, 0.1270494721559694284, 0.02993049492647828144 ) ) ; -#963 = EDGE_LOOP ( 'NONE', ( #29866, #34587, #739, #1128 ) ) ; -#964 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #20966, #17256 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#965 = CIRCLE ( 'NONE', #25804, 4.999999999999990230 ) ; -#966 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; -#967 = CARTESIAN_POINT ( 'NONE', ( -45.39258384773165034, 124.3433029335535878, 88.43811771986804615 ) ) ; -#968 = VECTOR ( 'NONE', #4303, 1000.000000000000114 ) ; -#969 = CIRCLE ( 'NONE', #3588, 6.000000588931215795 ) ; -#970 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319387907129 ) ) ; -#971 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36827, #5753, #17596, #14560 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#972 = FACE_BOUND ( 'NONE', #9002, .T. ) ; -#973 = DIRECTION ( 'NONE', ( 0.0002393071182782299474, 0.2252352986010034697, -0.9743043687658493601 ) ) ; -#974 = CARTESIAN_POINT ( 'NONE', ( -13.46970022169197989, 176.3366686086323227, 152.9217692962739079 ) ) ; -#975 = VECTOR ( 'NONE', #27436, 999.9999999999998863 ) ; -#976 = CARTESIAN_POINT ( 'NONE', ( -5.667187237236853470, 130.2293307052626687, 92.64134285576068351 ) ) ; -#977 = CARTESIAN_POINT ( 'NONE', ( 13.50156854163491005, 188.0558794582128996, 103.3088726825072001 ) ) ; -#978 = VERTEX_POINT ( 'NONE', #15879 ) ; -#979 = CARTESIAN_POINT ( 'NONE', ( -2.689544897498777232, 209.6680443742787077, 75.89346469953468954 ) ) ; -#980 = CARTESIAN_POINT ( 'NONE', ( 18.98507725696123671, 148.2474724526778687, 184.5421123104517278 ) ) ; -#981 = DIRECTION ( 'NONE', ( 0.6087611427424929333, 0.7731004630501246977, 0.1781166615410725018 ) ) ; -#982 = VERTEX_POINT ( 'NONE', #10176 ) ; -#983 = CARTESIAN_POINT ( 'NONE', ( 26.87666215091000055, 135.1099595320999924, 91.08585649840999565 ) ) ; -#984 = ORIENTED_EDGE ( 'NONE', *, *, #30565, .T. ) ; -#985 = DIRECTION ( 'NONE', ( 0.0006039748319386881474, 1.110222822128452674E-14, 0.9999998176071845934 ) ) ; -#986 = DIRECTION ( 'NONE', ( 0.0005884951729871207987, -0.2249510544218079611, 0.9743698870490344888 ) ) ; -#987 = CARTESIAN_POINT ( 'NONE', ( 25.99875258092378161, 117.7155965479965687, 87.25208169694612081 ) ) ; -#988 = EDGE_LOOP ( 'NONE', ( #17595, #16179, #35857, #39446, #26286, #13976, #8313, #4701, #28650, #18373, #38755, #31568 ) ) ; -#989 = CARTESIAN_POINT ( 'NONE', ( -14.42373142009429365, 182.0239085154369150, 104.5930275125517852 ) ) ; -#990 = CARTESIAN_POINT ( 'NONE', ( 24.50320502934976830, 213.7111511448713088, 76.04368778216444014 ) ) ; -#991 = ADVANCED_FACE ( 'NONE', ( #6674 ), #19549, .F. ) ; -#992 = ADVANCED_FACE ( 'NONE', ( #542 ), #13629, .T. ) ; -#993 = CARTESIAN_POINT ( 'NONE', ( -12.63680864157205086, 130.5439919522491721, 90.20625573009445475 ) ) ; -#994 = CARTESIAN_POINT ( 'NONE', ( -38.38796632900000105, 191.2261826337999935, 104.0807279818999973 ) ) ; -#995 = VECTOR ( 'NONE', #25432, 1000.000000000000000 ) ; -#996 = ORIENTED_EDGE ( 'NONE', *, *, #38160, .F. ) ; -#997 = DIRECTION ( 'NONE', ( 0.0005884949961162573573, -0.2249510543439059151, 0.9743698870671263501 ) ) ; -#998 = CARTESIAN_POINT ( 'NONE', ( 42.78873758771006663, 120.8665316288775102, 92.29373204621693105 ) ) ; -#999 = CONICAL_SURFACE ( 'NONE', #40172, 22.50000000000898837, 0.7853981633973132759 ) ; -#1000 = CARTESIAN_POINT ( 'NONE', ( -40.45487666593005827, 220.4002261020000049, 76.08293836150286893 ) ) ; -#1001 = AXIS2_PLACEMENT_3D ( 'NONE', #6931, #28422, #31898 ) ; -#1002 = CARTESIAN_POINT ( 'NONE', ( -36.44734101958000849, 191.1363885723000067, 103.6637415026000042 ) ) ; -#1003 = ORIENTED_EDGE ( 'NONE', *, *, #18303, .F. ) ; -#1004 = AXIS2_PLACEMENT_3D ( 'NONE', #18866, #31367, #25245 ) ; -#1005 = ORIENTED_EDGE ( 'NONE', *, *, #34200, .T. ) ; -#1006 = DIRECTION ( 'NONE', ( -2.081668171217371032E-15, 0.9743700557921590732, 0.2249510932971540700 ) ) ; -#1007 = LINE ( 'NONE', #24331, #24282 ) ; -#1008 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8362, #16921, #14290, #11025 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1009 = CARTESIAN_POINT ( 'NONE', ( 14.07223717073995672, 122.5303360716178105, 176.5193168095456713 ) ) ; -#1010 = CARTESIAN_POINT ( 'NONE', ( 32.56862209515505668, 137.3592834573111929, 91.34514006402139330 ) ) ; -#1011 = CARTESIAN_POINT ( 'NONE', ( -12.63649281426050663, 129.9703308633319807, 92.23232912533514138 ) ) ; -#1012 = CARTESIAN_POINT ( 'NONE', ( 25.93424969579000106, 190.6798797952000086, 106.6095218724999967 ) ) ; -#1013 = EDGE_CURVE ( 'NONE', #28881, #10321, #31673, .T. ) ; -#1014 = CARTESIAN_POINT ( 'NONE', ( 38.16410284748000237, 119.4654676515000062, 87.14306831961999933 ) ) ; -#1015 = CARTESIAN_POINT ( 'NONE', ( -3.046821091270000004, 209.4711209118999875, 72.92944012904000317 ) ) ; -#1016 = CARTESIAN_POINT ( 'NONE', ( 38.15391655548999950, 118.9232721861999948, 90.39751939907000633 ) ) ; -#1017 = ORIENTED_EDGE ( 'NONE', *, *, #40315, .F. ) ; -#1018 = AXIS2_PLACEMENT_3D ( 'NONE', #24305, #5258, #36747 ) ; -#1019 = DIRECTION ( 'NONE', ( -0.1843855713908465477, -0.08049128666858569592, 0.9795525069302342125 ) ) ; -#1020 = DIRECTION ( 'NONE', ( 1.156372029607614051E-16, 0.9743043966640312359, 0.2252353050503803356 ) ) ; -#1021 = VERTEX_POINT ( 'NONE', #12832 ) ; -#1022 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20394, #27176, #26965, #17521 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1023 = VERTEX_POINT ( 'NONE', #25922 ) ; -#1024 = CARTESIAN_POINT ( 'NONE', ( 25.66576336802040359, 118.8155664474191724, 87.58560832463771817 ) ) ; -#1025 = VECTOR ( 'NONE', #1639, 1000.000000000000114 ) ; -#1026 = EDGE_CURVE ( 'NONE', #39304, #1429, #6173, .T. ) ; -#1027 = DIRECTION ( 'NONE', ( 0.5968393679912002980, 0.8023607473050164973, 0.000000000000000000 ) ) ; -#1028 = CARTESIAN_POINT ( 'NONE', ( -6.831231556254691917, 155.4618032185357492, 100.6797548176731993 ) ) ; -#1029 = VECTOR ( 'NONE', #30178, 1000.000000000000000 ) ; -#1030 = EDGE_LOOP ( 'NONE', ( #33987, #10661, #36469, #4591 ) ) ; -#1031 = CARTESIAN_POINT ( 'NONE', ( -14.76234657499968783, 188.0332833685391734, 103.0727436135631194 ) ) ; -#1032 = EDGE_CURVE ( 'NONE', #13945, #16868, #22247, .T. ) ; -#1033 = CARTESIAN_POINT ( 'NONE', ( -38.72644908288000209, 118.7070105194000007, 89.71289965706000658 ) ) ; -#1034 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 135.6474414654788347, 90.98047230848234790 ) ) ; -#1035 = LINE ( 'NONE', #7370, #24335 ) ; -#1036 = ORIENTED_EDGE ( 'NONE', *, *, #17518, .T. ) ; -#1037 = CARTESIAN_POINT ( 'NONE', ( 19.70863784699480448, 149.1560517737245561, 182.9541186021026817 ) ) ; -#1038 = ORIENTED_EDGE ( 'NONE', *, *, #30182, .T. ) ; -#1039 = CARTESIAN_POINT ( 'NONE', ( 31.79572357098799174, 220.4002260771000294, 76.03930080927051449 ) ) ; -#1040 = CARTESIAN_POINT ( 'NONE', ( -25.50006284340070906, 118.1130153187805689, 89.78316558933853742 ) ) ; -#1041 = EDGE_CURVE ( 'NONE', #23754, #39643, #27745, .T. ) ; -#1042 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10861, #38439, #10653, #13315, #35755, #14130, #10260, #11057, #26394, #7765, #16956 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999876765, 0.3749999999999565348, 0.4374999999999233946, 0.4687499999999067968, 0.4999999999998901989, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1043 = EDGE_CURVE ( 'NONE', #35217, #8772, #31851, .T. ) ; -#1044 = FACE_OUTER_BOUND ( 'NONE', #4555, .T. ) ; -#1045 = CARTESIAN_POINT ( 'NONE', ( 17.30417074659255761, 152.9391053872499526, 180.9092052391793004 ) ) ; -#1046 = DIRECTION ( 'NONE', ( -0.0005884949961227338390, 0.2249510543439056653, -0.9743698870671265722 ) ) ; -#1047 = EDGE_CURVE ( 'NONE', #27481, #31227, #27695, .T. ) ; -#1048 = ORIENTED_EDGE ( 'NONE', *, *, #21134, .T. ) ; -#1049 = CARTESIAN_POINT ( 'NONE', ( -0.6157399968410001145, 188.8694429141000057, 103.5223704861000158 ) ) ; -#1050 = ADVANCED_FACE ( 'NONE', ( #17070 ), #35525, .F. ) ; -#1051 = DIRECTION ( 'NONE', ( -0.6319268263561552690, -0.7750280550608716901, 0.000000000000000000 ) ) ; -#1052 = CARTESIAN_POINT ( 'NONE', ( 32.66389061773956826, 141.7118122376935219, 282.5421777876526335 ) ) ; -#1053 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #23744, #1865 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1054 = ORIENTED_EDGE ( 'NONE', *, *, #10117, .T. ) ; -#1055 = CARTESIAN_POINT ( 'NONE', ( 24.00841289415539848, 118.3368870854502717, 189.6331392867438979 ) ) ; -#1056 = CARTESIAN_POINT ( 'NONE', ( -24.52910917930924484, 213.7107200543937608, 76.07243698009752109 ) ) ; -#1057 = AXIS2_PLACEMENT_3D ( 'NONE', #24137, #5096, #11053 ) ; -#1058 = ORIENTED_EDGE ( 'NONE', *, *, #18855, .T. ) ; -#1059 = DIRECTION ( 'NONE', ( 0.5988683521957600675, -0.8008474865655350605, 0.000000000000000000 ) ) ; -#1060 = CIRCLE ( 'NONE', #26563, 4.999999999999990230 ) ; -#1061 = ORIENTED_EDGE ( 'NONE', *, *, #38829, .T. ) ; -#1062 = CARTESIAN_POINT ( 'NONE', ( 22.50176470574832877, 126.7597147172538570, 91.98302937056051576 ) ) ; -#1063 = CARTESIAN_POINT ( 'NONE', ( 20.50029383489984980, 127.3219018132126479, 89.54826866284827247 ) ) ; -#1064 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218858604, 138.4701267047078659, 297.5295786860737053 ) ) ; -#1065 = EDGE_CURVE ( 'NONE', #30696, #29413, #13049, .T. ) ; -#1066 = VERTEX_POINT ( 'NONE', #17684 ) ; -#1067 = ORIENTED_EDGE ( 'NONE', *, *, #30273, .T. ) ; -#1068 = CARTESIAN_POINT ( 'NONE', ( 26.00304017342149621, 120.1091259005509926, 90.45343346466181345 ) ) ; -#1069 = LINE ( 'NONE', #31360, #32580 ) ; -#1071 = CARTESIAN_POINT ( 'NONE', ( -37.29404342678407858, 118.1039676111839754, 123.2219287228025735 ) ) ; -#1070 = CARTESIAN_POINT ( 'NONE', ( 20.48158208153664361, 208.7639276185600750, 75.71837906042235034 ) ) ; -#1072 = ORIENTED_EDGE ( 'NONE', *, *, #3432, .T. ) ; -#1073 = CARTESIAN_POINT ( 'NONE', ( -2.937322199011638268, 191.1124755427409809, 103.7764892006471058 ) ) ; -#1074 = EDGE_CURVE ( 'NONE', #7652, #39292, #10973, .T. ) ; -#1075 = VECTOR ( 'NONE', #11856, 1000.000000000000114 ) ; -#1076 = FACE_OUTER_BOUND ( 'NONE', #19236, .T. ) ; -#1077 = ORIENTED_EDGE ( 'NONE', *, *, #1641, .T. ) ; -#1078 = CIRCLE ( 'NONE', #9592, 5.000000000000007994 ) ; -#1079 = CIRCLE ( 'NONE', #4344, 7.499999999930377470 ) ; -#1080 = ORIENTED_EDGE ( 'NONE', *, *, #25991, .F. ) ; -#1081 = CARTESIAN_POINT ( 'NONE', ( 38.92749941854999918, 118.9318509131999946, 89.81972100347999799 ) ) ; -#1082 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971548471 ) ) ; -#1083 = EDGE_CURVE ( 'NONE', #34462, #12345, #14026, .T. ) ; -#1084 = DIRECTION ( 'NONE', ( -0.0005884949961248158324, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#1085 = CARTESIAN_POINT ( 'NONE', ( 5.669618588597917785, 187.4181796362739476, 105.6527527589996254 ) ) ; -#1086 = CARTESIAN_POINT ( 'NONE', ( -2.557265678393000119, 190.9742781186000116, 106.4347167855000009 ) ) ; -#1087 = ORIENTED_EDGE ( 'NONE', *, *, #19759, .T. ) ; -#1088 = VECTOR ( 'NONE', #12974, 1000.000000000000227 ) ; -#1089 = EDGE_CURVE ( 'NONE', #37866, #2346, #11401, .T. ) ; -#1090 = ORIENTED_EDGE ( 'NONE', *, *, #11398, .F. ) ; -#1091 = ORIENTED_EDGE ( 'NONE', *, *, #30837, .T. ) ; -#1092 = CYLINDRICAL_SURFACE ( 'NONE', #33710, 6.000000000000001776 ) ; -#1093 = CARTESIAN_POINT ( 'NONE', ( 20.00153785277168339, 160.0757089691884971, 99.67622395206049646 ) ) ; -#1094 = FACE_OUTER_BOUND ( 'NONE', #8198, .T. ) ; -#1095 = ORIENTED_EDGE ( 'NONE', *, *, #21134, .F. ) ; -#1096 = EDGE_CURVE ( 'NONE', #37155, #19698, #19870, .T. ) ; -#1097 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#1098 = VERTEX_POINT ( 'NONE', #32635 ) ; -#1099 = CARTESIAN_POINT ( 'NONE', ( 20.16688071201305732, 174.4873282160424139, 100.0954865458536887 ) ) ; -#1100 = ORIENTED_EDGE ( 'NONE', *, *, #7043, .F. ) ; -#1101 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1102 = CARTESIAN_POINT ( 'NONE', ( -23.36052865740974838, 181.6105241605473282, 104.1608863659234885 ) ) ; -#1103 = ORIENTED_EDGE ( 'NONE', *, *, #12151, .F. ) ; -#1104 = CARTESIAN_POINT ( 'NONE', ( 25.02588108245754484, 153.6585318740197010, 181.6250235156477402 ) ) ; -#1105 = DIRECTION ( 'NONE', ( 0.0005884949961231158034, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1106 = LINE ( 'NONE', #19702, #11746 ) ; -#1107 = DIRECTION ( 'NONE', ( 0.0005884949961256949035, -0.2249510543439057209, 0.9743698870671265722 ) ) ; -#1108 = AXIS2_PLACEMENT_3D ( 'NONE', #4558, #693, #28716 ) ; -#1109 = EDGE_LOOP ( 'NONE', ( #17306, #7928, #21301, #122 ) ) ; -#1110 = ORIENTED_EDGE ( 'NONE', *, *, #39682, .T. ) ; -#1111 = CARTESIAN_POINT ( 'NONE', ( -3.631498268106390537, 112.1323247865684607, 152.4707203835916687 ) ) ; -#1112 = CARTESIAN_POINT ( 'NONE', ( 20.06100899634295587, 211.8492643960386488, 73.04638773564751375 ) ) ; -#1113 = AXIS2_PLACEMENT_3D ( 'NONE', #12392, #24895, #3574 ) ; -#1114 = CARTESIAN_POINT ( 'NONE', ( 19.39305163340773674, 125.4565983441243162, 175.2227004938931429 ) ) ; -#1115 = CARTESIAN_POINT ( 'NONE', ( -25.49166336760104912, 196.1181869298516744, 103.6951339797178804 ) ) ; -#1116 = VERTEX_POINT ( 'NONE', #1551 ) ; -#1117 = CARTESIAN_POINT ( 'NONE', ( -39.71549914202294218, 121.2606343799488826, 123.5760462896040934 ) ) ; -#1118 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29860, #39241, #36176, #8179, #39438, #2462, #20644, #17560, #21063, #33106, #20849, #27429 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2492599143486034785, 0.4985198286972069570, 0.7477797430458104078, 0.8724097002201126605, 0.9970396573944148022 ), - .UNSPECIFIED. ) ; -#1119 = CARTESIAN_POINT ( 'NONE', ( -38.38756031713000283, 118.2000217570000018, 89.55403246576000242 ) ) ; -#1120 = VERTEX_POINT ( 'NONE', #17482 ) ; -#1121 = ORIENTED_EDGE ( 'NONE', *, *, #32048, .F. ) ; -#1122 = EDGE_CURVE ( 'NONE', #35790, #8868, #8685, .T. ) ; -#1123 = CARTESIAN_POINT ( 'NONE', ( 8.046776639317595681, 161.2737771581006996, 96.88104755365348808 ) ) ; -#1124 = ADVANCED_FACE ( 'NONE', ( #14854 ), #2280, .F. ) ; -#1125 = CARTESIAN_POINT ( 'NONE', ( -27.65251932003710422, 124.5980834872316194, 88.43535643343921038 ) ) ; -#1126 = EDGE_CURVE ( 'NONE', #14712, #19860, #36433, .T. ) ; -#1127 = CARTESIAN_POINT ( 'NONE', ( -13.49986562384761690, 124.0034607844170722, 91.10007752827642946 ) ) ; -#1128 = ORIENTED_EDGE ( 'NONE', *, *, #13655, .F. ) ; -#1129 = ADVANCED_FACE ( 'NONE', ( #28090 ), #23169, .F. ) ; -#1130 = ORIENTED_EDGE ( 'NONE', *, *, #30388, .F. ) ; -#1131 = CARTESIAN_POINT ( 'NONE', ( 13.50000077932746834, 151.9719590241109870, 94.73025978658517943 ) ) ; -#1132 = VERTEX_POINT ( 'NONE', #38068 ) ; -#1133 = ORIENTED_EDGE ( 'NONE', *, *, #10008, .F. ) ; -#1134 = ORIENTED_EDGE ( 'NONE', *, *, #8058, .T. ) ; -#1135 = CARTESIAN_POINT ( 'NONE', ( 1.541641309182932407, 189.2503461931255515, 105.8091309696538360 ) ) ; -#1136 = DIRECTION ( 'NONE', ( 0.0001358647752415049960, 0.9743700647852354679, 0.2249510133144081714 ) ) ; -#1137 = LINE ( 'NONE', #22636, #16996 ) ; -#1138 = VERTEX_POINT ( 'NONE', #22948 ) ; -#1139 = EDGE_CURVE ( 'NONE', #7358, #34014, #4723, .T. ) ; -#1140 = VECTOR ( 'NONE', #9060, 1000.000000000000114 ) ; -#1141 = ORIENTED_EDGE ( 'NONE', *, *, #26637, .T. ) ; -#1142 = CARTESIAN_POINT ( 'NONE', ( -25.50961619573916295, 207.5944492561152117, 74.07776327504342362 ) ) ; -#1143 = CARTESIAN_POINT ( 'NONE', ( 38.53687076957470481, 218.5902260770998282, 61.03522658939011336 ) ) ; -#1144 = CARTESIAN_POINT ( 'NONE', ( -38.54589056617000153, 119.0161585872999979, 90.15889641821000566 ) ) ; -#1145 = CARTESIAN_POINT ( 'NONE', ( -44.77736910497013412, 122.8593275267315619, 91.09968955831281789 ) ) ; -#1146 = VECTOR ( 'NONE', #24084, 1000.000000000000000 ) ; -#1147 = EDGE_CURVE ( 'NONE', #3990, #1116, #13938, .T. ) ; -#1148 = CARTESIAN_POINT ( 'NONE', ( -45.92960031148149369, 125.5172539323009886, 88.65860258904321256 ) ) ; -#1149 = CARTESIAN_POINT ( 'NONE', ( 36.04619750388000199, 209.7096540190999860, 75.11813308473999484 ) ) ; -#1150 = ORIENTED_EDGE ( 'NONE', *, *, #34677, .T. ) ; -#1151 = FACE_OUTER_BOUND ( 'NONE', #16523, .T. ) ; -#1152 = CARTESIAN_POINT ( 'NONE', ( 25.18370408048160769, 116.8541948698079835, 87.75240084223993620 ) ) ; -#1153 = CARTESIAN_POINT ( 'NONE', ( -24.95545957861278197, 159.0476773995373208, 180.5017353223074110 ) ) ; -#1154 = PLANE ( 'NONE', #18984 ) ; -#1155 = VERTEX_POINT ( 'NONE', #29477 ) ; -#1156 = EDGE_CURVE ( 'NONE', #37208, #29757, #29031, .T. ) ; -#1157 = CARTESIAN_POINT ( 'NONE', ( -22.78469271946612196, 158.3009118758265004, 96.21332883968871386 ) ) ; -#1158 = CARTESIAN_POINT ( 'NONE', ( 0.8736985995922892378, 189.0243393747963125, 103.6919201171674132 ) ) ; -#1159 = CARTESIAN_POINT ( 'NONE', ( -2.915934786403184820, 190.5310171364556879, 106.7211489447119135 ) ) ; -#1160 = CARTESIAN_POINT ( 'NONE', ( -2.438441566312121278, 191.9759150222000130, 101.9229200979920620 ) ) ; -#1161 = CARTESIAN_POINT ( 'NONE', ( -25.87265514998000171, 191.7182740471999978, 104.0421947181999940 ) ) ; -#1162 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927784831808, -0.0005734119022074042876 ) ) ; -#1163 = CARTESIAN_POINT ( 'NONE', ( -3.501640554245670334, 183.5236249414575127, 104.7616159400518541 ) ) ; -#1164 = CARTESIAN_POINT ( 'NONE', ( -3.893460981304297963, 148.9599728392922771, 129.9645419182680541 ) ) ; -#1165 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971553745 ) ) ; -#1166 = ORIENTED_EDGE ( 'NONE', *, *, #19596, .T. ) ; -#1167 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#1168 = VECTOR ( 'NONE', #6521, 999.9999999999998863 ) ; -#1169 = AXIS2_PLACEMENT_3D ( 'NONE', #5667, #24495, #36955 ) ; -#1170 = CARTESIAN_POINT ( 'NONE', ( 39.05618840313393747, 127.6228071286297734, 91.65913731599329139 ) ) ; -#1171 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1172 = VERTEX_POINT ( 'NONE', #13538 ) ; -#1173 = CARTESIAN_POINT ( 'NONE', ( -34.95638759933999751, 226.4002260771000010, 73.57961695570000416 ) ) ; -#1174 = CARTESIAN_POINT ( 'NONE', ( -37.35285048055809654, 145.6614909859866884, 280.9747434382983329 ) ) ; -#1175 = DIRECTION ( 'NONE', ( 0.0006039748319385826545, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#1176 = CARTESIAN_POINT ( 'NONE', ( 20.41970764888255729, 118.1111884937556908, 89.83743835591825189 ) ) ; -#1177 = EDGE_CURVE ( 'NONE', #901, #21181, #38658, .T. ) ; -#1178 = CARTESIAN_POINT ( 'NONE', ( -39.39119571213127102, 179.7048915881142648, 119.1251828874389389 ) ) ; -#1179 = EDGE_CURVE ( 'NONE', #9277, #25509, #18559, .T. ) ; -#1180 = CARTESIAN_POINT ( 'NONE', ( 35.68878940061000549, 192.8595724163999989, 106.6974279695000121 ) ) ; -#1181 = ORIENTED_EDGE ( 'NONE', *, *, #19909, .F. ) ; -#1182 = ORIENTED_EDGE ( 'NONE', *, *, #21145, .F. ) ; -#1183 = FACE_OUTER_BOUND ( 'NONE', #17663, .T. ) ; -#1184 = CARTESIAN_POINT ( 'NONE', ( -2.849114641686540050, 209.7153547210247666, 76.06022791818580231 ) ) ; -#1185 = CARTESIAN_POINT ( 'NONE', ( -15.99823432472775941, 127.0706064849903782, 92.07805732825173095 ) ) ; -#1186 = EDGE_CURVE ( 'NONE', #26180, #33812, #25777, .T. ) ; -#1187 = CARTESIAN_POINT ( 'NONE', ( 20.48253891412411321, 207.4083879957671002, 77.06951181954761410 ) ) ; -#1188 = VERTEX_POINT ( 'NONE', #19653 ) ; -#1189 = CARTESIAN_POINT ( 'NONE', ( 9.150602861467000082, 130.7229476589999990, 90.08374091371000247 ) ) ; -#1190 = ORIENTED_EDGE ( 'NONE', *, *, #17562, .T. ) ; -#1191 = EDGE_CURVE ( 'NONE', #32568, #10330, #4513, .T. ) ; -#1192 = CARTESIAN_POINT ( 'NONE', ( -5.039516421625153342, 130.9623293100809747, 89.89100093531286007 ) ) ; -#1193 = FACE_OUTER_BOUND ( 'NONE', #23968, .T. ) ; -#1194 = ORIENTED_EDGE ( 'NONE', *, *, #16495, .F. ) ; -#1195 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673442394, 160.6295158081618411, 97.24216643309391372 ) ) ; -#1196 = AXIS2_PLACEMENT_3D ( 'NONE', #34674, #9566, #28372 ) ; -#1197 = CARTESIAN_POINT ( 'NONE', ( -45.74740226047678959, 185.6973914029000809, 105.7298533567153669 ) ) ; -#1198 = CARTESIAN_POINT ( 'NONE', ( 22.99423289560478167, 177.7941910958035976, 100.6860584427342218 ) ) ; -#1199 = VECTOR ( 'NONE', #32180, 1000.000000000000114 ) ; -#1200 = CARTESIAN_POINT ( 'NONE', ( -48.16156435861396545, 130.6626959207983703, 336.5737388819031821 ) ) ; -#1201 = VERTEX_POINT ( 'NONE', #13331 ) ; -#1202 = EDGE_CURVE ( 'NONE', #7538, #22666, #23804, .T. ) ; -#1203 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971542920 ) ) ; -#1204 = CARTESIAN_POINT ( 'NONE', ( -4.387522495294643221, 177.1923504851183395, 100.5636504583834920 ) ) ; -#1205 = CARTESIAN_POINT ( 'NONE', ( 3.535852102820259191, 167.8277681301466941, 101.4758341492079410 ) ) ; -#1206 = CARTESIAN_POINT ( 'NONE', ( -37.95565868480999683, 191.5245969965999961, 104.5544014840999978 ) ) ; -#1207 = ORIENTED_EDGE ( 'NONE', *, *, #18754, .F. ) ; -#1208 = LINE ( 'NONE', #17136, #37489 ) ; -#1209 = CARTESIAN_POINT ( 'NONE', ( 38.56885418974432866, 118.4610218664272452, 89.66265752007532797 ) ) ; -#1210 = CARTESIAN_POINT ( 'NONE', ( -2.770499765333565456, 191.4885340689822613, 104.0342591781858061 ) ) ; -#1211 = DIRECTION ( 'NONE', ( -0.6982900371914135818, 0.000000000000000000, -0.7158149369489396063 ) ) ; -#1212 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #9486, #25440 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1213 = DIRECTION ( 'NONE', ( 0.5987319960704027277, 0.8009494346596114367, 0.000000000000000000 ) ) ; -#1214 = DIRECTION ( 'NONE', ( 0.0004270746993296993988, 0.7071067811864992780, 0.7071066522153991452 ) ) ; -#1215 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552144553, 153.0051697192221241, 291.5584375788738498 ) ) ; -#1216 = AXIS2_PLACEMENT_3D ( 'NONE', #13921, #26403, #638 ) ; -#1217 = CARTESIAN_POINT ( 'NONE', ( 28.46561332783693743, 183.4529609800732146, 105.0712386042130646 ) ) ; -#1218 = CARTESIAN_POINT ( 'NONE', ( 38.39577698277999929, 118.8040257133999944, 90.10298124054000368 ) ) ; -#1219 = EDGE_LOOP ( 'NONE', ( #13416, #313, #14610, #3967 ) ) ; -#1220 = FACE_OUTER_BOUND ( 'NONE', #40208, .T. ) ; -#1221 = CIRCLE ( 'NONE', #27393, 5.499999999682917640 ) ; -#1222 = CARTESIAN_POINT ( 'NONE', ( 13.76437287213889604, 149.5973107319868802, 180.3792966454857094 ) ) ; -#1223 = CARTESIAN_POINT ( 'NONE', ( 45.29457532323036162, 180.8691996123082220, 102.9219678205533910 ) ) ; -#1224 = EDGE_CURVE ( 'NONE', #38924, #22051, #9190, .T. ) ; -#1225 = EDGE_CURVE ( 'NONE', #15470, #8707, #19840, .T. ) ; -#1226 = VECTOR ( 'NONE', #20632, 1000.000000000000114 ) ; -#1228 = VERTEX_POINT ( 'NONE', #13732 ) ; -#1227 = CARTESIAN_POINT ( 'NONE', ( -20.50078406871936920, 194.1847361021935683, 103.1282549620370759 ) ) ; -#1229 = ORIENTED_EDGE ( 'NONE', *, *, #6904, .T. ) ; -#1230 = ORIENTED_EDGE ( 'NONE', *, *, #13104, .F. ) ; -#1231 = ORIENTED_EDGE ( 'NONE', *, *, #31118, .T. ) ; -#1232 = DIRECTION ( 'NONE', ( 0.0005884949961248703678, -0.2249510543439058319, 0.9743698870671263501 ) ) ; -#1233 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971561239 ) ) ; -#1234 = ORIENTED_EDGE ( 'NONE', *, *, #16406, .T. ) ; -#1235 = CARTESIAN_POINT ( 'NONE', ( -15.03332272964733463, 187.8566649671956554, 103.0321316980956254 ) ) ; -#1236 = CARTESIAN_POINT ( 'NONE', ( -13.50000254341547468, 188.3456888787851540, 103.1410290439362001 ) ) ; -#1237 = CARTESIAN_POINT ( 'NONE', ( -38.46629707384001051, 119.1630541435999930, 87.59461058415000423 ) ) ; -#1238 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319414569829 ) ) ; -#1239 = VERTEX_POINT ( 'NONE', #4312 ) ; -#1240 = CARTESIAN_POINT ( 'NONE', ( -19.46385895993763882, 125.8676358703096696, 177.6266660728926183 ) ) ; -#1241 = CARTESIAN_POINT ( 'NONE', ( 25.99030105615392827, 209.7097546603872900, 73.04280869622928662 ) ) ; -#1242 = CYLINDRICAL_SURFACE ( 'NONE', #28694, 2.500000000000000888 ) ; -#1243 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; -#1244 = ORIENTED_EDGE ( 'NONE', *, *, #38617, .F. ) ; -#1245 = AXIS2_PLACEMENT_3D ( 'NONE', #34468, #19347, #32239 ) ; -#1246 = EDGE_CURVE ( 'NONE', #13095, #5536, #28398, .T. ) ; -#1247 = CARTESIAN_POINT ( 'NONE', ( -0.4376680304626999751, 188.6124753596999994, 103.1978087006000067 ) ) ; -#1248 = CARTESIAN_POINT ( 'NONE', ( -0.4555724317109230981, 208.9999999999988631, 73.55877932794840035 ) ) ; -#1249 = DIRECTION ( 'NONE', ( -0.0002393071182785117045, -0.2252352986010040525, 0.9743043687658490271 ) ) ; -#1250 = VECTOR ( 'NONE', #38324, 1000.000000000000114 ) ; -#1251 = ORIENTED_EDGE ( 'NONE', *, *, #7446, .T. ) ; -#1252 = ORIENTED_EDGE ( 'NONE', *, *, #36781, .F. ) ; -#1253 = CARTESIAN_POINT ( 'NONE', ( -19.99931527105535878, 118.1256151686936420, 90.27945241601419468 ) ) ; -#1254 = DIRECTION ( 'NONE', ( 0.0006039748319379876444, 1.544770086762009064E-14, 0.9999998176071845934 ) ) ; -#1255 = ORIENTED_EDGE ( 'NONE', *, *, #5400, .F. ) ; -#1256 = AXIS2_PLACEMENT_3D ( 'NONE', #38670, #7394, #29897 ) ; -#1257 = EDGE_CURVE ( 'NONE', #13611, #38012, #4103, .T. ) ; -#1258 = ORIENTED_EDGE ( 'NONE', *, *, #9270, .F. ) ; -#1259 = VERTEX_POINT ( 'NONE', #19450 ) ; -#1260 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14050, #8323, #39782, #1990 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.002947668951464836248, 0.009586839455661846573 ), - .UNSPECIFIED. ) ; -#1261 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1262 = CARTESIAN_POINT ( 'NONE', ( -20.00062605139820704, 196.5784656963837733, 103.8871944330217048 ) ) ; -#1263 = ADVANCED_FACE ( 'NONE', ( #31952 ), #23142, .F. ) ; -#1264 = ORIENTED_EDGE ( 'NONE', *, *, #37564, .F. ) ; -#1265 = EDGE_LOOP ( 'NONE', ( #17541, #39004, #30215, #34853 ) ) ; -#1266 = CARTESIAN_POINT ( 'NONE', ( 25.83357363015789687, 120.1280924554769740, 90.26901784129513828 ) ) ; -#1267 = CARTESIAN_POINT ( 'NONE', ( -25.20351987054574394, 212.3494581010839397, 75.57404532580622458 ) ) ; -#1268 = ADVANCED_FACE ( 'NONE', ( #22749 ), #16385, .F. ) ; -#1269 = EDGE_CURVE ( 'NONE', #39173, #30729, #1815, .T. ) ; -#1270 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19151, #16293, #19750, #6682 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1272 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#1271 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 1.238758140229869926E-30, -0.0006039748319385906776 ) ) ; -#1273 = ADVANCED_FACE ( 'NONE', ( #5532 ), #628, .F. ) ; -#1274 = ORIENTED_EDGE ( 'NONE', *, *, #29674, .F. ) ; -#1275 = CARTESIAN_POINT ( 'NONE', ( -2.198820561365330217, 189.3382245203125365, 103.3664250168511387 ) ) ; -#1276 = VECTOR ( 'NONE', #26107, 1000.000000000000114 ) ; -#1277 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#1278 = VECTOR ( 'NONE', #32982, 1000.000000000000114 ) ; -#1279 = CARTESIAN_POINT ( 'NONE', ( -20.51990970300121830, 210.6301663998115146, 73.57089453299630577 ) ) ; -#1280 = ORIENTED_EDGE ( 'NONE', *, *, #19274, .T. ) ; -#1281 = CIRCLE ( 'NONE', #31337, 2.499999999988501198 ) ; -#1282 = ORIENTED_EDGE ( 'NONE', *, *, #2745, .F. ) ; -#1283 = CARTESIAN_POINT ( 'NONE', ( 37.28562273942550576, 118.1774615424172339, 122.8329667304428909 ) ) ; -#1284 = CARTESIAN_POINT ( 'NONE', ( -22.50000104909151943, 127.7435495815598614, 89.15524414322925395 ) ) ; -#1285 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501096727, 179.0628333272140367, 104.0826189413666043 ) ) ; -#1286 = ORIENTED_EDGE ( 'NONE', *, *, #33213, .F. ) ; -#1287 = ORIENTED_EDGE ( 'NONE', *, *, #9048, .F. ) ; -#1288 = FACE_OUTER_BOUND ( 'NONE', #38470, .T. ) ; -#1289 = VERTEX_POINT ( 'NONE', #22097 ) ; -#1290 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #13567, #38103, #38300, #10105 ), - ( #4137, #7621, #13366, #10315 ), - ( #22777, #4548, #17008, #35213 ), - ( #7411, #29109, #1081, #23989 ), - ( #33369, #24200, #36852, #23780 ), - ( #17420, #8861, #33161, #36652 ), - ( #33570, #30530, #5776, #17623 ), - ( #39094, #36446, #2112, #11106 ), - ( #23569, #14582, #17816, #36024 ), - ( #2721, #18421, #24805, #13475 ), - ( #12121, #40309, #10415, #34171 ), - ( #40107, #28067, #25002, #28263 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.03178433120621999841, 0.000000000000000000, 0.04166546341146999677, 0.08333232016817999910, 0.1666660336816999932, 0.2499997471950000105, 0.3333334607083999757, 0.6666667335578000397, 1.000000000000000000, 1.093460235121999968 ), - ( 0.0007981880968812000250, 0.9999999654241999991 ), - .UNSPECIFIED. ) ; -#1291 = CARTESIAN_POINT ( 'NONE', ( -35.43460945665400175, 192.7871044595100045, 106.8782972701939968 ) ) ; -#1292 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10596, #9996, #13654, #12860 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1293 = ORIENTED_EDGE ( 'NONE', *, *, #7424, .T. ) ; -#1294 = CARTESIAN_POINT ( 'NONE', ( -20.90347901032547639, 150.8128521043120429, 179.9383906111355031 ) ) ; -#1295 = ORIENTED_EDGE ( 'NONE', *, *, #31159, .T. ) ; -#1296 = CARTESIAN_POINT ( 'NONE', ( 27.38172910116941949, 155.9316580491613706, 179.7942429727659146 ) ) ; -#1297 = CIRCLE ( 'NONE', #20905, 59.40509898896999630 ) ; -#1298 = CONICAL_SURFACE ( 'NONE', #16962, 2.502994014014904955, 0.7853981633916174987 ) ; -#1299 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1300 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#1301 = CARTESIAN_POINT ( 'NONE', ( -20.46828127178381962, 162.3883493913741347, 152.4706590458624760 ) ) ; -#1302 = EDGE_CURVE ( 'NONE', #4671, #7229, #22299, .T. ) ; -#1303 = CIRCLE ( 'NONE', #15051, 2.500000000086348706 ) ; -#1304 = ORIENTED_EDGE ( 'NONE', *, *, #7600, .T. ) ; -#1305 = EDGE_LOOP ( 'NONE', ( #20097, #33483, #32804, #5597, #31459 ) ) ; -#1306 = VECTOR ( 'NONE', #6786, 1000.000000000000000 ) ; -#1307 = CARTESIAN_POINT ( 'NONE', ( 5.659931281361317623, 181.6896837046558346, 101.5959228839198687 ) ) ; -#1308 = CARTESIAN_POINT ( 'NONE', ( -20.01829689993581596, 209.7096928646539880, 76.07061354826153377 ) ) ; -#1309 = CARTESIAN_POINT ( 'NONE', ( 45.12699821176128978, 130.9347303581116364, 89.85432989627193479 ) ) ; -#1310 = ADVANCED_FACE ( 'NONE', ( #9827 ), #34237, .F. ) ; -#1311 = DIRECTION ( 'NONE', ( 0.0006039748319392047697, 1.158053700410192562E-15, 0.9999998176071845934 ) ) ; -#1312 = ORIENTED_EDGE ( 'NONE', *, *, #37295, .F. ) ; -#1313 = EDGE_CURVE ( 'NONE', #2172, #30753, #19864, .T. ) ; -#1314 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 5.991633438574710639E-15, -0.0006039748319372744562 ) ) ; -#1315 = EDGE_CURVE ( 'NONE', #19509, #36951, #36147, .T. ) ; -#1316 = CARTESIAN_POINT ( 'NONE', ( -37.56814571527999647, 118.0504501373000039, 90.15109701891999805 ) ) ; -#1317 = EDGE_CURVE ( 'NONE', #8891, #34551, #35517, .T. ) ; -#1318 = VERTEX_POINT ( 'NONE', #598 ) ; -#1319 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672796982, 173.9550015251411992, 102.3712056567855058 ) ) ; -#1320 = ADVANCED_FACE ( 'NONE', ( #16737 ), #29432, .T. ) ; -#1321 = VERTEX_POINT ( 'NONE', #13090 ) ; -#1322 = CARTESIAN_POINT ( 'NONE', ( 39.72744467449597039, 107.0407412472234370, 185.0027118236955062 ) ) ; -#1323 = LINE ( 'NONE', #20330, #18963 ) ; -#1324 = CARTESIAN_POINT ( 'NONE', ( 37.43237754270795392, 168.1027941077541925, 183.6367509868652519 ) ) ; -#1325 = ORIENTED_EDGE ( 'NONE', *, *, #28213, .F. ) ; -#1326 = ORIENTED_EDGE ( 'NONE', *, *, #40323, .T. ) ; -#1327 = DIRECTION ( 'NONE', ( 0.0005884949961246214349, -0.2249510543438803523, 0.9743698870671323453 ) ) ; -#1328 = ORIENTED_EDGE ( 'NONE', *, *, #20901, .T. ) ; -#1329 = ORIENTED_EDGE ( 'NONE', *, *, #25236, .F. ) ; -#1331 = CIRCLE ( 'NONE', #32690, 2.250000000041461945 ) ; -#1330 = CARTESIAN_POINT ( 'NONE', ( 22.78222448925487953, 163.9654955388074029, 100.5724953333896536 ) ) ; -#1332 = CIRCLE ( 'NONE', #31389, 5.000000000044655835 ) ; -#1333 = CARTESIAN_POINT ( 'NONE', ( 19.71701219870257304, 124.6133069866743455, 177.2811646003819135 ) ) ; -#1334 = VECTOR ( 'NONE', #30355, 1000.000000000000000 ) ; -#1335 = ORIENTED_EDGE ( 'NONE', *, *, #24900, .F. ) ; -#1336 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#1337 = AXIS2_PLACEMENT_3D ( 'NONE', #29058, #13320, #12504 ) ; -#1338 = CARTESIAN_POINT ( 'NONE', ( 37.12346960361000470, 117.3680689878000010, 87.58200843903000532 ) ) ; -#1339 = CARTESIAN_POINT ( 'NONE', ( 36.03638591485000831, 191.4347906147000060, 103.6972876298000017 ) ) ; -#1340 = CARTESIAN_POINT ( 'NONE', ( 3.045988519791387628, 209.1419319775010877, 76.13893608185537687 ) ) ; -#1341 = ORIENTED_EDGE ( 'NONE', *, *, #29907, .F. ) ; -#1342 = CARTESIAN_POINT ( 'NONE', ( -40.95517856246386401, 220.4002260740000168, 75.58324044005986764 ) ) ; -#1343 = ORIENTED_EDGE ( 'NONE', *, *, #4217, .T. ) ; -#1344 = CARTESIAN_POINT ( 'NONE', ( 0.5883234961168344324, 188.6054712616331699, 103.1955722014524355 ) ) ; -#1345 = CARTESIAN_POINT ( 'NONE', ( 5.667815391071374442, 128.0240139252287861, 91.77193103160428223 ) ) ; -#1346 = CARTESIAN_POINT ( 'NONE', ( -21.44693686545786449, 130.1487540525002657, 89.71308199639462089 ) ) ; -#1347 = DIRECTION ( 'NONE', ( 0.0006039748319391886151, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#1348 = ORIENTED_EDGE ( 'NONE', *, *, #22580, .T. ) ; -#1349 = DIRECTION ( 'NONE', ( -0.0005559617641590978683, 0.3907311285029293479, -0.9205046855531719974 ) ) ; -#1350 = CARTESIAN_POINT ( 'NONE', ( 1.084497557541584056, 189.0692846685636539, 103.7040743146856698 ) ) ; -#1351 = FACE_OUTER_BOUND ( 'NONE', #4289, .T. ) ; -#1352 = EDGE_CURVE ( 'NONE', #21410, #3576, #33010, .T. ) ; -#1354 = EDGE_CURVE ( 'NONE', #21126, #19429, #38172, .T. ) ; -#1353 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39129, #13792, #19902, #4377, #29337, #26277, #11135, #26476, #23599, #20731 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1355 = CARTESIAN_POINT ( 'NONE', ( 20.50100932471902482, 118.1127835883590365, 89.75563873136169946 ) ) ; -#1356 = EDGE_CURVE ( 'NONE', #12793, #34762, #3293, .T. ) ; -#1357 = CARTESIAN_POINT ( 'NONE', ( -25.87951586735999854, 191.5803385735999882, 104.0212822168000031 ) ) ; -#1358 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971537369 ) ) ; -#1359 = CARTESIAN_POINT ( 'NONE', ( -23.67442327598790541, 213.5252042271739867, 73.57279381178021538 ) ) ; -#1360 = EDGE_CURVE ( 'NONE', #8220, #20950, #10629, .T. ) ; -#1361 = AXIS2_PLACEMENT_3D ( 'NONE', #29124, #4357, #7423 ) ; -#1362 = FACE_OUTER_BOUND ( 'NONE', #3551, .T. ) ; -#1363 = VERTEX_POINT ( 'NONE', #32493 ) ; -#1364 = EDGE_CURVE ( 'NONE', #18267, #13786, #12522, .T. ) ; -#1365 = AXIS2_PLACEMENT_3D ( 'NONE', #9551, #33873, #25302 ) ; -#1366 = VECTOR ( 'NONE', #16081, 1000.000000000000000 ) ; -#1367 = FACE_OUTER_BOUND ( 'NONE', #14627, .T. ) ; -#1368 = EDGE_CURVE ( 'NONE', #30529, #23353, #39220, .T. ) ; -#1369 = LINE ( 'NONE', #24078, #27614 ) ; -#1370 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927779942056, 0.0005734119022074188159 ) ) ; -#1371 = CARTESIAN_POINT ( 'NONE', ( 3.666638755409086681, 184.0129645450027738, 102.6466012127862371 ) ) ; -#1372 = CARTESIAN_POINT ( 'NONE', ( 36.59177244347999647, 191.2969789047999996, 106.4552055056999933 ) ) ; -#1373 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606776115838874, 137.3532831589803322, 178.0585834212922123 ) ) ; -#1374 = PLANE ( 'NONE', #10301 ) ; -#1375 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#1376 = CARTESIAN_POINT ( 'NONE', ( 37.33707104902199347, 104.0050695705055546, 184.3033154091657480 ) ) ; -#1377 = ORIENTED_EDGE ( 'NONE', *, *, #17243, .F. ) ; -#1378 = ORIENTED_EDGE ( 'NONE', *, *, #28879, .F. ) ; -#1379 = ADVANCED_FACE ( 'NONE', ( #14497 ), #20829, .T. ) ; -#1380 = CARTESIAN_POINT ( 'NONE', ( -2.614686376829999936, 209.2342314638000005, 75.76577055027999563 ) ) ; -#1381 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5159, #38906, #23579, #23790 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1382 = DIRECTION ( 'NONE', ( 0.7947985590179719173, -0.5913221741348984040, -0.1365039814779490934 ) ) ; -#1383 = CARTESIAN_POINT ( 'NONE', ( 13.51396216897000002, 163.2545600168000135, 28.07991271570000080 ) ) ; -#1384 = ORIENTED_EDGE ( 'NONE', *, *, #8405, .T. ) ; -#1385 = DIRECTION ( 'NONE', ( -0.0004161288024570960900, -0.5299192578740949955, -0.8480479980348919478 ) ) ; -#1386 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #27789, #30031 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1387 = AXIS2_PLACEMENT_3D ( 'NONE', #29828, #38600, #14284 ) ; -#1388 = VERTEX_POINT ( 'NONE', #39824 ) ; -#1389 = AXIS2_PLACEMENT_3D ( 'NONE', #20504, #13781, #4156 ) ; -#1390 = AXIS2_PLACEMENT_3D ( 'NONE', #38484, #13559, #26043 ) ; -#1391 = DIRECTION ( 'NONE', ( 0.0006039748319388572829, 3.099784637799882324E-15, 0.9999998176071847045 ) ) ; -#1392 = CARTESIAN_POINT ( 'NONE', ( -8.717675269239875870E-13, 155.6803346353160578, 98.67347229710807710 ) ) ; -#1393 = VERTEX_POINT ( 'NONE', #11842 ) ; -#1394 = CARTESIAN_POINT ( 'NONE', ( 36.23356337170621799, 191.9704930452380438, 106.3944001953638860 ) ) ; -#1395 = CARTESIAN_POINT ( 'NONE', ( -37.17455842349777129, 80.91246596882704978, 284.1870184124936145 ) ) ; -#1396 = CARTESIAN_POINT ( 'NONE', ( 4.035676231532755232, 174.7936433537611265, 102.5705385171684298 ) ) ; -#1397 = FACE_OUTER_BOUND ( 'NONE', #26232, .T. ) ; -#1398 = CARTESIAN_POINT ( 'NONE', ( -30.45076008202071804, 127.0987129668839373, 89.01436241067176525 ) ) ; -#1399 = EDGE_LOOP ( 'NONE', ( #22723, #37355, #27529, #9228 ) ) ; -#1400 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319378609011 ) ) ; -#1401 = CARTESIAN_POINT ( 'NONE', ( -30.07067142585793462, 177.4371639094459283, 100.9353481595662885 ) ) ; -#1402 = CARTESIAN_POINT ( 'NONE', ( -3.168142195203446754, 126.1261981506732468, 91.85226338672082136 ) ) ; -#1403 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24541, #24944, #15904, #34493 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1404 = ADVANCED_FACE ( 'NONE', ( #17940 ), #33282, .T. ) ; -#1405 = CARTESIAN_POINT ( 'NONE', ( -23.37153626856268218, 181.6857280266875421, 101.6124992246220842 ) ) ; -#1406 = ORIENTED_EDGE ( 'NONE', *, *, #15378, .F. ) ; -#1407 = EDGE_CURVE ( 'NONE', #5782, #38340, #24323, .T. ) ; -#1408 = ORIENTED_EDGE ( 'NONE', *, *, #14742, .F. ) ; -#1409 = CARTESIAN_POINT ( 'NONE', ( 30.02141571457803337, 185.4797026207797899, 105.5350675521475381 ) ) ; -#1410 = EDGE_CURVE ( 'NONE', #10753, #12419, #14037, .T. ) ; -#1411 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18806, #3090, #37046, #25383 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1412 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1413 = CARTESIAN_POINT ( 'NONE', ( 36.53073584806749352, 115.3012705596803613, 89.70707320453416855 ) ) ; -#1414 = CARTESIAN_POINT ( 'NONE', ( 2.462157221798171314, 209.5677243469951634, 73.55701709285500556 ) ) ; -#1415 = EDGE_CURVE ( 'NONE', #22040, #8707, #36885, .T. ) ; -#1416 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1417 = AXIS2_PLACEMENT_3D ( 'NONE', #17177, #21084, #33335 ) ; -#1418 = CARTESIAN_POINT ( 'NONE', ( 41.04644941596783525, 217.7719116456999870, 75.53371351155776381 ) ) ; -#1419 = CARTESIAN_POINT ( 'NONE', ( 25.92670928620000126, 190.7418989758000123, 106.6263904082999971 ) ) ; -#1420 = CARTESIAN_POINT ( 'NONE', ( -15.91646557088323100, 147.2350097630058201, 179.8259003790471979 ) ) ; -#1421 = CARTESIAN_POINT ( 'NONE', ( 36.04678030622115159, 205.1071296091856482, 76.08307765920791610 ) ) ; -#1422 = VERTEX_POINT ( 'NONE', #2438 ) ; -#1423 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173459745, 127.6315666250176548, 89.64029552920665367 ) ) ; -#1424 = CARTESIAN_POINT ( 'NONE', ( -28.35193061917324897, 125.4776039296643120, 88.98093332774035957 ) ) ; -#1425 = CARTESIAN_POINT ( 'NONE', ( 35.54675198585685791, 209.7096512551739238, 76.03703539298859937 ) ) ; -#1426 = CARTESIAN_POINT ( 'NONE', ( 21.44870233977301410, 176.2493420812517968, 103.4092482268179936 ) ) ; -#1427 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#1428 = ORIENTED_EDGE ( 'NONE', *, *, #173, .F. ) ; -#1429 = VERTEX_POINT ( 'NONE', #20408 ) ; -#1430 = EDGE_LOOP ( 'NONE', ( #37144, #22256, #6075, #28590, #2549, #26712, #13131, #33626, #10219, #40165, #4400, #1207, #29926 ) ) ; -#1431 = CARTESIAN_POINT ( 'NONE', ( -26.00855467233698093, 208.9309408413571987, 76.19155773393745790 ) ) ; -#1432 = PLANE ( 'NONE', #2368 ) ; -#1433 = CARTESIAN_POINT ( 'NONE', ( -2.693126113164496793, 209.6623431126212722, 73.22679707159588247 ) ) ; -#1434 = CARTESIAN_POINT ( 'NONE', ( 16.00000031304551129, 127.7446264382961232, 89.13542822417404921 ) ) ; -#1435 = ORIENTED_EDGE ( 'NONE', *, *, #9653, .T. ) ; -#1436 = ORIENTED_EDGE ( 'NONE', *, *, #2240, .F. ) ; -#1437 = CARTESIAN_POINT ( 'NONE', ( -16.49964056687395697, 137.3541725157726887, 178.0547363146727093 ) ) ; -#1438 = CARTESIAN_POINT ( 'NONE', ( -35.78508929150346773, 160.5808268139875565, 188.4031816783294744 ) ) ; -#1439 = CARTESIAN_POINT ( 'NONE', ( 20.50153854971994960, 118.8155953598612484, 89.75541792533370256 ) ) ; -#1440 = CARTESIAN_POINT ( 'NONE', ( -30.07171558059459215, 177.1876876956736169, 101.0912387261568028 ) ) ; -#1441 = CARTESIAN_POINT ( 'NONE', ( -36.09965786878999694, 116.0947685687000046, 87.39754037820000576 ) ) ; -#1442 = ORIENTED_EDGE ( 'NONE', *, *, #26926, .T. ) ; -#1443 = CARTESIAN_POINT ( 'NONE', ( -38.91441614853255260, 170.2396169009835489, 164.5533723942515394 ) ) ; -#1444 = ORIENTED_EDGE ( 'NONE', *, *, #18163, .F. ) ; -#1445 = DIRECTION ( 'NONE', ( -0.0005884949961184506983, 0.2249510543501584692, -0.9743698870656828381 ) ) ; -#1446 = CARTESIAN_POINT ( 'NONE', ( -23.00127433123727982, 118.1131156702009548, 87.78148031792997585 ) ) ; -#1447 = LINE ( 'NONE', #13933, #1932 ) ; -#1448 = CARTESIAN_POINT ( 'NONE', ( -12.63866240555081255, 181.1745339601329476, 104.4280621927508008 ) ) ; -#1449 = ORIENTED_EDGE ( 'NONE', *, *, #10745, .T. ) ; -#1450 = CARTESIAN_POINT ( 'NONE', ( -2.088909101511000177, 189.3888656793000109, 103.5213134137000139 ) ) ; -#1451 = CARTESIAN_POINT ( 'NONE', ( 25.49191818104053198, 208.7356988742139663, 75.68967923392696662 ) ) ; -#1452 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#1453 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#1454 = VERTEX_POINT ( 'NONE', #20202 ) ; -#1455 = EDGE_CURVE ( 'NONE', #31222, #12675, #9615, .T. ) ; -#1456 = ORIENTED_EDGE ( 'NONE', *, *, #6142, .T. ) ; -#1457 = CARTESIAN_POINT ( 'NONE', ( -20.00089539691495233, 118.1272453392662527, 87.27993277136866368 ) ) ; -#1458 = DIRECTION ( 'NONE', ( 0.0006039748319385504537, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#1459 = EDGE_CURVE ( 'NONE', #34038, #4088, #29684, .T. ) ; -#1460 = ORIENTED_EDGE ( 'NONE', *, *, #23387, .T. ) ; -#1461 = ORIENTED_EDGE ( 'NONE', *, *, #21562, .T. ) ; -#1462 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16618, #31987, #7220, #16424 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 4.318577332577606880E-07, 6.344312035917670865E-05 ), - .UNSPECIFIED. ) ; -#1463 = ORIENTED_EDGE ( 'NONE', *, *, #35373, .T. ) ; -#1464 = ORIENTED_EDGE ( 'NONE', *, *, #30144, .F. ) ; -#1465 = ADVANCED_FACE ( 'NONE', ( #1609 ), #1817, .F. ) ; -#1466 = CARTESIAN_POINT ( 'NONE', ( -28.25571791307000069, 186.4543155771000045, 105.2821207260000023 ) ) ; -#1467 = CARTESIAN_POINT ( 'NONE', ( 37.96499143901794326, 190.9636352903536363, 106.2831835502989719 ) ) ; -#1468 = CARTESIAN_POINT ( 'NONE', ( 16.16445611536306259, 152.0055496971487514, 180.9366119946107858 ) ) ; -#1469 = ORIENTED_EDGE ( 'NONE', *, *, #34319, .F. ) ; -#1470 = DIRECTION ( 'NONE', ( 0.6087613505916679157, -0.7729391288194348286, -0.1788147677504891564 ) ) ; -#1471 = AXIS2_PLACEMENT_3D ( 'NONE', #11355, #23842, #8300 ) ; -#1472 = ORIENTED_EDGE ( 'NONE', *, *, #10336, .T. ) ; -#1473 = CARTESIAN_POINT ( 'NONE', ( 25.83309271880579416, 120.1166353669539291, 90.25644155803026081 ) ) ; -#1474 = CARTESIAN_POINT ( 'NONE', ( -26.00831778362747215, 205.1071295951792592, 76.12055741643118267 ) ) ; -#1475 = VECTOR ( 'NONE', #12424, 1000.000000000000114 ) ; -#1477 = CARTESIAN_POINT ( 'NONE', ( -42.99989013480271183, 189.1985352993988556, 106.4377309217844072 ) ) ; -#1476 = CARTESIAN_POINT ( 'NONE', ( -12.63633279611100591, 183.4482084008280367, 105.0918242824060513 ) ) ; -#1478 = ORIENTED_EDGE ( 'NONE', *, *, #31513, .T. ) ; -#1479 = EDGE_CURVE ( 'NONE', #12315, #13881, #31051, .T. ) ; -#1480 = AXIS2_PLACEMENT_3D ( 'NONE', #13691, #38029, #10638 ) ; -#1481 = ORIENTED_EDGE ( 'NONE', *, *, #30432, .F. ) ; -#1482 = CARTESIAN_POINT ( 'NONE', ( -36.03459587967929423, 192.0647978141948897, 104.4267888369482904 ) ) ; -#1483 = CARTESIAN_POINT ( 'NONE', ( 25.50924446128380296, 191.7417201544551517, 104.3989876494856190 ) ) ; -#1484 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25659, #37908, #16020, #7215 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1485 = ORIENTED_EDGE ( 'NONE', *, *, #7914, .T. ) ; -#1486 = CARTESIAN_POINT ( 'NONE', ( -35.57348742053811463, 114.4243515753128975, 87.28926978703593420 ) ) ; -#1487 = CARTESIAN_POINT ( 'NONE', ( -46.27971317312926658, 126.2404065528360775, 91.90467990004428600 ) ) ; -#1488 = LINE ( 'NONE', #36449, #22201 ) ; -#1489 = EDGE_LOOP ( 'NONE', ( #30427, #7866, #24975, #16004 ) ) ; -#1490 = EDGE_CURVE ( 'NONE', #18185, #26876, #25780, .T. ) ; -#1491 = ORIENTED_EDGE ( 'NONE', *, *, #4941, .F. ) ; -#1492 = CARTESIAN_POINT ( 'NONE', ( -12.63608108984827183, 177.6170740679187077, 100.8143728218807240 ) ) ; -#1493 = CARTESIAN_POINT ( 'NONE', ( -23.36111095637491886, 134.5088611855341583, 93.57062850653878172 ) ) ; -#1494 = VERTEX_POINT ( 'NONE', #11419 ) ; -#1495 = LINE ( 'NONE', #8037, #29155 ) ; -#1496 = CONICAL_SURFACE ( 'NONE', #11973, 2.500003536218122768, 0.7853981633752317171 ) ; -#1497 = VERTEX_POINT ( 'NONE', #8570 ) ; -#1498 = ADVANCED_FACE ( 'NONE', ( #36367 ), #27095, .T. ) ; -#1499 = LINE ( 'NONE', #2129, #12435 ) ; -#1500 = EDGE_CURVE ( 'NONE', #4088, #29586, #14709, .T. ) ; -#1501 = EDGE_LOOP ( 'NONE', ( #35487, #27362, #37177, #36310 ) ) ; -#1502 = CARTESIAN_POINT ( 'NONE', ( 39.17245388525562788, 118.9831901207053022, 89.68900349796480498 ) ) ; -#1503 = CIRCLE ( 'NONE', #37425, 4.500000000025920599 ) ; -#1504 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825866425532276, 0.0005734119036248240715 ) ) ; -#1505 = CARTESIAN_POINT ( 'NONE', ( -41.44647100807553386, 120.2182348193094015, 89.99828044825905238 ) ) ; -#1506 = CARTESIAN_POINT ( 'NONE', ( 44.64373491923319648, 189.2041368418193201, 103.8203288493235164 ) ) ; -#1507 = ORIENTED_EDGE ( 'NONE', *, *, #34488, .F. ) ; -#1508 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 67.27946979429630403, 312.5857197240632104 ) ) ; -#1509 = CARTESIAN_POINT ( 'NONE', ( 15.50147166113565866, 173.9550007122092836, 102.3699975097636496 ) ) ; -#1510 = CARTESIAN_POINT ( 'NONE', ( 3.046672840550818329, 207.8686389444351050, 77.27521480614490201 ) ) ; -#1511 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19835, #22944, #16782, #32343 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1512 = ORIENTED_EDGE ( 'NONE', *, *, #40323, .F. ) ; -#1513 = DIRECTION ( 'NONE', ( -0.0005884949961251572477, 0.2249510543439052768, -0.9743698870671265722 ) ) ; -#1515 = CARTESIAN_POINT ( 'NONE', ( -38.20586753382468004, 218.5902260770999987, 73.08157946901140178 ) ) ; -#1514 = FACE_OUTER_BOUND ( 'NONE', #31287, .T. ) ; -#1516 = ORIENTED_EDGE ( 'NONE', *, *, #3159, .T. ) ; -#1517 = EDGE_CURVE ( 'NONE', #39006, #20649, #2256, .T. ) ; -#1518 = CIRCLE ( 'NONE', #24417, 2.250000000000011102 ) ; -#1519 = VERTEX_POINT ( 'NONE', #21455 ) ; -#1520 = CARTESIAN_POINT ( 'NONE', ( -27.19780697399936642, 110.6131156702000027, 87.78421117711411625 ) ) ; -#1521 = CARTESIAN_POINT ( 'NONE', ( 36.46845686390152252, 264.8832191855225915, 206.0097772883433720 ) ) ; -#1522 = CARTESIAN_POINT ( 'NONE', ( 37.96499143901794326, 190.9636352903536363, 106.2831835502989719 ) ) ; -#1523 = CARTESIAN_POINT ( 'NONE', ( 39.05501141534195853, 128.0727083965270197, 89.71040118434773092 ) ) ; -#1525 = VERTEX_POINT ( 'NONE', #5890 ) ; -#1524 = CIRCLE ( 'NONE', #33519, 2.499999999952864371 ) ; -#1526 = ORIENTED_EDGE ( 'NONE', *, *, #39576, .T. ) ; -#1527 = FACE_OUTER_BOUND ( 'NONE', #35468, .T. ) ; -#1528 = ORIENTED_EDGE ( 'NONE', *, *, #16494, .T. ) ; -#1529 = ORIENTED_EDGE ( 'NONE', *, *, #23163, .F. ) ; -#1530 = CARTESIAN_POINT ( 'NONE', ( 30.50895605381732523, 153.0051697192226641, 335.7848420411070833 ) ) ; -#1531 = CIRCLE ( 'NONE', #18508, 2.500000000021232349 ) ; -#1532 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8807, #35971, #14532, #21073 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 2.072238197984719300E-05, 0.0007937364710496124746 ), - .UNSPECIFIED. ) ; -#1533 = CARTESIAN_POINT ( 'NONE', ( 39.61232211476462339, 114.7578009829419159, 151.0282930554255927 ) ) ; -#1534 = CARTESIAN_POINT ( 'NONE', ( 34.04100125716845326, 108.7218726133717723, 175.0403703967984939 ) ) ; -#1535 = ORIENTED_EDGE ( 'NONE', *, *, #38424, .T. ) ; -#1536 = EDGE_CURVE ( 'NONE', #16952, #10330, #21239, .T. ) ; -#1537 = VERTEX_POINT ( 'NONE', #40224 ) ; -#1538 = CARTESIAN_POINT ( 'NONE', ( -20.47540048824957992, 211.0902980118789571, 75.61425432729411966 ) ) ; -#1539 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772234801672, 136.6775772631780796, 180.9814965275865575 ) ) ; -#1540 = CARTESIAN_POINT ( 'NONE', ( 37.52439582013000319, 118.3551633538000090, 87.34611301001000072 ) ) ; -#1541 = CARTESIAN_POINT ( 'NONE', ( 36.36513335903000410, 191.2465653387999964, 103.6487651568999979 ) ) ; -#1542 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19208, #612, #38031, #10030 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1543 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -5.029098237799274788E-18, 0.0006039748319384018096 ) ) ; -#1544 = EDGE_CURVE ( 'NONE', #33925, #27579, #34001, .T. ) ; -#1545 = CARTESIAN_POINT ( 'NONE', ( -22.83746502234654940, 149.9685939482776007, 190.2127349222744783 ) ) ; -#1546 = ORIENTED_EDGE ( 'NONE', *, *, #39115, .T. ) ; -#1547 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452352341, 0.1781166614240801416 ) ) ; -#1548 = FACE_OUTER_BOUND ( 'NONE', #1751, .T. ) ; -#1549 = CYLINDRICAL_SURFACE ( 'NONE', #11742, 2.000000000000000444 ) ; -#1550 = ORIENTED_EDGE ( 'NONE', *, *, #8651, .T. ) ; -#1551 = CARTESIAN_POINT ( 'NONE', ( -42.72903334360638894, 77.14301703112133168, 281.5709244913558109 ) ) ; -#1552 = DIRECTION ( 'NONE', ( -0.0005884949961215159547, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#1553 = ADVANCED_FACE ( 'NONE', ( #27790 ), #160, .T. ) ; -#1554 = CARTESIAN_POINT ( 'NONE', ( 38.11757776978107159, 119.1971814748143146, 87.25517274288121428 ) ) ; -#1555 = EDGE_CURVE ( 'NONE', #20125, #31008, #12620, .T. ) ; -#1556 = CARTESIAN_POINT ( 'NONE', ( 45.03146303534695960, 186.3613416546399719, 106.7606159694749408 ) ) ; -#1557 = ADVANCED_FACE ( 'NONE', ( #36764 ), #8979, .T. ) ; -#1558 = ORIENTED_EDGE ( 'NONE', *, *, #10939, .F. ) ; -#1559 = CARTESIAN_POINT ( 'NONE', ( 37.68445503166663713, 212.3970731212107239, 28.08071801548966562 ) ) ; -#1560 = ADVANCED_FACE ( 'NONE', ( #15691 ), #3413, .F. ) ; -#1561 = CARTESIAN_POINT ( 'NONE', ( 1.762914848455207739, 189.4001637137704677, 103.7992039644048106 ) ) ; -#1562 = CIRCLE ( 'NONE', #30942, 22.50000000000000000 ) ; -#1563 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#1564 = ORIENTED_EDGE ( 'NONE', *, *, #11161, .F. ) ; -#1565 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#1566 = AXIS2_PLACEMENT_3D ( 'NONE', #26387, #23112, #16547 ) ; -#1567 = CARTESIAN_POINT ( 'NONE', ( -26.12781411639000240, 191.8675859534999972, 103.7979175393000162 ) ) ; -#1568 = CARTESIAN_POINT ( 'NONE', ( -5.960622341254478762, 149.1452448442896923, 94.08941484461983862 ) ) ; -#1569 = CARTESIAN_POINT ( 'NONE', ( 17.36823235697561074, 148.6268409572465430, 177.2656691734900107 ) ) ; -#1570 = CIRCLE ( 'NONE', #28985, 6.000000000011024071 ) ; -#1571 = CARTESIAN_POINT ( 'NONE', ( -30.06407784565124430, 177.7873364699197793, 100.7165267053679969 ) ) ; -#1572 = ORIENTED_EDGE ( 'NONE', *, *, #26073, .F. ) ; -#1573 = LINE ( 'NONE', #10791, #6311 ) ; -#1574 = EDGE_CURVE ( 'NONE', #9665, #468, #27993, .T. ) ; -#1575 = CARTESIAN_POINT ( 'NONE', ( 37.42082352723856076, 132.6200669550715929, 336.9739440566017379 ) ) ; -#1576 = CARTESIAN_POINT ( 'NONE', ( 17.99676327751897276, 132.8602135917374767, 90.82840093797520353 ) ) ; -#1577 = CARTESIAN_POINT ( 'NONE', ( 5.667003785789049175, 181.2013499400138130, 104.4023232969187944 ) ) ; -#1578 = CARTESIAN_POINT ( 'NONE', ( 38.05634169542999956, 191.1278539811999906, 106.1815489157999934 ) ) ; -#1579 = CARTESIAN_POINT ( 'NONE', ( 31.01176814742588661, 177.6154148053649351, 100.6399422860269937 ) ) ; -#1580 = DIRECTION ( 'NONE', ( 0.0006039748319383107366, 1.234791622901071989E-14, 0.9999998176071845934 ) ) ; -#1581 = LINE ( 'NONE', #35700, #10853 ) ; -#1582 = ORIENTED_EDGE ( 'NONE', *, *, #38078, .F. ) ; -#1583 = CIRCLE ( 'NONE', #9516, 1.749999999975493381 ) ; -#1584 = CARTESIAN_POINT ( 'NONE', ( 26.84904664283360276, 120.0929502244215428, 171.5090809722007350 ) ) ; -#1585 = CIRCLE ( 'NONE', #14688, 59.40509898896999630 ) ; -#1586 = LINE ( 'NONE', #5051, #18350 ) ; -#1587 = AXIS2_PLACEMENT_3D ( 'NONE', #1248, #25620, #25824 ) ; -#1588 = EDGE_CURVE ( 'NONE', #26442, #6684, #12427, .T. ) ; -#1589 = CARTESIAN_POINT ( 'NONE', ( -17.34531841451655509, 148.6239897228831239, 177.2780028082611068 ) ) ; -#1590 = ORIENTED_EDGE ( 'NONE', *, *, #27546, .F. ) ; -#1591 = FACE_OUTER_BOUND ( 'NONE', #1961, .T. ) ; -#1592 = CONICAL_SURFACE ( 'NONE', #2254, 5.999999999897309699, 0.7853981633778843729 ) ; -#1593 = DIRECTION ( 'NONE', ( 1.249000902683486815E-14, 0.9743700557921588512, 0.2249510932971550692 ) ) ; -#1594 = EDGE_LOOP ( 'NONE', ( #10058, #4390, #33919, #16483 ) ) ; -#1595 = EDGE_CURVE ( 'NONE', #38340, #39475, #24727, .T. ) ; -#1596 = CARTESIAN_POINT ( 'NONE', ( -16.04815223297914528, 152.0446744236089671, 184.5300512474807704 ) ) ; -#1597 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971551247 ) ) ; -#1598 = VERTEX_POINT ( 'NONE', #9572 ) ; -#1599 = CARTESIAN_POINT ( 'NONE', ( 36.30316923674414653, 191.8403127940163415, 106.3905535285534683 ) ) ; -#1600 = ADVANCED_FACE ( 'NONE', ( #30646 ), #21650, .T. ) ; -#1601 = CARTESIAN_POINT ( 'NONE', ( 20.00000522920557700, 138.5176112521621690, 91.62015419223651236 ) ) ; -#1602 = CYLINDRICAL_SURFACE ( 'NONE', #2883, 2.000000000000014655 ) ; -#1603 = CARTESIAN_POINT ( 'NONE', ( -12.63048181974366990, 130.3451622633888576, 92.83206449613362565 ) ) ; -#1604 = LINE ( 'NONE', #23484, #11780 ) ; -#1605 = DIRECTION ( 'NONE', ( -0.0005884949961234174284, 0.2249510543439059151, -0.9743698870671263501 ) ) ; -#1606 = ADVANCED_FACE ( 'NONE', ( #9371 ), #36921, .F. ) ; -#1607 = ORIENTED_EDGE ( 'NONE', *, *, #40327, .T. ) ; -#1608 = CARTESIAN_POINT ( 'NONE', ( 17.25779205791675253, 152.0580948532353034, 184.5595410583348439 ) ) ; -#1609 = FACE_OUTER_BOUND ( 'NONE', #9086, .T. ) ; -#1610 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1611 = ORIENTED_EDGE ( 'NONE', *, *, #16778, .T. ) ; -#1612 = CARTESIAN_POINT ( 'NONE', ( -25.49734528616909301, 118.8155664120999973, 94.28318532642107641 ) ) ; -#1613 = VERTEX_POINT ( 'NONE', #2642 ) ; -#1614 = LINE ( 'NONE', #26374, #40113 ) ; -#1615 = AXIS2_PLACEMENT_3D ( 'NONE', #20107, #23598, #24012 ) ; -#1616 = CARTESIAN_POINT ( 'NONE', ( 21.44693881909371669, 176.9241929811547038, 100.4861407201621120 ) ) ; -#1617 = DIRECTION ( 'NONE', ( -0.8142022563027235815, 0.000000000000000000, -0.5805813343809409499 ) ) ; -#1618 = AXIS2_PLACEMENT_3D ( 'NONE', #19511, #7436, #10136 ) ; -#1619 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; -#1620 = AXIS2_PLACEMENT_3D ( 'NONE', #18712, #36952, #8747 ) ; -#1621 = CARTESIAN_POINT ( 'NONE', ( 8.271042397109361843, 124.3676236163658899, 88.36049928470526993 ) ) ; -#1622 = CARTESIAN_POINT ( 'NONE', ( 25.38728234211000157, 191.0564470040000060, 106.1766889295000169 ) ) ; -#1623 = LINE ( 'NONE', #1420, #30995 ) ; -#1624 = CARTESIAN_POINT ( 'NONE', ( 3.293163761662359690, 183.3573071469507454, 101.9823041688293301 ) ) ; -#1625 = ORIENTED_EDGE ( 'NONE', *, *, #24351, .F. ) ; -#1626 = CARTESIAN_POINT ( 'NONE', ( 16.38737785140941483, 122.7247190552318585, 172.1149118660857766 ) ) ; -#1627 = FACE_OUTER_BOUND ( 'NONE', #17426, .T. ) ; -#1628 = CARTESIAN_POINT ( 'NONE', ( 18.98506067126258046, 148.2070439170772431, 184.7168109706149721 ) ) ; -#1629 = DIRECTION ( 'NONE', ( 0.0006039748319371618076, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#1631 = VERTEX_POINT ( 'NONE', #34093 ) ; -#1630 = CARTESIAN_POINT ( 'NONE', ( -48.01998785487717214, 140.9756894717409921, 337.4478224868454390 ) ) ; -#1632 = ORIENTED_EDGE ( 'NONE', *, *, #7968, .T. ) ; -#1633 = VERTEX_POINT ( 'NONE', #34286 ) ; -#1634 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #1014, #19805, #4275, #29244 ), - ( #13698, #4479, #26790, #8383 ), - ( #24339, #33705, #23926, #30664 ), - ( #23712, #24125, #15126, #17552 ), - ( #23505, #35950, #2246, #30056 ), - ( #14514, #20423, #26997, #17755 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 4 ), - ( 4, 4 ), - ( -0.4155779329647000253, 0.000000000000000000, 1.000000000000000000, 1.415577932946999962 ), - ( -2.649034374246999819E-06, 1.000000498574000085 ), - .UNSPECIFIED. ) ; -#1635 = ORIENTED_EDGE ( 'NONE', *, *, #21232, .T. ) ; -#1636 = DIRECTION ( 'NONE', ( -0.0005884949961222158072, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#1637 = EDGE_CURVE ( 'NONE', #1066, #6048, #15476, .T. ) ; -#1638 = EDGE_CURVE ( 'NONE', #29169, #315, #15885, .T. ) ; -#1639 = DIRECTION ( 'NONE', ( -0.0005884949961259294164, 0.2255194585872565272, -0.9742384859325513569 ) ) ; -#1640 = CARTESIAN_POINT ( 'NONE', ( 5.666479358130328770, 124.0060029548555747, 91.08908426695600724 ) ) ; -#1641 = EDGE_CURVE ( 'NONE', #16629, #28767, #11431, .T. ) ; -#1642 = EDGE_CURVE ( 'NONE', #27747, #26044, #969, .T. ) ; -#1643 = EDGE_LOOP ( 'NONE', ( #39936, #1550, #8615, #26290 ) ) ; -#1644 = VECTOR ( 'NONE', #26638, 1000.000000000000114 ) ; -#1645 = CARTESIAN_POINT ( 'NONE', ( -39.38652048934942940, 144.7445250280709388, 291.5823324066636815 ) ) ; -#1646 = CARTESIAN_POINT ( 'NONE', ( -38.89126635191712467, 161.9501278596379450, 193.0760327218276871 ) ) ; -#1647 = CARTESIAN_POINT ( 'NONE', ( 13.00945118851879201, 131.0224190692395041, 89.89397262767793961 ) ) ; -#1648 = CARTESIAN_POINT ( 'NONE', ( 20.33240943743538054, 194.1236379049751406, 102.8213690648429548 ) ) ; -#1649 = AXIS2_PLACEMENT_3D ( 'NONE', #49, #31942, #3106 ) ; -#1650 = VECTOR ( 'NONE', #23242, 1000.000000000000227 ) ; -#1651 = CARTESIAN_POINT ( 'NONE', ( -35.29591335509000771, 113.4357239256000014, 87.14400150545999679 ) ) ; -#1652 = ORIENTED_EDGE ( 'NONE', *, *, #4773, .T. ) ; -#1653 = AXIS2_PLACEMENT_3D ( 'NONE', #11224, #26369, #25973 ) ; -#1654 = EDGE_CURVE ( 'NONE', #11739, #21377, #31707, .T. ) ; -#1655 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; -#1656 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11659, #30471, #33312, #33107 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1657 = ORIENTED_EDGE ( 'NONE', *, *, #24759, .T. ) ; -#1658 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; -#1659 = CARTESIAN_POINT ( 'NONE', ( 5.669252811192786012, 130.1726803172889788, 92.54178110873570517 ) ) ; -#1660 = DIRECTION ( 'NONE', ( 0.0006039748319383109534, 1.233022124494217175E-14, 0.9999998176071845934 ) ) ; -#1661 = DIRECTION ( 'NONE', ( 0.0005884949961230158400, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1662 = ADVANCED_FACE ( 'NONE', ( #6681 ), #7285, .T. ) ; -#1663 = VERTEX_POINT ( 'NONE', #16688 ) ; -#1664 = CARTESIAN_POINT ( 'NONE', ( -1.066844550517989987, 188.6634431852420164, 103.2086216232000027 ) ) ; -#1665 = CARTESIAN_POINT ( 'NONE', ( 0.5626216234312498843, 189.0102564277180477, 103.6972895962819763 ) ) ; -#1666 = CARTESIAN_POINT ( 'NONE', ( 26.00516268442190793, 120.3264862181168269, 90.49568530838079994 ) ) ; -#1667 = VERTEX_POINT ( 'NONE', #25729 ) ; -#1668 = ORIENTED_EDGE ( 'NONE', *, *, #3138, .T. ) ; -#1669 = CARTESIAN_POINT ( 'NONE', ( -19.73768723704201378, 124.3505960279316014, 178.1528323905962452 ) ) ; -#1670 = CARTESIAN_POINT ( 'NONE', ( 2.561557522426483491, 191.9759150222000130, 101.9199002238076162 ) ) ; -#1671 = ORIENTED_EDGE ( 'NONE', *, *, #18153, .T. ) ; -#1672 = ORIENTED_EDGE ( 'NONE', *, *, #35442, .F. ) ; -#1673 = EDGE_CURVE ( 'NONE', #28941, #31885, #10125, .T. ) ; -#1674 = ORIENTED_EDGE ( 'NONE', *, *, #28442, .T. ) ; -#1675 = LINE ( 'NONE', #34979, #25682 ) ; -#1676 = CONICAL_SURFACE ( 'NONE', #15486, 2.502997276898424772, 0.7853981634249621591 ) ; -#1677 = ORIENTED_EDGE ( 'NONE', *, *, #29348, .F. ) ; -#1678 = CARTESIAN_POINT ( 'NONE', ( -26.88272198619890929, 189.0093189843405810, 103.3053996347941563 ) ) ; -#1679 = VECTOR ( 'NONE', #1020, 1000.000000000000114 ) ; -#1680 = CARTESIAN_POINT ( 'NONE', ( -27.86327580912480073, 186.6948185159119760, 105.3339871752620240 ) ) ; -#1681 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#1682 = VECTOR ( 'NONE', #5234, 1000.000000000000227 ) ; -#1683 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700556569576676, 0.2249510938827756212 ) ) ; -#1684 = CARTESIAN_POINT ( 'NONE', ( 33.79593125840131762, 218.5902260770999987, 76.03809273397367008 ) ) ; -#1685 = AXIS2_PLACEMENT_3D ( 'NONE', #34781, #19251, #31761 ) ; -#1686 = ORIENTED_EDGE ( 'NONE', *, *, #13023, .T. ) ; -#1687 = AXIS2_PLACEMENT_3D ( 'NONE', #27779, #11623, #27387 ) ; -#1688 = CARTESIAN_POINT ( 'NONE', ( 27.65192971970000002, 123.9789225586000043, 91.33799792313000410 ) ) ; -#1689 = CARTESIAN_POINT ( 'NONE', ( -15.10714331244187214, 129.6097141051087362, 89.58480571958619976 ) ) ; -#1691 = CARTESIAN_POINT ( 'NONE', ( -30.06407784565124430, 177.7873364699197793, 100.7165267053679969 ) ) ; -#1690 = CARTESIAN_POINT ( 'NONE', ( 20.48207276949980127, 207.8589230177659601, 76.36517592881708083 ) ) ; -#1692 = ORIENTED_EDGE ( 'NONE', *, *, #687, .F. ) ; -#1693 = CYLINDRICAL_SURFACE ( 'NONE', #148, 2.000000000000001332 ) ; -#1694 = ORIENTED_EDGE ( 'NONE', *, *, #9777, .T. ) ; -#1695 = CARTESIAN_POINT ( 'NONE', ( -36.00652865386367552, 192.1144112819058023, 104.4280603975805235 ) ) ; -#1696 = DIRECTION ( 'NONE', ( -0.5668486650917774483, -0.8238218701100766816, 0.0003423623896884662554 ) ) ; -#1697 = EDGE_CURVE ( 'NONE', #9728, #723, #23856, .T. ) ; -#1698 = ADVANCED_FACE ( 'NONE', ( #17489 ), #29581, .F. ) ; -#1699 = VERTEX_POINT ( 'NONE', #4817 ) ; -#1700 = LINE ( 'NONE', #36026, #20439 ) ; -#1701 = CYLINDRICAL_SURFACE ( 'NONE', #37611, 1.999999999999996891 ) ; -#1702 = DIRECTION ( 'NONE', ( -0.0005884949961247390709, 0.2249510543439058041, -0.9743698870671265722 ) ) ; -#1703 = CARTESIAN_POINT ( 'NONE', ( 39.06422788861904394, 183.0561992322088543, 104.9700959750892366 ) ) ; -#1704 = CARTESIAN_POINT ( 'NONE', ( 36.42052453417999658, 191.8205691569000066, 104.3714196691999945 ) ) ; -#1705 = ORIENTED_EDGE ( 'NONE', *, *, #24149, .T. ) ; -#1706 = ORIENTED_EDGE ( 'NONE', *, *, #7178, .F. ) ; -#1707 = CARTESIAN_POINT ( 'NONE', ( -12.63072017624268106, 177.7897717398484474, 100.7065154983451407 ) ) ; -#1708 = CARTESIAN_POINT ( 'NONE', ( -59.73339157710076819, 246.2640820602804013, 199.3617278787578755 ) ) ; -#1709 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16202, #9892, #35192, #31965 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1710 = CIRCLE ( 'NONE', #8248, 2.249999999984614973 ) ; -#1711 = VECTOR ( 'NONE', #27959, 1000.000000000000227 ) ; -#1712 = CARTESIAN_POINT ( 'NONE', ( 15.83961671131613613, 186.7686801668171483, 102.7623040876351723 ) ) ; -#1713 = ORIENTED_EDGE ( 'NONE', *, *, #1798, .T. ) ; -#1714 = CARTESIAN_POINT ( 'NONE', ( -48.18209110666130357, 82.27946979429619034, 302.5876467172398634 ) ) ; -#1715 = VECTOR ( 'NONE', #11009, 1000.000000000000227 ) ; -#1716 = AXIS2_PLACEMENT_3D ( 'NONE', #6774, #18833, #34571 ) ; -#1717 = CARTESIAN_POINT ( 'NONE', ( 3.064242058871999852, 190.8511667218000127, 106.7914563315000009 ) ) ; -#1718 = ORIENTED_EDGE ( 'NONE', *, *, #7086, .T. ) ; -#1719 = CARTESIAN_POINT ( 'NONE', ( -40.98386719339310957, 220.4002260739994199, 28.08353656469164150 ) ) ; -#1720 = ADVANCED_FACE ( 'NONE', ( #23651 ), #9482, .F. ) ; -#1721 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971519328 ) ) ; -#1722 = CARTESIAN_POINT ( 'NONE', ( 20.00028792540915035, 151.9820690596619102, 94.72877128701482263 ) ) ; -#1723 = VERTEX_POINT ( 'NONE', #23445 ) ; -#1724 = CARTESIAN_POINT ( 'NONE', ( 3.534086375177905914, 137.3581944094399603, 91.36238397499714381 ) ) ; -#1725 = CARTESIAN_POINT ( 'NONE', ( 28.46393509241999809, 182.0672870804658601, 102.1824291493838359 ) ) ; -#1726 = VERTEX_POINT ( 'NONE', #20360 ) ; -#1727 = CONICAL_SURFACE ( 'NONE', #414, 5.250000000012863488, 0.7853981634080012819 ) ; -#1728 = FACE_OUTER_BOUND ( 'NONE', #19275, .T. ) ; -#1729 = AXIS2_PLACEMENT_3D ( 'NONE', #17464, #8496, #30162 ) ; -#1730 = AXIS2_PLACEMENT_3D ( 'NONE', #35295, #32460, #17094 ) ; -#1732 = CARTESIAN_POINT ( 'NONE', ( 13.46612284730906950, 158.3062971533392158, 96.19268454968825210 ) ) ; -#1731 = DIRECTION ( 'NONE', ( -0.6087613503636615242, -0.7731003948486159238, -0.1781162479627431405 ) ) ; -#1733 = EDGE_LOOP ( 'NONE', ( #25016, #28531, #11838, #826, #10425, #31844, #3411, #24731 ) ) ; -#1734 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1735 = ORIENTED_EDGE ( 'NONE', *, *, #20374, .F. ) ; -#1736 = LINE ( 'NONE', #23413, #17276 ) ; -#1737 = CARTESIAN_POINT ( 'NONE', ( 37.20222003302175295, 191.1065312683467994, 106.3012689043733729 ) ) ; -#1738 = VECTOR ( 'NONE', #1349, 1000.000000000000227 ) ; -#1739 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178539432571E-05, -0.0002331579774923554001 ) ) ; -#1740 = ADVANCED_FACE ( 'NONE', ( #2186 ), #32835, .T. ) ; -#1741 = EDGE_LOOP ( 'NONE', ( #19569, #17634, #19280, #10149 ) ) ; -#1742 = EDGE_CURVE ( 'NONE', #10482, #24364, #33640, .T. ) ; -#1743 = EDGE_LOOP ( 'NONE', ( #26143, #15422, #26768, #25960 ) ) ; -#1744 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001011, 118.9382625071999939, 90.21260570929000266 ) ) ; -#1745 = ORIENTED_EDGE ( 'NONE', *, *, #25624, .F. ) ; -#1746 = VERTEX_POINT ( 'NONE', #26936 ) ; -#1747 = ORIENTED_EDGE ( 'NONE', *, *, #37374, .T. ) ; -#1748 = CARTESIAN_POINT ( 'NONE', ( -76.10925030609094222, 156.2403276578085354, 96.28296423947058713 ) ) ; -#1749 = CARTESIAN_POINT ( 'NONE', ( 2.711028262986999948, 208.9737165866999931, 73.44859440743999812 ) ) ; -#1750 = CARTESIAN_POINT ( 'NONE', ( -15.74985326587000145, 145.0241313536000121, 93.40046917799001847 ) ) ; -#1751 = EDGE_LOOP ( 'NONE', ( #22994, #11975, #15487, #4511 ) ) ; -#1752 = DIRECTION ( 'NONE', ( -0.6087614115774880874, -0.7729348350621346730, -0.1788331191967951483 ) ) ; -#1753 = CARTESIAN_POINT ( 'NONE', ( -36.08413483559999690, 192.4673174437999990, 104.5417621097000165 ) ) ; -#1754 = CARTESIAN_POINT ( 'NONE', ( 36.48506658101999989, 191.6574214057999939, 104.2272696579999973 ) ) ; -#1755 = CARTESIAN_POINT ( 'NONE', ( -25.50167171021992729, 120.6339921492297691, 88.03071599454854379 ) ) ; -#1756 = EDGE_LOOP ( 'NONE', ( #9880, #9265, #18210, #21821 ) ) ; -#1757 = CARTESIAN_POINT ( 'NONE', ( 22.78039439248025388, 158.5567501843645175, 96.58697503864370049 ) ) ; -#1758 = LINE ( 'NONE', #35462, #17587 ) ; -#1759 = EDGE_LOOP ( 'NONE', ( #24890, #13185, #25553, #34734 ) ) ; -#1760 = CIRCLE ( 'NONE', #40278, 40.49999999999691624 ) ; -#1761 = CARTESIAN_POINT ( 'NONE', ( -6.036405711824646581, 134.8430548843712131, 93.35330002513178727 ) ) ; -#1762 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#1763 = VECTOR ( 'NONE', #5679, 1000.000000000000114 ) ; -#1764 = CARTESIAN_POINT ( 'NONE', ( -20.68588240384768540, 105.5805168953082926, 90.28027859384218345 ) ) ; -#1765 = FACE_OUTER_BOUND ( 'NONE', #17434, .T. ) ; -#1766 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #24992, #16165, #13109, #15953 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.841034667652916568, 4.841107087194696845 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999995629507143, 0.9999999995629507143, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#1767 = AXIS2_PLACEMENT_3D ( 'NONE', #1939, #5398, #36891 ) ; -#1768 = ORIENTED_EDGE ( 'NONE', *, *, #251, .F. ) ; -#1769 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425095181, 127.0691889891074879, 92.07622024688510010 ) ) ; -#1770 = CARTESIAN_POINT ( 'NONE', ( 1.556177609192770150, 189.2631122045734458, 103.7597856918706043 ) ) ; -#1771 = CARTESIAN_POINT ( 'NONE', ( 30.39613569156224315, 134.9224406131777982, 90.78386258933660713 ) ) ; -#1772 = VECTOR ( 'NONE', #18026, 1000.000000000000227 ) ; -#1773 = ORIENTED_EDGE ( 'NONE', *, *, #29619, .T. ) ; -#1774 = DIRECTION ( 'NONE', ( -0.7933533411653076461, -0.5931840316265235558, -0.1368326740407657394 ) ) ; -#1775 = ORIENTED_EDGE ( 'NONE', *, *, #30553, .T. ) ; -#1776 = ORIENTED_EDGE ( 'NONE', *, *, #3338, .T. ) ; -#1777 = CARTESIAN_POINT ( 'NONE', ( -26.12781721057000084, 191.8495054948000131, 103.7969297097000094 ) ) ; -#1778 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825791858209745, 0.0005734119053476003985 ) ) ; -#1779 = CARTESIAN_POINT ( 'NONE', ( -20.07746641892443407, 128.4445336449384740, 89.31880444343536851 ) ) ; -#1780 = CYLINDRICAL_SURFACE ( 'NONE', #38877, 1.999999999999999112 ) ; -#1781 = ORIENTED_EDGE ( 'NONE', *, *, #23518, .F. ) ; -#1782 = ADVANCED_FACE ( 'NONE', ( #8316 ), #20556, .T. ) ; -#1783 = DIRECTION ( 'NONE', ( -0.0005884949961230898910, 0.2249510543439054988, -0.9743698870671265722 ) ) ; -#1784 = EDGE_CURVE ( 'NONE', #38161, #711, #5559, .T. ) ; -#1785 = CARTESIAN_POINT ( 'NONE', ( -23.39847246861572927, 115.1132396649264962, 87.28191638308530287 ) ) ; -#1786 = CARTESIAN_POINT ( 'NONE', ( -16.42123257736666275, 122.1227050838390653, 174.6864616558028445 ) ) ; -#1787 = AXIS2_PLACEMENT_3D ( 'NONE', #24210, #18032, #11309 ) ; -#1788 = CARTESIAN_POINT ( 'NONE', ( -38.21276943808967275, 153.0051697192222093, 297.5816245847972255 ) ) ; -#1789 = FACE_OUTER_BOUND ( 'NONE', #23420, .T. ) ; -#1790 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490108596958, 156.2427122712026062, 96.23754757949618011 ) ) ; -#1791 = DIRECTION ( 'NONE', ( 0.0006039748319369173200, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#1792 = ADVANCED_FACE ( 'NONE', ( #3164 ), #33844, .F. ) ; -#1793 = CARTESIAN_POINT ( 'NONE', ( -29.78212191064955761, 126.7137319910847708, 90.46453513447823980 ) ) ; -#1794 = EDGE_CURVE ( 'NONE', #5370, #20125, #40300, .T. ) ; -#1795 = CARTESIAN_POINT ( 'NONE', ( -38.57808178432087942, 119.0279670604091820, 87.73290398861043116 ) ) ; -#1796 = AXIS2_PLACEMENT_3D ( 'NONE', #38585, #39197, #5045 ) ; -#1797 = ORIENTED_EDGE ( 'NONE', *, *, #40436, .T. ) ; -#1798 = EDGE_CURVE ( 'NONE', #33715, #35551, #23732, .T. ) ; -#1799 = CARTESIAN_POINT ( 'NONE', ( 3.655560249847248144, 144.1901243002204751, 93.06410108720389474 ) ) ; -#1800 = EDGE_CURVE ( 'NONE', #23221, #37342, #16890, .T. ) ; -#1801 = CARTESIAN_POINT ( 'NONE', ( -31.70566062302000887, 225.9002260770971873, 73.07765350693868811 ) ) ; -#1802 = ORIENTED_EDGE ( 'NONE', *, *, #2451, .T. ) ; -#1803 = CARTESIAN_POINT ( 'NONE', ( 5.659931281361317623, 181.6896837046558346, 101.5959228839198687 ) ) ; -#1804 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927782063840, 0.0005734119022076108281 ) ) ; -#1805 = EDGE_LOOP ( 'NONE', ( #15677, #28919, #3361, #5002 ) ) ; -#1806 = CARTESIAN_POINT ( 'NONE', ( 24.52696613582132557, 213.0893819282258050, 73.54350799898485036 ) ) ; -#1807 = EDGE_LOOP ( 'NONE', ( #22407, #15989, #4038 ) ) ; -#1808 = DIRECTION ( 'NONE', ( -0.7075229308291650643, 0.000000000000000000, -0.7066903864854172657 ) ) ; -#1809 = FACE_OUTER_BOUND ( 'NONE', #21480, .T. ) ; -#1810 = DIRECTION ( 'NONE', ( -0.7947985590179719173, 0.5913221741348984040, 0.1365039814779489546 ) ) ; -#1811 = CARTESIAN_POINT ( 'NONE', ( 39.71700394620562946, 182.4828400535788546, 106.8893805178791894 ) ) ; -#1812 = CARTESIAN_POINT ( 'NONE', ( -4.036264725700203115, 136.7920597759830628, 93.80205530682346193 ) ) ; -#1813 = ORIENTED_EDGE ( 'NONE', *, *, #33990, .F. ) ; -#1814 = DIRECTION ( 'NONE', ( -0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; -#1815 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1870, #17589, #14345, #27035 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1816 = EDGE_CURVE ( 'NONE', #16566, #18505, #15353, .T. ) ; -#1817 = PLANE ( 'NONE', #4204 ) ; -#1818 = AXIS2_PLACEMENT_3D ( 'NONE', #14542, #14339, #35984 ) ; -#1819 = CARTESIAN_POINT ( 'NONE', ( -13.47107783232944378, 153.8044057555319739, 95.68275536702104489 ) ) ; -#1820 = VERTEX_POINT ( 'NONE', #24680 ) ; -#1821 = CARTESIAN_POINT ( 'NONE', ( 25.53747175047978857, 190.9172658757476313, 106.2799836673595024 ) ) ; -#1822 = CARTESIAN_POINT ( 'NONE', ( -41.76265597088985970, 120.7057567815182182, 90.62417689729259962 ) ) ; -#1823 = AXIS2_PLACEMENT_3D ( 'NONE', #1523, #26485, #23824 ) ; -#1824 = CARTESIAN_POINT ( 'NONE', ( 4.034499241564549976, 175.2435454650956217, 100.6217987443190509 ) ) ; -#1825 = FACE_OUTER_BOUND ( 'NONE', #26481, .T. ) ; -#1826 = CARTESIAN_POINT ( 'NONE', ( 36.05502599160040234, 113.1256265659911264, 89.73543636218946062 ) ) ; -#1827 = CARTESIAN_POINT ( 'NONE', ( 2.510969621544003605, 209.3808403806999934, 73.56099024588000646 ) ) ; -#1828 = EDGE_CURVE ( 'NONE', #10693, #14260, #7128, .T. ) ; -#1829 = CARTESIAN_POINT ( 'NONE', ( 13.50147201671756214, 126.2418300118542902, 91.35575004871967053 ) ) ; -#1830 = CARTESIAN_POINT ( 'NONE', ( 5.659153654835778369, 124.3673852322629187, 88.36203164978959990 ) ) ; -#1831 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825905884072336, 0.0005734119027128889391 ) ) ; -#1832 = ADVANCED_FACE ( 'NONE', ( #30596 ), #32333, .F. ) ; -#1833 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1978, #24056, #17073, #39170 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1834 = CARTESIAN_POINT ( 'NONE', ( -35.69795641737000125, 112.9281708400999946, 87.53934500879000780 ) ) ; -#1835 = CARTESIAN_POINT ( 'NONE', ( 3.467344452005765909, 182.9186892984050701, 101.8809360402982094 ) ) ; -#1836 = VERTEX_POINT ( 'NONE', #36930 ) ; -#1837 = ADVANCED_FACE ( 'NONE', ( #33647 ), #10130, .F. ) ; -#1838 = CARTESIAN_POINT ( 'NONE', ( 44.97084429314561049, 114.9968340379079166, 129.9902062988158491 ) ) ; -#1839 = CARTESIAN_POINT ( 'NONE', ( -44.46004285478915108, 188.8078265508242168, 105.8352584314367135 ) ) ; -#1840 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825996983, 153.3598638654817989, 97.61100683840648173 ) ) ; -#1841 = FACE_OUTER_BOUND ( 'NONE', #12286, .T. ) ; -#1842 = ADVANCED_FACE ( 'NONE', ( #11793 ), #27743, .F. ) ; -#1843 = CYLINDRICAL_SURFACE ( 'NONE', #1057, 2.000000000000001332 ) ; -#1844 = ORIENTED_EDGE ( 'NONE', *, *, #8927, .F. ) ; -#1845 = VERTEX_POINT ( 'NONE', #12569 ) ; -#1846 = ADVANCED_FACE ( 'NONE', ( #24273 ), #4885, .F. ) ; -#1847 = EDGE_LOOP ( 'NONE', ( #37, #29008, #34458, #6440 ) ) ; -#1848 = CARTESIAN_POINT ( 'NONE', ( -23.35923118230594042, 177.6405394001936315, 100.8049717976453508 ) ) ; -#1849 = VECTOR ( 'NONE', #847, 1000.000000000000227 ) ; -#1850 = PLANE ( 'NONE', #8544 ) ; -#1851 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#1852 = VECTOR ( 'NONE', #28308, 1000.000000000000114 ) ; -#1853 = ORIENTED_EDGE ( 'NONE', *, *, #9315, .F. ) ; -#1854 = DIRECTION ( 'NONE', ( 0.0004161288024546937149, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#1855 = CARTESIAN_POINT ( 'NONE', ( -13.49694790808628042, 187.4862234950086588, 105.7766966278750971 ) ) ; -#1856 = CARTESIAN_POINT ( 'NONE', ( 19.99905349769186458, 193.8169544161346494, 102.6908434160864800 ) ) ; -#1857 = CARTESIAN_POINT ( 'NONE', ( -37.63347317150000038, 118.2019778077000041, 87.61857096769999487 ) ) ; -#1858 = ORIENTED_EDGE ( 'NONE', *, *, #1898, .F. ) ; -#1859 = CARTESIAN_POINT ( 'NONE', ( -19.40391524180801852, 125.1988234544515137, 176.6053550468570563 ) ) ; -#1860 = ORIENTED_EDGE ( 'NONE', *, *, #26133, .F. ) ; -#1861 = CARTESIAN_POINT ( 'NONE', ( -15.99864732207169027, 174.8804197950794901, 100.0369119330590593 ) ) ; -#1862 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971549027 ) ) ; -#1863 = CARTESIAN_POINT ( 'NONE', ( -20.50069624036807880, 196.1175417876341385, 103.6936179443737842 ) ) ; -#1864 = LINE ( 'NONE', #30276, #25443 ) ; -#1865 = CARTESIAN_POINT ( 'NONE', ( 28.46460725226640065, 186.8972851080696387, 105.8632825901553218 ) ) ; -#1866 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#1867 = ORIENTED_EDGE ( 'NONE', *, *, #36044, .T. ) ; -#1868 = ORIENTED_EDGE ( 'NONE', *, *, #763, .T. ) ; -#1869 = CARTESIAN_POINT ( 'NONE', ( -2.551856185010000111, 190.4600180632000104, 103.9472556680999986 ) ) ; -#1870 = CARTESIAN_POINT ( 'NONE', ( 39.53379105069361543, 120.3902222971681368, 87.42331650858173475 ) ) ; -#1871 = DIRECTION ( 'NONE', ( -0.0005884949961373456316, 0.2249510543438897892, -0.9743698870671301249 ) ) ; -#1872 = VERTEX_POINT ( 'NONE', #8727 ) ; -#1873 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498900786, 134.9773540766985604, 93.88293913757411246 ) ) ; -#1874 = ORIENTED_EDGE ( 'NONE', *, *, #26487, .T. ) ; -#1875 = ORIENTED_EDGE ( 'NONE', *, *, #27403, .F. ) ; -#1876 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15344, #21497, #40268, #34135, #33738, #33528, #5521, #11883, #18187, #27838, #30690, #3058, #12277, #2689, #37615, #15153, #27640 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000005668521, 0.1875000000008565093, 0.2187500000009763579, 0.2343750000010360601, 0.2500000000010957346, 0.3750000000009479639, 0.4375000000008490431, 0.4687500000008210654, 0.5000000000007931433, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1877 = AXIS2_PLACEMENT_3D ( 'NONE', #18183, #24763, #24560 ) ; -#1878 = EDGE_CURVE ( 'NONE', #23153, #3788, #6428, .T. ) ; -#1879 = EDGE_CURVE ( 'NONE', #14192, #36762, #38196, .T. ) ; -#1880 = VECTOR ( 'NONE', #2439, 1000.000000000000227 ) ; -#1881 = ORIENTED_EDGE ( 'NONE', *, *, #362, .F. ) ; -#1882 = AXIS2_PLACEMENT_3D ( 'NONE', #2339, #36675, #27306 ) ; -#1883 = ADVANCED_FACE ( 'NONE', ( #2965 ), #35556, .F. ) ; -#1884 = EDGE_LOOP ( 'NONE', ( #23826, #31130, #8831, #15200 ) ) ; -#1885 = CARTESIAN_POINT ( 'NONE', ( 3.066237086918227384, 190.8104827972501596, 106.7820556061583517 ) ) ; -#1886 = DIRECTION ( 'NONE', ( 9.251858538558595218E-16, -0.9743700557921587402, -0.2249510932971549027 ) ) ; -#1887 = VECTOR ( 'NONE', #9433, 1000.000000000000114 ) ; -#1888 = LINE ( 'NONE', #23155, #14993 ) ; -#1889 = EDGE_LOOP ( 'NONE', ( #17118, #22770, #25889, #13226 ) ) ; -#1890 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1891 = ORIENTED_EDGE ( 'NONE', *, *, #10254, .F. ) ; -#1892 = ADVANCED_FACE ( 'NONE', ( #24877 ), #7504, .F. ) ; -#1893 = CARTESIAN_POINT ( 'NONE', ( 25.92039983084000099, 121.8646700609999982, 90.50868154741999660 ) ) ; -#1894 = DIRECTION ( 'NONE', ( 0.0005884949961255130828, -0.2249510543439061094, 0.9743698870671263501 ) ) ; -#1896 = FACE_OUTER_BOUND ( 'NONE', #17446, .T. ) ; -#1895 = CARTESIAN_POINT ( 'NONE', ( -12.63767699503999964, 177.1899956627526365, 101.0812418394431518 ) ) ; -#1897 = ORIENTED_EDGE ( 'NONE', *, *, #6812, .F. ) ; -#1898 = EDGE_CURVE ( 'NONE', #39827, #17225, #11059, .T. ) ; -#1899 = ORIENTED_EDGE ( 'NONE', *, *, #444, .F. ) ; -#1900 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#1901 = VERTEX_POINT ( 'NONE', #15837 ) ; -#1902 = CARTESIAN_POINT ( 'NONE', ( -36.68630558007769338, 117.4611287568297939, 87.28994190131942332 ) ) ; -#1903 = EDGE_CURVE ( 'NONE', #4191, #20872, #25172, .T. ) ; -#1904 = AXIS2_PLACEMENT_3D ( 'NONE', #22440, #9763, #31641 ) ; -#1905 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35639, #16112, #11138, #23604 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1906 = LINE ( 'NONE', #39300, #13505 ) ; -#1907 = CARTESIAN_POINT ( 'NONE', ( 16.16705078777268056, 152.4576016466090778, 178.9883717186631031 ) ) ; -#1908 = CARTESIAN_POINT ( 'NONE', ( 36.32604205261999653, 191.7173161736999987, 104.1914432412000195 ) ) ; -#1909 = ORIENTED_EDGE ( 'NONE', *, *, #21663, .F. ) ; -#1910 = VERTEX_POINT ( 'NONE', #25881 ) ; -#1911 = CONICAL_SURFACE ( 'NONE', #12350, 6.499999999869967127, 0.7853981633308297905 ) ; -#1912 = EDGE_LOOP ( 'NONE', ( #31595, #3027, #3584, #27622 ) ) ; -#1913 = VECTOR ( 'NONE', #12959, 1000.000000000000000 ) ; -#1914 = DIRECTION ( 'NONE', ( 0.7855473026356885047, 0.6188014303620751333, -0.0004744508866335521804 ) ) ; -#1915 = VECTOR ( 'NONE', #33904, 1000.000000000000114 ) ; -#1916 = CARTESIAN_POINT ( 'NONE', ( 15.97824167254727890, 186.2916992871397781, 102.6521006286546083 ) ) ; -#1917 = VERTEX_POINT ( 'NONE', #28533 ) ; -#1918 = CARTESIAN_POINT ( 'NONE', ( -35.64467888793660677, 191.6889051035020088, 106.9474356354359941 ) ) ; -#1919 = DIRECTION ( 'NONE', ( -0.1843855713908465477, -0.08049128666858569592, 0.9795525069302342125 ) ) ; -#1920 = ORIENTED_EDGE ( 'NONE', *, *, #21800, .F. ) ; -#1921 = CARTESIAN_POINT ( 'NONE', ( 3.668109984895000508, 124.1793125683000056, 91.39867154092999613 ) ) ; -#1922 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#1923 = CARTESIAN_POINT ( 'NONE', ( -5.668109638569103659, 126.1268167267171378, 91.85392722789381992 ) ) ; -#1924 = DIRECTION ( 'NONE', ( 1.734723475976797036E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#1925 = ADVANCED_FACE ( 'NONE', ( #35234 ), #19221, .F. ) ; -#1926 = ORIENTED_EDGE ( 'NONE', *, *, #8645, .T. ) ; -#1927 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; -#1928 = EDGE_CURVE ( 'NONE', #34430, #36179, #19427, .T. ) ; -#1929 = EDGE_CURVE ( 'NONE', #34340, #14392, #17951, .T. ) ; -#1930 = CARTESIAN_POINT ( 'NONE', ( 17.99823451501000093, 132.2978359559000410, 93.26432565574999956 ) ) ; -#1931 = CARTESIAN_POINT ( 'NONE', ( 25.67581203438339799, 191.9371493622001594, 104.2389531613646909 ) ) ; -#1932 = VECTOR ( 'NONE', #15830, 1000.000000000000227 ) ; -#1933 = EDGE_LOOP ( 'NONE', ( #24863, #21164, #1329 ) ) ; -#1934 = ADVANCED_FACE ( 'NONE', ( #7640 ), #13392, .F. ) ; -#1935 = VECTOR ( 'NONE', #39229, 1000.000000000000114 ) ; -#1936 = AXIS2_PLACEMENT_3D ( 'NONE', #568, #10204, #12862 ) ; -#1937 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.702666754117757870E-16, 0.0006039748319385827629 ) ) ; -#1939 = CARTESIAN_POINT ( 'NONE', ( 39.36767498017007227, 125.1708217663776423, 106.4887638017983704 ) ) ; -#1938 = CARTESIAN_POINT ( 'NONE', ( 15.99998378901094576, 184.9656665294078266, 102.3459542884652365 ) ) ; -#1940 = ORIENTED_EDGE ( 'NONE', *, *, #16823, .F. ) ; -#1941 = EDGE_CURVE ( 'NONE', #22242, #35941, #28428, .T. ) ; -#1942 = VERTEX_POINT ( 'NONE', #27086 ) ; -#1943 = ORIENTED_EDGE ( 'NONE', *, *, #28656, .T. ) ; -#1944 = CARTESIAN_POINT ( 'NONE', ( 3.073788346373000024, 209.7471523734000129, 76.19157238271999688 ) ) ; -#1945 = CARTESIAN_POINT ( 'NONE', ( 37.04254647716739157, 191.1764927423541565, 106.3114722328703010 ) ) ; -#1946 = LINE ( 'NONE', #14413, #26298 ) ; -#1947 = CARTESIAN_POINT ( 'NONE', ( -38.81665153276784963, 106.4214194585135544, 168.3324293193781784 ) ) ; -#1948 = VERTEX_POINT ( 'NONE', #20506 ) ; -#1949 = EDGE_LOOP ( 'NONE', ( #32841, #11567, #39473, #17013, #23360 ) ) ; -#1950 = CARTESIAN_POINT ( 'NONE', ( 13.88399914228467757, 136.0347715473272672, 91.56378953181273062 ) ) ; -#1951 = VERTEX_POINT ( 'NONE', #32787 ) ; -#1952 = VERTEX_POINT ( 'NONE', #35623 ) ; -#1953 = ORIENTED_EDGE ( 'NONE', *, *, #12137, .T. ) ; -#1954 = CARTESIAN_POINT ( 'NONE', ( 37.96340687623389698, 191.0388351520254560, 103.7347888148996446 ) ) ; -#1955 = LINE ( 'NONE', #14421, #7363 ) ; -#1956 = EDGE_CURVE ( 'NONE', #17689, #18171, #4910, .T. ) ; -#1957 = MANIFOLD_SOLID_BREP ( '\X2\570689d2\X0\12', #39407 ) ; -#1958 = CARTESIAN_POINT ( 'NONE', ( -2.480274637552000172, 189.0000000000000000, 32.65999473746001058 ) ) ; -#1959 = CARTESIAN_POINT ( 'NONE', ( -2.913189425919000097, 209.5191065594000008, 76.06629948724000201 ) ) ; -#1960 = EDGE_LOOP ( 'NONE', ( #27625, #36394, #34968, #4517, #16647, #38599, #15194, #17030, #38398, #13864 ) ) ; -#1961 = EDGE_LOOP ( 'NONE', ( #37045, #30897, #19780, #13910 ) ) ; -#1962 = CARTESIAN_POINT ( 'NONE', ( 14.55306318046054592, 176.9232825744718411, 100.4900915860747403 ) ) ; -#1963 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -1.540743955509789367E-33, 0.0006039748319385908944 ) ) ; -#1964 = CARTESIAN_POINT ( 'NONE', ( -36.35858970950000213, 191.9077732178000133, 104.5549816818000011 ) ) ; -#1965 = CARTESIAN_POINT ( 'NONE', ( 36.54974486126000244, 191.8647094490000029, 104.5085210141999994 ) ) ; -#1966 = CARTESIAN_POINT ( 'NONE', ( -26.00926449878999946, 121.0814862561000069, 87.62239126132999445 ) ) ; -#1967 = CONICAL_SURFACE ( 'NONE', #24837, 2.749999999872844381, 0.7853981633697728615 ) ; -#1968 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#1969 = EDGE_LOOP ( 'NONE', ( #19302, #18667, #40148, #18441 ) ) ; -#1970 = CARTESIAN_POINT ( 'NONE', ( 42.94150479285965361, 103.2019334172786529, 168.6346152762044710 ) ) ; -#1971 = CARTESIAN_POINT ( 'NONE', ( -26.75653968529694282, 131.0179918129932730, 89.91699612660660534 ) ) ; -#1972 = AXIS2_PLACEMENT_3D ( 'NONE', #26297, #35452, #29165 ) ; -#1973 = VERTEX_POINT ( 'NONE', #32979 ) ; -#1974 = VECTOR ( 'NONE', #24903, 1000.000000000000114 ) ; -#1975 = CARTESIAN_POINT ( 'NONE', ( -6.037294616552872029, 134.7461518313687066, 93.41385221303204389 ) ) ; -#1976 = AXIS2_PLACEMENT_3D ( 'NONE', #37774, #38186, #38378 ) ; -#1977 = CARTESIAN_POINT ( 'NONE', ( -35.93878493987466527, 193.8169247290984458, 102.7246158654606347 ) ) ; -#1978 = CARTESIAN_POINT ( 'NONE', ( -14.55306118018871508, 176.9194272080598296, 100.5067835523781667 ) ) ; -#1979 = CARTESIAN_POINT ( 'NONE', ( -21.44517133412774967, 181.8810903885702999, 104.7353468333731428 ) ) ; -#1980 = ORIENTED_EDGE ( 'NONE', *, *, #3474, .F. ) ; -#1981 = CARTESIAN_POINT ( 'NONE', ( 30.07038983360635243, 136.6834034282913422, 94.27269756974730797 ) ) ; -#1982 = CARTESIAN_POINT ( 'NONE', ( 2.243938541402742182, 189.9166128731624212, 103.9479121654673435 ) ) ; -#1983 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#1984 = VERTEX_POINT ( 'NONE', #11318 ) ; -#1985 = CARTESIAN_POINT ( 'NONE', ( -22.49862694078846559, 157.6261014233649576, 99.13627282167615817 ) ) ; -#1986 = ORIENTED_EDGE ( 'NONE', *, *, #35543, .T. ) ; -#1987 = EDGE_CURVE ( 'NONE', #7212, #13591, #38881, .T. ) ; -#1988 = CARTESIAN_POINT ( 'NONE', ( 3.166350953592421025, 126.8041585549839709, 88.92605846951083493 ) ) ; -#1989 = EDGE_CURVE ( 'NONE', #28826, #2748, #8159, .T. ) ; -#1990 = CARTESIAN_POINT ( 'NONE', ( -45.27486310239934397, 116.8517531720308540, 123.7677792994715560 ) ) ; -#1991 = DIRECTION ( 'NONE', ( -0.7066795775298636562, -1.911073989161491327E-16, 0.7075337269008548091 ) ) ; -#1992 = CARTESIAN_POINT ( 'NONE', ( -20.51880467302672173, 211.0905570380611493, 75.57084890002228406 ) ) ; -#1993 = CARTESIAN_POINT ( 'NONE', ( 6.030824592693510233, 134.9998097734520570, 90.92594956691499419 ) ) ; -#1994 = ORIENTED_EDGE ( 'NONE', *, *, #3019, .T. ) ; -#1995 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #25417, #34964 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#1996 = CARTESIAN_POINT ( 'NONE', ( -6.040934757040731462, 134.9721311960137200, 90.89113414393979440 ) ) ; -#1997 = CIRCLE ( 'NONE', #39189, 9.499999999982289722 ) ; -#1998 = CARTESIAN_POINT ( 'NONE', ( -26.00135273745824449, 117.7151665234863600, 87.28348845754496210 ) ) ; -#1999 = CARTESIAN_POINT ( 'NONE', ( -19.99829785685910011, 119.7153791177249502, 90.38236254249699186 ) ) ; -#2000 = AXIS2_PLACEMENT_3D ( 'NONE', #19223, #16170, #38044 ) ; -#2001 = CARTESIAN_POINT ( 'NONE', ( 19.71713340877300169, 124.4083419986981909, 178.1703837097148551 ) ) ; -#2002 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971522104 ) ) ; -#2003 = VECTOR ( 'NONE', #27728, 1000.000000000000227 ) ; -#2004 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971552635 ) ) ; -#2005 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455648501747, -31.54510897440487938, 136.4474729010642875 ) ) ; -#2006 = ORIENTED_EDGE ( 'NONE', *, *, #34992, .T. ) ; -#2007 = VERTEX_POINT ( 'NONE', #24006 ) ; -#2008 = CARTESIAN_POINT ( 'NONE', ( -30.07185925050865904, 175.2389475684547051, 100.6413366228390345 ) ) ; -#2009 = EDGE_CURVE ( 'NONE', #40324, #26903, #39351, .T. ) ; -#2010 = LINE ( 'NONE', #4847, #7908 ) ; -#2011 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28614, #38005, #22692, #12463 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2012 = EDGE_LOOP ( 'NONE', ( #27721, #39508, #16212, #10953 ) ) ; -#2013 = CARTESIAN_POINT ( 'NONE', ( -18.69575332400200907, 125.9675347290306036, 174.7275314831792912 ) ) ; -#2014 = CARTESIAN_POINT ( 'NONE', ( 3.869973094273203351, 136.7573060621185448, 93.95941861830546316 ) ) ; -#2015 = ORIENTED_EDGE ( 'NONE', *, *, #2178, .T. ) ; -#2016 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #13516, #3891, #20234, #10461 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.197186637354022753, 1.570796326794899667 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9884017699607163809, 0.9884017699607163809, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#2017 = CARTESIAN_POINT ( 'NONE', ( 23.64497629418776015, 213.5251522717376531, 73.54403244452512922 ) ) ; -#2018 = EDGE_LOOP ( 'NONE', ( #12154, #34064, #13154, #2370 ) ) ; -#2019 = CARTESIAN_POINT ( 'NONE', ( 75.24011746878784379, 195.1293300889719546, 195.0257767563242055 ) ) ; -#2020 = EDGE_CURVE ( 'NONE', #29127, #11548, #29735, .T. ) ; -#2021 = CARTESIAN_POINT ( 'NONE', ( -29.94659852274795497, 109.6131156702000027, 89.78587174317453901 ) ) ; -#2022 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#2023 = LINE ( 'NONE', #35928, #9015 ) ; -#2024 = CARTESIAN_POINT ( 'NONE', ( 33.37602094669033193, 84.06324503389978986, 284.1448219155665242 ) ) ; -#2025 = PLANE ( 'NONE', #21050 ) ; -#2026 = ORIENTED_EDGE ( 'NONE', *, *, #14707, .F. ) ; -#2027 = CARTESIAN_POINT ( 'NONE', ( 60.86545082361659809, 245.5374438537401147, 206.6753669249971495 ) ) ; -#2028 = VECTOR ( 'NONE', #28916, 1000.000000000000000 ) ; -#2029 = DIRECTION ( 'NONE', ( 0.6087614810001803489, -0.7729390313185899863, -0.1788147452386047165 ) ) ; -#2030 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#2031 = AXIS2_PLACEMENT_3D ( 'NONE', #6507, #21485, #6317 ) ; -#2032 = AXIS2_PLACEMENT_3D ( 'NONE', #26114, #13822, #21123 ) ; -#2033 = DIRECTION ( 'NONE', ( 0.7933533411653066469, 0.5931840316265238888, 0.1368326740407706521 ) ) ; -#2034 = EDGE_CURVE ( 'NONE', #30287, #23153, #14095, .T. ) ; -#2035 = ORIENTED_EDGE ( 'NONE', *, *, #27069, .F. ) ; -#2036 = CARTESIAN_POINT ( 'NONE', ( 3.168113141152071321, 127.9133523189982498, 92.26104312719712652 ) ) ; -#2037 = EDGE_CURVE ( 'NONE', #28262, #21459, #7637, .T. ) ; -#2038 = CARTESIAN_POINT ( 'NONE', ( 21.74144897322905479, 115.9285972877331830, 89.75488417657916784 ) ) ; -#2040 = ADVANCED_FACE ( 'NONE', ( #17026 ), #24531, .F. ) ; -#2039 = CARTESIAN_POINT ( 'NONE', ( 6.032898680163828686, 134.3314735182171944, 93.66704928364619320 ) ) ; -#2041 = LINE ( 'NONE', #23919, #607 ) ; -#2042 = CARTESIAN_POINT ( 'NONE', ( 21.59709472431439181, 115.2762503876805624, 188.9250028067568508 ) ) ; -#2043 = CARTESIAN_POINT ( 'NONE', ( -25.88585013892983966, 209.7107922446395207, 73.19837119205239162 ) ) ; -#2044 = CARTESIAN_POINT ( 'NONE', ( 0.5459373230907974550, 209.0000000000000000, 76.05817508704146235 ) ) ; -#2045 = CARTESIAN_POINT ( 'NONE', ( 20.48026842689764848, 209.2780769040354869, 73.54613605110799313 ) ) ; -#2046 = DIRECTION ( 'NONE', ( 0.0005559617617595236224, -0.3907311284869797730, 0.9205046855599435807 ) ) ; -#2047 = ORIENTED_EDGE ( 'NONE', *, *, #331, .F. ) ; -#2048 = DIRECTION ( 'NONE', ( -0.7933532411131101192, -0.5932638852154232811, -0.1364866195435442964 ) ) ; -#2049 = CARTESIAN_POINT ( 'NONE', ( -34.02993892823075583, 92.27472273181228957, 297.5790982599829704 ) ) ; -#2050 = CYLINDRICAL_SURFACE ( 'NONE', #33237, 2.000000000000014655 ) ; -#2051 = DIRECTION ( 'NONE', ( 0.0006039748319386405509, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#2053 = ORIENTED_EDGE ( 'NONE', *, *, #22665, .F. ) ; -#2052 = DIRECTION ( 'NONE', ( 0.0005884949961190483105, -0.2249510543439053878, 0.9743698870671265722 ) ) ; -#2054 = ORIENTED_EDGE ( 'NONE', *, *, #25083, .T. ) ; -#2055 = ORIENTED_EDGE ( 'NONE', *, *, #24760, .T. ) ; -#2056 = VECTOR ( 'NONE', #30544, 1000.000000000000000 ) ; -#2057 = CARTESIAN_POINT ( 'NONE', ( -2.902524173895590920, 190.6910093414263372, 103.6791650777964833 ) ) ; -#2058 = VERTEX_POINT ( 'NONE', #20313 ) ; -#2059 = CARTESIAN_POINT ( 'NONE', ( -23.36087230894777989, 177.4951561493269878, 100.8958181500985205 ) ) ; -#2060 = LINE ( 'NONE', #17768, #4606 ) ; -#2061 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425095181, 127.0691889891074879, 92.07622024688510010 ) ) ; -#2062 = ORIENTED_EDGE ( 'NONE', *, *, #29330, .F. ) ; -#2063 = LINE ( 'NONE', #17978, #24448 ) ; -#2064 = CARTESIAN_POINT ( 'NONE', ( -39.39285454264343400, 114.3643166784735712, 151.6767146082210047 ) ) ; -#2065 = CARTESIAN_POINT ( 'NONE', ( -20.01777344647963730, 205.1071326358727163, 76.11698016271346035 ) ) ; -#2066 = CARTESIAN_POINT ( 'NONE', ( -38.17491265577000092, 118.4147068048000193, 87.83922331386000337 ) ) ; -#2067 = VERTEX_POINT ( 'NONE', #16831 ) ; -#2068 = CARTESIAN_POINT ( 'NONE', ( -42.84327062420202026, 120.8099927651375936, 92.42850709477329474 ) ) ; -#2069 = ORIENTED_EDGE ( 'NONE', *, *, #28702, .T. ) ; -#2070 = DIRECTION ( 'NONE', ( 0.5987319960703996191, 0.8009494346596138792, 0.000000000000000000 ) ) ; -#2071 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30910, #37237, #36633, #39688 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2072 = DIRECTION ( 'NONE', ( 0.7066897571212915619, 0.1533500351137353224, -0.6907049687894724066 ) ) ; -#2073 = CARTESIAN_POINT ( 'NONE', ( -45.58628251432046596, 77.27946979429611929, 297.5860780019314120 ) ) ; -#2074 = CARTESIAN_POINT ( 'NONE', ( -20.16504595039701897, 190.8883395378736907, 106.6429623803627891 ) ) ; -#2075 = ORIENTED_EDGE ( 'NONE', *, *, #16204, .F. ) ; -#2076 = EDGE_CURVE ( 'NONE', #6998, #21074, #11128, .T. ) ; -#2077 = LINE ( 'NONE', #23958, #40228 ) ; -#2078 = CARTESIAN_POINT ( 'NONE', ( 0.5945138864921091226, 189.0183369199829713, 103.6969883959349801 ) ) ; -#2079 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091565633 ) ) ; -#2080 = CARTESIAN_POINT ( 'NONE', ( 26.00099507788276298, 120.2141150864606089, 90.46974490087802678 ) ) ; -#2081 = EDGE_CURVE ( 'NONE', #39778, #13439, #7844, .T. ) ; -#2082 = ORIENTED_EDGE ( 'NONE', *, *, #34054, .T. ) ; -#2083 = CIRCLE ( 'NONE', #23603, 7.500000000039277914 ) ; -#2084 = CARTESIAN_POINT ( 'NONE', ( -2.454301921840380096, 209.0000005845445230, 75.66282330657800514 ) ) ; -#2085 = ORIENTED_EDGE ( 'NONE', *, *, #15330, .T. ) ; -#2086 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #7451, #19718 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 0.9999998458841763416 ), - .UNSPECIFIED. ) ; -#2087 = ADVANCED_FACE ( 'NONE', ( #38916 ), #999, .T. ) ; -#2088 = EDGE_CURVE ( 'NONE', #32344, #30574, #7534, .T. ) ; -#2089 = CONICAL_SURFACE ( 'NONE', #6637, 4.500002634206803798, 0.7853981634336496542 ) ; -#2090 = EDGE_CURVE ( 'NONE', #21377, #11739, #30407, .T. ) ; -#2091 = CIRCLE ( 'NONE', #22979, 4.500000000005264233 ) ; -#2092 = ORIENTED_EDGE ( 'NONE', *, *, #32395, .F. ) ; -#2093 = ORIENTED_EDGE ( 'NONE', *, *, #22489, .F. ) ; -#2094 = CARTESIAN_POINT ( 'NONE', ( 3.027911450587273290, 190.4527856945552458, 106.6994978557500531 ) ) ; -#2095 = DIRECTION ( 'NONE', ( -0.0006039748319387576447, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#2096 = CARTESIAN_POINT ( 'NONE', ( -14.16859888750098406, 182.3077195333686120, 104.3162949350999185 ) ) ; -#2097 = CARTESIAN_POINT ( 'NONE', ( -41.70913856584510881, 120.6942229597581644, 90.62148178139578647 ) ) ; -#2098 = VERTEX_POINT ( 'NONE', #14202 ) ; -#2099 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.110223024625155594E-14, -1.000000000000000000 ) ) ; -#2100 = EDGE_LOOP ( 'NONE', ( #13564, #24934, #16974, #28888, #15211, #34512, #20267, #11906, #13227, #18932, #31618 ) ) ; -#2101 = CARTESIAN_POINT ( 'NONE', ( 26.06404824249079866, 120.9045055373159983, 90.63257663708037626 ) ) ; -#2102 = FACE_OUTER_BOUND ( 'NONE', #9994, .T. ) ; -#2104 = FACE_OUTER_BOUND ( 'NONE', #10167, .T. ) ; -#2103 = CARTESIAN_POINT ( 'NONE', ( -35.94780537806290965, 112.9281708400999946, 87.78949595528006000 ) ) ; -#2105 = ORIENTED_EDGE ( 'NONE', *, *, #32297, .F. ) ; -#2106 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971560406 ) ) ; -#2107 = EDGE_CURVE ( 'NONE', #7231, #25578, #11572, .T. ) ; -#2108 = ORIENTED_EDGE ( 'NONE', *, *, #30357, .F. ) ; -#2109 = CARTESIAN_POINT ( 'NONE', ( 36.44436247437651133, 190.8511614233640330, 106.7712946021073606 ) ) ; -#2110 = CONICAL_SURFACE ( 'NONE', #5361, 3.499999999893422586, 0.7853981634347139140 ) ; -#2111 = ORIENTED_EDGE ( 'NONE', *, *, #40007, .T. ) ; -#2112 = CARTESIAN_POINT ( 'NONE', ( 39.23603512625999912, 119.1639279199000043, 89.84421601804000090 ) ) ; -#2114 = VECTOR ( 'NONE', #12197, 1000.000000000000114 ) ; -#2113 = CARTESIAN_POINT ( 'NONE', ( -35.98614470123553843, 115.9822958763201655, 87.28951902169316668 ) ) ; -#2115 = CIRCLE ( 'NONE', #26279, 2.249999999963666397 ) ; -#2116 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386905326 ) ) ; -#2117 = CARTESIAN_POINT ( 'NONE', ( 3.534086375177905914, 137.3581944094399603, 91.36238397499714381 ) ) ; -#2118 = ORIENTED_EDGE ( 'NONE', *, *, #15549, .T. ) ; -#2119 = ORIENTED_EDGE ( 'NONE', *, *, #16309, .T. ) ; -#2120 = EDGE_CURVE ( 'NONE', #11382, #1948, #39121, .T. ) ; -#2121 = ORIENTED_EDGE ( 'NONE', *, *, #31154, .T. ) ; -#2122 = CARTESIAN_POINT ( 'NONE', ( -35.94659742830589266, 112.4664344042326576, 89.78949559119494950 ) ) ; -#2123 = DIRECTION ( 'NONE', ( 0.6087614115774879764, -0.7730004600455407937, -0.1785492440296699013 ) ) ; -#2124 = CARTESIAN_POINT ( 'NONE', ( 14.13092599226599155, 188.2870105248598236, 103.1138703412405846 ) ) ; -#2125 = ORIENTED_EDGE ( 'NONE', *, *, #11073, .F. ) ; -#2126 = ADVANCED_FACE ( 'NONE', ( #18044, #8470 ), #15597, .F. ) ; -#2127 = CARTESIAN_POINT ( 'NONE', ( 30.06790063874939634, 135.1133124594595643, 91.08871632618496506 ) ) ; -#2128 = ADVANCED_FACE ( 'NONE', ( #28095 ), #9517, .F. ) ; -#2129 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 151.1459109378392327, 96.08716200003422614 ) ) ; -#2130 = EDGE_LOOP ( 'NONE', ( #4325, #31033, #31887, #27472 ) ) ; -#2131 = CARTESIAN_POINT ( 'NONE', ( 5.667748567169940799, 130.5464144240118287, 90.19576013559581895 ) ) ; -#2132 = EDGE_CURVE ( 'NONE', #28309, #22653, #31556, .T. ) ; -#2133 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; -#2134 = DIRECTION ( 'NONE', ( -0.0005884949961240271837, 0.2249510543439050270, -0.9743698870671266832 ) ) ; -#2135 = CARTESIAN_POINT ( 'NONE', ( 5.505231156190700581, 148.7676655288644838, 93.99531868697803816 ) ) ; -#2136 = ORIENTED_EDGE ( 'NONE', *, *, #21192, .F. ) ; -#2137 = AXIS2_PLACEMENT_3D ( 'NONE', #24109, #36760, #39618 ) ; -#2138 = CARTESIAN_POINT ( 'NONE', ( 35.80370676812943742, 112.9281706819409692, 87.49619306724476075 ) ) ; -#2139 = LINE ( 'NONE', #10540, #16885 ) ; -#2140 = AXIS2_PLACEMENT_3D ( 'NONE', #1195, #10817, #17318 ) ; -#2141 = CIRCLE ( 'NONE', #18423, 2.000000000000000000 ) ; -#2142 = ORIENTED_EDGE ( 'NONE', *, *, #14080, .T. ) ; -#2143 = CYLINDRICAL_SURFACE ( 'NONE', #31272, 2.000000000000001332 ) ; -#2145 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2144 = CYLINDRICAL_SURFACE ( 'NONE', #22033, 6.000000000000001776 ) ; -#2146 = ORIENTED_EDGE ( 'NONE', *, *, #23311, .T. ) ; -#2147 = ORIENTED_EDGE ( 'NONE', *, *, #9702, .T. ) ; -#2148 = ORIENTED_EDGE ( 'NONE', *, *, #34626, .F. ) ; -#2149 = CARTESIAN_POINT ( 'NONE', ( 20.00006507825687407, 169.9346765372802963, 98.87342171090897125 ) ) ; -#2150 = DIRECTION ( 'NONE', ( -0.7066795775300234173, -3.556109467271558380E-18, 0.7075337269006952701 ) ) ; -#2151 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; -#2152 = CARTESIAN_POINT ( 'NONE', ( 15.05197310825490398, 136.6013035982805661, 91.18072662319218580 ) ) ; -#2153 = ORIENTED_EDGE ( 'NONE', *, *, #138, .T. ) ; -#2154 = ORIENTED_EDGE ( 'NONE', *, *, #38231, .T. ) ; -#2155 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35300, #32271, #9998, #4034 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2156 = PLANE ( 'NONE', #7618 ) ; -#2157 = ORIENTED_EDGE ( 'NONE', *, *, #15545, .T. ) ; -#2158 = ORIENTED_EDGE ( 'NONE', *, *, #20715, .F. ) ; -#2159 = ORIENTED_EDGE ( 'NONE', *, *, #33764, .T. ) ; -#2160 = CARTESIAN_POINT ( 'NONE', ( -20.00025820447960001, 138.1823733798348428, 91.56700283718186029 ) ) ; -#2161 = CARTESIAN_POINT ( 'NONE', ( 2.621867308820999831, 209.6150350132000426, 73.39025393530999963 ) ) ; -#2162 = VECTOR ( 'NONE', #23463, 1000.000000000000114 ) ; -#2163 = ORIENTED_EDGE ( 'NONE', *, *, #37508, .T. ) ; -#2164 = ADVANCED_FACE ( 'NONE', ( #33994 ), #12144, .F. ) ; -#2165 = ORIENTED_EDGE ( 'NONE', *, *, #38076, .F. ) ; -#2166 = FACE_OUTER_BOUND ( 'NONE', #5977, .T. ) ; -#2167 = EDGE_CURVE ( 'NONE', #7762, #34936, #22219, .T. ) ; -#2168 = CARTESIAN_POINT ( 'NONE', ( -36.07647867781999906, 191.8527882484000315, 104.2980684900999933 ) ) ; -#2170 = CONICAL_SURFACE ( 'NONE', #23059, 17.00000000000409273, 0.7853981633973132759 ) ; -#2169 = CARTESIAN_POINT ( 'NONE', ( 37.33863555023999936, 190.9616902955000057, 103.5698611074000013 ) ) ; -#2171 = EDGE_CURVE ( 'NONE', #9488, #14192, #25026, .T. ) ; -#2172 = VERTEX_POINT ( 'NONE', #2917 ) ; -#2173 = CARTESIAN_POINT ( 'NONE', ( -26.00150954189000174, 120.7873587952999941, 87.55495400204000589 ) ) ; -#2174 = VERTEX_POINT ( 'NONE', #18248 ) ; -#2175 = PLANE ( 'NONE', #27839 ) ; -#2176 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775999513 ) ) ; -#2177 = VERTEX_POINT ( 'NONE', #2329 ) ; -#2178 = EDGE_CURVE ( 'NONE', #21459, #23019, #15404, .T. ) ; -#2179 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3884, #1227, #16951, #35148, #16360, #28846, #824, #10854, #8598, #21065, #36796, #17963, #21266, #36178, #5304 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 1, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2080554551301270760, 0.2600693189126438987, 0.3120831826951607213, 0.4161109102601944221, 0.6241663653902360664, 0.7281940929552587205, 0.8322218205202811525 ), - .UNSPECIFIED. ) ; -#2180 = CARTESIAN_POINT ( 'NONE', ( -16.52242372029886042, 151.4997482901518424, 184.4407432091828412 ) ) ; -#2181 = CARTESIAN_POINT ( 'NONE', ( -6.063496305472453329, 163.0526542675453925, 100.2081181894236011 ) ) ; -#2182 = CARTESIAN_POINT ( 'NONE', ( -15.85326334123286784, 125.9778002666185017, 88.74676275371332679 ) ) ; -#2183 = ORIENTED_EDGE ( 'NONE', *, *, #39860, .T. ) ; -#2185 = ADVANCED_FACE ( 'NONE', ( #36668 ), #30545, .T. ) ; -#2184 = CARTESIAN_POINT ( 'NONE', ( -45.18718350925745852, 79.77698873149398651, 284.4103241537512190 ) ) ; -#2186 = FACE_OUTER_BOUND ( 'NONE', #12611, .T. ) ; -#2187 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; -#2188 = VERTEX_POINT ( 'NONE', #6191 ) ; -#2189 = DIRECTION ( 'NONE', ( -0.0004161288024660041661, 0.8480480897817621599, -0.5299191110483975065 ) ) ; -#2190 = ORIENTED_EDGE ( 'NONE', *, *, #8875, .F. ) ; -#2191 = CARTESIAN_POINT ( 'NONE', ( -6.635715103306525878E-14, 155.6803346354327289, 98.67347229705578115 ) ) ; -#2192 = CARTESIAN_POINT ( 'NONE', ( -2.455538055765680738, 209.0000002601700544, 73.61629604161946361 ) ) ; -#2193 = CARTESIAN_POINT ( 'NONE', ( -20.38954068182721713, 129.0978827080468534, 89.46983047235534059 ) ) ; -#2194 = CARTESIAN_POINT ( 'NONE', ( 17.25788849119799195, 152.5371962406647413, 182.4889206688251306 ) ) ; -#2195 = AXIS2_PLACEMENT_3D ( 'NONE', #20480, #30111, #36646 ) ; -#2196 = CARTESIAN_POINT ( 'NONE', ( -89.80707058824756928, 73.37406685903091841, 291.6127851554912240 ) ) ; -#2197 = ORIENTED_EDGE ( 'NONE', *, *, #5892, .F. ) ; -#2198 = VECTOR ( 'NONE', #10051, 1000.000000000000000 ) ; -#2199 = CARTESIAN_POINT ( 'NONE', ( 15.99998568644542907, 127.1172274350850557, 88.99058172675916012 ) ) ; -#2200 = AXIS2_PLACEMENT_3D ( 'NONE', #11977, #21591, #33833 ) ; -#2201 = DIRECTION ( 'NONE', ( 0.0005884949961193429967, -0.2249510543439072197, 0.9743698870671261281 ) ) ; -#2202 = CARTESIAN_POINT ( 'NONE', ( 5.666635157737871964, 181.3283579457949770, 104.3229600593109723 ) ) ; -#2203 = DIRECTION ( 'NONE', ( 0.0005884949521151187956, -0.2249510543284071740, 0.9743698870707311332 ) ) ; -#2204 = CARTESIAN_POINT ( 'NONE', ( 31.71706711663377476, 177.1986094558884020, 100.5432891884866393 ) ) ; -#2205 = CARTESIAN_POINT ( 'NONE', ( 44.72966403672144509, 167.5186349756792765, 188.6353666065691925 ) ) ; -#2206 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971560961 ) ) ; -#2207 = CARTESIAN_POINT ( 'NONE', ( -35.43806428669827824, 192.3002664666033468, 103.9163745585288297 ) ) ; -#2208 = EDGE_LOOP ( 'NONE', ( #19528, #38681, #10561 ) ) ; -#2209 = ORIENTED_EDGE ( 'NONE', *, *, #14999, .F. ) ; -#2210 = LINE ( 'NONE', #39601, #30858 ) ; -#2211 = LINE ( 'NONE', #20392, #13777 ) ; -#2212 = ORIENTED_EDGE ( 'NONE', *, *, #37778, .F. ) ; -#2213 = CARTESIAN_POINT ( 'NONE', ( -20.49970533150650454, 174.4001369415204863, 100.4419005550919906 ) ) ; -#2214 = EDGE_CURVE ( 'NONE', #189, #9198, #5613, .T. ) ; -#2215 = CARTESIAN_POINT ( 'NONE', ( -20.37991618439152930, 116.5981088392802718, 90.28009379790530886 ) ) ; -#2216 = EDGE_CURVE ( 'NONE', #4989, #12211, #2532, .T. ) ; -#2217 = VERTEX_POINT ( 'NONE', #30749 ) ; -#2218 = CARTESIAN_POINT ( 'NONE', ( 13.50164015316000032, 187.2961052448821704, 105.4512426002658003 ) ) ; -#2219 = CARTESIAN_POINT ( 'NONE', ( 25.67720680875275008, 191.4606997587383148, 106.5440792307656750 ) ) ; -#2220 = CARTESIAN_POINT ( 'NONE', ( -0.4376666143244844487, 188.6124751099401351, 103.1978086576974221 ) ) ; -#2221 = ORIENTED_EDGE ( 'NONE', *, *, #30441, .T. ) ; -#2222 = DIRECTION ( 'NONE', ( -0.6087614810001754639, 0.7729390313185934280, 0.1788147452386056047 ) ) ; -#2223 = CONICAL_SURFACE ( 'NONE', #25087, 2.500000004635095419, 0.7853981633778834848 ) ; -#2224 = VECTOR ( 'NONE', #970, 1000.000000000000227 ) ; -#2225 = CARTESIAN_POINT ( 'NONE', ( 2.012984916457277468E-13, 155.6803346353121356, 98.67347229714482637 ) ) ; -#2226 = CARTESIAN_POINT ( 'NONE', ( 17.99794026751098386, 132.4103114830794254, 92.77714071224164627 ) ) ; -#2227 = AXIS2_PLACEMENT_3D ( 'NONE', #26207, #16767, #32919 ) ; -#2228 = DIRECTION ( 'NONE', ( 0.0005884949961231939744, -0.2249510543439056098, 0.9743698870671265722 ) ) ; -#2229 = CARTESIAN_POINT ( 'NONE', ( -3.668796569719823264, 185.4948906969666211, 104.3615670296347560 ) ) ; -#2230 = EDGE_LOOP ( 'NONE', ( #7577, #33234, #3497, #14273, #7207, #5262, #7868, #24348, #1325, #36443, #36692, #35364, #36420, #23391, #15085, #36180, #15646, #31204, #2359, #19113, #10680, #21162, #14416, #20925, #1853, #6398, #15758, #21228, #14330, #21736, #14581, #9397, #28739, #36442, #6985, #24752, #1436, #8689, #31144, #20285, #9946, #16459, #6404, #36649, #29302, #21214, #40379, #3887, #14196, #30835, #39125, #37256, #33222, #20032, #34801, #24052, #18175, #38553, #9426, #17252, #36372, #20255, #18588, #40462, #2614, #9427, #5165, #26758, #27703, #26828, #16453, #36200, #3998, #18988, #20754, #6622, #39689, #26090, #18789, #4332, #12667, #6072, #9855, #10313, #24525, #11576, #30280, #39563, #6018, #39085, #255, #26525 ) ) ; -#2231 = FACE_OUTER_BOUND ( 'NONE', #39019, .T. ) ; -#2232 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561517 ) ) ; -#2233 = CARTESIAN_POINT ( 'NONE', ( 28.25950385170297352, 125.5846682600628412, 89.14251585184922533 ) ) ; -#2234 = DIRECTION ( 'NONE', ( -0.0006039748319384393230, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#2235 = EDGE_LOOP ( 'NONE', ( #24633, #32521, #356, #12081 ) ) ; -#2236 = LINE ( 'NONE', #18355, #31644 ) ; -#2237 = CARTESIAN_POINT ( 'NONE', ( -42.44123101563632616, 121.4084042097561422, 91.21054638067076326 ) ) ; -#2238 = CARTESIAN_POINT ( 'NONE', ( 6.034558854670474481, 134.6330650579004100, 93.47859313952841376 ) ) ; -#2239 = CARTESIAN_POINT ( 'NONE', ( 30.07009376553777713, 136.7965748649584441, 93.78249831157448568 ) ) ; -#2240 = EDGE_CURVE ( 'NONE', #8264, #10957, #32487, .T. ) ; -#2241 = CARTESIAN_POINT ( 'NONE', ( 19.98059076253610300, 209.7097557544199162, 73.04669817794425057 ) ) ; -#2242 = LINE ( 'NONE', #12050, #1226 ) ; -#2243 = CARTESIAN_POINT ( 'NONE', ( 3.166350703034567449, 184.1264558197564156, 102.1599558388959537 ) ) ; -#2244 = CARTESIAN_POINT ( 'NONE', ( -25.50991579498579398, 209.7152486954105086, 73.57374465072240355 ) ) ; -#2245 = FACE_OUTER_BOUND ( 'NONE', #8397, .T. ) ; -#2246 = CARTESIAN_POINT ( 'NONE', ( 37.97817678914999817, 118.4650513228999955, 87.57063408596999921 ) ) ; -#2247 = DATE_AND_TIME ( #14726, #30341 ) ; -#2248 = LINE ( 'NONE', #39642, #34999 ) ; -#2249 = CIRCLE ( 'NONE', #13997, 9.500000000005877965 ) ; -#2250 = DIRECTION ( 'NONE', ( 0.0004161288024529937943, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#2251 = CARTESIAN_POINT ( 'NONE', ( 42.50830921456510936, 147.1394519918483468, 291.5328699816350309 ) ) ; -#2252 = LINE ( 'NONE', #30670, #17561 ) ; -#2253 = CARTESIAN_POINT ( 'NONE', ( 22.50216366289214065, 153.7345681062837457, 98.21065990825610470 ) ) ; -#2254 = AXIS2_PLACEMENT_3D ( 'NONE', #10203, #38391, #9797 ) ; -#2255 = CARTESIAN_POINT ( 'NONE', ( 37.28139524443679420, 185.5739301951794289, 107.6056048166977916 ) ) ; -#2256 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #18347, #31045, #6090, #22048 ), - .UNSPECIFIED., .F., .F. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 5.967414621972016775, 6.106579042305979144 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9983867564016686291, 0.9983867564016686291, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#2257 = ORIENTED_EDGE ( 'NONE', *, *, #7291, .T. ) ; -#2258 = ORIENTED_EDGE ( 'NONE', *, *, #26685, .T. ) ; -#2259 = CARTESIAN_POINT ( 'NONE', ( -2.558442632295163666, 189.7708140492636630, 103.4665133998351649 ) ) ; -#2260 = ORIENTED_EDGE ( 'NONE', *, *, #34479, .F. ) ; -#2261 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 137.0112424259995976, 291.5876487235603918 ) ) ; -#2262 = CARTESIAN_POINT ( 'NONE', ( 16.77620139486186801, 151.9520352481422663, 184.1071290740507322 ) ) ; -#2263 = DIRECTION ( 'NONE', ( -0.0002393071182786170347, -0.2252352986010032754, 0.9743043687658493601 ) ) ; -#2264 = ADVANCED_FACE ( 'NONE', ( #2739, #27697, #40128 ), #29086, .T. ) ; -#2265 = EDGE_CURVE ( 'NONE', #25353, #37130, #22154, .T. ) ; -#2266 = ORIENTED_EDGE ( 'NONE', *, *, #25673, .T. ) ; -#2267 = LINE ( 'NONE', #20865, #4823 ) ; -#2268 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 108.4362817545589905, 169.8438797714867405 ) ) ; -#2269 = DIRECTION ( 'NONE', ( -0.9914446239183341003, -0.1273125500237936858, -0.02879361578322678708 ) ) ; -#2270 = CARTESIAN_POINT ( 'NONE', ( -1.962318082198259761, 162.0965106997445844, 100.1559487201849521 ) ) ; -#2271 = ORIENTED_EDGE ( 'NONE', *, *, #17043, .T. ) ; -#2272 = CARTESIAN_POINT ( 'NONE', ( -21.21399076556896546, 136.5867924462192207, 91.71243192711530412 ) ) ; -#2273 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #40183, #5231, #21412, #8937 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2274 = CARTESIAN_POINT ( 'NONE', ( -19.32822035155621165, 147.9764759943865897, 183.5528329745226017 ) ) ; -#2275 =( GEOMETRIC_REPRESENTATION_CONTEXT ( 3 ) GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT ( ( #20372 ) ) GLOBAL_UNIT_ASSIGNED_CONTEXT ( ( #20638, #36787, #34108 ) ) REPRESENTATION_CONTEXT ( 'NONE', 'WORKASPACE' ) ); -#2276 = EDGE_LOOP ( 'NONE', ( #17915, #21348, #22739, #29294, #6079, #20237, #20126, #4371, #11098, #8130, #36486, #8137, #38867, #5564 ) ) ; -#2277 = CARTESIAN_POINT ( 'NONE', ( -27.24093993282000170, 187.8262165483999979, 103.4208887112000070 ) ) ; -#2278 = CARTESIAN_POINT ( 'NONE', ( 0.6561006408056999639, 188.6069392329000038, 103.1942120530000011 ) ) ; -#2279 = CONICAL_SURFACE ( 'NONE', #7475, 8.000000000029075409, 0.7853981633973019516 ) ; -#2280 = CONICAL_SURFACE ( 'NONE', #25138, 2.500000015113073903, 0.7853981633586051281 ) ; -#2281 = CARTESIAN_POINT ( 'NONE', ( -3.893460976669078200, 148.9599728450052396, 129.9645419195898342 ) ) ; -#2282 = CARTESIAN_POINT ( 'NONE', ( -35.53841825476909122, 192.0417956556318586, 106.9432359204027847 ) ) ; -#2283 = CIRCLE ( 'NONE', #337, 1.999999999960905495 ) ; -#2284 = ORIENTED_EDGE ( 'NONE', *, *, #26823, .T. ) ; -#2285 = CARTESIAN_POINT ( 'NONE', ( -5.668109638568818553, 183.4491308723886789, 105.0878286196073645 ) ) ; -#2286 = VERTEX_POINT ( 'NONE', #34973 ) ; -#2287 = EDGE_CURVE ( 'NONE', #23892, #33001, #25631, .T. ) ; -#2288 = EDGE_LOOP ( 'NONE', ( #10688, #35256, #7808, #24465 ) ) ; -#2289 = EDGE_LOOP ( 'NONE', ( #28848, #31206, #24233, #30254, #8907, #3948, #21695, #7325, #33408 ) ) ; -#2290 = LINE ( 'NONE', #39686, #38785 ) ; -#2291 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568178 ) ) ; -#2292 = CARTESIAN_POINT ( 'NONE', ( 39.05126608408746591, 77.57947994969133276, 289.7423654207750019 ) ) ; -#2293 = VERTEX_POINT ( 'NONE', #25830 ) ; -#2294 = DIRECTION ( 'NONE', ( -0.7066795775021792458, 8.805378661621471798E-15, 0.7075337269285059127 ) ) ; -#2295 = VERTEX_POINT ( 'NONE', #659 ) ; -#2296 = ADVANCED_FACE ( 'NONE', ( #855 ), #38079, .F. ) ; -#2297 = CARTESIAN_POINT ( 'NONE', ( 28.53370192849249776, 124.6069703449200006, 91.48759531593780991 ) ) ; -#2298 = PLANE ( 'NONE', #31955 ) ; -#2300 = CARTESIAN_POINT ( 'NONE', ( -28.94810864222802849, 110.6131156702000027, 87.28526822420690223 ) ) ; -#2299 = LINE ( 'NONE', #14786, #21278 ) ; -#2301 = CIRCLE ( 'NONE', #12743, 2.000000000070082162 ) ; -#2302 = ORIENTED_EDGE ( 'NONE', *, *, #37094, .F. ) ; -#2303 = EDGE_CURVE ( 'NONE', #37835, #25286, #19786, .T. ) ; -#2304 = VECTOR ( 'NONE', #2588, 1000.000000000000114 ) ; -#2305 = ORIENTED_EDGE ( 'NONE', *, *, #18740, .F. ) ; -#2306 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418800025, 218.5902260770999987, 73.08022052563953253 ) ) ; -#2307 = AXIS2_PLACEMENT_3D ( 'NONE', #18173, #30875, #40456 ) ; -#2308 = EDGE_CURVE ( 'NONE', #7061, #15824, #31549, .T. ) ; -#2309 = ADVANCED_FACE ( 'NONE', ( #19662 ), #3511, .F. ) ; -#2310 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20149, #38752, #23237, #20352 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2311 = ORIENTED_EDGE ( 'NONE', *, *, #25348, .F. ) ; -#2312 = EDGE_CURVE ( 'NONE', #12419, #10753, #35587, .T. ) ; -#2313 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971557631 ) ) ; -#2314 = EDGE_CURVE ( 'NONE', #13097, #8665, #31349, .T. ) ; -#2315 = CARTESIAN_POINT ( 'NONE', ( -14.60099755400268506, 128.1392381506334175, 179.4895675734404392 ) ) ; -#2316 = CARTESIAN_POINT ( 'NONE', ( -30.17967533865709129, 185.9478674444400497, 102.6005990038461988 ) ) ; -#2317 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971578725 ) ) ; -#2318 = VERTEX_POINT ( 'NONE', #13544 ) ; -#2319 = ORIENTED_EDGE ( 'NONE', *, *, #1798, .F. ) ; -#2320 = ORIENTED_EDGE ( 'NONE', *, *, #29307, .T. ) ; -#2321 = CARTESIAN_POINT ( 'NONE', ( -2.180037377191725412, 189.9716679226577014, 103.9664554834080832 ) ) ; -#2322 = CARTESIAN_POINT ( 'NONE', ( -37.28964217851551410, 124.9030048851708585, 93.64309515347763124 ) ) ; -#2323 = DIRECTION ( 'NONE', ( 0.0005884949961232894926, -0.2249510543439051935, 0.9743698870671265722 ) ) ; -#2324 = ORIENTED_EDGE ( 'NONE', *, *, #4402, .F. ) ; -#2325 = CARTESIAN_POINT ( 'NONE', ( -35.94898838659999996, 191.8605118499999946, 106.6098996716000045 ) ) ; -#2326 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3463, #15944, #25375, #22311, #26584, #22908 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2327 = CARTESIAN_POINT ( 'NONE', ( 2.957254264836670199, 190.0891094935151955, 106.6212271850417892 ) ) ; -#2328 = CARTESIAN_POINT ( 'NONE', ( -12.92592855545641228, 126.1600735973864289, 178.8056805775503335 ) ) ; -#2329 = CARTESIAN_POINT ( 'NONE', ( -5.668553076709809346, 181.6128662714581310, 104.1507415746884391 ) ) ; -#2330 = VECTOR ( 'NONE', #18409, 1000.000000000000114 ) ; -#2331 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971541810 ) ) ; -#2332 = LINE ( 'NONE', #14809, #6498 ) ; -#2333 = ORIENTED_EDGE ( 'NONE', *, *, #8742, .F. ) ; -#2334 = VECTOR ( 'NONE', #37320, 1000.000000000000114 ) ; -#2335 = CARTESIAN_POINT ( 'NONE', ( -21.96624583357523619, 177.4045611624641765, 100.6232602709462043 ) ) ; -#2336 = DIRECTION ( 'NONE', ( 1.156504871743948528E-16, 0.9743043966640312359, 0.2252353050503803078 ) ) ; -#2337 = ORIENTED_EDGE ( 'NONE', *, *, #24428, .T. ) ; -#2338 = ADVANCED_FACE ( 'NONE', ( #15993 ), #3722, .F. ) ; -#2339 = CARTESIAN_POINT ( 'NONE', ( 5.667815391071213682, 183.5631071180958998, 104.5941433521421686 ) ) ; -#2340 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35572, #32350, #4317, #1253 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2341 = ORIENTED_EDGE ( 'NONE', *, *, #31171, .T. ) ; -#2343 = DIRECTION ( 'NONE', ( -0.0005884949961237706615, 0.2249510543439053323, -0.9743698870671265722 ) ) ; -#2342 = CARTESIAN_POINT ( 'NONE', ( -29.90873775226999953, 109.6131156702000027, 152.4718672074000381 ) ) ; -#2344 = EDGE_LOOP ( 'NONE', ( #29913, #5816, #33576, #2751 ) ) ; -#2346 = VERTEX_POINT ( 'NONE', #28484 ) ; -#2345 = EDGE_CURVE ( 'NONE', #14103, #2188, #28681, .T. ) ; -#2347 = CYLINDRICAL_SURFACE ( 'NONE', #11924, 6.000000000278002510 ) ; -#2348 = VERTEX_POINT ( 'NONE', #460 ) ; -#2349 = CARTESIAN_POINT ( 'NONE', ( -21.58773827856466454, 112.4042505803199532, 201.3497749872313420 ) ) ; -#2350 = ADVANCED_FACE ( 'NONE', ( #13344 ), #12948, .T. ) ; -#2351 = AXIS2_PLACEMENT_3D ( 'NONE', #30371, #14845, #24258 ) ; -#2352 = DIRECTION ( 'NONE', ( 0.5634794340701355653, -0.8261300910752492621, 0.000000000000000000 ) ) ; -#2353 = CARTESIAN_POINT ( 'NONE', ( 14.94854772523675557, 136.6910697646424069, 91.37256421016206787 ) ) ; -#2354 = EDGE_LOOP ( 'NONE', ( #5341, #15112, #13293, #1341 ) ) ; -#2355 = VECTOR ( 'NONE', #29045, 1000.000000000000227 ) ; -#2356 = ORIENTED_EDGE ( 'NONE', *, *, #17380, .F. ) ; -#2357 = CARTESIAN_POINT ( 'NONE', ( -3.668109984895000508, 187.1813567023000076, 105.9482730532999994 ) ) ; -#2358 = ORIENTED_EDGE ( 'NONE', *, *, #25724, .T. ) ; -#2359 = ORIENTED_EDGE ( 'NONE', *, *, #23409, .F. ) ; -#2360 = ORIENTED_EDGE ( 'NONE', *, *, #24337, .F. ) ; -#2361 = ADVANCED_FACE ( 'NONE', ( #16585 ), #35189, .F. ) ; -#2362 = CARTESIAN_POINT ( 'NONE', ( 21.25891409511187291, 128.8498498509368915, 89.90056508924928380 ) ) ; -#2363 = CARTESIAN_POINT ( 'NONE', ( 30.31667092456163459, 126.5682557959073335, 91.76305689627588436 ) ) ; -#2364 = LINE ( 'NONE', #14636, #18039 ) ; -#2365 = CARTESIAN_POINT ( 'NONE', ( 3.002302857372999956, 209.4500945363000142, 73.06113814329000888 ) ) ; -#2366 = VERTEX_POINT ( 'NONE', #6386 ) ; -#2367 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6595, #25644, #22168, #37896 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2368 = AXIS2_PLACEMENT_3D ( 'NONE', #35354, #38841, #39046 ) ; -#2369 = EDGE_LOOP ( 'NONE', ( #14562, #23434, #21178, #33610 ) ) ; -#2370 = ORIENTED_EDGE ( 'NONE', *, *, #10778, .T. ) ; -#2371 = LINE ( 'NONE', #14230, #25890 ) ; -#2372 = CARTESIAN_POINT ( 'NONE', ( -35.30527578227999896, 192.3918037269000081, 103.7496537549999971 ) ) ; -#2373 = VERTEX_POINT ( 'NONE', #3321 ) ; -#2374 = CARTESIAN_POINT ( 'NONE', ( -26.00179438729000125, 120.8350387973000153, 87.56562579824000636 ) ) ; -#2375 = ORIENTED_EDGE ( 'NONE', *, *, #31610, .T. ) ; -#2376 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927790623616, 0.0005734119022072373204 ) ) ; -#2377 = DIRECTION ( 'NONE', ( -0.1782640835105696875, -0.3528946327679918782, 0.9185245204640325456 ) ) ; -#2378 = ORIENTED_EDGE ( 'NONE', *, *, #39307, .F. ) ; -#2379 = CARTESIAN_POINT ( 'NONE', ( 0.7432696594355128195, 188.6192524948516223, 103.1986602668173276 ) ) ; -#2380 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#2381 = CARTESIAN_POINT ( 'NONE', ( 38.73751167838227616, 119.2159698917354120, 90.26423455750220626 ) ) ; -#2382 = ORIENTED_EDGE ( 'NONE', *, *, #24612, .F. ) ; -#2383 = CARTESIAN_POINT ( 'NONE', ( -21.27837344614222559, 182.7516671288082364, 101.8573217206271693 ) ) ; -#2384 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2385 = FACE_OUTER_BOUND ( 'NONE', #21956, .T. ) ; -#2386 = VECTOR ( 'NONE', #9307, 1000.000000000000227 ) ; -#2387 = ORIENTED_EDGE ( 'NONE', *, *, #2460, .F. ) ; -#2388 = CARTESIAN_POINT ( 'NONE', ( -28.94720267997999841, 103.6131156702000027, 88.78526795067999444 ) ) ; -#2389 = ORIENTED_EDGE ( 'NONE', *, *, #23872, .F. ) ; -#2390 = DIRECTION ( 'NONE', ( 0.9999998268368246457, 0.0001323826181902279108, -0.0005734118615388824605 ) ) ; -#2391 = CIRCLE ( 'NONE', #12166, 2.749999999949217511 ) ; -#2392 = CARTESIAN_POINT ( 'NONE', ( -2.421792290688875138, 209.3823634036505439, 73.56388561843570528 ) ) ; -#2393 = CARTESIAN_POINT ( 'NONE', ( -14.16977587005254158, 182.7576216332787737, 102.3675551592481696 ) ) ; -#2394 = DIRECTION ( 'NONE', ( 0.0005884949961267937424, -0.2249510543439074417, 0.9743698870671260170 ) ) ; -#2395 = CARTESIAN_POINT ( 'NONE', ( -22.49823373577851271, 184.2867149872474783, 105.2913651576170651 ) ) ; -#2396 = EDGE_CURVE ( 'NONE', #31197, #2940, #12946, .T. ) ; -#2397 = EDGE_LOOP ( 'NONE', ( #9377, #8025, #8488, #29693, #28155, #36909 ) ) ; -#2398 = AXIS2_PLACEMENT_3D ( 'NONE', #10486, #7594, #23355 ) ; -#2399 = ADVANCED_FACE ( 'NONE', ( #17946 ), #14714, .F. ) ; -#2400 = ADVANCED_FACE ( 'NONE', ( #39631 ), #30655, .F. ) ; -#2401 = VECTOR ( 'NONE', #18140, 1000.000000000000114 ) ; -#2402 = ADVANCED_FACE ( 'NONE', ( #5486 ), #17543, .T. ) ; -#2403 = DIRECTION ( 'NONE', ( -0.5988974202702721517, 0.8008257488327987783, 0.000000000000000000 ) ) ; -#2404 = CARTESIAN_POINT ( 'NONE', ( 22.31312662366504540, 116.2335386298891393, 182.3227435278615474 ) ) ; -#2405 = CARTESIAN_POINT ( 'NONE', ( -23.78120603611477790, 115.1892833753767036, 87.28214754456956825 ) ) ; -#2406 = DIRECTION ( 'NONE', ( 0.0001358647752772932629, 0.9743700647730598741, 0.2249510133671457635 ) ) ; -#2407 = ADVANCED_FACE ( 'NONE', ( #27411 ), #6410, .F. ) ; -#2408 = CARTESIAN_POINT ( 'NONE', ( -22.99976245438101330, 118.1131156702000169, 90.28469153849982831 ) ) ; -#2409 = CARTESIAN_POINT ( 'NONE', ( 32.42164055602032136, 176.1828832701569638, 100.3083647338347646 ) ) ; -#2410 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#2411 = CARTESIAN_POINT ( 'NONE', ( 22.21137596932447522, 115.2160762028210428, 90.25436972469280761 ) ) ; -#2412 = ORIENTED_EDGE ( 'NONE', *, *, #14675, .F. ) ; -#2414 = ADVANCED_FACE ( 'NONE', ( #5900 ), #31055, .F. ) ; -#2413 = CARTESIAN_POINT ( 'NONE', ( 14.55485738440738963, 181.8858882541513537, 104.7147121319332825 ) ) ; -#2415 = CARTESIAN_POINT ( 'NONE', ( -19.99971477990169788, 118.1214470234825029, 90.27986416578403350 ) ) ; -#2416 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11807, #14266, #26739, #20792, #20378, #23665 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2417 = FACE_OUTER_BOUND ( 'NONE', #4445, .T. ) ; -#2418 = AXIS2_PLACEMENT_3D ( 'NONE', #27308, #24642, #36472 ) ; -#2419 = EDGE_LOOP ( 'NONE', ( #30600, #18884, #37995, #19455 ) ) ; -#2420 = CARTESIAN_POINT ( 'NONE', ( -12.59997215317999952, 115.9590670145843205, 152.9217693939943388 ) ) ; -#2421 = FACE_OUTER_BOUND ( 'NONE', #28104, .T. ) ; -#2422 = VECTOR ( 'NONE', #4496, 999.9999999999998863 ) ; -#2423 = ORIENTED_EDGE ( 'NONE', *, *, #1654, .F. ) ; -#2424 = CARTESIAN_POINT ( 'NONE', ( -38.15613654141999689, 119.1005567029999952, 87.44234925840000017 ) ) ; -#2425 = ADVANCED_FACE ( 'NONE', ( #27797 ), #40038, .F. ) ; -#2426 = CARTESIAN_POINT ( 'NONE', ( 16.24603267945985507, 152.0453547567774706, 181.0525560685096593 ) ) ; -#2427 = CARTESIAN_POINT ( 'NONE', ( -5.663464557155529988, 131.0206703453534374, 89.90489628355439322 ) ) ; -#2428 = ORIENTED_EDGE ( 'NONE', *, *, #20324, .F. ) ; -#2429 = CARTESIAN_POINT ( 'NONE', ( 35.86915118585585560, 191.5522503802022811, 106.8824361391712898 ) ) ; -#2430 = AXIS2_PLACEMENT_3D ( 'NONE', #36448, #5366, #27487 ) ; -#2431 = CARTESIAN_POINT ( 'NONE', ( -45.39773774286052088, 124.2994142384970218, 88.45363130071420699 ) ) ; -#2432 = CARTESIAN_POINT ( 'NONE', ( 17.20373620539847792, 122.0130630878173861, 174.6141869257109533 ) ) ; -#2433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #797, #21896, #18589, #31096 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2434 = FACE_OUTER_BOUND ( 'NONE', #35609, .T. ) ; -#2435 = DIRECTION ( 'NONE', ( 0.0006039748319383109534, 1.233022124494217175E-14, 0.9999998176071845934 ) ) ; -#2436 = ORIENTED_EDGE ( 'NONE', *, *, #19025, .F. ) ; -#2437 = CARTESIAN_POINT ( 'NONE', ( 38.33729829349999818, 118.8626431811999993, 87.57247875375999513 ) ) ; -#2438 = CARTESIAN_POINT ( 'NONE', ( -23.35081975911714380, 130.3436102262665486, 92.83812635286813020 ) ) ; -#2439 = DIRECTION ( 'NONE', ( 0.0005884948598593896978, -0.2255194595956526160, 0.9742384856992073461 ) ) ; -#2440 = CARTESIAN_POINT ( 'NONE', ( 20.00028792540915035, 151.9820690596619102, 94.72877128701482263 ) ) ; -#2441 = ORIENTED_EDGE ( 'NONE', *, *, #33295, .T. ) ; -#2442 = ORIENTED_EDGE ( 'NONE', *, *, #33075, .T. ) ; -#2443 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749903839, 130.6678814337496135, 90.32225895349807843 ) ) ; -#2444 = CARTESIAN_POINT ( 'NONE', ( -43.10638044614131559, 120.9782189030739232, 90.80560025573178962 ) ) ; -#2445 = CARTESIAN_POINT ( 'NONE', ( 25.83702252211450912, 212.0387306411581676, 73.04289916821271333 ) ) ; -#2446 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2447 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17403, #4121, #38476, #13745 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2448 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749098554, 132.4103119504792119, 92.77713868755240867 ) ) ; -#2449 = EDGE_CURVE ( 'NONE', #1363, #7877, #21277, .T. ) ; -#2450 = AXIS2_PLACEMENT_3D ( 'NONE', #4757, #29724, #17221 ) ; -#2451 = EDGE_CURVE ( 'NONE', #28767, #19429, #37186, .T. ) ; -#2452 = EDGE_CURVE ( 'NONE', #22589, #5068, #3222, .T. ) ; -#2453 = CARTESIAN_POINT ( 'NONE', ( -25.91665832970164374, 209.7105128082618251, 73.16760013480885050 ) ) ; -#2454 = AXIS2_PLACEMENT_3D ( 'NONE', #27916, #25242, #9487 ) ; -#2455 = CARTESIAN_POINT ( 'NONE', ( -0.02657825335728297364, 128.5632152146144449, 291.5585599878308471 ) ) ; -#2456 = PERSON_AND_ORGANIZATION_ROLE ( 'design_owner' ) ; -#2457 = CARTESIAN_POINT ( 'NONE', ( 38.80965466373000083, 119.1329998486999955, 90.12137990267000021 ) ) ; -#2458 = CARTESIAN_POINT ( 'NONE', ( 17.11663184279114347, 122.6447230097683843, 172.0965978585869607 ) ) ; -#2459 = DIRECTION ( 'NONE', ( -0.9999998268368044396, -0.0001323825928669451334, 0.0005734119025882206512 ) ) ; -#2460 = EDGE_CURVE ( 'NONE', #35062, #13439, #28453, .T. ) ; -#2461 = CARTESIAN_POINT ( 'NONE', ( 38.12525175933708965, 171.3045222593593166, 164.7303159086331448 ) ) ; -#2462 = CARTESIAN_POINT ( 'NONE', ( -20.60014793633816765, 116.2721715147326904, 87.28022626518796301 ) ) ; -#2463 = FACE_OUTER_BOUND ( 'NONE', #23516, .T. ) ; -#2464 = VERTEX_POINT ( 'NONE', #34292 ) ; -#2465 = ORIENTED_EDGE ( 'NONE', *, *, #18705, .T. ) ; -#2466 = EDGE_CURVE ( 'NONE', #31711, #7061, #6686, .T. ) ; -#2467 = CARTESIAN_POINT ( 'NONE', ( -1.063471189976053832, 188.6709375346488287, 103.2116839268398536 ) ) ; -#2468 = ORIENTED_EDGE ( 'NONE', *, *, #26367, .T. ) ; -#2469 = LINE ( 'NONE', #23941, #34625 ) ; -#2470 = LINE ( 'NONE', #30261, #31080 ) ; -#2471 = ORIENTED_EDGE ( 'NONE', *, *, #30996, .T. ) ; -#2472 = CARTESIAN_POINT ( 'NONE', ( -39.55746895486999648, 119.4471732075000006, 89.94349737900999742 ) ) ; -#2473 = ADVANCED_FACE ( 'NONE', ( #24733 ), #2834, .F. ) ; -#2474 = FACE_OUTER_BOUND ( 'NONE', #13977, .T. ) ; -#2475 = CARTESIAN_POINT ( 'NONE', ( -43.18873574177670349, 153.0051697192221241, 291.5846288494004739 ) ) ; -#2476 = EDGE_LOOP ( 'NONE', ( #6274, #22374, #13519, #13414 ) ) ; -#2477 = DIRECTION ( 'NONE', ( 0.9914447795421099663, -0.1270909273343945323, -0.02975139169821508847 ) ) ; -#2478 = CIRCLE ( 'NONE', #26645, 30.49999999998560085 ) ; -#2479 = CARTESIAN_POINT ( 'NONE', ( 16.56014902165552272, 121.8510385007027992, 177.5702860362286799 ) ) ; -#2480 = FACE_OUTER_BOUND ( 'NONE', #33139, .T. ) ; -#2481 = DIRECTION ( 'NONE', ( 0.0005884949961224158425, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2482 = AXIS2_PLACEMENT_3D ( 'NONE', #23464, #25949, #23264 ) ; -#2483 = CARTESIAN_POINT ( 'NONE', ( 15.75014751337000263, 145.1854452732999903, 93.41868622648999576 ) ) ; -#2484 = ORIENTED_EDGE ( 'NONE', *, *, #3814, .T. ) ; -#2485 = CARTESIAN_POINT ( 'NONE', ( -25.36704866655999879, 191.4398696147000010, 104.5177098329999978 ) ) ; -#2486 = CARTESIAN_POINT ( 'NONE', ( 1.253857910261999997, 188.7050348800999870, 103.2175213973000041 ) ) ; -#2487 = CARTESIAN_POINT ( 'NONE', ( 26.00268413466335460, 120.2421824539040358, 90.47622374426396163 ) ) ; -#2488 = ORIENTED_EDGE ( 'NONE', *, *, #24198, .F. ) ; -#2489 = EDGE_LOOP ( 'NONE', ( #36940, #30496, #27906, #8078, #30851, #22442, #39546, #38862 ) ) ; -#2490 = CARTESIAN_POINT ( 'NONE', ( -38.01211212650550664, 119.1971871873620472, 87.30118044812934386 ) ) ; -#2491 = ORIENTED_EDGE ( 'NONE', *, *, #23776, .F. ) ; -#2492 = EDGE_LOOP ( 'NONE', ( #1304, #25304, #38059, #9645 ) ) ; -#2493 = EDGE_LOOP ( 'NONE', ( #26634, #16558, #27972, #13628 ) ) ; -#2494 = EDGE_CURVE ( 'NONE', #31566, #8772, #26498, .T. ) ; -#2495 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2496 = EDGE_CURVE ( 'NONE', #2793, #4933, #6487, .T. ) ; -#2497 = CARTESIAN_POINT ( 'NONE', ( 23.36940079100686063, 177.7945392694463749, 100.6858723966742843 ) ) ; -#2498 = CARTESIAN_POINT ( 'NONE', ( 39.79988895049328335, 119.8651423291884726, 87.81508310122019623 ) ) ; -#2499 = CARTESIAN_POINT ( 'NONE', ( -37.67910728328570258, 190.9663396873137060, 106.3291846998849053 ) ) ; -#2500 = ORIENTED_EDGE ( 'NONE', *, *, #35353, .F. ) ; -#2501 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22035, #27584, #6073, #12604 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2502 = CARTESIAN_POINT ( 'NONE', ( 21.63968124537738547, 115.2790863461608097, 189.0193985308339393 ) ) ; -#2503 = VERTEX_POINT ( 'NONE', #31657 ) ; -#2504 = CARTESIAN_POINT ( 'NONE', ( 26.79907597897999949, 123.2871420175000026, 91.00767973732999394 ) ) ; -#2505 = VECTOR ( 'NONE', #7477, 1000.000000000000227 ) ; -#2506 = CARTESIAN_POINT ( 'NONE', ( 20.00150936005196201, 118.3414216785000121, 90.25570442875019239 ) ) ; -#2507 = VECTOR ( 'NONE', #4590, 1000.000000000000000 ) ; -#2509 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7071067167008887600, -0.7071068456722005013 ) ) ; -#2508 = CARTESIAN_POINT ( 'NONE', ( 15.53838427372360798, 112.1323247865566941, 152.4707203835889402 ) ) ; -#2510 = ORIENTED_EDGE ( 'NONE', *, *, #25823, .F. ) ; -#2511 = ORIENTED_EDGE ( 'NONE', *, *, #11299, .F. ) ; -#2512 = CARTESIAN_POINT ( 'NONE', ( -2.452854086982361626, 209.7096538831000032, 78.05998645676569936 ) ) ; -#2513 = ORIENTED_EDGE ( 'NONE', *, *, #4222, .F. ) ; -#2514 = DIRECTION ( 'NONE', ( -0.0005884949961241434102, 0.2249510543439057764, -0.9743698870671265722 ) ) ; -#2515 = EDGE_CURVE ( 'NONE', #5612, #14084, #37344, .T. ) ; -#2516 = DIRECTION ( 'NONE', ( -0.6087602338625655030, -0.7731011424623617234, -0.1781168189447182304 ) ) ; -#2517 = CARTESIAN_POINT ( 'NONE', ( 15.66823628282405423, 184.3661235549490129, 104.9445449394547438 ) ) ; -#2518 = CARTESIAN_POINT ( 'NONE', ( -12.64208105978997665, 134.9837024878036118, 90.91483575941917650 ) ) ; -#2519 = EDGE_LOOP ( 'NONE', ( #20999, #9202, #8933, #37777 ) ) ; -#2520 = EDGE_LOOP ( 'NONE', ( #11010, #319, #11078, #23029 ) ) ; -#2521 = DIRECTION ( 'NONE', ( 1.328421402153733269E-20, -0.9743043966640312359, -0.2252353050503803356 ) ) ; -#2522 = CARTESIAN_POINT ( 'NONE', ( 15.51352726335324483, 187.3921001862149467, 102.9064289159318690 ) ) ; -#2523 = ORIENTED_EDGE ( 'NONE', *, *, #11684, .T. ) ; -#2524 = AXIS2_PLACEMENT_3D ( 'NONE', #10267, #26208, #22735 ) ; -#2525 = CARTESIAN_POINT ( 'NONE', ( -4.037441717428633225, 144.1002716341167229, 93.43668138785120902 ) ) ; -#2526 = ADVANCED_FACE ( 'NONE', ( #25131 ), #12849, .F. ) ; -#2527 = CONICAL_SURFACE ( 'NONE', #3179, 2.502994210670941744, 0.7853981633984441491 ) ; -#2528 = CARTESIAN_POINT ( 'NONE', ( 1.799632749338529791, 188.6738461430155667, 106.2963457010693986 ) ) ; -#2529 = ORIENTED_EDGE ( 'NONE', *, *, #9279, .T. ) ; -#2530 = CARTESIAN_POINT ( 'NONE', ( -20.51970368596797556, 209.1729065476789913, 73.59374226241675387 ) ) ; -#2531 = EDGE_CURVE ( 'NONE', #26268, #10159, #37840, .T. ) ; -#2532 = LINE ( 'NONE', #33795, #6231 ) ; -#2533 = CARTESIAN_POINT ( 'NONE', ( 20.33484954814858270, 137.9142791705131970, 94.21752540843081647 ) ) ; -#2534 = CARTESIAN_POINT ( 'NONE', ( 18.99695336057541795, 148.4229678448664060, 183.7014091461406622 ) ) ; -#2535 = EDGE_LOOP ( 'NONE', ( #4795, #9710, #875, #18970, #20198 ) ) ; -#2536 = CYLINDRICAL_SURFACE ( 'NONE', #26308, 4.999999999999994671 ) ; -#2537 = EDGE_CURVE ( 'NONE', #26211, #23072, #10783, .T. ) ; -#2538 = EDGE_CURVE ( 'NONE', #21067, #7275, #10189, .T. ) ; -#2539 = CARTESIAN_POINT ( 'NONE', ( -0.04020359587071823532, 99.17590004611790278, 343.2031739270701678 ) ) ; -#2540 = CARTESIAN_POINT ( 'NONE', ( 6.034364035348885658, 135.2945551070078238, 91.39763805326617785 ) ) ; -#2541 = EDGE_CURVE ( 'NONE', #3107, #3241, #19867, .T. ) ; -#2542 = VERTEX_POINT ( 'NONE', #760 ) ; -#2543 = CARTESIAN_POINT ( 'NONE', ( -14.75947401827107974, 154.0969921037251424, 95.23793027177912052 ) ) ; -#2544 = VERTEX_POINT ( 'NONE', #3617 ) ; -#2546 = CARTESIAN_POINT ( 'NONE', ( 76.10748482111097246, 155.7951947758858182, 98.14087069360385840 ) ) ; -#2545 = CYLINDRICAL_SURFACE ( 'NONE', #31163, 3.000000000000002220 ) ; -#2547 = ORIENTED_EDGE ( 'NONE', *, *, #14868, .F. ) ; -#2548 = VECTOR ( 'NONE', #15680, 1000.000000000000000 ) ; -#2549 = ORIENTED_EDGE ( 'NONE', *, *, #39868, .T. ) ; -#2550 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36197, #2074, #13934, #27241 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2551 = ORIENTED_EDGE ( 'NONE', *, *, #1364, .F. ) ; -#2552 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2553 = VECTOR ( 'NONE', #9622, 1000.000000000000000 ) ; -#2554 = CARTESIAN_POINT ( 'NONE', ( -14.91027384103292874, 124.4773777159772550, 171.6934768334666899 ) ) ; -#2555 = DIRECTION ( 'NONE', ( 0.0006039748319385408043, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#2556 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 132.9726895863780385, 90.34121396988766151 ) ) ; -#2557 = AXIS2_PLACEMENT_3D ( 'NONE', #36887, #33398, #34007 ) ; -#2558 = CARTESIAN_POINT ( 'NONE', ( 31.79542158357200776, 220.4002260771000010, 75.53930090045915335 ) ) ; -#2559 = ORIENTED_EDGE ( 'NONE', *, *, #24055, .T. ) ; -#2560 = ORIENTED_EDGE ( 'NONE', *, *, #25261, .F. ) ; -#2561 = DIRECTION ( 'NONE', ( -0.0006039748319391170578, -1.156482106403593688E-14, -0.9999998176071845934 ) ) ; -#2562 = VECTOR ( 'NONE', #14208, 1000.000000000000227 ) ; -#2563 = ORIENTED_EDGE ( 'NONE', *, *, #9363, .F. ) ; -#2564 = ORIENTED_EDGE ( 'NONE', *, *, #24534, .F. ) ; -#2565 = CARTESIAN_POINT ( 'NONE', ( -75.98858757284095589, 155.6702750673094329, 98.71704506522667089 ) ) ; -#2566 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366368657916, 137.4659008082770697, 177.5714312369256049 ) ) ; -#2567 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596097999, 131.0247019790824083, 89.88805227292419886 ) ) ; -#2568 = CARTESIAN_POINT ( 'NONE', ( 2.461607553392946901, 209.5695820990317202, 73.55701783320675702 ) ) ; -#2569 = VERTEX_POINT ( 'NONE', #13449 ) ; -#2570 = ORIENTED_EDGE ( 'NONE', *, *, #24712, .F. ) ; -#2571 = ORIENTED_EDGE ( 'NONE', *, *, #26835, .F. ) ; -#2572 = DIRECTION ( 'NONE', ( 0.0005884949961230356809, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2573 = CARTESIAN_POINT ( 'NONE', ( -36.25900725070000874, 191.9988562334999926, 104.5625822764999953 ) ) ; -#2574 = EDGE_LOOP ( 'NONE', ( #6057, #6846, #15636, #2491 ) ) ; -#2575 = CARTESIAN_POINT ( 'NONE', ( -25.50130725202999926, 120.7286589635999974, 88.05403516466999747 ) ) ; -#2576 = ORIENTED_EDGE ( 'NONE', *, *, #11303, .F. ) ; -#2577 = ORIENTED_EDGE ( 'NONE', *, *, #29776, .T. ) ; -#2578 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282898364, 154.4034317162757475, 95.31352405033304365 ) ) ; -#2579 = CARTESIAN_POINT ( 'NONE', ( 37.28562273942550576, 118.1774615424172339, 122.8329667304428909 ) ) ; -#2580 = PLANE ( 'NONE', #16279 ) ; -#2581 = EDGE_LOOP ( 'NONE', ( #36892, #28216, #18170, #39993 ) ) ; -#2582 = EDGE_CURVE ( 'NONE', #34131, #2295, #10554, .T. ) ; -#2583 = CARTESIAN_POINT ( 'NONE', ( 3.797364302584283813, 174.7411840455865217, 102.8032958810170783 ) ) ; -#2584 = CARTESIAN_POINT ( 'NONE', ( -3.794011246975583340, 167.8782899004469868, 101.2272116182543868 ) ) ; -#2585 = DIRECTION ( 'NONE', ( 0.7933535325932957738, -0.5931614258681779939, -0.1369295263402617313 ) ) ; -#2586 = VECTOR ( 'NONE', #36195, 1000.000000000000114 ) ; -#2587 = EDGE_CURVE ( 'NONE', #12430, #36191, #13839, .T. ) ; -#2588 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927792771421, 0.0005734119022071876640 ) ) ; -#2589 = DIRECTION ( 'NONE', ( 0.5987319967475925875, 0.8009494341533932582, 0.000000000000000000 ) ) ; -#2590 = EDGE_CURVE ( 'NONE', #15550, #12347, #10615, .T. ) ; -#2591 = AXIS2_PLACEMENT_3D ( 'NONE', #17490, #29582, #1563 ) ; -#2592 = VERTEX_POINT ( 'NONE', #32063 ) ; -#2593 = PLANE ( 'NONE', #11922 ) ; -#2594 = VERTEX_POINT ( 'NONE', #25934 ) ; -#2595 = AXIS2_PLACEMENT_3D ( 'NONE', #25594, #10037, #28447 ) ; -#2596 = CARTESIAN_POINT ( 'NONE', ( -25.91449224140000140, 181.8727335915000367, 101.9137800610000113 ) ) ; -#2597 = ADVANCED_FACE ( 'NONE', ( #16884 ), #13355, .F. ) ; -#2598 = CARTESIAN_POINT ( 'NONE', ( -38.00841869184999666, 119.4135498740000116, 87.18468147088000819 ) ) ; -#2599 = AXIS2_PLACEMENT_3D ( 'NONE', #36218, #14360, #4738 ) ; -#2600 = CARTESIAN_POINT ( 'NONE', ( 36.30117620144000057, 114.1276906072999964, 89.58115698366999879 ) ) ; -#2601 = ADVANCED_FACE ( 'NONE', ( #4023 ), #32301, .F. ) ; -#2602 = ADVANCED_FACE ( 'NONE', ( #7489 ), #36199, .F. ) ; -#2603 = CARTESIAN_POINT ( 'NONE', ( -1.458415330484564842, 144.9404864492794047, 129.0359332385724258 ) ) ; -#2604 = CARTESIAN_POINT ( 'NONE', ( -25.75508418156459456, 122.1544537738279388, 90.43581502352311929 ) ) ; -#2605 = ORIENTED_EDGE ( 'NONE', *, *, #5620, .F. ) ; -#2606 = CARTESIAN_POINT ( 'NONE', ( -13.55543936426466267, 163.9606855452657044, 100.5933297005652349 ) ) ; -#2607 = ORIENTED_EDGE ( 'NONE', *, *, #31944, .T. ) ; -#2608 = FACE_OUTER_BOUND ( 'NONE', #36592, .T. ) ; -#2609 = FACE_OUTER_BOUND ( 'NONE', #35760, .T. ) ; -#2610 = FACE_OUTER_BOUND ( 'NONE', #2574, .T. ) ; -#2611 = LINE ( 'NONE', #17715, #9042 ) ; -#2612 = CARTESIAN_POINT ( 'NONE', ( -17.26247767858138005, 152.5342161776122225, 182.4800534808789791 ) ) ; -#2613 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2614 = ORIENTED_EDGE ( 'NONE', *, *, #33542, .F. ) ; -#2615 = DIRECTION ( 'NONE', ( -0.6087611434179127645, -0.7731004625452339019, -0.1781166614240815016 ) ) ; -#2616 = CARTESIAN_POINT ( 'NONE', ( 1.050070742191543838, 189.0588793901672773, 105.7534012852386951 ) ) ; -#2617 = CIRCLE ( 'NONE', #28103, 1.750000000000001998 ) ; -#2618 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; -#2619 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31747, #25013, #3705, #9059, #34379, #33982 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2620 = ORIENTED_EDGE ( 'NONE', *, *, #21659, .F. ) ; -#2621 = CARTESIAN_POINT ( 'NONE', ( 19.98110224327852080, 206.5438147855657007, 74.14602195566800447 ) ) ; -#2622 = VECTOR ( 'NONE', #2918, 1000.000000000000227 ) ; -#2623 = LINE ( 'NONE', #27978, #11984 ) ; -#2624 = VECTOR ( 'NONE', #35335, 1000.000000000000227 ) ; -#2625 = ORIENTED_EDGE ( 'NONE', *, *, #16537, .F. ) ; -#2626 = CARTESIAN_POINT ( 'NONE', ( -38.98627109030000071, 119.3757285326999948, 87.77087478292000355 ) ) ; -#2627 = CARTESIAN_POINT ( 'NONE', ( -4.036264727520263662, 143.6503695267791727, 95.38542116167025142 ) ) ; -#2628 = PLANE ( 'NONE', #69 ) ; -#2629 = VERTEX_POINT ( 'NONE', #23248 ) ; -#2630 = DIRECTION ( 'NONE', ( 0.6188015000093128881, -0.7855473910504855439, 0.000000000000000000 ) ) ; -#2631 = EDGE_CURVE ( 'NONE', #6854, #5478, #9449, .T. ) ; -#2632 = EDGE_CURVE ( 'NONE', #19017, #31008, #40106, .T. ) ; -#2633 = CARTESIAN_POINT ( 'NONE', ( 3.658380091855549132, 167.8528591461128485, 101.3558085340577861 ) ) ; -#2634 = EDGE_CURVE ( 'NONE', #5073, #26865, #18554, .T. ) ; -#2635 = DIRECTION ( 'NONE', ( -0.0006039748319346909108, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#2636 = CARTESIAN_POINT ( 'NONE', ( -20.00006126831510400, 120.3902141372887087, 87.45929000627990035 ) ) ; -#2637 = DIRECTION ( 'NONE', ( -0.0005884949961261437632, 0.2249510543439059151, -0.9743698870671263501 ) ) ; -#2638 = EDGE_LOOP ( 'NONE', ( #6449, #13575, #38237, #23383 ) ) ; -#2639 = LINE ( 'NONE', #37179, #426 ) ; -#2640 = ADVANCED_FACE ( 'NONE', ( #38377 ), #19371, .F. ) ; -#2641 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #30802, #21609 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2642 = CARTESIAN_POINT ( 'NONE', ( 14.74167426920670465, 136.8705781667366068, 91.75623271434285755 ) ) ; -#2643 = CARTESIAN_POINT ( 'NONE', ( 36.55775395379972537, 191.7245065411347866, 104.3510190822927512 ) ) ; -#2644 = EDGE_CURVE ( 'NONE', #12309, #3470, #22856, .T. ) ; -#2645 = CARTESIAN_POINT ( 'NONE', ( -46.08310388805222146, 124.8206055617895629, 91.40572349197309165 ) ) ; -#2646 = ORIENTED_EDGE ( 'NONE', *, *, #20612, .F. ) ; -#2647 = ORIENTED_EDGE ( 'NONE', *, *, #31666, .T. ) ; -#2648 = CARTESIAN_POINT ( 'NONE', ( 3.667815737293329548, 128.0237491601668012, 91.77307785500387638 ) ) ; -#2649 = CARTESIAN_POINT ( 'NONE', ( -42.71664881039649941, 121.2026473532693416, 91.16230517282474466 ) ) ; -#2650 = CARTESIAN_POINT ( 'NONE', ( -13.55573361191901327, 147.5088701836791643, 96.28197591222276230 ) ) ; -#2651 = ADVANCED_FACE ( 'NONE', ( #16296 ), #27833, .T. ) ; -#2652 = AXIS2_PLACEMENT_3D ( 'NONE', #10017, #3652, #34915 ) ; -#2653 = AXIS2_PLACEMENT_3D ( 'NONE', #10967, #11354, #23840 ) ; -#2654 = CARTESIAN_POINT ( 'NONE', ( 42.93322021095036689, 121.2550468398670631, 90.69983607254528124 ) ) ; -#2655 = CARTESIAN_POINT ( 'NONE', ( -35.89858226441000966, 191.4429044599000065, 103.7433184509000057 ) ) ; -#2656 = CARTESIAN_POINT ( 'NONE', ( 45.33167067307282849, 106.4616227746064965, 168.3623917205906935 ) ) ; -#2657 = AXIS2_PLACEMENT_3D ( 'NONE', #1373, #26342, #31679 ) ; -#2658 = AXIS2_PLACEMENT_3D ( 'NONE', #2650, #16491, #26132 ) ; -#2659 = CARTESIAN_POINT ( 'NONE', ( -25.87351351544322142, 209.7109041514216301, 73.21069294904006597 ) ) ; -#2660 = CARTESIAN_POINT ( 'NONE', ( 16.29163119313890462, 127.8751207047643135, 174.7510531964512381 ) ) ; -#2661 = ADVANCED_FACE ( 'NONE', ( #38569 ), #10194, .F. ) ; -#2662 = DATE_AND_TIME ( #30461, #21856 ) ; -#2663 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#2664 = CARTESIAN_POINT ( 'NONE', ( 15.59057381604194958, 127.7851801377129561, 174.7303348606990596 ) ) ; -#2665 = CARTESIAN_POINT ( 'NONE', ( 28.53094770716555217, 124.6122665164779164, 91.48361085109841895 ) ) ; -#2666 = CARTESIAN_POINT ( 'NONE', ( 37.31693588142861273, 172.3309151562380919, 164.9673944986862466 ) ) ; -#2667 = CARTESIAN_POINT ( 'NONE', ( 37.18465433961090127, 191.0605235969299827, 106.3282138741240175 ) ) ; -#2668 = CARTESIAN_POINT ( 'NONE', ( 36.28210829689000150, 191.1903982848999988, 106.7086603135000047 ) ) ; -#2669 = ORIENTED_EDGE ( 'NONE', *, *, #2631, .T. ) ; -#2670 = ORIENTED_EDGE ( 'NONE', *, *, #29219, .T. ) ; -#2671 = CARTESIAN_POINT ( 'NONE', ( -3.775665312923583983, 136.3156088712283633, 91.12613979520395446 ) ) ; -#2672 = ORIENTED_EDGE ( 'NONE', *, *, #22906, .F. ) ; -#2673 = CARTESIAN_POINT ( 'NONE', ( -23.36068474349395885, 177.2840630309062817, 101.0277236918410324 ) ) ; -#2674 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2675 = ORIENTED_EDGE ( 'NONE', *, *, #11593, .T. ) ; -#2676 = CARTESIAN_POINT ( 'NONE', ( -39.04616526641999741, 119.6286227024000084, 90.51519719377000683 ) ) ; -#2677 = CIRCLE ( 'NONE', #22262, 2.000000000000011546 ) ; -#2678 = AXIS2_PLACEMENT_3D ( 'NONE', #30918, #22117, #37244 ) ; -#2679 = CARTESIAN_POINT ( 'NONE', ( -15.60948748269644781, 129.0994725037932653, 89.46731047333636866 ) ) ; -#2680 = CARTESIAN_POINT ( 'NONE', ( -28.75108559008205233, 179.7798527233168500, 27.87065912392118605 ) ) ; -#2681 = CARTESIAN_POINT ( 'NONE', ( -1.458415328219436757, 152.0517121881307503, 130.6798743971081365 ) ) ; -#2682 = EDGE_CURVE ( 'NONE', #39309, #21279, #1260, .T. ) ; -#2683 = ORIENTED_EDGE ( 'NONE', *, *, #37605, .T. ) ; -#2684 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#2685 = AXIS2_PLACEMENT_3D ( 'NONE', #25798, #1232, #16366 ) ; -#2686 = EDGE_CURVE ( 'NONE', #39904, #12942, #33239, .T. ) ; -#2687 = AXIS2_PLACEMENT_3D ( 'NONE', #31604, #18907, #28737 ) ; -#2688 = EDGE_CURVE ( 'NONE', #16955, #38290, #965, .T. ) ; -#2689 = CARTESIAN_POINT ( 'NONE', ( 23.36439094505924885, 176.9364792392202048, 103.3159941272735836 ) ) ; -#2690 = EDGE_CURVE ( 'NONE', #19715, #326, #39495, .T. ) ; -#2691 = CARTESIAN_POINT ( 'NONE', ( -14.31745456527091065, 135.5135842727596867, 90.94734476969833281 ) ) ; -#2692 = CARTESIAN_POINT ( 'NONE', ( -16.00000031268763934, 184.9628657724767606, 102.3646292465979855 ) ) ; -#2693 = ORIENTED_EDGE ( 'NONE', *, *, #35963, .F. ) ; -#2694 = CARTESIAN_POINT ( 'NONE', ( 44.86784790978150994, 186.3346043671313623, 107.7755195579999850 ) ) ; -#2695 = CARTESIAN_POINT ( 'NONE', ( 2.506441910316879795, 190.4796823909260013, 104.1213521451730060 ) ) ; -#2696 = CARTESIAN_POINT ( 'NONE', ( -42.85608556665479796, 121.2471205135300920, 90.71943177383317902 ) ) ; -#2697 = ADVANCED_FACE ( 'NONE', ( #20574 ), #31667, .F. ) ; -#2698 = EDGE_LOOP ( 'NONE', ( #16415, #40389, #1348, #4785, #12096, #13170, #38230, #16916, #20711, #13465 ) ) ; -#2699 = ORIENTED_EDGE ( 'NONE', *, *, #30565, .F. ) ; -#2700 = CARTESIAN_POINT ( 'NONE', ( -38.22874400428858621, 119.4291492467365430, 87.31414389642802121 ) ) ; -#2701 = ORIENTED_EDGE ( 'NONE', *, *, #7573, .F. ) ; -#2702 = ADVANCED_FACE ( 'NONE', ( #29588 ), #8528, .F. ) ; -#2703 = CARTESIAN_POINT ( 'NONE', ( -37.98607222914999682, 191.2865337069999896, 104.9454608741999948 ) ) ; -#2704 = LINE ( 'NONE', #24588, #6475 ) ; -#2705 = CIRCLE ( 'NONE', #11839, 2.000000000035895731 ) ; -#2706 = DIRECTION ( 'NONE', ( 0.6974360921310663874, 0.000000000000000000, -0.7166469824069217065 ) ) ; -#2707 = VECTOR ( 'NONE', #32176, 1000.000000000000114 ) ; -#2708 = ORIENTED_EDGE ( 'NONE', *, *, #18123, .F. ) ; -#2709 = LINE ( 'NONE', #12105, #17887 ) ; -#2710 = CARTESIAN_POINT ( 'NONE', ( -25.83319905905518610, 118.8155673861722761, 90.11672205215975850 ) ) ; -#2711 = ORIENTED_EDGE ( 'NONE', *, *, #9789, .T. ) ; -#2712 = AXIS2_PLACEMENT_3D ( 'NONE', #17110, #16320, #35104 ) ; -#2713 = CARTESIAN_POINT ( 'NONE', ( -38.95638687694488311, 209.7096538831000032, 73.58203285567579144 ) ) ; -#2714 = AXIS2_PLACEMENT_3D ( 'NONE', #29465, #29269, #4709 ) ; -#2715 = CARTESIAN_POINT ( 'NONE', ( -39.71549914202294218, 121.2606343799488826, 123.5760462896040934 ) ) ; -#2717 = CYLINDRICAL_SURFACE ( 'NONE', #15516, 6.000000000000008882 ) ; -#2716 = CARTESIAN_POINT ( 'NONE', ( -23.36160747139575022, 175.2398358893866828, 100.6374888825866378 ) ) ; -#2718 = ORIENTED_EDGE ( 'NONE', *, *, #15045, .T. ) ; -#2719 = CARTESIAN_POINT ( 'NONE', ( 20.20324609528008963, 117.0251910644186495, 87.25558203764020959 ) ) ; -#2720 = ORIENTED_EDGE ( 'NONE', *, *, #537, .F. ) ; -#2721 = CARTESIAN_POINT ( 'NONE', ( 39.38871638061999647, 119.7579850174000029, 90.49501021186000571 ) ) ; -#2722 = DIRECTION ( 'NONE', ( 0.0005884949961273644664, -0.2249510543439051102, 0.9743698870671265722 ) ) ; -#2723 = DIRECTION ( 'NONE', ( 0.7072735235945706300, 0.6508952239913731175, 0.2758615054829884894 ) ) ; -#2724 = CARTESIAN_POINT ( 'NONE', ( 29.91522852905242402, 130.5857354469581537, 89.78294558542910409 ) ) ; -#2725 = LINE ( 'NONE', #30933, #19071 ) ; -#2726 = ORIENTED_EDGE ( 'NONE', *, *, #14656, .T. ) ; -#2727 = ORIENTED_EDGE ( 'NONE', *, *, #38334, .T. ) ; -#2728 = ADVANCED_FACE ( 'NONE', ( #33450 ), #27768, .T. ) ; -#2729 = CARTESIAN_POINT ( 'NONE', ( 30.07825772506129525, 177.1204444582162409, 103.6051399121813859 ) ) ; -#2730 = EDGE_CURVE ( 'NONE', #36211, #10675, #31477, .T. ) ; -#2731 = FACE_OUTER_BOUND ( 'NONE', #37378, .T. ) ; -#2732 = CARTESIAN_POINT ( 'NONE', ( 39.71627783778711773, 128.2995111889279656, 93.17753252016933629 ) ) ; -#2733 = ORIENTED_EDGE ( 'NONE', *, *, #30832, .F. ) ; -#2734 = CARTESIAN_POINT ( 'NONE', ( -35.79834011994000065, 191.7755580150999890, 106.7769966834000002 ) ) ; -#2735 = CONICAL_SURFACE ( 'NONE', #25589, 59.40509898898601904, 0.7853981633972927368 ) ; -#2736 = PLANE ( 'NONE', #31893 ) ; -#2737 = CARTESIAN_POINT ( 'NONE', ( 31.91158940776717046, 137.5571349200599798, 93.95697525044668907 ) ) ; -#2738 = CARTESIAN_POINT ( 'NONE', ( -20.51893387759604082, 207.0373196925199011, 74.44320791140408744 ) ) ; -#2739 = FACE_BOUND ( 'NONE', #7188, .T. ) ; -#2740 = CARTESIAN_POINT ( 'NONE', ( -14.22274084689574636, 128.8778062397453539, 177.5848030100378026 ) ) ; -#2741 = CARTESIAN_POINT ( 'NONE', ( 3.534327104360340588, 144.2236672556986434, 92.94748474794259607 ) ) ; -#2742 = EDGE_LOOP ( 'NONE', ( #6288, #35655, #1003, #25189, #38738, #19601, #16761, #33005, #4527, #15563, #23152, #9113, #3922, #11528, #9787, #39752 ) ) ; -#2743 = CARTESIAN_POINT ( 'NONE', ( -82.80843920860921514, 105.1411378422745315, 24.32376295616780482 ) ) ; -#2744 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971581223 ) ) ; -#2745 = EDGE_CURVE ( 'NONE', #25509, #26218, #12006, .T. ) ; -#2746 = VERTEX_POINT ( 'NONE', #26528 ) ; -#2747 = CARTESIAN_POINT ( 'NONE', ( 16.15375828964846860, 121.3852290249194823, 177.4225633343677089 ) ) ; -#2748 = VERTEX_POINT ( 'NONE', #11799 ) ; -#2749 = VECTOR ( 'NONE', #7330, 999.9999999999998863 ) ; -#2750 = CARTESIAN_POINT ( 'NONE', ( -16.17310216730872696, 121.3958435379269361, 177.4085436696588545 ) ) ; -#2751 = ORIENTED_EDGE ( 'NONE', *, *, #3245, .T. ) ; -#2752 = CIRCLE ( 'NONE', #7282, 22.50000000000899902 ) ; -#2753 = ORIENTED_EDGE ( 'NONE', *, *, #10704, .F. ) ; -#2754 = AXIS2_PLACEMENT_3D ( 'NONE', #35598, #17003, #13965 ) ; -#2755 = ORIENTED_EDGE ( 'NONE', *, *, #12494, .T. ) ; -#2756 = CARTESIAN_POINT ( 'NONE', ( 2.666556751974999973, 208.9737835306000022, 75.79860644781000190 ) ) ; -#2757 = CARTESIAN_POINT ( 'NONE', ( 36.06505478217123795, 192.7057421143160525, 106.3400883098223915 ) ) ; -#2758 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452351231, 0.1781166614240801693 ) ) ; -#2759 = ORIENTED_EDGE ( 'NONE', *, *, #4118, .T. ) ; -#2760 = ORIENTED_EDGE ( 'NONE', *, *, #32084, .F. ) ; -#2761 = EDGE_LOOP ( 'NONE', ( #7505, #1166, #24850, #31777 ) ) ; -#2762 = ORIENTED_EDGE ( 'NONE', *, *, #30260, .F. ) ; -#2763 = FACE_OUTER_BOUND ( 'NONE', #20064, .T. ) ; -#2764 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; -#2765 = FACE_BOUND ( 'NONE', #10228, .T. ) ; -#2766 = ORIENTED_EDGE ( 'NONE', *, *, #11303, .T. ) ; -#2767 = ORIENTED_EDGE ( 'NONE', *, *, #13162, .T. ) ; -#2768 = LINE ( 'NONE', #15825, #2386 ) ; -#2769 = EDGE_CURVE ( 'NONE', #12555, #16053, #2301, .T. ) ; -#2770 = CARTESIAN_POINT ( 'NONE', ( -23.36150835702999728, 130.4188133232366340, 90.28973853306328579 ) ) ; -#2771 = EDGE_CURVE ( 'NONE', #22073, #29530, #19292, .T. ) ; -#2772 = ORIENTED_EDGE ( 'NONE', *, *, #38385, .F. ) ; -#2773 = CARTESIAN_POINT ( 'NONE', ( 32.37225758321823577, 137.6347993665977185, 94.48777941942033465 ) ) ; -#2774 = ORIENTED_EDGE ( 'NONE', *, *, #35353, .T. ) ; -#2775 = CARTESIAN_POINT ( 'NONE', ( -27.39351927441814638, 155.9581902257390880, 179.7869227509170003 ) ) ; -#2776 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457973672226, -32.89481530046830926, 142.2936922234670476 ) ) ; -#2777 = ORIENTED_EDGE ( 'NONE', *, *, #27707, .T. ) ; -#2778 = AXIS2_PLACEMENT_3D ( 'NONE', #27769, #12219, #18517 ) ; -#2779 = CARTESIAN_POINT ( 'NONE', ( 20.50124359822353881, 192.8415971392297195, 106.3310570022938322 ) ) ; -#2780 = CARTESIAN_POINT ( 'NONE', ( 39.23222213371558098, 119.5446253043629952, 90.30966899337110476 ) ) ; -#2781 = VECTOR ( 'NONE', #37657, 999.9999999999998863 ) ; -#2782 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#2783 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14652, #2181, #7689, #38967 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2784 = PLANE ( 'NONE', #36521 ) ; -#2785 = ORIENTED_EDGE ( 'NONE', *, *, #29901, .T. ) ; -#2786 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319378513601 ) ) ; -#2787 = CARTESIAN_POINT ( 'NONE', ( 3.166361538018682253, 127.9931434315633680, 89.20057147989687962 ) ) ; -#2788 = CARTESIAN_POINT ( 'NONE', ( -38.02586384959000299, 119.0401732150000100, 87.39466375838000545 ) ) ; -#2789 = CARTESIAN_POINT ( 'NONE', ( 35.67189333922000571, 113.0182598455999994, 90.12293602590000319 ) ) ; -#2790 = CARTESIAN_POINT ( 'NONE', ( 15.50029466864684835, 174.4049028184354881, 100.4212577462347866 ) ) ; -#2791 = ORIENTED_EDGE ( 'NONE', *, *, #30996, .F. ) ; -#2792 = CARTESIAN_POINT ( 'NONE', ( -13.73941655677348628, 149.5987884763016496, 180.3728828259357897 ) ) ; -#2793 = VERTEX_POINT ( 'NONE', #26944 ) ; -#2794 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 7.822507694019388974E-18, 0.0006039748319385908944 ) ) ; -#2795 = CARTESIAN_POINT ( 'NONE', ( -42.87043966560433716, 121.9075745850112753, 87.82339463871453233 ) ) ; -#2796 = CARTESIAN_POINT ( 'NONE', ( 15.66686156597643631, 151.8948118906095601, 95.05324321876020122 ) ) ; -#2797 = AXIS2_PLACEMENT_3D ( 'NONE', #17005, #10910, #35808 ) ; -#2798 = VERTEX_POINT ( 'NONE', #8735 ) ; -#2799 = DIRECTION ( 'NONE', ( 0.7865509479255969882, 0.6175253892086907115, 0.000000000000000000 ) ) ; -#2800 = ADVANCED_FACE ( 'NONE', ( #38980 ), #12086, .F. ) ; -#2801 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2802 = CARTESIAN_POINT ( 'NONE', ( 0.5640095659521695559, 188.6937662663199546, 105.9805870164321959 ) ) ; -#2803 = AXIS2_PLACEMENT_3D ( 'NONE', #26495, #11151, #39553 ) ; -#2804 = CARTESIAN_POINT ( 'NONE', ( 45.38353882083961821, 130.5441024140029924, 92.50080282210461746 ) ) ; -#2805 = VERTEX_POINT ( 'NONE', #23452 ) ; -#2806 = FACE_OUTER_BOUND ( 'NONE', #3480, .T. ) ; -#2807 = EDGE_CURVE ( 'NONE', #11663, #18757, #35522, .T. ) ; -#2808 = AXIS2_PLACEMENT_3D ( 'NONE', #10678, #29685, #29076 ) ; -#2809 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988446461073, 161.7142231051529677, 96.98759364904307745 ) ) ; -#2810 = ORIENTED_EDGE ( 'NONE', *, *, #6040, .F. ) ; -#2811 = CARTESIAN_POINT ( 'NONE', ( 19.98193060325066384, 205.2974737221514658, 75.64420744299060573 ) ) ; -#2812 = EDGE_CURVE ( 'NONE', #34518, #38661, #11378, .T. ) ; -#2813 = ADVANCED_FACE ( 'NONE', ( #27148 ), #4826, .T. ) ; -#2814 = ORIENTED_EDGE ( 'NONE', *, *, #22234, .T. ) ; -#2815 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#2816 = EDGE_CURVE ( 'NONE', #5155, #6206, #11486, .T. ) ; -#2817 = ADVANCED_FACE ( 'NONE', ( #5033 ), #33849, .F. ) ; -#2818 = DIRECTION ( 'NONE', ( -0.0005884949961248158324, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#2819 = ORIENTED_EDGE ( 'NONE', *, *, #34467, .F. ) ; -#2820 = DIRECTION ( 'NONE', ( 0.6088160902985568779, -0.7729595817128234181, -0.1785397805306046526 ) ) ; -#2821 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#2822 = CARTESIAN_POINT ( 'NONE', ( -15.99823486132552119, 118.9409032897876841, 90.20116722531848552 ) ) ; -#2823 = LINE ( 'NONE', #40027, #28101 ) ; -#2824 = LINE ( 'NONE', #15101, #1475 ) ; -#2825 = ORIENTED_EDGE ( 'NONE', *, *, #10668, .F. ) ; -#2826 = CARTESIAN_POINT ( 'NONE', ( -20.34738573694473729, 105.2139170220266777, 87.78007369431503548 ) ) ; -#2827 = DIRECTION ( 'NONE', ( 0.2974094561516589241, -0.7922998565502274992, 0.5327368512709285131 ) ) ; -#2828 = AXIS2_PLACEMENT_3D ( 'NONE', #29800, #26735, #23660 ) ; -#2829 = CARTESIAN_POINT ( 'NONE', ( 3.667815737396241893, 185.3461555469997109, 105.0070005409011742 ) ) ; -#2830 = CARTESIAN_POINT ( 'NONE', ( -46.08406567220261252, 125.3099125453316702, 91.70648740491583339 ) ) ; -#2831 = ORIENTED_EDGE ( 'NONE', *, *, #29624, .F. ) ; -#2832 = VECTOR ( 'NONE', #21327, 999.9999999999998863 ) ; -#2833 = CARTESIAN_POINT ( 'NONE', ( -43.57149696744355083, 121.9974121635120383, 87.84455870325962223 ) ) ; -#2834 = PLANE ( 'NONE', #18617 ) ; -#2835 = CARTESIAN_POINT ( 'NONE', ( 25.40408268398181235, 212.9186129770236846, 73.04316065302639061 ) ) ; -#2836 = DIRECTION ( 'NONE', ( 0.0005884949961259294164, -0.2255194585872565272, 0.9742384859325513569 ) ) ; -#2837 = CARTESIAN_POINT ( 'NONE', ( 14.17036433007075757, 182.7613733346053380, 102.3513045738081502 ) ) ; -#2838 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452351231, -0.1781166614240801693 ) ) ; -#2839 = CARTESIAN_POINT ( 'NONE', ( 15.10714331102995800, 183.1006619385863701, 101.9159176678921312 ) ) ; -#2840 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1093, #7421, #13578, #26060 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2841 = SECURITY_CLASSIFICATION_LEVEL ( 'unclassified' ) ; -#2842 = DIRECTION ( 'NONE', ( -0.0004161288024524960371, -0.5299192578740949955, -0.8480479980348919478 ) ) ; -#2843 = FACE_OUTER_BOUND ( 'NONE', #27795, .T. ) ; -#2844 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001722, 130.3419545077132682, 92.84535593379679597 ) ) ; -#2845 = EDGE_CURVE ( 'NONE', #35508, #32912, #30605, .T. ) ; -#2846 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#2847 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8519, #2383, #24061, #26933 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2849 = VERTEX_POINT ( 'NONE', #39990 ) ; -#2848 = CARTESIAN_POINT ( 'NONE', ( 36.82578048503000190, 191.4974673927000026, 106.2209708588000012 ) ) ; -#2850 = EDGE_LOOP ( 'NONE', ( #12807, #15761 ) ) ; -#2851 = ORIENTED_EDGE ( 'NONE', *, *, #16040, .T. ) ; -#2852 = DIRECTION ( 'NONE', ( 0.7933533411653069800, -0.5930537057989941907, -0.1373964268091564245 ) ) ; -#2853 = EDGE_CURVE ( 'NONE', #16970, #17201, #27954, .T. ) ; -#2854 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24266, #8722, #8925, #37321, #39764, #27551, #24672, #34230, #33638, #9313, #36511, #27337, #31187, #21180, #36919, #18085 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.0004796803808468277225, 0.0009593607616936554450, 0.001439041142540483167, 0.001918721523387310890, 0.002398401904234139046, 0.002878082285080966335, 0.003837443046774705480 ), - .UNSPECIFIED. ) ; -#2855 = PLANE ( 'NONE', #2031 ) ; -#2856 = EDGE_CURVE ( 'NONE', #27307, #25353, #298, .T. ) ; -#2857 = DIRECTION ( 'NONE', ( -0.6087614810001780175, 0.7729390313185915407, 0.1788147452386051883 ) ) ; -#2858 = EDGE_LOOP ( 'NONE', ( #15921, #1293, #9765, #36742 ) ) ; -#2859 = FACE_OUTER_BOUND ( 'NONE', #35206, .T. ) ; -#2860 = ADVANCED_FACE ( 'NONE', ( #31201 ), #5852, .T. ) ; -#2861 = CIRCLE ( 'NONE', #13313, 2.000000000000011546 ) ; -#2862 = CARTESIAN_POINT ( 'NONE', ( -15.99993873281328050, 165.3377715421495111, 97.83388156752448594 ) ) ; -#2863 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#2864 = ORIENTED_EDGE ( 'NONE', *, *, #4865, .F. ) ; -#2865 = LINE ( 'NONE', #11467, #13995 ) ; -#2866 = CARTESIAN_POINT ( 'NONE', ( 36.05382442436784629, 113.8881156701999942, 87.74600877634995300 ) ) ; -#2867 = CARTESIAN_POINT ( 'NONE', ( 36.56518236884102890, 116.6077097462014933, 90.24570038530379179 ) ) ; -#2868 = CARTESIAN_POINT ( 'NONE', ( -4.704247605369164198, 188.1541984058357286, 103.0945842148524605 ) ) ; -#2869 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2870 = ORIENTED_EDGE ( 'NONE', *, *, #6162, .T. ) ; -#2871 = ORIENTED_EDGE ( 'NONE', *, *, #7035, .T. ) ; -#2872 = DIRECTION ( 'NONE', ( 1.040834085586078261E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#2873 = CARTESIAN_POINT ( 'NONE', ( 1.870897341094000188, 189.3091107925999950, 103.6431386051000061 ) ) ; -#2874 = CARTESIAN_POINT ( 'NONE', ( 20.25161797161999999, 167.0117879878999929, 101.0207373691000043 ) ) ; -#2875 = ORIENTED_EDGE ( 'NONE', *, *, #6847, .F. ) ; -#2876 = CARTESIAN_POINT ( 'NONE', ( -15.56603823807074782, 147.4087826306812019, 179.2784924189769242 ) ) ; -#2877 = ORIENTED_EDGE ( 'NONE', *, *, #16160, .T. ) ; -#2878 = VECTOR ( 'NONE', #8767, 1000.000000000000227 ) ; -#2879 = AXIS2_PLACEMENT_3D ( 'NONE', #33926, #27231, #18181 ) ; -#2880 = CARTESIAN_POINT ( 'NONE', ( 25.50041447495308233, 118.1134306400200416, 89.75249416949174019 ) ) ; -#2881 = CARTESIAN_POINT ( 'NONE', ( 22.64184747305000300, 153.5472371799000086, 97.91075667399999816 ) ) ; -#2882 = FACE_OUTER_BOUND ( 'NONE', #14817, .T. ) ; -#2883 = AXIS2_PLACEMENT_3D ( 'NONE', #30024, #2022, #14087 ) ; -#2884 = FACE_OUTER_BOUND ( 'NONE', #10490, .T. ) ; -#2885 = CARTESIAN_POINT ( 'NONE', ( -12.63737457481493465, 134.4755188138004769, 93.58620110311106544 ) ) ; -#2886 = DIRECTION ( 'NONE', ( -0.0005884949961244347353, 0.2249510543439056098, -0.9743698870671265722 ) ) ; -#2887 = EDGE_LOOP ( 'NONE', ( #2814, #7899, #26105, #7331 ) ) ; -#2888 = EDGE_CURVE ( 'NONE', #1525, #12519, #18497, .T. ) ; -#2889 = ADVANCED_FACE ( 'NONE', ( #3170 ), #6825, .F. ) ; -#2890 = CARTESIAN_POINT ( 'NONE', ( -42.69302072565936612, 103.2982249598779276, 168.6358421031195860 ) ) ; -#2891 = PLANE ( 'NONE', #33993 ) ; -#2892 = ADVANCED_FACE ( 'NONE', ( #9129 ), #36227, .T. ) ; -#2893 = EDGE_CURVE ( 'NONE', #30526, #21678, #15462, .T. ) ; -#2895 = CARTESIAN_POINT ( 'NONE', ( 16.22188721871033934, 122.1949268581505521, 174.0451402755014101 ) ) ; -#2894 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709481474, 82.27946979429644614, 322.5205145037751890 ) ) ; -#2896 = CARTESIAN_POINT ( 'NONE', ( 3.993984635816554718, 143.6429547678539507, 95.42167272605998107 ) ) ; -#2897 = ORIENTED_EDGE ( 'NONE', *, *, #18106, .T. ) ; -#2898 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319383136639 ) ) ; -#2899 = ORIENTED_EDGE ( 'NONE', *, *, #20092, .T. ) ; -#2900 = CARTESIAN_POINT ( 'NONE', ( 27.41760324789147418, 125.0582898930202589, 89.02149762882548600 ) ) ; -#2901 = EDGE_CURVE ( 'NONE', #12880, #5671, #30374, .T. ) ; -#2902 = CARTESIAN_POINT ( 'NONE', ( 29.62326790002893162, 185.7454482597306651, 103.0308995128836216 ) ) ; -#2903 = CARTESIAN_POINT ( 'NONE', ( -25.49213558285381254, 194.2771767961476996, 102.9136721320308538 ) ) ; -#2904 = AXIS2_PLACEMENT_3D ( 'NONE', #21038, #17538, #17737 ) ; -#2905 = CARTESIAN_POINT ( 'NONE', ( -45.15244941250207944, 106.4211879749299925, 169.3571905553632746 ) ) ; -#2906 = ORIENTED_EDGE ( 'NONE', *, *, #3889, .F. ) ; -#2907 = ORIENTED_EDGE ( 'NONE', *, *, #35218, .F. ) ; -#2908 = FACE_OUTER_BOUND ( 'NONE', #18219, .T. ) ; -#2909 = AXIS2_PLACEMENT_3D ( 'NONE', #12257, #9194, #9587 ) ; -#2910 = LINE ( 'NONE', #37068, #4658 ) ; -#2911 = ADVANCED_FACE ( 'NONE', ( #6243 ), #18698, .F. ) ; -#2912 = ORIENTED_EDGE ( 'NONE', *, *, #20668, .T. ) ; -#2913 = CARTESIAN_POINT ( 'NONE', ( -2.437379602309801996, 196.1181861109790532, 103.6812116298660129 ) ) ; -#2914 = CARTESIAN_POINT ( 'NONE', ( 55.76220932283968068, 8.811273727124799393, 151.9488229758013347 ) ) ; -#2915 = CARTESIAN_POINT ( 'NONE', ( 2.328920004101604491, 189.0592395469226972, 106.3913415630415926 ) ) ; -#2916 = CARTESIAN_POINT ( 'NONE', ( -28.45663166759245399, 131.0177812377234545, 89.91795229967709702 ) ) ; -#2917 = CARTESIAN_POINT ( 'NONE', ( 30.07478355117409308, 177.7951688118731681, 100.6820556990014950 ) ) ; -#2918 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#2919 = CARTESIAN_POINT ( 'NONE', ( 4.067263459342049359, 146.7371158628018293, 93.52739776953615092 ) ) ; -#2920 = ORIENTED_EDGE ( 'NONE', *, *, #21000, .F. ) ; -#2921 = CARTESIAN_POINT ( 'NONE', ( 44.88156389711864591, 173.0388276432278190, 165.3842276987274147 ) ) ; -#2922 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825994489843006, 0.0005734119006650908101 ) ) ; -#2923 = CARTESIAN_POINT ( 'NONE', ( -20.33420132830697469, 127.1423375402870306, 91.75263487369595339 ) ) ; -#2924 = AXIS2_PLACEMENT_3D ( 'NONE', #16837, #39128, #11322 ) ; -#2925 = CIRCLE ( 'NONE', #32303, 4.499999279730864998 ) ; -#2926 = ORIENTED_EDGE ( 'NONE', *, *, #36637, .F. ) ; -#2927 = CARTESIAN_POINT ( 'NONE', ( 41.34016251261648023, 109.2214168434603039, 170.0257790416202397 ) ) ; -#2928 = EDGE_LOOP ( 'NONE', ( #5157, #11625, #34525, #5805, #17815 ) ) ; -#2929 = EDGE_CURVE ( 'NONE', #19656, #5211, #32411, .T. ) ; -#2930 = VECTOR ( 'NONE', #2406, 1000.000000000000227 ) ; -#2931 = EDGE_CURVE ( 'NONE', #12603, #2592, #29942, .T. ) ; -#2933 = CARTESIAN_POINT ( 'NONE', ( -3.169881662145332513, 128.5839160399947332, 89.34077473205128683 ) ) ; -#2932 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2934 = ORIENTED_EDGE ( 'NONE', *, *, #635, .F. ) ; -#2935 = ORIENTED_EDGE ( 'NONE', *, *, #21894, .T. ) ; -#2936 = ORIENTED_EDGE ( 'NONE', *, *, #34942, .T. ) ; -#2937 = CARTESIAN_POINT ( 'NONE', ( -13.49852954174901143, 127.1816645162778769, 91.58903530335827270 ) ) ; -#2938 = CARTESIAN_POINT ( 'NONE', ( -76.10954455358901782, 156.3528031849876072, 95.79577929590617202 ) ) ; -#2939 = EDGE_LOOP ( 'NONE', ( #1582, #33183, #27530, #14563 ) ) ; -#2940 = VERTEX_POINT ( 'NONE', #13593 ) ; -#2941 = ORIENTED_EDGE ( 'NONE', *, *, #27801, .F. ) ; -#2942 = CARTESIAN_POINT ( 'NONE', ( -19.33539756116881847, 125.3880314484919722, 178.3186149148302775 ) ) ; -#2943 = PLANE ( 'NONE', #22624 ) ; -#2944 = CARTESIAN_POINT ( 'NONE', ( 22.98769521848599595, 181.6927287775007755, 101.5861108980980987 ) ) ; -#2945 = CARTESIAN_POINT ( 'NONE', ( 21.72804141255551968, 135.8412665901933281, 91.00123227078390187 ) ) ; -#2946 = ORIENTED_EDGE ( 'NONE', *, *, #36645, .F. ) ; -#2947 = ORIENTED_EDGE ( 'NONE', *, *, #40253, .T. ) ; -#2948 = ORIENTED_EDGE ( 'NONE', *, *, #39983, .F. ) ; -#2949 = FACE_OUTER_BOUND ( 'NONE', #39766, .T. ) ; -#2950 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; -#2951 = CARTESIAN_POINT ( 'NONE', ( -28.02783910825000291, 125.2760234380999833, 88.93426760747999538 ) ) ; -#2952 = VECTOR ( 'NONE', #34198, 1000.000000000000000 ) ; -#2953 = ORIENTED_EDGE ( 'NONE', *, *, #15818, .T. ) ; -#2954 = EDGE_CURVE ( 'NONE', #23911, #12970, #34831, .T. ) ; -#2955 = EDGE_LOOP ( 'NONE', ( #25879, #17638, #17452, #30852 ) ) ; -#2956 = DIRECTION ( 'NONE', ( -0.0005734119072319342333, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#2957 = CARTESIAN_POINT ( 'NONE', ( -40.99137513204986050, 188.9331334093535872, 107.3249050511072369 ) ) ; -#2958 = ORIENTED_EDGE ( 'NONE', *, *, #38990, .T. ) ; -#2959 = AXIS2_PLACEMENT_3D ( 'NONE', #36257, #19892, #33177 ) ; -#2960 = CYLINDRICAL_SURFACE ( 'NONE', #38766, 6.000000000048013149 ) ; -#2961 = VECTOR ( 'NONE', #17478, 1000.000000000000227 ) ; -#2962 = AXIS2_PLACEMENT_3D ( 'NONE', #21691, #2, #28616 ) ; -#2963 = CARTESIAN_POINT ( 'NONE', ( 3.993858315201923137, 174.7847376312480776, 102.6114509115379718 ) ) ; -#2964 = CARTESIAN_POINT ( 'NONE', ( -3.820567177493512823, 167.8841678059111757, 101.2013462384420990 ) ) ; -#2965 = FACE_OUTER_BOUND ( 'NONE', #5281, .T. ) ; -#2966 = CARTESIAN_POINT ( 'NONE', ( -3.537744320960331645, 175.3497732290038300, 100.1377481765469355 ) ) ; -#2967 = VERTEX_POINT ( 'NONE', #1308 ) ; -#2968 = CARTESIAN_POINT ( 'NONE', ( -20.51863885680050359, 209.7097602209678939, 75.57089512796630970 ) ) ; -#2969 = ORIENTED_EDGE ( 'NONE', *, *, #25163, .T. ) ; -#2970 = CARTESIAN_POINT ( 'NONE', ( 29.98785144339129616, 77.14301703112315067, 291.5404320243928282 ) ) ; -#2971 = CARTESIAN_POINT ( 'NONE', ( -37.67452696363999820, 118.6320779777999945, 87.39106427871999472 ) ) ; -#2972 = DIRECTION ( 'NONE', ( 0.7933533411653070910, -0.5930537057989941907, -0.1373964268091563690 ) ) ; -#2973 = CARTESIAN_POINT ( 'NONE', ( -28.79107131398339448, 181.6858502269169264, 101.6157959367960189 ) ) ; -#2974 = EDGE_LOOP ( 'NONE', ( #21035, #24661, #17242, #28641 ) ) ; -#2975 = DIRECTION ( 'NONE', ( 0.0004161288024490636698, -0.8480480897979184585, 0.5299191110225421886 ) ) ; -#2976 = ORIENTED_EDGE ( 'NONE', *, *, #37448, .F. ) ; -#2977 = DIRECTION ( 'NONE', ( 0.0005884949961242894522, -0.2249510543439076082, 0.9743698870671259060 ) ) ; -#2978 = VECTOR ( 'NONE', #14074, 1000.000000000000114 ) ; -#2979 = EDGE_CURVE ( 'NONE', #24908, #8891, #6832, .T. ) ; -#2980 = EDGE_CURVE ( 'NONE', #18813, #3536, #13791, .T. ) ; -#2981 = VECTOR ( 'NONE', #31122, 1000.000000000000227 ) ; -#2982 = VECTOR ( 'NONE', #23974, 1000.000000000000114 ) ; -#2983 = CARTESIAN_POINT ( 'NONE', ( -38.37912446231000274, 118.5515219785000056, 89.85344207503999314 ) ) ; -#2984 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#2985 = VECTOR ( 'NONE', #19754, 1000.000000000000114 ) ; -#2986 = ORIENTED_EDGE ( 'NONE', *, *, #36163, .F. ) ; -#2988 = AXIS2_PLACEMENT_3D ( 'NONE', #4084, #23519, #16556 ) ; -#2987 = CARTESIAN_POINT ( 'NONE', ( -25.49999614779992640, 119.8278461530000101, 89.89852083536001714 ) ) ; -#2989 = CARTESIAN_POINT ( 'NONE', ( -23.36160747139494021, 184.0091663913295577, 102.6620487233715551 ) ) ; -#2990 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11577, #10970, #14648, #13277 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#2991 = AXIS2_PLACEMENT_3D ( 'NONE', #20767, #26713, #38748 ) ; -#2992 = CARTESIAN_POINT ( 'NONE', ( 19.98210856654580780, 205.1070970766282358, 76.09272704596726555 ) ) ; -#2993 = CARTESIAN_POINT ( 'NONE', ( 17.27264158547648165, 121.9609240029174941, 174.6061468887760668 ) ) ; -#2994 = CARTESIAN_POINT ( 'NONE', ( -35.44460436179470264, 113.0640021328997875, 90.28919249207498865 ) ) ; -#2995 = VERTEX_POINT ( 'NONE', #19707 ) ; -#2996 = EDGE_LOOP ( 'NONE', ( #34523, #5630, #33469, #11148, #36155 ) ) ; -#2997 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749905615, 132.8602140593031891, 90.82839891348385208 ) ) ; -#2998 = CARTESIAN_POINT ( 'NONE', ( 26.00067918362605468, 118.8155664802563791, 90.25207353690788636 ) ) ; -#2999 = EDGE_LOOP ( 'NONE', ( #5197, #35022, #14101, #9515, #6734, #2069 ) ) ; -#3000 = CARTESIAN_POINT ( 'NONE', ( -23.36207384156027089, 135.2596320619993264, 91.36483358189200032 ) ) ; -#3001 = ORIENTED_EDGE ( 'NONE', *, *, #8106, .T. ) ; -#3002 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971574284 ) ) ; -#3003 = ADVANCED_FACE ( 'NONE', ( #26077 ), #29336, .T. ) ; -#3004 = CARTESIAN_POINT ( 'NONE', ( -21.44517133412774967, 181.8810903885702999, 104.7353468333731428 ) ) ; -#3005 = CARTESIAN_POINT ( 'NONE', ( -42.87041437821633139, 121.8978841230586170, 87.86525719409469559 ) ) ; -#3006 = ORIENTED_EDGE ( 'NONE', *, *, #30138, .T. ) ; -#3007 = CARTESIAN_POINT ( 'NONE', ( -39.12307687603004780, 119.5446354990494342, 90.35700216072328317 ) ) ; -#3008 = CARTESIAN_POINT ( 'NONE', ( 3.867917397069210228, 167.8992108979956015, 101.1512074224550588 ) ) ; -#3009 = CARTESIAN_POINT ( 'NONE', ( 16.92920261701720364, 122.1329027301315477, 174.6418107832293742 ) ) ; -#3010 = AXIS2_PLACEMENT_3D ( 'NONE', #22825, #3786, #35053 ) ; -#3011 = DIRECTION ( 'NONE', ( 0.0005884949961217976304, -0.2249510543439088295, 0.9743698870671256840 ) ) ; -#3012 = CARTESIAN_POINT ( 'NONE', ( -5.670816646075872214, 124.6073922305314881, 88.75515748818936856 ) ) ; -#3013 = VECTOR ( 'NONE', #8225, 1000.000000000000000 ) ; -#3014 = ORIENTED_EDGE ( 'NONE', *, *, #30797, .F. ) ; -#3015 = CARTESIAN_POINT ( 'NONE', ( 15.50147167040193885, 126.2420947773999984, 91.35460322364998831 ) ) ; -#3016 = CARTESIAN_POINT ( 'NONE', ( 21.15458122718195000, 129.0140306984282859, 89.76749365585642693 ) ) ; -#3017 = FACE_OUTER_BOUND ( 'NONE', #18420, .T. ) ; -#3018 = CIRCLE ( 'NONE', #8253, 4.500000000138546952 ) ; -#3019 = EDGE_CURVE ( 'NONE', #27631, #39445, #23657, .T. ) ; -#3020 = CARTESIAN_POINT ( 'NONE', ( -46.09662356910047265, 125.3295157413326422, 91.69427356735783974 ) ) ; -#3021 = ORIENTED_EDGE ( 'NONE', *, *, #7401, .T. ) ; -#3022 = PLANE ( 'NONE', #15352 ) ; -#3023 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#3024 = CARTESIAN_POINT ( 'NONE', ( 25.99015001018950244, 211.2814243414217401, 73.04280668304699020 ) ) ; -#3025 = ADVANCED_FACE ( 'NONE', ( #3567 ), #3556, .F. ) ; -#3026 = CARTESIAN_POINT ( 'NONE', ( -35.90297270143999953, 191.4412966076000089, 103.7424780479999953 ) ) ; -#3027 = ORIENTED_EDGE ( 'NONE', *, *, #22435, .F. ) ; -#3028 = CARTESIAN_POINT ( 'NONE', ( -25.88079993598000073, 189.6069161131000271, 106.1795723502000044 ) ) ; -#3029 = EDGE_CURVE ( 'NONE', #9503, #25148, #16048, .T. ) ; -#3030 = EDGE_CURVE ( 'NONE', #26246, #33584, #23151, .T. ) ; -#3031 = EDGE_CURVE ( 'NONE', #6620, #4954, #8820, .T. ) ; -#3032 = ADVANCED_FACE ( 'NONE', ( #12999 ), #29142, .F. ) ; -#3033 = FACE_OUTER_BOUND ( 'NONE', #7012, .T. ) ; -#3034 = COORDINATED_UNIVERSAL_TIME_OFFSET ( 8, 0, .AHEAD. ) ; -#3035 = CARTESIAN_POINT ( 'NONE', ( 4.469208178247156660, 181.9837231390557122, 101.6644769543693343 ) ) ; -#3036 = CARTESIAN_POINT ( 'NONE', ( 20.45340480371016767, 105.2139170030256281, 87.75543103923976673 ) ) ; -#3037 = FACE_OUTER_BOUND ( 'NONE', #5511, .T. ) ; -#3038 = CARTESIAN_POINT ( 'NONE', ( -13.50718409113456886, 124.3648481134796242, 88.37302201493642428 ) ) ; -#3039 = CONICAL_SURFACE ( 'NONE', #25921, 5.999999999877434931, 0.7853981633861987222 ) ; -#3040 = CARTESIAN_POINT ( 'NONE', ( 38.09222635126999990, 190.2036213682000039, 106.7598474027000037 ) ) ; -#3041 = CARTESIAN_POINT ( 'NONE', ( 37.96379117489740906, 191.4230855713359745, 104.2930860270950006 ) ) ; -#3042 = CARTESIAN_POINT ( 'NONE', ( 36.36134859205999703, 190.7141038027000093, 106.8889422767999946 ) ) ; -#3043 = VECTOR ( 'NONE', #23257, 1000.000000000000227 ) ; -#3044 = ORIENTED_EDGE ( 'NONE', *, *, #21570, .F. ) ; -#3045 = EDGE_LOOP ( 'NONE', ( #15326, #10594, #7691, #23629 ) ) ; -#3046 = LINE ( 'NONE', #15526, #16008 ) ; -#3047 = CARTESIAN_POINT ( 'NONE', ( 20.16621962310517091, 126.7988427542629211, 91.82459364418598113 ) ) ; -#3048 = AXIS2_PLACEMENT_3D ( 'NONE', #11110, #20915, #33163 ) ; -#3049 = CARTESIAN_POINT ( 'NONE', ( 39.04493984371199389, 209.7096538830999748, 73.03492191709887038 ) ) ; -#3050 = CARTESIAN_POINT ( 'NONE', ( -28.47589466077455356, 181.0102030230047774, 104.5385275604374868 ) ) ; -#3051 = ORIENTED_EDGE ( 'NONE', *, *, #19811, .F. ) ; -#3052 = CARTESIAN_POINT ( 'NONE', ( 36.18220281975000319, 191.5955271818000085, 103.9696148665999971 ) ) ; -#3053 = CARTESIAN_POINT ( 'NONE', ( 25.99874167938696345, 118.1131156663084738, 87.25205387058410622 ) ) ; -#3054 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; -#3055 = CARTESIAN_POINT ( 'NONE', ( 25.75064116263000003, 119.9649558487000007, 90.15579708161000383 ) ) ; -#3056 = ORIENTED_EDGE ( 'NONE', *, *, #3209, .F. ) ; -#3057 = CARTESIAN_POINT ( 'NONE', ( 35.04675249777811530, 220.4002260771000294, 76.03733726949710103 ) ) ; -#3058 = CARTESIAN_POINT ( 'NONE', ( 23.36437870454795984, 176.9522535532045424, 103.3412383233359435 ) ) ; -#3059 = CARTESIAN_POINT ( 'NONE', ( -14.03369136115023075, 135.3010097591426302, 90.89809668144418708 ) ) ; -#3060 = FACE_OUTER_BOUND ( 'NONE', #12196, .T. ) ; -#3061 = EDGE_LOOP ( 'NONE', ( #11402, #19829, #12800, #27926 ) ) ; -#3062 = EDGE_LOOP ( 'NONE', ( #15157, #14035, #37232, #35570 ) ) ; -#3063 = CARTESIAN_POINT ( 'NONE', ( 15.95615386316613282, 121.8819051936993816, 174.5510063636885150 ) ) ; -#3064 = CARTESIAN_POINT ( 'NONE', ( 1.635480799156000087, 189.1538750077000088, 103.6018120742999997 ) ) ; -#3065 = CARTESIAN_POINT ( 'NONE', ( -22.78405533929291948, 158.5507182435040079, 96.61310224121642420 ) ) ; -#3066 = EDGE_CURVE ( 'NONE', #16493, #6692, #14812, .T. ) ; -#3067 = CONICAL_SURFACE ( 'NONE', #29204, 2.999999999919114035, 0.7853981633692810327 ) ; -#3068 = EDGE_LOOP ( 'NONE', ( #7435, #9216, #38555, #4790, #34771 ) ) ; -#3069 = ORIENTED_EDGE ( 'NONE', *, *, #38556, .F. ) ; -#3070 = FACE_OUTER_BOUND ( 'NONE', #38897, .T. ) ; -#3071 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38379, #26332, #10787, #13453 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3072 = AXIS2_PLACEMENT_3D ( 'NONE', #2061, #11456, #23942 ) ; -#3073 = VERTEX_POINT ( 'NONE', #35631 ) ; -#3074 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #36647, #29910, #33364, #8649 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.570796326794906994, 1.749868521873144678 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973295471489362907, 0.9973295471489362907, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#3075 = AXIS2_PLACEMENT_3D ( 'NONE', #26138, #10593, #13846 ) ; -#3076 = ADVANCED_FACE ( 'NONE', ( #14207 ), #14607, .F. ) ; -#3077 = CARTESIAN_POINT ( 'NONE', ( -17.26187873221201130, 121.2921859730249849, 177.4392858027187003 ) ) ; -#3079 = EDGE_CURVE ( 'NONE', #18693, #38501, #38192, .T. ) ; -#3078 = CARTESIAN_POINT ( 'NONE', ( -3.786117645261999787, 140.1650965393000092, 94.83720733612000231 ) ) ; -#3080 = CARTESIAN_POINT ( 'NONE', ( -35.45366962802970789, 209.7096538831000032, 78.07991812242468654 ) ) ; -#3081 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4681, #33290, #11232, #33093 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.002027470929952764501 ), - .UNSPECIFIED. ) ; -#3082 = EDGE_CURVE ( 'NONE', #15187, #7826, #4223, .T. ) ; -#3083 = CARTESIAN_POINT ( 'NONE', ( -25.02112439774744246, 181.4181497952224333, 104.6306287658777165 ) ) ; -#3084 = EDGE_CURVE ( 'NONE', #34551, #7887, #4775, .T. ) ; -#3085 = DIRECTION ( 'NONE', ( -0.0006039748319384231684, -2.335630580398557718E-15, -0.9999998176071847045 ) ) ; -#3086 = EDGE_CURVE ( 'NONE', #36516, #15062, #5390, .T. ) ; -#3087 = PLANE ( 'NONE', #35585 ) ; -#3088 = CARTESIAN_POINT ( 'NONE', ( -0.9305748042227944827, 189.0423004457716161, 105.7504655986643911 ) ) ; -#3089 = VERTEX_POINT ( 'NONE', #5176 ) ; -#3090 = CARTESIAN_POINT ( 'NONE', ( -7.998197201794713607, 181.6877316537963907, 101.6036458862231058 ) ) ; -#3091 = CARTESIAN_POINT ( 'NONE', ( -39.71708503720267203, 121.0975557797884932, 124.2941153462564756 ) ) ; -#3092 = LINE ( 'NONE', #31510, #21621 ) ; -#3094 = CARTESIAN_POINT ( 'NONE', ( 16.22047286113847164, 122.4940578689917601, 172.7457956654259590 ) ) ; -#3093 = FACE_OUTER_BOUND ( 'NONE', #38541, .T. ) ; -#3095 = EDGE_LOOP ( 'NONE', ( #33717, #38442, #21115, #9200, #16559 ) ) ; -#3096 = AXIS2_PLACEMENT_3D ( 'NONE', #39306, #14797, #7828 ) ; -#3097 = CARTESIAN_POINT ( 'NONE', ( 21.73150615163542554, 115.3932069353914471, 87.25465900686118914 ) ) ; -#3098 = CARTESIAN_POINT ( 'NONE', ( 46.55403492231632612, 110.7336015912822376, 151.9816296823271955 ) ) ; -#3099 = ORIENTED_EDGE ( 'NONE', *, *, #8822, .F. ) ; -#3100 = CARTESIAN_POINT ( 'NONE', ( -27.65129847970650800, 123.9714961408685951, 91.36960946739799283 ) ) ; -#3101 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319386436951 ) ) ; -#3102 = CARTESIAN_POINT ( 'NONE', ( 29.46758137170211356, 130.8205874185748598, 89.83743581285379776 ) ) ; -#3103 = DIRECTION ( 'NONE', ( 1.734723476008841552E-15, 0.9743700557921586292, 0.2249510932971562072 ) ) ; -#3104 = CARTESIAN_POINT ( 'NONE', ( -12.64130811310021762, 134.9973451780017228, 90.93666802679005912 ) ) ; -#3105 = ORIENTED_EDGE ( 'NONE', *, *, #31685, .F. ) ; -#3106 = DIRECTION ( 'NONE', ( -0.0005734119072321099825, 0.000000000000000000, -0.9999998355993788834 ) ) ; -#3107 = VERTEX_POINT ( 'NONE', #27091 ) ; -#3108 = CARTESIAN_POINT ( 'NONE', ( 5.664720472934660300, 124.5090647592738975, 88.58889915586530606 ) ) ; -#3109 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#3110 = CARTESIAN_POINT ( 'NONE', ( -38.72339233899131727, 70.77327613454784228, 322.7414739270242308 ) ) ; -#3111 = ORIENTED_EDGE ( 'NONE', *, *, #11119, .T. ) ; -#3112 = ORIENTED_EDGE ( 'NONE', *, *, #4816, .F. ) ; -#3113 = CARTESIAN_POINT ( 'NONE', ( -35.64769185326999690, 191.6906041802000118, 106.9440936951999959 ) ) ; -#3114 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971522381 ) ) ; -#3115 = EDGE_CURVE ( 'NONE', #13026, #14171, #20317, .T. ) ; -#3116 = CARTESIAN_POINT ( 'NONE', ( 2.428755093643999885, 191.0297069190999935, 106.1808341487000007 ) ) ; -#3117 = ADVANCED_FACE ( 'NONE', ( #39320 ), #26883, .T. ) ; -#3118 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29702, #20275, #14569, #39486, #16992, #29494, #23366, #9033, #31114, #34352, #24393, #27474 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999996406208, 0.3749999999994609312, 0.4374999999993957056, 0.4687499999993570143, 0.4843749999993131050, 0.4999999999992691402, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3119 = ADVANCED_FACE ( 'NONE', ( #32593 ), #36466, .F. ) ; -#3120 = VERTEX_POINT ( 'NONE', #10940 ) ; -#3121 = CARTESIAN_POINT ( 'NONE', ( 2.563235677694000181, 190.8834820154999932, 106.2802016037999948 ) ) ; -#3122 = VERTEX_POINT ( 'NONE', #17235 ) ; -#3123 = CARTESIAN_POINT ( 'NONE', ( -37.26517045375702963, 190.4055305187127374, 106.7129241467131493 ) ) ; -#3124 = CARTESIAN_POINT ( 'NONE', ( 36.34648484248651812, 191.3863812484165692, 103.8159989434559236 ) ) ; -#3125 = CARTESIAN_POINT ( 'NONE', ( -25.62251701078999844, 120.0771796793000163, 90.08090160909999611 ) ) ; -#3126 = ADVANCED_FACE ( 'NONE', ( #4980 ), #39526, .T. ) ; -#3127 = AXIS2_PLACEMENT_3D ( 'NONE', #2226, #8360, #20613 ) ; -#3128 = ORIENTED_EDGE ( 'NONE', *, *, #15640, .F. ) ; -#3129 = CARTESIAN_POINT ( 'NONE', ( 23.44927699246683162, 122.1667780762339959, 174.9970789168699525 ) ) ; -#3130 = DIRECTION ( 'NONE', ( -0.7933310414247657372, -0.5931044597393388962, -0.1373060761554398823 ) ) ; -#3131 = EDGE_CURVE ( 'NONE', #13855, #15604, #24616, .T. ) ; -#3132 = ORIENTED_EDGE ( 'NONE', *, *, #6864, .F. ) ; -#3133 = FACE_OUTER_BOUND ( 'NONE', #29079, .T. ) ; -#3134 = EDGE_LOOP ( 'NONE', ( #34278, #8195, #30284 ) ) ; -#3136 = DIRECTION ( 'NONE', ( -9.842052273231448302E-18, 0.9743043966640313469, 0.2252353050503801690 ) ) ; -#3135 = CARTESIAN_POINT ( 'NONE', ( 36.17584157855313265, 192.0444006922266453, 104.3821376135421417 ) ) ; -#3137 = VERTEX_POINT ( 'NONE', #29535 ) ; -#3138 = EDGE_CURVE ( 'NONE', #34249, #19429, #26475, .T. ) ; -#3139 = ORIENTED_EDGE ( 'NONE', *, *, #6715, .T. ) ; -#3140 = CARTESIAN_POINT ( 'NONE', ( 2.869617488373000125, 209.5348629560000120, 75.94025826473999530 ) ) ; -#3141 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#3142 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#3143 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #32691, #7133, #23094 ), - ( #29629, #4672, #19603 ), - ( #29430, #35516, #32101 ), - ( #1608, #29019, #4055 ) ), - .UNSPECIFIED., .F., .F., .T. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), - ( 3, 3 ), - ( 0.4676625337841107677, 0.4676714590453207032 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.7512080252030892691, 1.000000000000000000), - ( 1.000000000000000000, 0.7512041196470712334, 1.000000000000000000), - ( 1.000000000000000000, 0.7512002140471668588, 1.000000000000000000), - ( 1.000000000000000000, 0.7511963084032677873, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#3144 = ORIENTED_EDGE ( 'NONE', *, *, #11721, .T. ) ; -#3145 = VERTEX_POINT ( 'NONE', #23402 ) ; -#3146 = CARTESIAN_POINT ( 'NONE', ( -10.07691662939999944, 159.1892556871999886, 28.07991271570000080 ) ) ; -#3147 = CARTESIAN_POINT ( 'NONE', ( 23.35635955975471134, 181.6919812636757285, 101.5857449861623110 ) ) ; -#3148 = CARTESIAN_POINT ( 'NONE', ( 2.939913603357601879, 209.7148157245962636, 73.05672935661613110 ) ) ; -#3149 = ORIENTED_EDGE ( 'NONE', *, *, #26909, .F. ) ; -#3150 = AXIS2_PLACEMENT_3D ( 'NONE', #4105, #19246, #16577 ) ; -#3151 = ORIENTED_EDGE ( 'NONE', *, *, #12026, .T. ) ; -#3152 = CARTESIAN_POINT ( 'NONE', ( -38.46311518618121994, 218.5902260770998282, 61.08173265144981201 ) ) ; -#3153 = CARTESIAN_POINT ( 'NONE', ( -3.168077782478838866, 185.2310913118877238, 105.4977280106237032 ) ) ; -#3154 = CARTESIAN_POINT ( 'NONE', ( -25.69440169518000161, 121.2625582629000007, 88.00628069721000202 ) ) ; -#3155 = ORIENTED_EDGE ( 'NONE', *, *, #13476, .F. ) ; -#3156 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178582675974E-05, -0.0002331579774919535406 ) ) ; -#3157 = CARTESIAN_POINT ( 'NONE', ( 36.06517739910999865, 192.1776130000999956, 106.5431043960000039 ) ) ; -#3158 = ORIENTED_EDGE ( 'NONE', *, *, #16427, .F. ) ; -#3159 = EDGE_CURVE ( 'NONE', #38835, #6430, #22649, .T. ) ; -#3160 = ADVANCED_FACE ( 'NONE', ( #35839 ), #29937, .T. ) ; -#3161 = ADVANCED_FACE ( 'NONE', ( #33801 ), #32978, .T. ) ; -#3162 = CARTESIAN_POINT ( 'NONE', ( 20.50133968371435600, 192.3938364616093395, 106.3952512657694740 ) ) ; -#3163 = CARTESIAN_POINT ( 'NONE', ( -45.39778118714025368, 124.3162297631632498, 88.38100305590371875 ) ) ; -#3164 = FACE_OUTER_BOUND ( 'NONE', #20719, .T. ) ; -#3165 = CARTESIAN_POINT ( 'NONE', ( 1.447658033344549455, 144.9407251398178005, 129.0349007176305065 ) ) ; -#3166 = ADVANCED_FACE ( 'NONE', ( #37082 ), #15007, .T. ) ; -#3167 = ORIENTED_EDGE ( 'NONE', *, *, #32934, .F. ) ; -#3168 = CARTESIAN_POINT ( 'NONE', ( 24.51658391451750063, 115.4942485871420530, 90.25297743685760565 ) ) ; -#3169 = DIRECTION ( 'NONE', ( 0.0005884949961226875435, -0.2249510543439053323, 0.9743698870671265722 ) ) ; -#3170 = FACE_OUTER_BOUND ( 'NONE', #32233, .T. ) ; -#3171 = CARTESIAN_POINT ( 'NONE', ( 36.04803287507999698, 114.1790057977000004, 89.85008343190000346 ) ) ; -#3172 = EDGE_CURVE ( 'NONE', #15935, #23183, #13866, .T. ) ; -#3173 = VECTOR ( 'NONE', #7574, 999.9999999999998863 ) ; -#3174 = CARTESIAN_POINT ( 'NONE', ( 5.957091369052168517, 163.5651307542015900, 97.41131042763848313 ) ) ; -#3175 = VERTEX_POINT ( 'NONE', #21355 ) ; -#3176 = LINE ( 'NONE', #18911, #10887 ) ; -#3177 = ORIENTED_EDGE ( 'NONE', *, *, #16231, .F. ) ; -#3178 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981262413, 143.0051697192221241, 291.5876487235602212 ) ) ; -#3179 = AXIS2_PLACEMENT_3D ( 'NONE', #10428, #3862, #32296 ) ; -#3180 = VECTOR ( 'NONE', #23202, 1000.000000000000114 ) ; -#3181 = AXIS2_PLACEMENT_3D ( 'NONE', #15744, #31715, #31499 ) ; -#3182 = FACE_OUTER_BOUND ( 'NONE', #34564, .T. ) ; -#3183 = ADVANCED_FACE ( 'NONE', ( #24635 ), #30756, .F. ) ; -#3184 = DIRECTION ( 'NONE', ( -0.0006039748319369852994, -1.041357760393576070E-14, -0.9999998176071845934 ) ) ; -#3185 = ORIENTED_EDGE ( 'NONE', *, *, #3482, .T. ) ; -#3186 = DIRECTION ( 'NONE', ( -0.6185863125140933505, -0.7857168535612663041, 0.000000000000000000 ) ) ; -#3187 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#3188 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2068, #20871, #15152, #36612, #20664, #39455 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 2.860979249076398407E-17, 0.0006096144684851653424, 0.001219228936970302062 ), - .UNSPECIFIED. ) ; -#3189 = CARTESIAN_POINT ( 'NONE', ( -26.69810905257040901, 110.6131156702000027, 87.28390928083501876 ) ) ; -#3190 = FACE_OUTER_BOUND ( 'NONE', #1109, .T. ) ; -#3191 = FACE_OUTER_BOUND ( 'NONE', #39757, .T. ) ; -#3192 = ORIENTED_EDGE ( 'NONE', *, *, #10341, .F. ) ; -#3193 = VERTEX_POINT ( 'NONE', #31353 ) ; -#3194 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; -#3195 = FACE_OUTER_BOUND ( 'NONE', #15204, .T. ) ; -#3196 = ORIENTED_EDGE ( 'NONE', *, *, #11647, .T. ) ; -#3197 = CARTESIAN_POINT ( 'NONE', ( -23.36258049448036545, 135.1102247128141869, 91.12573217262112735 ) ) ; -#3198 = EDGE_LOOP ( 'NONE', ( #36355, #8871, #6552, #27673 ) ) ; -#3199 = CARTESIAN_POINT ( 'NONE', ( 31.30352330330278576, 110.6131156702000027, 87.24887774834422771 ) ) ; -#3200 = CARTESIAN_POINT ( 'NONE', ( -3.544777117989765358, 143.5348730270079045, 95.86257910123372028 ) ) ; -#3201 = CARTESIAN_POINT ( 'NONE', ( -30.07082631362985836, 134.8398731441967868, 93.36708164982407254 ) ) ; -#3202 = ORIENTED_EDGE ( 'NONE', *, *, #23674, .F. ) ; -#3203 = CARTESIAN_POINT ( 'NONE', ( 28.50030073765000438, 125.2690929875000023, 88.55614377201999332 ) ) ; -#3204 = VECTOR ( 'NONE', #31398, 1000.000000000000114 ) ; -#3205 = CARTESIAN_POINT ( 'NONE', ( 3.951797994296321281, 167.9176274429178477, 101.0692708321294617 ) ) ; -#3206 = VECTOR ( 'NONE', #33150, 1000.000000000000114 ) ; -#3207 = DIRECTION ( 'NONE', ( 0.6087611427424952648, 0.7731004630501230324, 0.1781166615410720855 ) ) ; -#3208 = ADVANCED_FACE ( 'NONE', ( #18853 ), #21559, .T. ) ; -#3209 = EDGE_CURVE ( 'NONE', #15600, #39537, #327, .T. ) ; -#3210 = CARTESIAN_POINT ( 'NONE', ( -23.47088702255031833, 115.1393135932683549, 90.28196066683830168 ) ) ; -#3211 = VECTOR ( 'NONE', #40335, 1000.000000000000114 ) ; -#3212 = CARTESIAN_POINT ( 'NONE', ( 20.48136443024816344, 209.7093559074854454, 75.54613107284740181 ) ) ; -#3213 = ORIENTED_EDGE ( 'NONE', *, *, #29997, .T. ) ; -#3214 = CARTESIAN_POINT ( 'NONE', ( -28.46687737262882578, 130.4181374544887717, 90.29266601121980784 ) ) ; -#3215 = CARTESIAN_POINT ( 'NONE', ( -38.01211212650550664, 119.1971871873620472, 87.30118044812934386 ) ) ; -#3216 = CARTESIAN_POINT ( 'NONE', ( 36.75389250537243413, 191.6320475598886617, 104.3442590335249491 ) ) ; -#3217 = CARTESIAN_POINT ( 'NONE', ( 20.50029382560668267, 151.8610500380989947, 95.21357841101577435 ) ) ; -#3218 = ORIENTED_EDGE ( 'NONE', *, *, #21345, .T. ) ; -#3219 = EDGE_CURVE ( 'NONE', #9009, #17381, #3328, .T. ) ; -#3220 = VERTEX_POINT ( 'NONE', #37481 ) ; -#3221 = CARTESIAN_POINT ( 'NONE', ( 38.51916230496642157, 119.0542509004514216, 90.25158710978716670 ) ) ; -#3222 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31244, #22260, #21851, #21462 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3223 = CARTESIAN_POINT ( 'NONE', ( 45.67081843470916880, 116.8212980865162507, 122.5178260610734355 ) ) ; -#3224 = DIRECTION ( 'NONE', ( 0.0006039748319386906410, -0.000000000000000000, 0.9999998176071845934 ) ) ; -#3225 = CARTESIAN_POINT ( 'NONE', ( -12.63810009328765815, 177.7933493439334995, 100.7042247836448752 ) ) ; -#3226 = CARTESIAN_POINT ( 'NONE', ( -25.50227423591953979, 190.9796784765214852, 106.3235097443510284 ) ) ; -#3227 = ORIENTED_EDGE ( 'NONE', *, *, #35102, .T. ) ; -#3228 = CARTESIAN_POINT ( 'NONE', ( -12.64562993050861550, 181.6872450680611450, 101.6064063805796280 ) ) ; -#3229 = AXIS2_PLACEMENT_3D ( 'NONE', #30492, #17990, #23743 ) ; -#3230 = EDGE_CURVE ( 'NONE', #33101, #31797, #14800, .T. ) ; -#3231 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#3232 = ORIENTED_EDGE ( 'NONE', *, *, #15673, .T. ) ; -#3233 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971562627 ) ) ; -#3234 = LINE ( 'NONE', #2844, #13337 ) ; -#3235 = AXIS2_PLACEMENT_3D ( 'NONE', #11050, #8797, #20429 ) ; -#3236 = CARTESIAN_POINT ( 'NONE', ( 15.94114414956070114, 127.7634661670421821, 175.0287683583358671 ) ) ; -#3237 = CARTESIAN_POINT ( 'NONE', ( 37.18464630843030250, 191.0632717833100003, 106.3149164087080010 ) ) ; -#3238 = CIRCLE ( 'NONE', #26753, 47.99999999997671551 ) ; -#3239 = AXIS2_PLACEMENT_3D ( 'NONE', #33349, #5346, #17800 ) ; -#3240 = CARTESIAN_POINT ( 'NONE', ( 36.82629873762999750, 191.4958914448999963, 106.2217378751000041 ) ) ; -#3241 = VERTEX_POINT ( 'NONE', #6395 ) ; -#3242 = VERTEX_POINT ( 'NONE', #9282 ) ; -#3243 = CARTESIAN_POINT ( 'NONE', ( 12.68911377202444690, 149.1576569327452830, 181.5431584767406719 ) ) ; -#3244 = CARTESIAN_POINT ( 'NONE', ( 18.27501454530099778, 148.8043935767992991, 179.5886459556068075 ) ) ; -#3245 = EDGE_CURVE ( 'NONE', #6212, #13097, #23870, .T. ) ; -#3246 = ORIENTED_EDGE ( 'NONE', *, *, #18524, .F. ) ; -#3247 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098504, 132.2930706491191302, 93.28496646305455897 ) ) ; -#3248 = VERTEX_POINT ( 'NONE', #39727 ) ; -#3249 = CARTESIAN_POINT ( 'NONE', ( 37.68422603034999696, 118.9267550994999993, 87.11617958790999694 ) ) ; -#3250 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#3251 = CARTESIAN_POINT ( 'NONE', ( -23.36055974376046152, 134.8407614661141167, 93.36323390133236444 ) ) ; -#3252 = ORIENTED_EDGE ( 'NONE', *, *, #25857, .F. ) ; -#3253 = DIRECTION ( 'NONE', ( -0.0006039748319369852994, -1.041357760393576070E-14, -0.9999998176071845934 ) ) ; -#3254 = PLANE ( 'NONE', #37712 ) ; -#3255 = EDGE_CURVE ( 'NONE', #5536, #3701, #11740, .T. ) ; -#3256 = EDGE_CURVE ( 'NONE', #14356, #26486, #29734, .T. ) ; -#3257 = CARTESIAN_POINT ( 'NONE', ( -20.00022154816416986, 118.3566885621645355, 87.28023708086698207 ) ) ; -#3258 = CARTESIAN_POINT ( 'NONE', ( -20.61947746437169471, 212.9340256350066625, 76.07098123360772490 ) ) ; -#3259 = EDGE_CURVE ( 'NONE', #5536, #723, #16660, .T. ) ; -#3260 = ORIENTED_EDGE ( 'NONE', *, *, #38392, .F. ) ; -#3261 = CIRCLE ( 'NONE', #4566, 2.000000000410405487 ) ; -#3262 = CARTESIAN_POINT ( 'NONE', ( 12.64014591831122658, 176.7741019297823470, 103.0645574512443829 ) ) ; -#3263 = VECTOR ( 'NONE', #13370, 1000.000000000000227 ) ; -#3264 = CARTESIAN_POINT ( 'NONE', ( 2.407405297639999997, 189.3998359004000349, 103.3772235684999998 ) ) ; -#3265 = CARTESIAN_POINT ( 'NONE', ( -22.49965381657531438, 154.2035805907503061, 95.43826538557833317 ) ) ; -#3266 = AXIS2_PLACEMENT_3D ( 'NONE', #8338, #17912, #17303 ) ; -#3267 = ORIENTED_EDGE ( 'NONE', *, *, #5427, .T. ) ; -#3268 = ORIENTED_EDGE ( 'NONE', *, *, #2954, .F. ) ; -#3269 = DIRECTION ( 'NONE', ( -0.7855779781279679241, -0.6187626687837380901, 0.000000000000000000 ) ) ; -#3270 = ORIENTED_EDGE ( 'NONE', *, *, #390, .T. ) ; -#3271 = CARTESIAN_POINT ( 'NONE', ( -17.02532382067440864, 121.5076908700915084, 177.5319285829079661 ) ) ; -#3272 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971551802 ) ) ; -#3273 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#3274 = CARTESIAN_POINT ( 'NONE', ( -17.26247767858138005, 152.5342161776122225, 182.4800534808789791 ) ) ; -#3275 = LINE ( 'NONE', #16159, #11544 ) ; -#3276 = CARTESIAN_POINT ( 'NONE', ( -12.64347415174542810, 134.2426399615423236, 93.73178815038983203 ) ) ; -#3277 = CARTESIAN_POINT ( 'NONE', ( -1.245306343188852249, 189.1709453704749819, 105.7877068131130471 ) ) ; -#3278 = ORIENTED_EDGE ( 'NONE', *, *, #2812, .F. ) ; -#3279 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; -#3280 = DIRECTION ( 'NONE', ( -0.5987319960703999522, -0.8009494346596135461, 0.000000000000000000 ) ) ; -#3281 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178630073228E-05, 0.0002331579774917273760 ) ) ; -#3282 = CARTESIAN_POINT ( 'NONE', ( -2.789070135026212149, 208.9474333102131709, 73.28733511393602384 ) ) ; -#3283 = VERTEX_POINT ( 'NONE', #24835 ) ; -#3284 = ORIENTED_EDGE ( 'NONE', *, *, #18399, .F. ) ; -#3285 = AXIS2_PLACEMENT_3D ( 'NONE', #31853, #7279, #25318 ) ; -#3286 = CIRCLE ( 'NONE', #10495, 2.000000000000005773 ) ; -#3287 = VERTEX_POINT ( 'NONE', #6195 ) ; -#3288 = EDGE_CURVE ( 'NONE', #29278, #35994, #13364, .T. ) ; -#3289 = AXIS2_PLACEMENT_3D ( 'NONE', #15025, #630, #21159 ) ; -#3290 = CIRCLE ( 'NONE', #5933, 51.40509898897001761 ) ; -#3291 = CARTESIAN_POINT ( 'NONE', ( -14.16859889492986468, 129.2741495211867004, 92.07252832466726034 ) ) ; -#3292 = ORIENTED_EDGE ( 'NONE', *, *, #11636, .F. ) ; -#3293 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25974, #10427, #22897, #32295 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3294 = ORIENTED_EDGE ( 'NONE', *, *, #7500, .F. ) ; -#3295 = CARTESIAN_POINT ( 'NONE', ( 8.048542121204103950, 160.5989240000510279, 99.80415721606205182 ) ) ; -#3296 = DIRECTION ( 'NONE', ( -0.9999998176071852596, 0.000000000000000000, 0.0006039748306867266138 ) ) ; -#3297 = ADVANCED_FACE ( 'NONE', ( #18048 ), #30549, .F. ) ; -#3298 = CARTESIAN_POINT ( 'NONE', ( -40.80719639505100105, 126.7988830470261092, 92.03030911972437877 ) ) ; -#3299 = DIRECTION ( 'NONE', ( -0.0006039748319384873531, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#3300 = CARTESIAN_POINT ( 'NONE', ( -12.63793204807002901, 135.2920832194301397, 91.40834497133602099 ) ) ; -#3301 = ORIENTED_EDGE ( 'NONE', *, *, #35203, .T. ) ; -#3302 = CARTESIAN_POINT ( 'NONE', ( 15.95571139697598717, 122.2635198402779366, 172.8964588220518124 ) ) ; -#3303 = ORIENTED_EDGE ( 'NONE', *, *, #14263, .F. ) ; -#3304 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#3305 = EDGE_CURVE ( 'NONE', #5125, #1066, #27079, .T. ) ; -#3306 = EDGE_CURVE ( 'NONE', #15935, #35968, #1709, .T. ) ; -#3307 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25192, #425, #6157, #15565 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 6.279468620546222013, 9.421061274136015129 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.3333333333333333703, 0.3333333333333333703, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#3308 = CARTESIAN_POINT ( 'NONE', ( -45.39778154263243692, 124.3161987079337507, 88.38112278943124522 ) ) ; -#3309 = EDGE_CURVE ( 'NONE', #29516, #13086, #34346, .T. ) ; -#3310 = EDGE_LOOP ( 'NONE', ( #31426, #2711 ) ) ; -#3311 = LINE ( 'NONE', #22350, #7569 ) ; -#3312 = ADVANCED_FACE ( 'NONE', ( #16000 ), #8189, .T. ) ; -#3313 = CARTESIAN_POINT ( 'NONE', ( 1.765720771383857191, 188.9184207026980005, 103.2671111675515476 ) ) ; -#3314 = CARTESIAN_POINT ( 'NONE', ( 16.24603267945985507, 152.0453547567774706, 181.0525560685096593 ) ) ; -#3315 = ORIENTED_EDGE ( 'NONE', *, *, #2634, .F. ) ; -#3316 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950931402, 137.3532831589782575, 178.0585834213011083 ) ) ; -#3317 = CARTESIAN_POINT ( 'NONE', ( 45.50974939072701630, 131.1361171346210313, 90.41374468093005135 ) ) ; -#3318 = ORIENTED_EDGE ( 'NONE', *, *, #27942, .F. ) ; -#3319 = AXIS2_PLACEMENT_3D ( 'NONE', #270, #10504, #35397 ) ; -#3320 = VECTOR ( 'NONE', #13579, 1000.000000000000227 ) ; -#3321 = CARTESIAN_POINT ( 'NONE', ( -17.26178222639411430, 121.7713432978476220, 175.3684242141576703 ) ) ; -#3322 = CARTESIAN_POINT ( 'NONE', ( 36.11364262193256280, 191.5260145455536929, 103.8483746271915322 ) ) ; -#3323 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048985379, 177.1117171981417471, 103.6430084149241679 ) ) ; -#3324 = VECTOR ( 'NONE', #140, 1000.000000000000000 ) ; -#3325 = ORIENTED_EDGE ( 'NONE', *, *, #35536, .T. ) ; -#3326 = AXIS2_PLACEMENT_3D ( 'NONE', #7074, #22838, #19941 ) ; -#3327 = CARTESIAN_POINT ( 'NONE', ( 0.7299322866671852372, 188.3861608050018219, 106.2237677405733081 ) ) ; -#3328 = LINE ( 'NONE', #15213, #6862 ) ; -#3329 = CARTESIAN_POINT ( 'NONE', ( -75.98888182033904570, 155.7827505944902953, 98.22986012165449665 ) ) ; -#3330 = ORIENTED_EDGE ( 'NONE', *, *, #29917, .F. ) ; -#3331 = FACE_OUTER_BOUND ( 'NONE', #28822, .T. ) ; -#3332 = CARTESIAN_POINT ( 'NONE', ( -25.50006458888940131, 118.8155663869242886, 89.78318340809063614 ) ) ; -#3334 = CARTESIAN_POINT ( 'NONE', ( 35.65490496190012237, 191.9590344014766572, 103.8998585555165590 ) ) ; -#3333 = DIRECTION ( 'NONE', ( 0.0005884949961249847511, -0.2249510543439063592, 0.9743698870671262391 ) ) ; -#3335 = EDGE_LOOP ( 'NONE', ( #4901, #11154 ) ) ; -#3336 = ORIENTED_EDGE ( 'NONE', *, *, #10892, .T. ) ; -#3337 = CARTESIAN_POINT ( 'NONE', ( -20.18507781052162287, 209.7097153168429600, 75.90405272105060419 ) ) ; -#3338 = EDGE_CURVE ( 'NONE', #10716, #14788, #10493, .T. ) ; -#3339 = CARTESIAN_POINT ( 'NONE', ( 26.71540924722000199, 177.4950356244999909, 100.8713215240999972 ) ) ; -#3340 = ORIENTED_EDGE ( 'NONE', *, *, #28037, .T. ) ; -#3341 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #477, #24853, #9905, #37302 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3342 = AXIS2_PLACEMENT_3D ( 'NONE', #39209, #23896, #23479 ) ; -#3343 = ORIENTED_EDGE ( 'NONE', *, *, #25724, .F. ) ; -#3345 = AXIS2_PLACEMENT_3D ( 'NONE', #36874, #5993, #5383 ) ; -#3344 = CARTESIAN_POINT ( 'NONE', ( -35.52033196490545208, 114.0817143859714662, 87.28923768247270232 ) ) ; -#3346 = EDGE_CURVE ( 'NONE', #29413, #33023, #36916, .T. ) ; -#3347 = VECTOR ( 'NONE', #6489, 1000.000000000000227 ) ; -#3348 = CARTESIAN_POINT ( 'NONE', ( 13.50310338664140986, 187.4678188521250775, 105.7260407433838338 ) ) ; -#3349 = CARTESIAN_POINT ( 'NONE', ( 23.03875873965262855, 135.0043594556615290, 90.80721871908795606 ) ) ; -#3350 = EDGE_CURVE ( 'NONE', #34342, #35508, #37760, .T. ) ; -#3351 = ORIENTED_EDGE ( 'NONE', *, *, #17326, .T. ) ; -#3352 = EDGE_LOOP ( 'NONE', ( #33209, #6934, #12947, #39276, #30298 ) ) ; -#3353 = FACE_OUTER_BOUND ( 'NONE', #13596, .T. ) ; -#3354 = FACE_OUTER_BOUND ( 'NONE', #8982, .T. ) ; -#3355 = CARTESIAN_POINT ( 'NONE', ( -25.83361275620000086, 122.1073251810999949, 88.20139195350000705 ) ) ; -#3356 = EDGE_CURVE ( 'NONE', #133, #16029, #37681, .T. ) ; -#3357 = ORIENTED_EDGE ( 'NONE', *, *, #15898, .F. ) ; -#3358 = CARTESIAN_POINT ( 'NONE', ( 0.04503145192460000085, 226.4002260771000010, 74.55847715811999876 ) ) ; -#3359 = DIRECTION ( 'NONE', ( 0.7856637149787866203, -0.6186538021912836305, 0.000000000000000000 ) ) ; -#3360 = CARTESIAN_POINT ( 'NONE', ( 17.07624313959705020, 121.4538017505177123, 177.4665436634097091 ) ) ; -#3361 = ORIENTED_EDGE ( 'NONE', *, *, #24391, .T. ) ; -#3362 = CARTESIAN_POINT ( 'NONE', ( -45.30371984282656683, 124.3227729409930618, 91.46136974178453727 ) ) ; -#3363 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#3364 = CARTESIAN_POINT ( 'NONE', ( -1.362136793684999958, 189.3876565648999986, 105.6752102165999929 ) ) ; -#3365 = LINE ( 'NONE', #35625, #9767 ) ; -#3366 = ORIENTED_EDGE ( 'NONE', *, *, #36327, .T. ) ; -#3367 = CARTESIAN_POINT ( 'NONE', ( -43.13843726988963567, 112.6550928102931834, 129.5909698073101595 ) ) ; -#3368 = ORIENTED_EDGE ( 'NONE', *, *, #27064, .F. ) ; -#3369 = CARTESIAN_POINT ( 'NONE', ( 36.05539628079529990, 119.7153706280430470, 90.34852804255076819 ) ) ; -#3370 = CARTESIAN_POINT ( 'NONE', ( -13.51345484135845965, 174.8561185417166826, 26.73029491429123894 ) ) ; -#3371 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#3372 = AXIS2_PLACEMENT_3D ( 'NONE', #20570, #4423, #35475 ) ; -#3373 = AXIS2_PLACEMENT_3D ( 'NONE', #1829, #1416, #35947 ) ; -#3374 = ORIENTED_EDGE ( 'NONE', *, *, #30051, .F. ) ; -#3375 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#3376 = ORIENTED_EDGE ( 'NONE', *, *, #19466, .T. ) ; -#3377 = CARTESIAN_POINT ( 'NONE', ( -25.65167874464251696, 209.7116445767937876, 73.43226018034312119 ) ) ; -#3378 = CARTESIAN_POINT ( 'NONE', ( -25.58080687204398629, 190.4782248801624007, 104.1568888495789480 ) ) ; -#3379 = VERTEX_POINT ( 'NONE', #16592 ) ; -#3380 = DIRECTION ( 'NONE', ( -0.0004161288024629044321, -0.5299192578506427553, -0.8480479980495465586 ) ) ; -#3381 = ADVANCED_FACE ( 'NONE', ( #10084 ), #5555, .F. ) ; -#3382 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#3383 = CARTESIAN_POINT ( 'NONE', ( -28.46737701140906651, 128.5818728498977634, 89.35557899873234078 ) ) ; -#3384 = ADVANCED_FACE ( 'NONE', ( #258 ), #12741, .T. ) ; -#3385 = CYLINDRICAL_SURFACE ( 'NONE', #35091, 6.000000000000008882 ) ; -#3386 = EDGE_CURVE ( 'NONE', #32614, #26491, #18615, .T. ) ; -#3387 = CARTESIAN_POINT ( 'NONE', ( -0.4543644846840136919, 210.9999999999990621, 75.55877896310728659 ) ) ; -#3388 = ORIENTED_EDGE ( 'NONE', *, *, #1455, .F. ) ; -#3389 = ORIENTED_EDGE ( 'NONE', *, *, #10181, .F. ) ; -#3390 = CARTESIAN_POINT ( 'NONE', ( 5.668045263090168540, 187.9945100871488251, 103.3510643583489639 ) ) ; -#3391 = CARTESIAN_POINT ( 'NONE', ( -35.98817295377529746, 191.5260130662397273, 103.8919236801626340 ) ) ; -#3392 = DIRECTION ( 'NONE', ( 0.0005884949961255732560, -0.2249510543439049715, 0.9743698870671266832 ) ) ; -#3393 = PLANE ( 'NONE', #11160 ) ; -#3394 = EDGE_CURVE ( 'NONE', #1633, #31589, #30972, .T. ) ; -#3395 = ORIENTED_EDGE ( 'NONE', *, *, #27581, .T. ) ; -#3396 = CARTESIAN_POINT ( 'NONE', ( 19.98046760410895573, 208.7354111918591570, 73.11857707450180044 ) ) ; -#3397 = CONICAL_SURFACE ( 'NONE', #17750, 5.249999999894133573, 0.7853981634251984145 ) ; -#3398 = ORIENTED_EDGE ( 'NONE', *, *, #22668, .F. ) ; -#3399 = LINE ( 'NONE', #340, #35260 ) ; -#3400 = VECTOR ( 'NONE', #18495, 1000.000000000000227 ) ; -#3401 = EDGE_CURVE ( 'NONE', #13672, #18171, #28491, .T. ) ; -#3402 = VECTOR ( 'NONE', #32018, 1000.000000000000227 ) ; -#3403 = LINE ( 'NONE', #15876, #40416 ) ; -#3404 = CARTESIAN_POINT ( 'NONE', ( 39.32399170537505029, 121.5657277381213817, 123.6169974531826341 ) ) ; -#3405 = ORIENTED_EDGE ( 'NONE', *, *, #18255, .T. ) ; -#3406 = CARTESIAN_POINT ( 'NONE', ( -20.34617778358973439, 105.2139170254723695, 89.78007332956207165 ) ) ; -#3407 = CARTESIAN_POINT ( 'NONE', ( -15.74985326587000145, 185.3779283803999931, 102.7168790019000113 ) ) ; -#3408 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#3409 = CARTESIAN_POINT ( 'NONE', ( 18.59950176168990055, 126.0162487695453706, 174.9291204768238117 ) ) ; -#3410 = CARTESIAN_POINT ( 'NONE', ( 4.468727364937352675, 124.6616761605458379, 88.43063753346716283 ) ) ; -#3411 = ORIENTED_EDGE ( 'NONE', *, *, #17615, .T. ) ; -#3412 = DIRECTION ( 'NONE', ( -0.6087611434211035455, 0.7728348337987402950, 0.1792656964617155846 ) ) ; -#3413 = PLANE ( 'NONE', #334 ) ; -#3414 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265228896, -0.1368326740407719011 ) ) ; -#3415 = FACE_OUTER_BOUND ( 'NONE', #4974, .T. ) ; -#3416 = ORIENTED_EDGE ( 'NONE', *, *, #24803, .F. ) ; -#3417 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971576782 ) ) ; -#3418 = DIRECTION ( 'NONE', ( 0.7933533411653060918, -0.5930537057989936356, -0.1373964268091645846 ) ) ; -#3419 = CARTESIAN_POINT ( 'NONE', ( -3.772473109594537188, 168.4423924140773465, 98.78424517642510239 ) ) ; -#3420 = VECTOR ( 'NONE', #35388, 1000.000000000000227 ) ; -#3421 = CARTESIAN_POINT ( 'NONE', ( -26.29277745650999876, 188.3533238026000163, 105.7193558339999981 ) ) ; -#3422 = VERTEX_POINT ( 'NONE', #7195 ) ; -#3423 = CARTESIAN_POINT ( 'NONE', ( 38.33010151215698613, 191.0388342792613798, 103.7345633339579365 ) ) ; -#3424 = CIRCLE ( 'NONE', #175, 2.749999999950412999 ) ; -#3425 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#3426 = CARTESIAN_POINT ( 'NONE', ( 20.50147137495634198, 190.9646546281344683, 106.2940065278771016 ) ) ; -#3427 = CARTESIAN_POINT ( 'NONE', ( 36.04689830208332069, 205.5673820496000133, 76.27844315544000153 ) ) ; -#3428 = CARTESIAN_POINT ( 'NONE', ( -25.02200714046000130, 181.7555764690000046, 103.1690735356000062 ) ) ; -#3429 = CARTESIAN_POINT ( 'NONE', ( 20.02762529703683825, 127.4325933158175985, 89.08929274300049883 ) ) ; -#3430 = CARTESIAN_POINT ( 'NONE', ( 36.67680774640550112, 191.6480351179000081, 104.3376580875839892 ) ) ; -#3431 = EDGE_CURVE ( 'NONE', #17689, #3422, #28885, .T. ) ; -#3432 = EDGE_CURVE ( 'NONE', #31885, #19846, #10292, .T. ) ; -#3433 = CARTESIAN_POINT ( 'NONE', ( 36.71549788546000315, 191.5837423664000028, 106.2320285050000024 ) ) ; -#3434 = EDGE_LOOP ( 'NONE', ( #25076, #16431, #18280 ) ) ; -#3435 = VERTEX_POINT ( 'NONE', #862 ) ; -#3436 = DIRECTION ( 'NONE', ( 0.0006039748319385504537, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#3437 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971557353 ) ) ; -#3438 = CC_DESIGN_PERSON_AND_ORGANIZATION_ASSIGNMENT ( #33706, #9191, ( #14451 ) ) ; -#3439 = DIRECTION ( 'NONE', ( 0.0005884941600622460708, -0.2249510532593050338, 0.9743698873180313136 ) ) ; -#3440 = ORIENTED_EDGE ( 'NONE', *, *, #29824, .F. ) ; -#3441 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927782437076, 0.0005734119022074447283 ) ) ; -#3442 = EDGE_LOOP ( 'NONE', ( #22171, #12261, #35414, #10284, #35925 ) ) ; -#3443 = CARTESIAN_POINT ( 'NONE', ( 12.63603855934096920, 128.0249363968860337, 91.76793536831303300 ) ) ; -#3444 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749386209, 132.8602140592488468, 90.82839891337145843 ) ) ; -#3445 = AXIS2_PLACEMENT_3D ( 'NONE', #28692, #6203, #9288 ) ; -#3446 = ORIENTED_EDGE ( 'NONE', *, *, #1794, .T. ) ; -#3447 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319376807067 ) ) ; -#3448 = PLANE ( 'NONE', #21137 ) ; -#3449 = CARTESIAN_POINT ( 'NONE', ( -28.46728868142984226, 182.0597503807817645, 102.2150741964074143 ) ) ; -#3450 = AXIS2_PLACEMENT_3D ( 'NONE', #1748, #20539, #33009 ) ; -#3451 = CARTESIAN_POINT ( 'NONE', ( 36.82553848920489514, 117.0567498273620402, 90.24554313673101547 ) ) ; -#3452 = DIRECTION ( 'NONE', ( -0.0003200578985643136158, 0.8480480961564359488, -0.5299191675797225720 ) ) ; -#3453 = ORIENTED_EDGE ( 'NONE', *, *, #1043, .T. ) ; -#3454 = EDGE_CURVE ( 'NONE', #25759, #27090, #19666, .T. ) ; -#3455 = DIRECTION ( 'NONE', ( 0.0001408404075805813865, -0.2249510913125021550, 0.9743700460714572742 ) ) ; -#3456 = AXIS2_PLACEMENT_3D ( 'NONE', #31218, #735, #13221 ) ; -#3457 = CARTESIAN_POINT ( 'NONE', ( 2.749831409735000065, 189.8396373187000279, 103.4785235852000085 ) ) ; -#3458 = CARTESIAN_POINT ( 'NONE', ( -22.78437402937589695, 158.4258150520903143, 96.41321554517463710 ) ) ; -#3459 = VERTEX_POINT ( 'NONE', #32163 ) ; -#3460 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#3461 = EDGE_LOOP ( 'NONE', ( #38467, #14315, #24519, #21418 ) ) ; -#3462 = LINE ( 'NONE', #34151, #35147 ) ; -#3463 = CARTESIAN_POINT ( 'NONE', ( -14.55306305638819886, 182.5568561273574630, 101.8082842025129366 ) ) ; -#3464 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#3465 = CARTESIAN_POINT ( 'NONE', ( -39.68697719330018714, 104.2905048274892437, 197.1740080326739530 ) ) ; -#3466 = CYLINDRICAL_SURFACE ( 'NONE', #32773, 2.000000000000011546 ) ; -#3467 = CARTESIAN_POINT ( 'NONE', ( -2.541354399913000162, 209.3993418770999995, 73.44252218553999967 ) ) ; -#3468 = CARTESIAN_POINT ( 'NONE', ( -42.70458103469926670, 67.79617006382294164, 322.0565592465368354 ) ) ; -#3469 = CIRCLE ( 'NONE', #26384, 2.000000000000011546 ) ; -#3470 = VERTEX_POINT ( 'NONE', #1063 ) ; -#3471 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363195980786E-14, -0.9999998176071845934 ) ) ; -#3472 = DIRECTION ( 'NONE', ( -0.0006039748319386984473, 0.000000000000000000, -0.9999998176071845934 ) ) ; -#3473 = FACE_OUTER_BOUND ( 'NONE', #6644, .T. ) ; -#3474 = EDGE_CURVE ( 'NONE', #7294, #21726, #36321, .T. ) ; -#3475 = EDGE_CURVE ( 'NONE', #5782, #21943, #9510, .T. ) ; -#3476 = CARTESIAN_POINT ( 'NONE', ( 12.64524319930002783, 177.7928828500099598, 100.6920447773197225 ) ) ; -#3477 = EDGE_LOOP ( 'NONE', ( #35651, #6362, #34196, #28564 ) ) ; -#3478 = ORIENTED_EDGE ( 'NONE', *, *, #31818, .T. ) ; -#3479 = VECTOR ( 'NONE', #30984, 1000.000000000000114 ) ; -#3480 = EDGE_LOOP ( 'NONE', ( #39399, #29383, #13365, #5446 ) ) ; -#3481 = CARTESIAN_POINT ( 'NONE', ( 25.70209235779490342, 191.4202673505085954, 104.1723544197036802 ) ) ; -#3482 = EDGE_CURVE ( 'NONE', #36851, #19053, #26465, .T. ) ; -#3483 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971581778 ) ) ; -#3484 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31280, #34331, #34132, #31483 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0002855128694785529853, 0.0003233533305980134482 ), - .UNSPECIFIED. ) ; -#3485 = VERTEX_POINT ( 'NONE', #10690 ) ; -#3486 = ORIENTED_EDGE ( 'NONE', *, *, #19723, .T. ) ; -#3487 = DIRECTION ( 'NONE', ( 2.151057110228587533E-14, 0.9743700557921592953, 0.2249510932971532096 ) ) ; -#3488 = CARTESIAN_POINT ( 'NONE', ( 38.46700359482129272, 118.8212168396402717, 87.67371270529410765 ) ) ; -#3489 = CARTESIAN_POINT ( 'NONE', ( -35.45414161172500656, 207.8686442644066403, 77.29845580048690579 ) ) ; -#3490 = CARTESIAN_POINT ( 'NONE', ( -24.42625686036400268, 103.6131156702357998, 89.78253759510907628 ) ) ; -#3491 = ORIENTED_EDGE ( 'NONE', *, *, #16417, .F. ) ; -#3492 = FACE_OUTER_BOUND ( 'NONE', #35380, .T. ) ; -#3493 = ORIENTED_EDGE ( 'NONE', *, *, #28787, .T. ) ; -#3494 = ORIENTED_EDGE ( 'NONE', *, *, #13841, .F. ) ; -#3495 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#3496 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971558463 ) ) ; -#3497 = ORIENTED_EDGE ( 'NONE', *, *, #21888, .F. ) ; -#3498 = EDGE_CURVE ( 'NONE', #19007, #26517, #31702, .T. ) ; -#3499 = CARTESIAN_POINT ( 'NONE', ( -2.943640821425400400, 190.8913430625419778, 103.7204105821340221 ) ) ; -#3500 = CARTESIAN_POINT ( 'NONE', ( 0.9003320879892923179, 188.6348484842668256, 103.2021660235679832 ) ) ; -#3501 = AXIS2_PLACEMENT_3D ( 'NONE', #34969, #19658, #19456 ) ; -#3502 = AXIS2_PLACEMENT_3D ( 'NONE', #34402, #18858, #19065 ) ; -#3503 = CARTESIAN_POINT ( 'NONE', ( -26.01026747887119583, 207.8020231323739608, 73.42646037265581072 ) ) ; -#3504 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#3505 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19755, #19372, #16695, #29195 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999992928434677797 ), - .UNSPECIFIED. ) ; -#3506 = AXIS2_PLACEMENT_3D ( 'NONE', #33765, #3279, #5763 ) ; -#3507 = ORIENTED_EDGE ( 'NONE', *, *, #10100, .F. ) ; -#3508 = CARTESIAN_POINT ( 'NONE', ( -22.62212617741983678, 214.0904530554988696, 73.07216727974267201 ) ) ; -#3509 = CARTESIAN_POINT ( 'NONE', ( -31.73518137046647780, 115.2741031936126177, 176.5389297272637634 ) ) ; -#3510 = VERTEX_POINT ( 'NONE', #27048 ) ; -#3511 = CYLINDRICAL_SURFACE ( 'NONE', #1685, 1.750000000000001998 ) ; -#3512 = PLANE ( 'NONE', #39836 ) ; -#3513 = CARTESIAN_POINT ( 'NONE', ( -25.36035329269000016, 120.6009619010000051, 89.93798750253999685 ) ) ; -#3514 = EDGE_CURVE ( 'NONE', #38213, #15039, #11932, .T. ) ; -#3515 = ORIENTED_EDGE ( 'NONE', *, *, #15151, .T. ) ; -#3516 = CARTESIAN_POINT ( 'NONE', ( -45.39778154263243692, 124.3161987079337507, 88.38112278943124522 ) ) ; -#3517 = CARTESIAN_POINT ( 'NONE', ( 37.55190133016288456, 77.26223394093688057, 291.2877482218110572 ) ) ; -#3518 = EDGE_CURVE ( 'NONE', #31222, #5278, #38875, .T. ) ; -#3519 = EDGE_LOOP ( 'NONE', ( #29552, #37330, #19170, #21640 ) ) ; -#3520 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749899931, 179.6299767373261602, 101.6260513916142116 ) ) ; -#3521 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#3522 = ADVANCED_FACE ( 'NONE', ( #20471 ), #6251, .T. ) ; -#3523 = EDGE_CURVE ( 'NONE', #35577, #21316, #11282, .T. ) ; -#3525 = CARTESIAN_POINT ( 'NONE', ( 35.56356469037133650, 192.3002554099812471, 103.8734939767707885 ) ) ; -#3524 = LINE ( 'NONE', #676, #21105 ) ; -#3526 = EDGE_CURVE ( 'NONE', #21067, #12970, #23249, .T. ) ; -#3527 = ORIENTED_EDGE ( 'NONE', *, *, #1989, .F. ) ; -#3528 = DIRECTION ( 'NONE', ( -0.0005884949961239638663, 0.2249510543439075250, -0.9743698870671260170 ) ) ; -#3529 = ADVANCED_FACE ( 'NONE', ( #8223 ), #39282, .T. ) ; -#3530 = VECTOR ( 'NONE', #27606, 1000.000000000000000 ) ; -#3531 = VECTOR ( 'NONE', #39789, 1000.000000000000114 ) ; -#3532 = EDGE_LOOP ( 'NONE', ( #23425, #4247, #36062, #1091, #564 ) ) ; -#3533 = CARTESIAN_POINT ( 'NONE', ( 38.54411846755796489, 218.5902260770999987, 73.03522440068014987 ) ) ; -#3534 = FACE_OUTER_BOUND ( 'NONE', #874, .T. ) ; -#3535 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971556243 ) ) ; -#3536 = VERTEX_POINT ( 'NONE', #39480 ) ; -#3537 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #18779, #25361, #9417, #34914 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.712388980384695003, 4.891461175462934463 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973295471489361796, 0.9973295471489361796, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#3538 = ORIENTED_EDGE ( 'NONE', *, *, #21888, .T. ) ; -#3539 = CARTESIAN_POINT ( 'NONE', ( -13.46991461394048706, 153.3545038370762654, 97.63149519329859061 ) ) ; -#3540 = CARTESIAN_POINT ( 'NONE', ( 21.96933826409811630, 182.0731317569477312, 101.6745489239626465 ) ) ; -#3541 = LINE ( 'NONE', #28909, #16933 ) ; -#3542 = ORIENTED_EDGE ( 'NONE', *, *, #31617, .F. ) ; -#3543 = ORIENTED_EDGE ( 'NONE', *, *, #14309, .F. ) ; -#3544 = ORIENTED_EDGE ( 'NONE', *, *, #10577, .T. ) ; -#3545 = LINE ( 'NONE', #16228, #21335 ) ; -#3546 = CARTESIAN_POINT ( 'NONE', ( 21.83140103668416998, 176.0486778938952739, 102.8495379525328985 ) ) ; -#3547 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971556798 ) ) ; -#3548 = ORIENTED_EDGE ( 'NONE', *, *, #30561, .F. ) ; -#3549 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #24071, #26328, #39182, #26945 ), - ( #38764, #39583, #11187, #4428 ), - ( #35687, #20784, #17702, #35898 ), - ( #5233, #7903, #14459, #20368 ), - ( #20575, #23250, #29799, #14257 ), - ( #23659, #36105, #33044, #5034 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 4 ), - ( 4, 4 ), - ( -0.4541100403105999828, 0.000000000000000000, 1.000000000000000000, 1.454054756616000033 ), - ( -2.029131470331999940E-05, 1.000000271963999987 ), - .UNSPECIFIED. ) ; -#3550 = CARTESIAN_POINT ( 'NONE', ( -21.02099060171535427, 212.6267540641154028, 73.57122262233082211 ) ) ; -#3551 = EDGE_LOOP ( 'NONE', ( #22885, #21728, #1632, #13966 ) ) ; -#3552 = CARTESIAN_POINT ( 'NONE', ( -36.97421542778027259, 116.5047944643511357, 89.73514664299061394 ) ) ; -#3553 = CARTESIAN_POINT ( 'NONE', ( 37.33114329194350489, 166.9001604414680173, 188.4905732344037119 ) ) ; -#3554 = EDGE_LOOP ( 'NONE', ( #7656, #17473, #16858, #18750 ) ) ; -#3555 = PLANE ( 'NONE', #21647 ) ; -#3556 = CONICAL_SURFACE ( 'NONE', #26441, 51.90509899272666416, 0.7853981633973107224 ) ; -#3557 = CARTESIAN_POINT ( 'NONE', ( -0.9776028703166999012, 188.8974623888000224, 105.8690628777000029 ) ) ; -#3558 = VECTOR ( 'NONE', #22209, 1000.000000000000114 ) ; -#3559 = AXIS2_PLACEMENT_3D ( 'NONE', #38015, #16526, #38805 ) ; -#3560 = CARTESIAN_POINT ( 'NONE', ( -44.92025114620013682, 180.7728939925537759, 104.3226271335811361 ) ) ; -#3561 = EDGE_CURVE ( 'NONE', #36902, #15091, #17196, .T. ) ; -#3562 = ORIENTED_EDGE ( 'NONE', *, *, #4113, .T. ) ; -#3563 = CARTESIAN_POINT ( 'NONE', ( -28.70758036415549697, 148.4279572010033519, 96.50331524374598757 ) ) ; -#3564 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13213, #26093, #25701, #34452 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3565 = CIRCLE ( 'NONE', #24508, 1.999999999999996891 ) ; -#3566 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; -#3567 = FACE_OUTER_BOUND ( 'NONE', #9650, .T. ) ; -#3568 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; -#3569 = ADVANCED_FACE ( 'NONE', ( #20890 ), #18885, .F. ) ; -#3570 = DIRECTION ( 'NONE', ( 0.7933535325932957738, -0.5931614258681779939, -0.1369295263402617313 ) ) ; -#3571 = ORIENTED_EDGE ( 'NONE', *, *, #3678, .T. ) ; -#3572 = EDGE_CURVE ( 'NONE', #25978, #25353, #36234, .T. ) ; -#3573 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775999513 ) ) ; -#3574 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825925439549636, 0.0005734119022586144088 ) ) ; -#3575 = EDGE_CURVE ( 'NONE', #29855, #16955, #24558, .T. ) ; -#3576 = VERTEX_POINT ( 'NONE', #1571 ) ; -#3577 = EDGE_LOOP ( 'NONE', ( #27279, #19247, #7667, #35253, #12995 ) ) ; -#3578 = CARTESIAN_POINT ( 'NONE', ( 1.752038607275829607, 145.3272753739126983, 129.1239590489928162 ) ) ; -#3579 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; -#3580 = CARTESIAN_POINT ( 'NONE', ( -38.93740081958814159, 190.3639749098083200, 106.7043400420495374 ) ) ; -#3581 = ORIENTED_EDGE ( 'NONE', *, *, #26633, .T. ) ; -#3582 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; -#3583 = ORIENTED_EDGE ( 'NONE', *, *, #27396, .F. ) ; -#3584 = ORIENTED_EDGE ( 'NONE', *, *, #11907, .F. ) ; -#3585 = CARTESIAN_POINT ( 'NONE', ( -6.033304800909325749, 177.7287101295752905, 100.7413749438379682 ) ) ; -#3586 = AXIS2_PLACEMENT_3D ( 'NONE', #34563, #6176, #19036 ) ; -#3587 = CARTESIAN_POINT ( 'NONE', ( -20.49853057565002601, 184.3993303303604705, 104.8029991440840973 ) ) ; -#3588 = AXIS2_PLACEMENT_3D ( 'NONE', #6886, #22655, #10381 ) ; -#3589 = CARTESIAN_POINT ( 'NONE', ( -21.82963555936113309, 135.9868450106493185, 91.57429495730107760 ) ) ; -#3590 = AXIS2_PLACEMENT_3D ( 'NONE', #21844, #24726, #34091 ) ; -#3591 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8849, #20697, #5142, #27478 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.003686124987248532749, 0.004393344453691859670 ), - .UNSPECIFIED. ) ; -#3592 = ORIENTED_EDGE ( 'NONE', *, *, #13764, .F. ) ; -#3593 = CARTESIAN_POINT ( 'NONE', ( -19.99823416869593373, 118.9403737594142854, 90.20346087292679726 ) ) ; -#3594 = AXIS2_PLACEMENT_3D ( 'NONE', #25149, #5724, #2852 ) ; -#3595 = CARTESIAN_POINT ( 'NONE', ( 27.71217996750916512, 149.2638841111731267, 291.5418064729402658 ) ) ; -#3596 = ORIENTED_EDGE ( 'NONE', *, *, #4858, .T. ) ; -#3597 = CARTESIAN_POINT ( 'NONE', ( 35.56237296995020358, 191.9759150222000130, 101.8999685582251260 ) ) ; -#3598 = CARTESIAN_POINT ( 'NONE', ( -23.36581923842090092, 181.0107737450888976, 104.5356085457618889 ) ) ; -#3599 = CARTESIAN_POINT ( 'NONE', ( 31.30533522768502763, 110.6131156702000027, 90.24887720109859401 ) ) ; -#3600 = ORIENTED_EDGE ( 'NONE', *, *, #19388, .T. ) ; -#3601 = CARTESIAN_POINT ( 'NONE', ( 27.83433066462000127, 125.1256074409000121, 88.86582280017999835 ) ) ; -#3602 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15490, #34866, #6876, #19346 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.9970396573944148022, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3603 = FACE_OUTER_BOUND ( 'NONE', #15855, .T. ) ; -#3604 = CARTESIAN_POINT ( 'NONE', ( 4.034499241564549976, 175.2435454650956217, 100.6217987443190509 ) ) ; -#3605 = CARTESIAN_POINT ( 'NONE', ( 5.668109638569079678, 185.2338525438773900, 105.4930173663374262 ) ) ; -#3606 = EDGE_LOOP ( 'NONE', ( #20977, #38043, #37815, #23828, #6626 ) ) ; -#3607 = CARTESIAN_POINT ( 'NONE', ( 16.55926621263987641, 122.5128711786446445, 174.6304772722791654 ) ) ; -#3608 = CARTESIAN_POINT ( 'NONE', ( 0.6894063899216041902, 189.0039686778983139, 103.6859152462737796 ) ) ; -#3609 = CARTESIAN_POINT ( 'NONE', ( 36.47897566921480461, 191.7700612336033430, 104.3554365893951825 ) ) ; -#3610 = ADVANCED_FACE ( 'NONE', ( #1362 ), #4025, .T. ) ; -#3611 = EDGE_CURVE ( 'NONE', #8754, #1723, #18696, .T. ) ; -#3612 = CARTESIAN_POINT ( 'NONE', ( 25.99876818124551292, 118.1164810761916470, 87.25208046938912787 ) ) ; -#3613 = EDGE_CURVE ( 'NONE', #33506, #24100, #27188, .T. ) ; -#3614 = DIRECTION ( 'NONE', ( -0.1305262051639064225, -0.9660383184132061984, -0.2230086929312280475 ) ) ; -#3615 = EDGE_CURVE ( 'NONE', #6960, #14645, #26048, .T. ) ; -#3616 = CONICAL_SURFACE ( 'NONE', #5582, 2.500000074000459094, 0.7853981633357993708 ) ; -#3617 = CARTESIAN_POINT ( 'NONE', ( 20.50147081616042755, 137.9496117178372003, 94.05447709939286938 ) ) ; -#3618 = AXIS2_PLACEMENT_3D ( 'NONE', #30399, #33654, #11190 ) ; -#3619 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; -#3620 = CARTESIAN_POINT ( 'NONE', ( -33.45586840016203922, 218.5902260770999987, 73.07871058858016511 ) ) ; -#3621 = CARTESIAN_POINT ( 'NONE', ( -44.46121984373956337, 189.2577286604973210, 103.8865186576782804 ) ) ; -#3622 = VECTOR ( 'NONE', #30854, 1000.000000000000227 ) ; -#3623 = CARTESIAN_POINT ( 'NONE', ( -25.50501342766671442, 190.9440501067191747, 106.3152859405670085 ) ) ; -#3624 = VERTEX_POINT ( 'NONE', #19961 ) ; -#3625 = CIRCLE ( 'NONE', #35589, 7.499999999921035609 ) ; -#3626 = EDGE_CURVE ( 'NONE', #15694, #22830, #23455, .T. ) ; -#3627 = CONICAL_SURFACE ( 'NONE', #31092, 2.503009339059525828, 0.7854392546297950251 ) ; -#3628 = PLANE ( 'NONE', #5683 ) ; -#3629 = EDGE_CURVE ( 'NONE', #5465, #34776, #13843, .T. ) ; -#3630 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552357 ) ) ; -#3631 = DIRECTION ( 'NONE', ( -5.782411586657655244E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; -#3632 = CARTESIAN_POINT ( 'NONE', ( 0.04412548967667000166, 9.379164112032999336E-13, 73.05847743171000275 ) ) ; -#3633 = CARTESIAN_POINT ( 'NONE', ( 20.41791641949827607, 127.3413591030548275, 89.46831587257177887 ) ) ; -#3634 = FACE_OUTER_BOUND ( 'NONE', #28847, .T. ) ; -#3635 = CARTESIAN_POINT ( 'NONE', ( -39.03036842895058811, 175.8132598316807105, 136.1868359458795510 ) ) ; -#3636 = ORIENTED_EDGE ( 'NONE', *, *, #23575, .F. ) ; -#3637 = EDGE_CURVE ( 'NONE', #39104, #33123, #17092, .T. ) ; -#3638 = CARTESIAN_POINT ( 'NONE', ( 14.93318671017543231, 151.7188427972803311, 177.9798661502222217 ) ) ; -#3639 = CARTESIAN_POINT ( 'NONE', ( -20.49970645903284705, 184.8492302318938698, 102.8542671896393301 ) ) ; -#3640 = LINE ( 'NONE', #8910, #27225 ) ; -#3641 = ORIENTED_EDGE ( 'NONE', *, *, #769, .F. ) ; -#3642 = LINE ( 'NONE', #30880, #22679 ) ; -#3643 = AXIS2_PLACEMENT_3D ( 'NONE', #28953, #4392, #6652 ) ; -#3644 = VERTEX_POINT ( 'NONE', #10590 ) ; -#3645 = CIRCLE ( 'NONE', #14125, 2.000000000000011546 ) ; -#3646 = LINE ( 'NONE', #28813, #10408 ) ; -#3647 = CARTESIAN_POINT ( 'NONE', ( -22.78246931443002055, 153.3538690588717941, 97.63697319274456277 ) ) ; -#3648 = CARTESIAN_POINT ( 'NONE', ( -3.669581230397975791, 128.4724600144964484, 89.82849395191713882 ) ) ; -#3649 = PLANE ( 'NONE', #28432 ) ; -#3650 = CARTESIAN_POINT ( 'NONE', ( -15.66510111023692176, 126.2008059057987452, 91.53494892955571061 ) ) ; -#3651 = CIRCLE ( 'NONE', #1716, 2.749999999886777236 ) ; -#3652 = DIRECTION ( 'NONE', ( -0.0006039748319383847876, -4.625770492314939281E-15, -0.9999998176071847045 ) ) ; -#3653 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3966, #4159, #12994, #25474 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3654 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191947214049181, 0.8480481395922153665 ) ) ; -#3655 = VERTEX_POINT ( 'NONE', #7906 ) ; -#3656 = CARTESIAN_POINT ( 'NONE', ( -14.55129769576823939, 181.8820030174664737, 104.7313938035605787 ) ) ; -#3657 = CARTESIAN_POINT ( 'NONE', ( 30.07309061344315992, 177.7341748906488021, 100.7202431291636628 ) ) ; -#3658 = PLANE ( 'NONE', #28643 ) ; -#3659 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #5717, #33309 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 6.391201751766900243E-06, 0.9999992928678075321 ), - .UNSPECIFIED. ) ; -#3660 = EDGE_CURVE ( 'NONE', #8079, #7563, #4431, .T. ) ; -#3661 = CARTESIAN_POINT ( 'NONE', ( -37.93405609845000015, 190.9294051681999917, 103.6063423062000197 ) ) ; -#3662 = ORIENTED_EDGE ( 'NONE', *, *, #34489, .T. ) ; -#3663 = EDGE_CURVE ( 'NONE', #11449, #31116, #12143, .T. ) ; -#3664 = EDGE_LOOP ( 'NONE', ( #9024, #478, #16128, #30068 ) ) ; -#3665 = CYLINDRICAL_SURFACE ( 'NONE', #17893, 8.999999999999996447 ) ; -#3666 = EDGE_CURVE ( 'NONE', #3536, #26219, #22138, .T. ) ; -#3667 = ORIENTED_EDGE ( 'NONE', *, *, #28798, .T. ) ; -#3668 = CARTESIAN_POINT ( 'NONE', ( 15.00009867560111232, 176.2215782928612668, 100.4988710758687205 ) ) ; -#3669 = DIRECTION ( 'NONE', ( 0.7691761624280191167, 0.6302414090841090832, -0.1056588729268960053 ) ) ; -#3670 = CARTESIAN_POINT ( 'NONE', ( 20.00136918061618374, 193.8834552009329855, 106.5568097150586482 ) ) ; -#3671 = ADVANCED_FACE ( 'NONE', ( #38767 ), #28986, .T. ) ; -#3672 = VECTOR ( 'NONE', #33304, 1000.000000000000227 ) ; -#3673 = CARTESIAN_POINT ( 'NONE', ( 25.42668613043140269, 211.7447100920389573, 75.54331620179917195 ) ) ; -#3674 = VECTOR ( 'NONE', #11058, 1000.000000000000114 ) ; -#3675 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425360569, 126.1257801542146666, 91.85841711592105696 ) ) ; -#3676 = VECTOR ( 'NONE', #15750, 1000.000000000000114 ) ; -#3677 = CARTESIAN_POINT ( 'NONE', ( 15.50068700633101670, 185.6474399458666937, 103.7010050552331677 ) ) ; -#3678 = EDGE_CURVE ( 'NONE', #13325, #12780, #3071, .T. ) ; -#3679 = CARTESIAN_POINT ( 'NONE', ( 20.48220618717283870, 205.6521300892295301, 76.08837086243011072 ) ) ; -#3680 = CARTESIAN_POINT ( 'NONE', ( 38.65781128404000100, 118.3725735404999995, 89.51293966676000480 ) ) ; -#3681 = ORIENTED_EDGE ( 'NONE', *, *, #25511, .T. ) ; -#3682 = CONICAL_SURFACE ( 'NONE', #4993, 2.249999999984611421, 0.7853981634347277918 ) ; -#3683 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825971794438422, 0.0005734119011913576657 ) ) ; -#3684 = CARTESIAN_POINT ( 'NONE', ( -28.55676206495941827, 225.5077044902725163, 73.57575174230528603 ) ) ; -#3685 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971592325 ) ) ; -#3686 = VECTOR ( 'NONE', #29579, 1000.000000000000114 ) ; -#3687 = CARTESIAN_POINT ( 'NONE', ( 3.061557431010443864, 191.9759150222000130, 101.9195982363917778 ) ) ; -#3688 = ORIENTED_EDGE ( 'NONE', *, *, #4920, .F. ) ; -#3689 = VERTEX_POINT ( 'NONE', #4220 ) ; -#3690 = EDGE_CURVE ( 'NONE', #16546, #5612, #25938, .T. ) ; -#3691 = ORIENTED_EDGE ( 'NONE', *, *, #23773, .T. ) ; -#3692 = CARTESIAN_POINT ( 'NONE', ( 5.669154559842989549, 131.0223146068671269, 89.89838186586590041 ) ) ; -#3693 = CARTESIAN_POINT ( 'NONE', ( 37.23701003965144452, 182.4168621411915581, 119.7221224191138020 ) ) ; -#3694 = ORIENTED_EDGE ( 'NONE', *, *, #36312, .T. ) ; -#3695 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#3696 = CARTESIAN_POINT ( 'NONE', ( 19.71401682987599457, 154.2187378489598188, 161.0543666918586609 ) ) ; -#3697 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#3698 = CARTESIAN_POINT ( 'NONE', ( -44.76461391232829357, 172.9647176225852832, 165.3418576905968678 ) ) ; -#3699 = DIRECTION ( 'NONE', ( -0.0005884949961153481453, 0.2249510543439053600, -0.9743698870671265722 ) ) ; -#3700 = CYLINDRICAL_SURFACE ( 'NONE', #28186, 9.999999999999998224 ) ; -#3701 = VERTEX_POINT ( 'NONE', #16299 ) ; -#3702 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825911326306185, 0.0005734119025866840115 ) ) ; -#3703 = CONICAL_SURFACE ( 'NONE', #4339, 5.000000000100857989, 0.7853981633860493972 ) ; -#3704 = ORIENTED_EDGE ( 'NONE', *, *, #27852, .T. ) ; -#3705 = CARTESIAN_POINT ( 'NONE', ( -20.01780204100229099, 208.2807494580173113, 76.61795221373991183 ) ) ; -#3706 = CARTESIAN_POINT ( 'NONE', ( 19.98246575633744726, 209.3198221927136160, 76.04644364893974284 ) ) ; -#3707 = CIRCLE ( 'NONE', #18639, 4.500000000083482554 ) ; -#3708 = CARTESIAN_POINT ( 'NONE', ( -20.89282324149344561, 183.0959377177359215, 101.9365769416837253 ) ) ; -#3709 = AXIS2_PLACEMENT_3D ( 'NONE', #14405, #36473, #8893 ) ; -#3710 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; -#3711 = ORIENTED_EDGE ( 'NONE', *, *, #29941, .F. ) ; -#3712 = CARTESIAN_POINT ( 'NONE', ( -2.938634685006000336, 190.8906618492000007, 103.7252800252999947 ) ) ; -#3713 = CARTESIAN_POINT ( 'NONE', ( 1.148973024146567434, 188.6822756551911198, 103.2129652778315858 ) ) ; -#3714 = CARTESIAN_POINT ( 'NONE', ( 19.99378154282333497, 200.3418858662740263, 94.99690145743463177 ) ) ; -#3715 = CIRCLE ( 'NONE', #3048, 2.000000000000007994 ) ; -#3716 = EDGE_CURVE ( 'NONE', #14645, #38065, #19957, .T. ) ; -#3717 = ORIENTED_EDGE ( 'NONE', *, *, #14784, .F. ) ; -#3718 = CARTESIAN_POINT ( 'NONE', ( -25.75142470483000068, 118.8155666110999960, 87.53333755287000884 ) ) ; -#3719 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#3720 = EDGE_CURVE ( 'NONE', #16466, #1023, #26994, .T. ) ; -#3721 = ORIENTED_EDGE ( 'NONE', *, *, #26259, .F. ) ; -#3722 = CYLINDRICAL_SURFACE ( 'NONE', #365, 9.999999999999998224 ) ; -#3723 = CARTESIAN_POINT ( 'NONE', ( 19.71670726246199123, 125.1288345936551423, 175.0446023669997260 ) ) ; -#3724 = CARTESIAN_POINT ( 'NONE', ( 17.02367223262315576, 152.0219492114602247, 183.9187395736230712 ) ) ; -#3725 = ORIENTED_EDGE ( 'NONE', *, *, #16999, .F. ) ; -#3726 = EDGE_CURVE ( 'NONE', #3624, #26044, #22861, .T. ) ; -#3727 = LINE ( 'NONE', #18852, #35964 ) ; -#3728 = CARTESIAN_POINT ( 'NONE', ( -39.77033354370986729, 107.3143903442909277, 174.6968655561054220 ) ) ; -#3729 = DIRECTION ( 'NONE', ( -0.5605393316030450324, 0.2603260636278126872, 0.7861462957503898563 ) ) ; -#3730 = ORIENTED_EDGE ( 'NONE', *, *, #30926, .T. ) ; -#3731 = CARTESIAN_POINT ( 'NONE', ( 26.00403119534400176, 120.1365576043379804, 90.45255660088920990 ) ) ; -#3732 = AXIS2_PLACEMENT_3D ( 'NONE', #33785, #28080, #51 ) ; -#3733 = DIRECTION ( 'NONE', ( 0.0005884949961250770167, -0.2249510543439080523, 0.9743698870671260170 ) ) ; -#3734 = LINE ( 'NONE', #6401, #30289 ) ; -#3735 = CIRCLE ( 'NONE', #1113, 2.000000001211691636 ) ; -#3737 = CARTESIAN_POINT ( 'NONE', ( -13.49615031087043704, 188.2556029912739461, 103.1973190696492253 ) ) ; -#3736 = CARTESIAN_POINT ( 'NONE', ( -36.18239550624663536, 191.7212396232838216, 104.2340660787839823 ) ) ; -#3738 = DIRECTION ( 'NONE', ( -0.1305262860326017182, 0.9659761103945228022, 0.2232779496537980746 ) ) ; -#3739 = ORIENTED_EDGE ( 'NONE', *, *, #6576, .T. ) ; -#3740 = CARTESIAN_POINT ( 'NONE', ( 20.50029381463220091, 127.3219018078964382, 89.54826868587551303 ) ) ; -#3741 = DIRECTION ( 'NONE', ( 0.6982900371914135818, 0.000000000000000000, 0.7158149369489396063 ) ) ; -#3742 = ORIENTED_EDGE ( 'NONE', *, *, #16645, .F. ) ; -#3743 = EDGE_LOOP ( 'NONE', ( #17821, #9746 ) ) ; -#3744 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#3745 = CARTESIAN_POINT ( 'NONE', ( -5.675513023005390956, 123.6907347205156924, 91.29157260444318922 ) ) ; -#3746 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540969802, 184.8500661882999054, 102.8514373824003343 ) ) ; -#3747 = CARTESIAN_POINT ( 'NONE', ( 5.669458964429918701, 187.5045916731542377, 105.7910410896365647 ) ) ; -#3748 = DIRECTION ( 'NONE', ( 0.5613714522130487383, -0.5784550691277038359, 0.5918207715522294521 ) ) ; -#3749 = EDGE_LOOP ( 'NONE', ( #11621, #22632, #1516, #23077 ) ) ; -#3750 = EDGE_CURVE ( 'NONE', #33855, #23012, #35613, .T. ) ; -#3751 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10143, #10345, #36840, #24591 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3752 = ORIENTED_EDGE ( 'NONE', *, *, #24619, .T. ) ; -#3753 = CARTESIAN_POINT ( 'NONE', ( -6.034863718937535815, 176.8968501839344469, 103.2756606735491403 ) ) ; -#3754 = PLANE ( 'NONE', #1108 ) ; -#3755 = DIRECTION ( 'NONE', ( 0.7075388796814503500, 9.784181737230435625E-15, 0.7066744184835885845 ) ) ; -#3756 = EDGE_CURVE ( 'NONE', #26044, #33081, #23567, .T. ) ; -#3757 = ORIENTED_EDGE ( 'NONE', *, *, #31446, .T. ) ; -#3758 = CARTESIAN_POINT ( 'NONE', ( 39.85586901997003650, 129.5283103249424244, 336.2586849593528768 ) ) ; -#3759 = EDGE_LOOP ( 'NONE', ( #2358, #17191, #20310, #3270 ) ) ; -#3760 = EDGE_CURVE ( 'NONE', #30155, #37805, #30200, .T. ) ; -#3761 = CARTESIAN_POINT ( 'NONE', ( -6.037735614373251458, 137.3541716869147820, 91.36728157005168782 ) ) ; -#3762 = EDGE_CURVE ( 'NONE', #19715, #23911, #28933, .T. ) ; -#3763 = ORIENTED_EDGE ( 'NONE', *, *, #2107, .F. ) ; -#3764 = CARTESIAN_POINT ( 'NONE', ( 36.03687122555673739, 218.5902260770998282, 61.03673652646995862 ) ) ; -#3765 = AXIS2_PLACEMENT_3D ( 'NONE', #19383, #24995, #35098 ) ; -#3766 = ADVANCED_FACE ( 'NONE', ( #14669 ), #1780, .F. ) ; -#3767 = CARTESIAN_POINT ( 'NONE', ( -1.616825569521000094, 188.8197794939999881, 106.1757460699000006 ) ) ; -#3768 = CARTESIAN_POINT ( 'NONE', ( 29.19927575787174234, 149.0747586894985659, 94.05190613317014936 ) ) ; -#3769 = EDGE_LOOP ( 'NONE', ( #18900, #26761, #37495, #24450 ) ) ; -#3770 = CARTESIAN_POINT ( 'NONE', ( 2.621864883072559937, 209.6150426461021254, 73.39025409901792329 ) ) ; -#3771 = ORIENTED_EDGE ( 'NONE', *, *, #36251, .F. ) ; -#3772 = CARTESIAN_POINT ( 'NONE', ( -45.25054442514785791, 110.5556416651509437, 150.9936149799888483 ) ) ; -#3773 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39426, #33294, #21048, #5289 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3774 = CARTESIAN_POINT ( 'NONE', ( -39.29583505786987274, 162.0679957853012354, 197.6227201487129150 ) ) ; -#3775 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; -#3776 = CARTESIAN_POINT ( 'NONE', ( 16.17545524454269312, 122.0361947523238229, 178.1139273532624259 ) ) ; -#3777 = ORIENTED_EDGE ( 'NONE', *, *, #27962, .F. ) ; -#3778 = CARTESIAN_POINT ( 'NONE', ( 19.98635445618997863, 211.0854288155255460, 76.04696776081749476 ) ) ; -#3779 = CARTESIAN_POINT ( 'NONE', ( -15.49970618472456074, 126.6879451655382809, 89.42365126055415203 ) ) ; -#3780 = DIRECTION ( 'NONE', ( -0.6771712326825307660, 0.7358254695423512848, 0.000000000000000000 ) ) ; -#3781 = ORIENTED_EDGE ( 'NONE', *, *, #29821, .F. ) ; -#3782 = ORIENTED_EDGE ( 'NONE', *, *, #35277, .F. ) ; -#3783 = CARTESIAN_POINT ( 'NONE', ( 8.420554314666548024, 160.7376577964533055, 96.75704887148856415 ) ) ; -#3784 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#3785 = CARTESIAN_POINT ( 'NONE', ( -40.45668859049753507, 217.7719116710999856, 73.08293890847663477 ) ) ; -#3786 = DIRECTION ( 'NONE', ( 0.0005884949961249387809, -0.2249510543439043608, 0.9743698870671267942 ) ) ; -#3787 = AXIS2_PLACEMENT_3D ( 'NONE', #8953, #14880, #8545 ) ; -#3788 = VERTEX_POINT ( 'NONE', #5445 ) ; -#3789 = ORIENTED_EDGE ( 'NONE', *, *, #26033, .F. ) ; -#3790 = CYLINDRICAL_SURFACE ( 'NONE', #3456, 5.000000000000007994 ) ; -#3791 = CARTESIAN_POINT ( 'NONE', ( -20.00000737806465523, 151.9608748777371545, 94.74793644920653435 ) ) ; -#3792 = CARTESIAN_POINT ( 'NONE', ( 40.54675149461998984, 206.4002260771000010, 76.03401540768531675 ) ) ; -#3793 = ADVANCED_FACE ( 'NONE', ( #8943 ), #26492, .T. ) ; -#3794 = ORIENTED_EDGE ( 'NONE', *, *, #4773, .F. ) ; -#3795 = CARTESIAN_POINT ( 'NONE', ( 3.784352160272999921, 171.8704258944000003, 99.58662759693000055 ) ) ; -#3796 = CARTESIAN_POINT ( 'NONE', ( 22.11658944985360264, 129.6856566903868213, 90.09300832417258675 ) ) ; -#3797 = CARTESIAN_POINT ( 'NONE', ( 36.33870953241000024, 191.7478208022000103, 104.2407745632000058 ) ) ; -#3798 = ORIENTED_EDGE ( 'NONE', *, *, #32167, .F. ) ; -#3799 = CARTESIAN_POINT ( 'NONE', ( 2.988438011343841794, 209.5693627156126126, 76.06144145553551539 ) ) ; -#3800 = ADVANCED_FACE ( 'NONE', ( #39183 ), #29761, .T. ) ; -#3801 = LINE ( 'NONE', #31846, #16034 ) ; -#3802 = CARTESIAN_POINT ( 'NONE', ( 17.73018223044451247, 121.4662574373030992, 177.9825536785120619 ) ) ; -#3803 = LINE ( 'NONE', #3404, #18351 ) ; -#3804 = EDGE_LOOP ( 'NONE', ( #14995, #32810, #9348, #32966 ) ) ; -#3805 = CARTESIAN_POINT ( 'NONE', ( 28.51215300032000144, 125.2759241664000172, 88.55825304898000638 ) ) ; -#3806 = CARTESIAN_POINT ( 'NONE', ( -23.36147737338999519, 177.1885760182403260, 101.0873909946558769 ) ) ; -#3807 = DIRECTION ( 'NONE', ( 0.6337575784460532935, -0.7735316317038959388, -0.0003827736967368305454 ) ) ; -#3808 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282901917, 148.0700263536807597, 93.85134194385574347 ) ) ; -#3809 = ADVANCED_FACE ( 'NONE', ( #23661 ), #33006, .T. ) ; -#3810 = CARTESIAN_POINT ( 'NONE', ( 21.84813133371958216, 158.3688974985749951, 96.20206744650923270 ) ) ; -#3811 = EDGE_CURVE ( 'NONE', #26636, #32491, #14305, .T. ) ; -#3812 = EDGE_LOOP ( 'NONE', ( #26900, #4720 ) ) ; -#3813 = CARTESIAN_POINT ( 'NONE', ( 23.36189995341599968, 184.1285021912421769, 102.1451486796015615 ) ) ; -#3814 = EDGE_CURVE ( 'NONE', #7673, #853, #36110, .T. ) ; -#3815 = CARTESIAN_POINT ( 'NONE', ( 1.068853090858757904, 189.0651350939791371, 103.7028959401992552 ) ) ; -#3816 = DIRECTION ( 'NONE', ( 0.7947983679126050527, -0.5912140607310475415, -0.1369725839625022812 ) ) ; -#3817 = VECTOR ( 'NONE', #18786, 1000.000000000000000 ) ; -#3818 = DIRECTION ( 'NONE', ( -0.0006039748319386124701, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#3819 = ORIENTED_EDGE ( 'NONE', *, *, #33484, .F. ) ; -#3820 = DIRECTION ( 'NONE', ( 0.7947985590179719173, -0.5913221741348984040, -0.1365039814779489546 ) ) ; -#3821 = CARTESIAN_POINT ( 'NONE', ( 13.81047920904208226, 125.0581942443353114, 174.4028524411866954 ) ) ; -#3822 = DIRECTION ( 'NONE', ( -0.0006039748319390056018, -1.156901198131326670E-14, -0.9999998176071845934 ) ) ; -#3823 = DIRECTION ( 'NONE', ( -0.0002393071182785538799, -0.2252352986010040803, 0.9743043687658492491 ) ) ; -#3824 = VERTEX_POINT ( 'NONE', #12001 ) ; -#3825 = CYLINDRICAL_SURFACE ( 'NONE', #15781, 1.999999999999989342 ) ; -#3826 = CARTESIAN_POINT ( 'NONE', ( -19.44510706094013486, 147.9316356728690209, 182.5581845579670528 ) ) ; -#3827 = CARTESIAN_POINT ( 'NONE', ( 19.98776270734149207, 201.3437068452617780, 84.95876186640749950 ) ) ; -#3828 = EDGE_LOOP ( 'NONE', ( #883, #31385, #19674, #21236 ) ) ; -#3829 = CARTESIAN_POINT ( 'NONE', ( 30.05503346839208945, 109.6131156702000027, 89.74963226103227498 ) ) ; -#3830 = CARTESIAN_POINT ( 'NONE', ( 3.534343284623258974, 175.3621990150981276, 100.1363906404241675 ) ) ; -#3831 = CARTESIAN_POINT ( 'NONE', ( -0.4540624946311256349, 209.0000000000000000, 76.05877887192488629 ) ) ; -#3832 = CARTESIAN_POINT ( 'NONE', ( 36.06384775776000140, 192.3136458038000001, 104.3415608640000158 ) ) ; -#3833 = CARTESIAN_POINT ( 'NONE', ( -15.94449010895081642, 152.1461032928982036, 184.5535245782780294 ) ) ; -#3834 = CARTESIAN_POINT ( 'NONE', ( 47.95547122009493535, 140.0147268217544934, 290.8391817639516148 ) ) ; -#3835 = VERTEX_POINT ( 'NONE', #39585 ) ; -#3837 = AXIS2_PLACEMENT_3D ( 'NONE', #341, #744, #25313 ) ; -#3836 = CARTESIAN_POINT ( 'NONE', ( -2.371531496848751086, 209.5696226675259197, 75.55993729815415350 ) ) ; -#3838 = CARTESIAN_POINT ( 'NONE', ( 20.49930103516235746, 196.1188360154283430, 103.6658478038365558 ) ) ; -#3839 = EDGE_CURVE ( 'NONE', #23778, #10555, #24283, .T. ) ; -#3840 = EDGE_CURVE ( 'NONE', #31651, #7316, #12864, .T. ) ; -#3841 = AXIS2_PLACEMENT_3D ( 'NONE', #11370, #2187, #35892 ) ; -#3842 = CARTESIAN_POINT ( 'NONE', ( 25.02112415049811389, 129.9425189236814049, 92.71631678198431814 ) ) ; -#3843 = ORIENTED_EDGE ( 'NONE', *, *, #6618, .T. ) ; -#3844 = CARTESIAN_POINT ( 'NONE', ( -32.35856811579363068, 153.0051697192221241, 291.5780876995356721 ) ) ; -#3845 = AXIS2_PLACEMENT_3D ( 'NONE', #29654, #11244, #23718 ) ; -#3846 = EDGE_CURVE ( 'NONE', #20460, #34687, #12204, .T. ) ; -#3847 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18737, #31445, #34681, #12619, #28774, #24928 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.003332437842000458231, 0.5016662189210002731, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3848 = AXIS2_PLACEMENT_3D ( 'NONE', #5903, #27610, #30857 ) ; -#3849 = EDGE_LOOP ( 'NONE', ( #29863, #11717, #5786 ) ) ; -#3850 = ADVANCED_FACE ( 'NONE', ( #9533 ), #417, .T. ) ; -#3851 = CARTESIAN_POINT ( 'NONE', ( -3.470874896381920482, 129.7916855490838657, 89.61978905829030850 ) ) ; -#3852 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; -#3853 = EDGE_CURVE ( 'NONE', #11101, #11920, #24690, .T. ) ; -#3854 = DIRECTION ( 'NONE', ( -0.0006039748319382906789, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#3855 = CARTESIAN_POINT ( 'NONE', ( -43.95866919468323886, 185.6592565981171390, 107.3047072462908460 ) ) ; -#3856 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559019 ) ) ; -#3857 = CARTESIAN_POINT ( 'NONE', ( -63.18208837076905127, 87.27946979429619034, 302.5967063397189349 ) ) ; -#3858 = EDGE_CURVE ( 'NONE', #8264, #11241, #13789, .T. ) ; -#3859 = ORIENTED_EDGE ( 'NONE', *, *, #8633, .T. ) ; -#3860 = CARTESIAN_POINT ( 'NONE', ( 12.64700864260225366, 177.1180462903230364, 103.6150826217330803 ) ) ; -#3861 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; -#3862 = DIRECTION ( 'NONE', ( 0.0005884949961181263050, -0.2249510543439084131, 0.9743698870671259060 ) ) ; -#3863 = CARTESIAN_POINT ( 'NONE', ( -37.97368744632999693, 191.1281716224000036, 103.9225511041999965 ) ) ; -#3864 = ORIENTED_EDGE ( 'NONE', *, *, #19650, .F. ) ; -#3865 = ORIENTED_EDGE ( 'NONE', *, *, #34085, .T. ) ; -#3866 = DIRECTION ( 'NONE', ( 0.0005884949961230984562, -0.2249510543439063037, 0.9743698870671264611 ) ) ; -#3867 = ORIENTED_EDGE ( 'NONE', *, *, #29488, .F. ) ; -#3868 = VECTOR ( 'NONE', #34042, 1000.000000000000114 ) ; -#3869 = LINE ( 'NONE', #28831, #24108 ) ; -#3870 = AXIS2_PLACEMENT_3D ( 'NONE', #12335, #37275, #34195 ) ; -#3871 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 77.27946979429611929, 297.5967072516833127 ) ) ; -#3872 = CONICAL_SURFACE ( 'NONE', #24815, 22.50000000000898837, 0.7853981633973132759 ) ; -#3873 = CIRCLE ( 'NONE', #610, 2.000000000000011546 ) ; -#3874 = FACE_OUTER_BOUND ( 'NONE', #16149, .T. ) ; -#3875 = CARTESIAN_POINT ( 'NONE', ( 41.20534109643615039, 166.2329448439782027, 182.1790434216227084 ) ) ; -#3876 = DIRECTION ( 'NONE', ( -0.0006039748319391913256, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#3877 = CARTESIAN_POINT ( 'NONE', ( 20.48167154976358262, 206.1645954224638047, 75.27430365288482506 ) ) ; -#3878 = CARTESIAN_POINT ( 'NONE', ( 38.33548734387000678, 118.7516758551000038, 90.10263491839000949 ) ) ; -#3879 = ORIENTED_EDGE ( 'NONE', *, *, #35483, .F. ) ; -#3880 = CARTESIAN_POINT ( 'NONE', ( -29.20280672794129373, 149.0670272684989186, 94.08539458806572497 ) ) ; -#3881 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5317, #17576, #38848, #26611 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3882 = CARTESIAN_POINT ( 'NONE', ( 20.79310939989340667, 105.5805168952036865, 87.25522577498226440 ) ) ; -#3883 = LINE ( 'NONE', #16358, #25557 ) ; -#3884 = CARTESIAN_POINT ( 'NONE', ( -20.50092100153493746, 194.2771564787859120, 102.9104786413515740 ) ) ; -#3885 = EDGE_LOOP ( 'NONE', ( #38415, #28250, #26385, #11969 ) ) ; -#3886 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #37655, #9654, #13126, #31937 ), - ( #35159, #31740, #10054, #13719 ), - ( #38446, #38641, #16176, #1033 ), - ( #38052, #835, #10465, #9862 ), - ( #19638, #35553, #22933, #29463 ), - ( #28857, #7169, #19229, #13318 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 4 ), - ( 4, 4 ), - ( 5.706021859055999814E-12, 0.3333331262859999811, 0.6666662542622999732, 0.9999999999862000388 ), - ( 0.1697962087406000020, 0.8302040021366999811 ), - .UNSPECIFIED. ) ; -#3887 = ORIENTED_EDGE ( 'NONE', *, *, #6261, .F. ) ; -#3888 = LINE ( 'NONE', #29661, #37922 ) ; -#3889 = EDGE_CURVE ( 'NONE', #2544, #16362, #13003, .T. ) ; -#3890 = EDGE_CURVE ( 'NONE', #27747, #13602, #6441, .T. ) ; -#3891 = CARTESIAN_POINT ( 'NONE', ( -48.18886129041272426, 139.8560090933335687, 291.3782681826108387 ) ) ; -#3892 = EDGE_CURVE ( 'NONE', #29469, #4808, #21417, .T. ) ; -#3893 = ADVANCED_FACE ( 'NONE', ( #30811 ), #22013, .F. ) ; -#3894 = ORIENTED_EDGE ( 'NONE', *, *, #18392, .F. ) ; -#3895 = LINE ( 'NONE', #25805, #34815 ) ; -#3896 = AXIS2_PLACEMENT_3D ( 'NONE', #36657, #40312, #2317 ) ; -#3897 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825975761958095, 0.0005734119010998334383 ) ) ; -#3898 = CARTESIAN_POINT ( 'NONE', ( -38.12770169932999664, 119.0718537988000065, 87.43999389818000623 ) ) ; -#3899 = DIRECTION ( 'NONE', ( 0.6087614883550946931, -0.7730004026499608383, -0.1785492307423600933 ) ) ; -#3900 = EDGE_LOOP ( 'NONE', ( #8599, #34901, #20291, #34315 ) ) ; -#3901 = EDGE_CURVE ( 'NONE', #36231, #20521, #18504, .T. ) ; -#3902 = CARTESIAN_POINT ( 'NONE', ( 17.27218345960016421, 121.9621389981125361, 174.6024314160012523 ) ) ; -#3903 = CIRCLE ( 'NONE', #39163, 2.000000000000011546 ) ; -#3904 = AXIS2_PLACEMENT_3D ( 'NONE', #5901, #37187, #12633 ) ; -#3905 = ORIENTED_EDGE ( 'NONE', *, *, #27391, .T. ) ; -#3906 = CARTESIAN_POINT ( 'NONE', ( 5.665047306215249989, 124.5420718655650489, 88.64172132599090048 ) ) ; -#3907 = CARTESIAN_POINT ( 'NONE', ( -39.69814225588821444, 114.9854446628631450, 150.7514082625260130 ) ) ; -#3908 = DIRECTION ( 'NONE', ( -1.387778780769265269E-15, 0.9743700557921585181, 0.2249510932971561517 ) ) ; -#3909 = ADVANCED_FACE ( 'NONE', ( #22216 ), #25089, .F. ) ; -#3910 = ORIENTED_EDGE ( 'NONE', *, *, #12056, .T. ) ; -#3911 = CARTESIAN_POINT ( 'NONE', ( -15.10714335758950888, 136.3268993782255620, 91.13559034338766196 ) ) ; -#3912 = CARTESIAN_POINT ( 'NONE', ( -16.27370299762399597, 147.0379182250262318, 180.4996822280638185 ) ) ; -#3913 = CARTESIAN_POINT ( 'NONE', ( -26.00831778363330571, 205.1071295951813340, 76.12055741644476825 ) ) ; -#3914 = FACE_OUTER_BOUND ( 'NONE', #24441, .T. ) ; -#3915 = VERTEX_POINT ( 'NONE', #21615 ) ; -#3916 = CARTESIAN_POINT ( 'NONE', ( -20.09540649625984798, 211.8672601595316110, 73.07064120436956500 ) ) ; -#3917 = DIRECTION ( 'NONE', ( -0.0004270258721590739501, -0.7071067811865945352, -0.7071066522447926328 ) ) ; -#3918 = EDGE_LOOP ( 'NONE', ( #37314, #5199, #29544, #11091 ) ) ; -#3919 = CARTESIAN_POINT ( 'NONE', ( -9.153839583927000589, 130.7205244689999972, 90.09423690069999680 ) ) ; -#3920 = CARTESIAN_POINT ( 'NONE', ( 21.44693881909371669, 176.9241929811547038, 100.4861407201621120 ) ) ; -#3921 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250618410, 179.6252109630661380, 101.6466942236366151 ) ) ; -#3922 = ORIENTED_EDGE ( 'NONE', *, *, #31476, .F. ) ; -#3923 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.261220487827980362E-14, 0.9999998176071844824 ) ) ; -#3924 = DIRECTION ( 'NONE', ( 0.0005884951729871207987, -0.2249510544218079611, 0.9743698870490344888 ) ) ; -#3925 = AXIS2_PLACEMENT_3D ( 'NONE', #38753, #29979, #32638 ) ; -#3926 = AXIS2_PLACEMENT_3D ( 'NONE', #40367, #12773, #25262 ) ; -#3927 = ORIENTED_EDGE ( 'NONE', *, *, #22353, .F. ) ; -#3928 = VECTOR ( 'NONE', #10951, 1000.000000000000114 ) ; -#3929 = CARTESIAN_POINT ( 'NONE', ( 25.83405454150999958, 120.1395495440000047, 90.28159412456000155 ) ) ; -#3930 = CIRCLE ( 'NONE', #25534, 10.00000000000000533 ) ; -#3931 = CARTESIAN_POINT ( 'NONE', ( 16.30346404997956000, 121.9765769214875490, 177.9351893625809282 ) ) ; -#3932 = CARTESIAN_POINT ( 'NONE', ( 3.666638747408697441, 128.4736512688499488, 89.82433808099703754 ) ) ; -#3933 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9402, #40457, #31269, #25150 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#3935 = CARTESIAN_POINT ( 'NONE', ( -13.49953887075311698, 187.7424330182009840, 103.5179849509054435 ) ) ; -#3934 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 77.27946979429611929, 297.5967072516830854 ) ) ; -#3936 = CARTESIAN_POINT ( 'NONE', ( -82.81915783535940534, 72.22391443751210716, 166.5742336941280257 ) ) ; -#3937 = ORIENTED_EDGE ( 'NONE', *, *, #33871, .T. ) ; -#3938 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989120913, 109.3655459317195522, 175.1905691378508436 ) ) ; -#3939 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825897900247689, 0.0005734119028982040270 ) ) ; -#3940 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -3.370379598151327408E-34, 0.0006039748319386880390 ) ) ; -#3941 = VERTEX_POINT ( 'NONE', #31609 ) ; -#3942 = EDGE_CURVE ( 'NONE', #25599, #30846, #34061, .T. ) ; -#3943 = VERTEX_POINT ( 'NONE', #40388 ) ; -#3944 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#3945 = CARTESIAN_POINT ( 'NONE', ( 44.64491191134371917, 188.7542347311224376, 105.7690686227471559 ) ) ; -#3946 = CARTESIAN_POINT ( 'NONE', ( 31.30352330330278576, 110.6131156702000027, 87.24887774834422771 ) ) ; -#3947 = LINE ( 'NONE', #32377, #3263 ) ; -#3948 = ORIENTED_EDGE ( 'NONE', *, *, #2037, .F. ) ; -#3949 = ORIENTED_EDGE ( 'NONE', *, *, #13693, .F. ) ; -#3950 = CARTESIAN_POINT ( 'NONE', ( 14.42353522632744678, 129.4117444856125871, 92.42912713004928094 ) ) ; -#3951 = CARTESIAN_POINT ( 'NONE', ( -12.63408200835842976, 177.6899303382640483, 100.7688461857968036 ) ) ; -#3952 = FACE_OUTER_BOUND ( 'NONE', #3310, .T. ) ; -#3953 = CARTESIAN_POINT ( 'NONE', ( 30.02141569587843151, 185.4797026447788255, 105.5350675575252524 ) ) ; -#3954 = EDGE_LOOP ( 'NONE', ( #32030, #30628, #38265, #9406 ) ) ; -#3955 = CARTESIAN_POINT ( 'NONE', ( -22.36573918166319430, 213.5251468429292458, 73.57207195213049999 ) ) ; -#3956 = CIRCLE ( 'NONE', #9854, 1.750000000000001998 ) ; -#3957 = ORIENTED_EDGE ( 'NONE', *, *, #5237, .T. ) ; -#3958 = CIRCLE ( 'NONE', #28788, 6.500000000066489925 ) ; -#3959 = CONICAL_SURFACE ( 'NONE', #2032, 6.000000367495921694, 0.7853981634064428619 ) ; -#3960 = ORIENTED_EDGE ( 'NONE', *, *, #22306, .T. ) ; -#3961 = PLANE ( 'NONE', #19602 ) ; -#3962 = ORIENTED_EDGE ( 'NONE', *, *, #22403, .T. ) ; -#3963 = CARTESIAN_POINT ( 'NONE', ( -37.27993193924111637, 164.6275578583710342, 198.2149168068204688 ) ) ; -#3964 = EDGE_CURVE ( 'NONE', #32767, #2748, #31408, .T. ) ; -#3965 = CARTESIAN_POINT ( 'NONE', ( -1.489481181603000026, 189.1037180294000279, 105.9254781432999977 ) ) ; -#3966 = CARTESIAN_POINT ( 'NONE', ( -2.435581690730916016, 190.9709058671855360, 106.3075837308457352 ) ) ; -#3967 = ORIENTED_EDGE ( 'NONE', *, *, #23483, .T. ) ; -#3968 = CARTESIAN_POINT ( 'NONE', ( 22.78253045494810891, 153.6097073741841541, 98.01061943718465841 ) ) ; -#3969 = CARTESIAN_POINT ( 'NONE', ( -25.18576680417500668, 116.8541585394636684, 87.78282270138144838 ) ) ; -#3970 = CARTESIAN_POINT ( 'NONE', ( 22.79043357853658591, 214.0899764684317574, 73.04473923159348203 ) ) ; -#3971 = CARTESIAN_POINT ( 'NONE', ( 13.50023901242825275, 124.1961254174222802, 90.96643860594015507 ) ) ; -#3972 = CARTESIAN_POINT ( 'NONE', ( -37.83775869339704201, 191.4135373797588215, 104.3802259940997033 ) ) ; -#3973 = VERTEX_POINT ( 'NONE', #2792 ) ; -#3974 = CARTESIAN_POINT ( 'NONE', ( 24.25953830040776893, 115.9286994022373420, 89.75330581144697817 ) ) ; -#3975 = AXIS2_PLACEMENT_3D ( 'NONE', #21077, #5929, #40263 ) ; -#3976 = CARTESIAN_POINT ( 'NONE', ( -37.97865408599000148, 118.8664476399000023, 90.44763526090001449 ) ) ; -#3977 = VECTOR ( 'NONE', #33589, 1000.000000000000114 ) ; -#3978 = VERTEX_POINT ( 'NONE', #27755 ) ; -#3979 = AXIS2_PLACEMENT_3D ( 'NONE', #25936, #10392, #7491 ) ; -#3980 = ORIENTED_EDGE ( 'NONE', *, *, #12311, .T. ) ; -#3981 = LINE ( 'NONE', #28551, #33606 ) ; -#3982 = CARTESIAN_POINT ( 'NONE', ( -26.79701054014554984, 123.5536321148342864, 88.19370908452887647 ) ) ; -#3983 = CARTESIAN_POINT ( 'NONE', ( -31.50112765883515564, 162.4459499757934964, 187.8003480921526318 ) ) ; -#3984 = CARTESIAN_POINT ( 'NONE', ( -13.50199777270016810, 123.7767173896095159, 91.24176358735705605 ) ) ; -#3985 = EDGE_CURVE ( 'NONE', #15161, #8051, #17686, .T. ) ; -#3986 = ORIENTED_EDGE ( 'NONE', *, *, #28562, .T. ) ; -#3987 = ADVANCED_FACE ( 'NONE', ( #31205 ), #9335, .T. ) ; -#3988 = ORIENTED_EDGE ( 'NONE', *, *, #631, .F. ) ; -#3989 = CARTESIAN_POINT ( 'NONE', ( -19.99799082025366204, 173.8313734241264967, 102.8761342917995734 ) ) ; -#3990 = VERTEX_POINT ( 'NONE', #120 ) ; -#3991 = ORIENTED_EDGE ( 'NONE', *, *, #1828, .F. ) ; -#3992 = ORIENTED_EDGE ( 'NONE', *, *, #32263, .T. ) ; -#3993 = CARTESIAN_POINT ( 'NONE', ( 5.696732336563999688, 172.5096616001999905, 152.4718672074000381 ) ) ; -#3994 = CARTESIAN_POINT ( 'NONE', ( -14.82260162707301809, 143.3364409748008086, 28.42526875798066399 ) ) ; -#3995 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 82.27946979429634666, 315.0857197240630967 ) ) ; -#3996 = ORIENTED_EDGE ( 'NONE', *, *, #31157, .F. ) ; -#3997 = EDGE_CURVE ( 'NONE', #3655, #13769, #3176, .T. ) ; -#3998 = ORIENTED_EDGE ( 'NONE', *, *, #7686, .F. ) ; -#3999 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263834, 86.95598109309847246, 291.5876487235610739 ) ) ; -#4000 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #4786, #13802 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4001 = CARTESIAN_POINT ( 'NONE', ( 20.48253891412411321, 207.4083879957671002, 77.06951181954761410 ) ) ; -#4002 = LINE ( 'NONE', #16671, #11745 ) ; -#4003 = CARTESIAN_POINT ( 'NONE', ( 43.13736350275988940, 121.9393806477530404, 87.86294449587100530 ) ) ; -#4004 = CARTESIAN_POINT ( 'NONE', ( 20.00007342045880065, 191.7526597988445189, 103.9104467472352979 ) ) ; -#4005 = DIRECTION ( 'NONE', ( -0.7933533411653073131, 0.5930537057989938576, 0.1373964268091566188 ) ) ; -#4006 = CARTESIAN_POINT ( 'NONE', ( -15.10713178427481651, 176.3794795624077096, 100.3824614381103828 ) ) ; -#4007 = ORIENTED_EDGE ( 'NONE', *, *, #14262, .T. ) ; -#4008 = DIRECTION ( 'NONE', ( 3.469446951931442070E-15, 0.9743700557921584071, 0.2249510932971566513 ) ) ; -#4009 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; -#4010 = CARTESIAN_POINT ( 'NONE', ( 22.50029346544275199, 184.8550509193516973, 102.8296322281952513 ) ) ; -#4011 = AXIS2_PLACEMENT_3D ( 'NONE', #22246, #28768, #4008 ) ; -#4012 = CARTESIAN_POINT ( 'NONE', ( -32.61688159666169184, 141.9329143176964863, 280.9718830317659695 ) ) ; -#4013 = CARTESIAN_POINT ( 'NONE', ( 5.035334123826465280, 124.4259184218055623, 88.37586634456850732 ) ) ; -#4014 = ORIENTED_EDGE ( 'NONE', *, *, #18481, .T. ) ; -#4015 = AXIS2_PLACEMENT_3D ( 'NONE', #12845, #33235, #32645 ) ; -#4016 = CARTESIAN_POINT ( 'NONE', ( -21.68500723473647795, 135.5097507517283759, 90.95090954866776656 ) ) ; -#4017 = ADVANCED_FACE ( 'NONE', ( #15847 ), #15655, .F. ) ; -#4018 = CIRCLE ( 'NONE', #7284, 2.499999999946084017 ) ; -#4019 = CARTESIAN_POINT ( 'NONE', ( 0.6665120506454667026, 189.0026601577200154, 103.6872697040404745 ) ) ; -#4020 = CARTESIAN_POINT ( 'NONE', ( -2.934188061559037219, 190.6895742892954217, 106.7577657789754966 ) ) ; -#4021 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049039381, 157.6243160761316346, 99.14398654755730433 ) ) ; -#4022 = CARTESIAN_POINT ( 'NONE', ( -26.12766474369999870, 191.8600560154999926, 103.7976276137000013 ) ) ; -#4023 = FACE_OUTER_BOUND ( 'NONE', #11056, .T. ) ; -#4024 = LINE ( 'NONE', #28984, #20910 ) ; -#4025 = PLANE ( 'NONE', #4287 ) ; -#4026 = ORIENTED_EDGE ( 'NONE', *, *, #489, .F. ) ; -#4027 = EDGE_CURVE ( 'NONE', #19373, #23019, #10220, .T. ) ; -#4028 = FACE_OUTER_BOUND ( 'NONE', #8833, .T. ) ; -#4029 = EDGE_CURVE ( 'NONE', #7166, #26491, #20150, .T. ) ; -#4030 = CARTESIAN_POINT ( 'NONE', ( -75.99005881032610432, 156.2326527032377328, 96.28112034756948390 ) ) ; -#4031 = LINE ( 'NONE', #31873, #2224 ) ; -#4032 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098148, 129.6135529956771677, 92.66635095651142251 ) ) ; -#4033 = CARTESIAN_POINT ( 'NONE', ( -35.98817295377529746, 191.5260130662397273, 103.8919236801626340 ) ) ; -#4034 = CARTESIAN_POINT ( 'NONE', ( -41.44764783254269958, 120.6681368631575850, 88.04954071273041905 ) ) ; -#4035 = CARTESIAN_POINT ( 'NONE', ( -6.037582702821003622, 135.2929569892681343, 91.40456025087448211 ) ) ; -#4036 = ADVANCED_FACE ( 'NONE', ( #10141 ), #22813, .T. ) ; -#4037 = CARTESIAN_POINT ( 'NONE', ( 35.72259725408999742, 192.2500497483999879, 106.7785130986000155 ) ) ; -#4038 = ORIENTED_EDGE ( 'NONE', *, *, #15850, .F. ) ; -#4039 = EDGE_CURVE ( 'NONE', #1663, #19888, #38274, .T. ) ; -#4040 = ORIENTED_EDGE ( 'NONE', *, *, #8017, .F. ) ; -#4041 = CIRCLE ( 'NONE', #33440, 2.499999889092850758 ) ; -#4042 = CARTESIAN_POINT ( 'NONE', ( -2.690201782050851698, 209.6661438676858040, 75.89346438378312598 ) ) ; -#4043 = EDGE_CURVE ( 'NONE', #21267, #35219, #23069, .T. ) ; -#4044 = CARTESIAN_POINT ( 'NONE', ( 5.675840488321574284, 188.3446150673902650, 103.1322824216947396 ) ) ; -#4045 = CARTESIAN_POINT ( 'NONE', ( 20.48811801917814179, 203.6451961417796781, 85.93495381676980571 ) ) ; -#4046 = ORIENTED_EDGE ( 'NONE', *, *, #3346, .F. ) ; -#4047 = CARTESIAN_POINT ( 'NONE', ( 6.035092514208784564, 177.2417361255070603, 101.0397482620736156 ) ) ; -#4048 = ORIENTED_EDGE ( 'NONE', *, *, #38078, .T. ) ; -#4049 = CARTESIAN_POINT ( 'NONE', ( 8.471266708538822243, 150.8425416249367004, 96.01200669677277233 ) ) ; -#4050 = DIRECTION ( 'NONE', ( -0.0005884949961181962360, 0.2249510543439063315, -0.9743698870671262391 ) ) ; -#4051 = CARTESIAN_POINT ( 'NONE', ( -45.98255491755426050, 185.1241532521533770, 105.4988869918989707 ) ) ; -#4052 = CARTESIAN_POINT ( 'NONE', ( 77.66065009075275327, 193.3992594998515244, 188.4681838635439419 ) ) ; -#4053 = LINE ( 'NONE', #795, #23644 ) ; -#4054 = EDGE_LOOP ( 'NONE', ( #16507, #1133, #10858, #7815 ) ) ; -#4055 = CARTESIAN_POINT ( 'NONE', ( 15.94054573232656047, 152.1434801212134857, 184.5792362023208284 ) ) ; -#4056 = CARTESIAN_POINT ( 'NONE', ( 35.55352252815201552, 111.2706431035999941, 87.24631085531800068 ) ) ; -#4057 = CARTESIAN_POINT ( 'NONE', ( 13.76437287132147169, 125.3330071254293898, 174.7699841533003564 ) ) ; -#4058 = CARTESIAN_POINT ( 'NONE', ( -35.95026569344999956, 191.6735383353999964, 104.0297955518999942 ) ) ; -#4059 = EDGE_LOOP ( 'NONE', ( #39536, #37006, #1773, #16711 ) ) ; -#4060 = VECTOR ( 'NONE', #9549, 1000.000000000000114 ) ; -#4061 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421484904, 126.1293544849782222, 91.84293499097150004 ) ) ; -#4062 = AXIS2_PLACEMENT_3D ( 'NONE', #35112, #25966, #389 ) ; -#4063 = AXIS2_PLACEMENT_3D ( 'NONE', #2448, #33297, #7954 ) ; -#4064 = DIRECTION ( 'NONE', ( -0.7933532970003738249, -0.5930762008556724751, -0.1372995488602875847 ) ) ; -#4065 = EDGE_CURVE ( 'NONE', #23158, #7827, #31402, .T. ) ; -#4066 = CARTESIAN_POINT ( 'NONE', ( -20.33182997993345964, 160.1345059202187713, 99.37190935997061558 ) ) ; -#4067 = PLANE ( 'NONE', #10912 ) ; -#4068 = EDGE_CURVE ( 'NONE', #35965, #15629, #15432, .T. ) ; -#4069 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#4070 = CARTESIAN_POINT ( 'NONE', ( -2.314308651363000013, 209.1937053114000378, 73.71695174304001341 ) ) ; -#4071 = CARTESIAN_POINT ( 'NONE', ( 38.31494853206999807, 118.7332877682000003, 90.10250374566000175 ) ) ; -#4072 = VERTEX_POINT ( 'NONE', #13205 ) ; -#4073 = EDGE_CURVE ( 'NONE', #20063, #25514, #14566, .T. ) ; -#4074 = CARTESIAN_POINT ( 'NONE', ( 27.38311190280682794, 119.8998877726164665, 171.4645808398473150 ) ) ; -#4075 = PLANE ( 'NONE', #10414 ) ; -#4076 = CARTESIAN_POINT ( 'NONE', ( -41.44764783254269958, 120.6681368631575850, 88.04954071273041905 ) ) ; -#4077 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #23595, #10934 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4078 = CARTESIAN_POINT ( 'NONE', ( 2.712461541526598463, 209.0473112905976905, 75.81951506724567480 ) ) ; -#4079 = ORIENTED_EDGE ( 'NONE', *, *, #34688, .F. ) ; -#4080 = EDGE_CURVE ( 'NONE', #24155, #35141, #16746, .T. ) ; -#4081 = EDGE_LOOP ( 'NONE', ( #24321, #7626, #36721, #32201 ) ) ; -#4082 = FACE_OUTER_BOUND ( 'NONE', #22958, .T. ) ; -#4083 = CIRCLE ( 'NONE', #14570, 2.500000007063326368 ) ; -#4084 = CARTESIAN_POINT ( 'NONE', ( -25.02112241941476611, 129.9358920626651752, 92.74501084285195418 ) ) ; -#4085 = DIRECTION ( 'NONE', ( -0.7933530821293308666, -0.5932640870757668328, -0.1364866662427074440 ) ) ; -#4086 = CARTESIAN_POINT ( 'NONE', ( 15.66680653501490283, 138.4328626290368618, 91.94536332186872585 ) ) ; -#4087 = ORIENTED_EDGE ( 'NONE', *, *, #19454, .F. ) ; -#4088 = VERTEX_POINT ( 'NONE', #715 ) ; -#4089 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927741987662, 0.0005734119022070274189 ) ) ; -#4090 = VECTOR ( 'NONE', #13858, 1000.000000000000114 ) ; -#4091 = LINE ( 'NONE', #32524, #3173 ) ; -#4092 = CARTESIAN_POINT ( 'NONE', ( -35.78755354827145396, 207.5618092979057678, 77.16841347661691941 ) ) ; -#4093 = CARTESIAN_POINT ( 'NONE', ( -22.49823373577465446, 160.0620215113764857, 99.69865297419991634 ) ) ; -#4094 = ORIENTED_EDGE ( 'NONE', *, *, #6040, .T. ) ; -#4095 = FACE_OUTER_BOUND ( 'NONE', #19162, .T. ) ; -#4096 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39041, #17351, #33511, #29862 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4097 = ORIENTED_EDGE ( 'NONE', *, *, #33070, .T. ) ; -#4098 = LINE ( 'NONE', #16777, #32465 ) ; -#4099 = PLANE ( 'NONE', #3229 ) ; -#4100 = LINE ( 'NONE', #7378, #39923 ) ; -#4101 = ORIENTED_EDGE ( 'NONE', *, *, #7198, .T. ) ; -#4102 = CARTESIAN_POINT ( 'NONE', ( -2.603750836884000108, 191.0374824654000179, 104.1011186467000016 ) ) ; -#4103 = LINE ( 'NONE', #7789, #33602 ) ; -#4104 = LINE ( 'NONE', #39880, #30922 ) ; -#4105 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250900735, 132.4055461762762604, 92.79778151960539390 ) ) ; -#4106 = VERTEX_POINT ( 'NONE', #3776 ) ; -#4107 = CARTESIAN_POINT ( 'NONE', ( -25.50863078827237018, 208.7343152597242977, 75.72119809267951496 ) ) ; -#4108 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999904787, 177.0581688368729374, 100.5408937735694224 ) ) ; -#4109 = VERTEX_POINT ( 'NONE', #32408 ) ; -#4110 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; -#4111 = AXIS2_PLACEMENT_3D ( 'NONE', #28390, #37384, #33903 ) ; -#4112 = EDGE_CURVE ( 'NONE', #29855, #9171, #23008, .T. ) ; -#4113 = EDGE_CURVE ( 'NONE', #26453, #18640, #22413, .T. ) ; -#4114 = ORIENTED_EDGE ( 'NONE', *, *, #38665, .F. ) ; -#4115 = CARTESIAN_POINT ( 'NONE', ( -35.95556595676193723, 218.5902260770999987, 73.58022043445957650 ) ) ; -#4116 = ADVANCED_FACE ( 'NONE', ( #34835 ), #35431, .T. ) ; -#4117 = VECTOR ( 'NONE', #23570, 1000.000000000000114 ) ; -#4118 = EDGE_CURVE ( 'NONE', #19190, #19220, #38685, .T. ) ; -#4119 = CARTESIAN_POINT ( 'NONE', ( 2.598437061832757689, 190.9999997773007578, 162.9812745352361389 ) ) ; -#4120 = CARTESIAN_POINT ( 'NONE', ( 37.96380763661293400, 191.4135383555317844, 104.3344495138068595 ) ) ; -#4121 = CARTESIAN_POINT ( 'NONE', ( 22.50193259072577945, 153.6096650756881274, 98.01077209009481805 ) ) ; -#4122 = AXIS2_PLACEMENT_3D ( 'NONE', #39106, #26456, #19884 ) ; -#4123 = ORIENTED_EDGE ( 'NONE', *, *, #34629, .F. ) ; -#4124 = ADVANCED_FACE ( 'NONE', ( #19903 ), #13795, .T. ) ; -#4125 = CARTESIAN_POINT ( 'NONE', ( 25.67739237361999827, 120.5334253433999976, 90.20131454888000633 ) ) ; -#4126 = LINE ( 'NONE', #672, #14964 ) ; -#4128 = CARTESIAN_POINT ( 'NONE', ( -12.40501934898651903, 154.3261979101877159, 95.28942457974159197 ) ) ; -#4127 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971562627 ) ) ; -#4129 = EDGE_CURVE ( 'NONE', #3510, #28860, #23766, .T. ) ; -#4130 = ORIENTED_EDGE ( 'NONE', *, *, #23122, .F. ) ; -#4131 = LINE ( 'NONE', #25851, #10169 ) ; -#4132 = CARTESIAN_POINT ( 'NONE', ( 38.35802587332594982, 118.7131882838841364, 87.66888804344846164 ) ) ; -#4133 = DIRECTION ( 'NONE', ( -0.6087604442381534531, -0.7731007285209676727, -0.1781178966059141500 ) ) ; -#4134 = CARTESIAN_POINT ( 'NONE', ( -13.83205090666964487, 150.4111610999959225, 179.9705989584246595 ) ) ; -#4135 = ORIENTED_EDGE ( 'NONE', *, *, #38297, .T. ) ; -#4136 = ORIENTED_EDGE ( 'NONE', *, *, #19082, .F. ) ; -#4137 = CARTESIAN_POINT ( 'NONE', ( 38.54429663914000059, 119.2351694718000061, 90.41614767503999417 ) ) ; -#4138 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#4139 = EDGE_CURVE ( 'NONE', #3107, #5073, #31843, .T. ) ; -#4140 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989908600, 0.1373964268091705798 ) ) ; -#4141 = DIRECTION ( 'NONE', ( 0.0002393071182785257178, 0.2252352986010041636, -0.9743043687658490271 ) ) ; -#4142 = CARTESIAN_POINT ( 'NONE', ( -2.300291980288000193, 191.0028055148000021, 106.1754316641000173 ) ) ; -#4143 = AXIS2_PLACEMENT_3D ( 'NONE', #17594, #13735, #26226 ) ; -#4144 = ORIENTED_EDGE ( 'NONE', *, *, #26355, .F. ) ; -#4145 = ORIENTED_EDGE ( 'NONE', *, *, #21153, .F. ) ; -#4146 = CARTESIAN_POINT ( 'NONE', ( 14.29577276298495825, 129.3448226987248688, 92.24270346485123184 ) ) ; -#4147 = CARTESIAN_POINT ( 'NONE', ( -12.63249231614464385, 177.7398399100670190, 100.7376584407296889 ) ) ; -#4148 = DIRECTION ( 'NONE', ( 0.0005884949961207905150, -0.2249510543439056653, 0.9743698870671265722 ) ) ; -#4149 = AXIS2_PLACEMENT_3D ( 'NONE', #12698, #19018, #18412 ) ; -#4150 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#4151 = ORIENTED_EDGE ( 'NONE', *, *, #27567, .T. ) ; -#4152 = DIRECTION ( 'NONE', ( -0.0005884949961251158311, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#4153 = ORIENTED_EDGE ( 'NONE', *, *, #11487, .T. ) ; -#4154 = CARTESIAN_POINT ( 'NONE', ( -13.49823352873892013, 173.8382768105483080, 102.8767958496218426 ) ) ; -#4155 = ORIENTED_EDGE ( 'NONE', *, *, #18392, .T. ) ; -#4156 = DIRECTION ( 'NONE', ( -0.0006039748319391919761, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#4157 = CARTESIAN_POINT ( 'NONE', ( -0.3440673525092000640, 189.1687001887999884, 105.6068241919000172 ) ) ; -#4158 = CARTESIAN_POINT ( 'NONE', ( -41.28986358703587456, 120.5685454323574817, 90.59221360106587895 ) ) ; -#4159 = CARTESIAN_POINT ( 'NONE', ( -2.435715612982877420, 190.9805827069217798, 106.3103827067138951 ) ) ; -#4160 = VERTEX_POINT ( 'NONE', #5757 ) ; -#4161 = ORIENTED_EDGE ( 'NONE', *, *, #12838, .F. ) ; -#4162 = ADVANCED_FACE ( 'NONE', ( #21102 ), #11518, .F. ) ; -#4163 = CARTESIAN_POINT ( 'NONE', ( -25.99272521086959387, 191.9759150222000130, 101.9371462950079774 ) ) ; -#4164 = EDGE_CURVE ( 'NONE', #11241, #7852, #23494, .T. ) ; -#4165 = CARTESIAN_POINT ( 'NONE', ( 19.79191328487740975, 119.7876596114540320, 175.4710310665177531 ) ) ; -#4166 = CARTESIAN_POINT ( 'NONE', ( 19.32153195108318755, 125.7880423541971311, 175.3576964661925217 ) ) ; -#4167 = AXIS2_PLACEMENT_3D ( 'NONE', #3407, #22445, #4205 ) ; -#4168 = CARTESIAN_POINT ( 'NONE', ( -45.34134577087812801, 120.7154725862561406, 105.4905015689576402 ) ) ; -#4169 = ORIENTED_EDGE ( 'NONE', *, *, #29013, .T. ) ; -#4170 = CC_DESIGN_DATE_AND_TIME_ASSIGNMENT ( #6104, #18556, ( #14451 ) ) ; -#4171 = CARTESIAN_POINT ( 'NONE', ( 23.32767345890041000, 115.6131156702012532, 89.75388588320586791 ) ) ; -#4172 = AXIS2_PLACEMENT_3D ( 'NONE', #13703, #26192, #10250 ) ; -#4173 = CARTESIAN_POINT ( 'NONE', ( -38.27202037554999947, 118.0785410800999955, 89.55555236154999932 ) ) ; -#4174 = EDGE_LOOP ( 'NONE', ( #30071, #30307, #39314, #16735 ) ) ; -#4175 = LINE ( 'NONE', #16651, #32796 ) ; -#4176 = ORIENTED_EDGE ( 'NONE', *, *, #37909, .F. ) ; -#4177 = CARTESIAN_POINT ( 'NONE', ( 9.000881520060126206, 160.1177476481799431, 96.61358080770237677 ) ) ; -#4178 = CARTESIAN_POINT ( 'NONE', ( -9.152368341089999859, 181.3125747747000105, 104.3400940192999968 ) ) ; -#4179 = CARTESIAN_POINT ( 'NONE', ( -29.44951657505878728, 160.9899919687744330, 187.1078845272746776 ) ) ; -#4180 = FACE_OUTER_BOUND ( 'NONE', #30971, .T. ) ; -#4181 = ORIENTED_EDGE ( 'NONE', *, *, #4544, .F. ) ; -#4182 = ORIENTED_EDGE ( 'NONE', *, *, #19408, .T. ) ; -#4183 = CARTESIAN_POINT ( 'NONE', ( -20.33170840607064633, 173.9106082832947493, 102.5524983983761445 ) ) ; -#4184 = ORIENTED_EDGE ( 'NONE', *, *, #27591, .T. ) ; -#4185 = ORIENTED_EDGE ( 'NONE', *, *, #7180, .T. ) ; -#4186 = ORIENTED_EDGE ( 'NONE', *, *, #23255, .T. ) ; -#4187 = FACE_BOUND ( 'NONE', #33089, .T. ) ; -#4188 = EDGE_CURVE ( 'NONE', #12815, #6603, #29798, .T. ) ; -#4189 = FACE_OUTER_BOUND ( 'NONE', #33949, .T. ) ; -#4190 = ORIENTED_EDGE ( 'NONE', *, *, #27164, .F. ) ; -#4191 = VERTEX_POINT ( 'NONE', #17801 ) ; -#4192 = CARTESIAN_POINT ( 'NONE', ( -48.18983608578390232, 82.56060091850311267, 289.7643016034785433 ) ) ; -#4193 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17335, #7742, #16741, #35732 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4194 = CARTESIAN_POINT ( 'NONE', ( 36.06237288312285472, 191.9759150222000130, 101.8996665707895488 ) ) ; -#4195 = CARTESIAN_POINT ( 'NONE', ( 35.40691481614999958, 112.8575867658999954, 87.09914284068000256 ) ) ; -#4196 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250612725, 132.8554482850445311, 90.84904174543022748 ) ) ; -#4197 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606776115838874, 137.3532831589803322, 178.0585834212922123 ) ) ; -#4198 = CC_DESIGN_APPROVAL ( #30192, ( #14451 ) ) ; -#4199 = AXIS2_PLACEMENT_3D ( 'NONE', #12632, #3023, #21660 ) ; -#4200 = CARTESIAN_POINT ( 'NONE', ( -18.71851310314255556, 125.9964326179262883, 174.7342168340691444 ) ) ; -#4201 = VERTEX_POINT ( 'NONE', #14969 ) ; -#4202 = CARTESIAN_POINT ( 'NONE', ( 27.75720308144000015, 124.8885774052999977, 88.64001580753000553 ) ) ; -#4203 = AXIS2_PLACEMENT_3D ( 'NONE', #4163, #32404, #32592 ) ; -#4204 = AXIS2_PLACEMENT_3D ( 'NONE', #5481, #23488, #7946 ) ; -#4205 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#4206 = CARTESIAN_POINT ( 'NONE', ( 15.59057381647033580, 147.4113417082091928, 179.2674225712073053 ) ) ; -#4207 = CIRCLE ( 'NONE', #37529, 2.000000000000011546 ) ; -#4208 = CARTESIAN_POINT ( 'NONE', ( 3.724081451453682856, 175.3147317747299496, 100.3200250948046772 ) ) ; -#4209 = CARTESIAN_POINT ( 'NONE', ( 3.785823397764000564, 171.3080482585999960, 102.0225523146000057 ) ) ; -#4210 = VERTEX_POINT ( 'NONE', #30295 ) ; -#4211 = LINE ( 'NONE', #35078, #22659 ) ; -#4212 = CARTESIAN_POINT ( 'NONE', ( 0.6150485984469488132, 189.0007186515956334, 103.6819504671993570 ) ) ; -#4213 = CARTESIAN_POINT ( 'NONE', ( 36.46626233178599819, 191.7780397924495617, 104.3563079202803010 ) ) ; -#4214 = CARTESIAN_POINT ( 'NONE', ( 12.63850258338070454, 130.2470009342416688, 92.65524625922149937 ) ) ; -#4215 = EDGE_CURVE ( 'NONE', #36508, #7897, #4322, .T. ) ; -#4216 = FACE_OUTER_BOUND ( 'NONE', #8258, .T. ) ; -#4217 = EDGE_CURVE ( 'NONE', #39537, #18545, #33553, .T. ) ; -#4218 = CARTESIAN_POINT ( 'NONE', ( -20.01418606989972204, 209.7097173109508503, 78.07055141587061087 ) ) ; -#4219 = CARTESIAN_POINT ( 'NONE', ( -4.037441716916447376, 168.3837378232288131, 99.04296232367518371 ) ) ; -#4220 = CARTESIAN_POINT ( 'NONE', ( 20.48021663872660625, 209.7101073659619601, 73.54617496015868028 ) ) ; -#4221 = ORIENTED_EDGE ( 'NONE', *, *, #21274, .T. ) ; -#4222 = EDGE_CURVE ( 'NONE', #31021, #31197, #2071, .T. ) ; -#4223 = CIRCLE ( 'NONE', #34890, 2.000000000000011546 ) ; -#4224 = CARTESIAN_POINT ( 'NONE', ( 3.046672840550818329, 207.8686389444351050, 77.27521480614490201 ) ) ; -#4225 = CONICAL_SURFACE ( 'NONE', #6197, 2.500000000022427393, 0.7853981634179985072 ) ; -#4226 = AXIS2_PLACEMENT_3D ( 'NONE', #15107, #9173, #21846 ) ; -#4227 = ORIENTED_EDGE ( 'NONE', *, *, #22709, .T. ) ; -#4228 = CARTESIAN_POINT ( 'NONE', ( -37.72490114302640762, 118.1295962051366644, 87.71953816704314022 ) ) ; -#4229 = CARTESIAN_POINT ( 'NONE', ( 0.5984363816331808028, 189.0000000000002842, 162.9824824855311931 ) ) ; -#4230 = CARTESIAN_POINT ( 'NONE', ( -37.26906488761501635, 185.6725334949844353, 105.6202278399714203 ) ) ; -#4231 = CARTESIAN_POINT ( 'NONE', ( 20.33633106218516318, 118.1105547769028021, 89.92091325015400116 ) ) ; -#4232 = VECTOR ( 'NONE', #31470, 1000.000000000000000 ) ; -#4233 = DIRECTION ( 'NONE', ( -0.7072759766252937341, -0.1592272936566909713, 0.6887723585071506838 ) ) ; -#4234 = CARTESIAN_POINT ( 'NONE', ( 40.01726673357607211, 182.7482725554044976, 105.5615746506993844 ) ) ; -#4235 = CARTESIAN_POINT ( 'NONE', ( 16.14865643636807846, 151.1202562712145152, 184.8374432047714606 ) ) ; -#4236 = ORIENTED_EDGE ( 'NONE', *, *, #11255, .F. ) ; -#4237 = CARTESIAN_POINT ( 'NONE', ( -2.585505525763999835, 209.4244858662999889, 75.73377336996000508 ) ) ; -#4238 = EDGE_CURVE ( 'NONE', #34827, #17792, #3645, .T. ) ; -#4239 = CARTESIAN_POINT ( 'NONE', ( 37.60707583988345704, 118.6216986129650479, 87.24507056057791488 ) ) ; -#4240 = CARTESIAN_POINT ( 'NONE', ( -23.16262457356699400, 49.03856518996145297, 291.5725335800685798 ) ) ; -#4241 = CARTESIAN_POINT ( 'NONE', ( 3.847675889067868393, 147.9886445650915618, 129.7371189396918680 ) ) ; -#4242 = ORIENTED_EDGE ( 'NONE', *, *, #25948, .F. ) ; -#4243 = DIRECTION ( 'NONE', ( 0.0005884965786932929224, -0.2255194605963585786, 0.9742384854665229188 ) ) ; -#4244 = CARTESIAN_POINT ( 'NONE', ( 3.756546640233114243, 136.7315605858967444, 94.07002193663585388 ) ) ; -#4245 = EDGE_LOOP ( 'NONE', ( #34445, #35515, #4979 ) ) ; -#4246 = CARTESIAN_POINT ( 'NONE', ( -39.01517791770809396, 88.99230595947560118, 291.5821081250562656 ) ) ; -#4247 = ORIENTED_EDGE ( 'NONE', *, *, #24577, .F. ) ; -#4248 = CARTESIAN_POINT ( 'NONE', ( 36.24343983389131552, 191.9507376470629367, 106.3940752163002088 ) ) ; -#4249 = EDGE_CURVE ( 'NONE', #35941, #22242, #36976, .T. ) ; -#4250 = CARTESIAN_POINT ( 'NONE', ( -3.668404233967317740, 183.5617789224675676, 104.5994755554405486 ) ) ; -#4251 = CARTESIAN_POINT ( 'NONE', ( -30.07053858951977432, 176.7377855870873873, 103.0399784982492264 ) ) ; -#4252 = DIRECTION ( 'NONE', ( 0.6087611434178766823, 0.7731004625452562173, 0.1781166614241080082 ) ) ; -#4253 = ORIENTED_EDGE ( 'NONE', *, *, #246, .T. ) ; -#4254 = EDGE_CURVE ( 'NONE', #37266, #34131, #32761, .T. ) ; -#4255 = CARTESIAN_POINT ( 'NONE', ( -47.98131261778327428, 61.12730635085708286, 282.5875218042072561 ) ) ; -#4256 = CARTESIAN_POINT ( 'NONE', ( -3.537408990743386550, 175.5045353393659866, 100.1734741104028643 ) ) ; -#4257 = VECTOR ( 'NONE', #2294, 1000.000000000000000 ) ; -#4258 = AXIS2_PLACEMENT_3D ( 'NONE', #4976, #11531, #32399 ) ; -#4259 = CARTESIAN_POINT ( 'NONE', ( -27.19720299916742690, 110.6131156702000027, 88.78421099472409139 ) ) ; -#4260 = CIRCLE ( 'NONE', #32984, 2.000000000000008882 ) ; -#4261 = DIRECTION ( 'NONE', ( -0.1943643238945204910, 0.07321898756438906253, -0.9781929714821465671 ) ) ; -#4262 = ORIENTED_EDGE ( 'NONE', *, *, #257, .F. ) ; -#4263 = ORIENTED_EDGE ( 'NONE', *, *, #12493, .F. ) ; -#4264 = AXIS2_PLACEMENT_3D ( 'NONE', #40370, #18684, #11985 ) ; -#4265 = EDGE_CURVE ( 'NONE', #32727, #23839, #34694, .T. ) ; -#4266 = VERTEX_POINT ( 'NONE', #5546 ) ; -#4267 = CARTESIAN_POINT ( 'NONE', ( -43.29998184106858616, 127.8267059849638230, 94.32171495544167783 ) ) ; -#4268 = ADVANCED_FACE ( 'NONE', ( #11903 ), #33758, .T. ) ; -#4269 = ADVANCED_FACE ( 'NONE', ( #2882 ), #15366, .F. ) ; -#4270 = CARTESIAN_POINT ( 'NONE', ( -20.08022789467965552, 137.4838439665992667, 91.40569571491579381 ) ) ; -#4271 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #35996, #14155 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4272 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#4273 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564847 ) ) ; -#4274 = CARTESIAN_POINT ( 'NONE', ( -2.787442205325794120, 209.0946219730610380, 75.98264626556951384 ) ) ; -#4275 = CARTESIAN_POINT ( 'NONE', ( 38.52450977667000132, 119.0470807367999981, 87.58348493723001127 ) ) ; -#4276 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5691, #15687, #18945, #2636 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4277 = CARTESIAN_POINT ( 'NONE', ( -2.794087745591999905, 209.4352313944999935, 73.18598115729000142 ) ) ; -#4278 = CARTESIAN_POINT ( 'NONE', ( 38.17455783781999656, 118.9402821446000047, 90.39771198626000626 ) ) ; -#4279 = ORIENTED_EDGE ( 'NONE', *, *, #15643, .F. ) ; -#4280 = CARTESIAN_POINT ( 'NONE', ( -18.76885123896627050, 125.8224625306723112, 175.1047239809785765 ) ) ; -#4281 = VECTOR ( 'NONE', #22831, 1000.000000000000227 ) ; -#4282 = CARTESIAN_POINT ( 'NONE', ( -36.34570124670982949, 191.6079946775634824, 106.4159430361022913 ) ) ; -#4283 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 132.6352630048999970, 91.80276880046000088 ) ) ; -#4284 = VECTOR ( 'NONE', #33152, 1000.000000000000000 ) ; -#4286 = ORIENTED_EDGE ( 'NONE', *, *, #4027, .T. ) ; -#4285 = CARTESIAN_POINT ( 'NONE', ( 25.49934386937603392, 120.6644425437606287, 88.00825483662825377 ) ) ; -#4287 = AXIS2_PLACEMENT_3D ( 'NONE', #32259, #29393, #38983 ) ; -#4288 = ORIENTED_EDGE ( 'NONE', *, *, #25301, .T. ) ; -#4289 = EDGE_LOOP ( 'NONE', ( #38892, #29341, #27081, #29680 ) ) ; -#4290 = EDGE_CURVE ( 'NONE', #35055, #11987, #10837, .T. ) ; -#4291 = ORIENTED_EDGE ( 'NONE', *, *, #34002, .F. ) ; -#4292 = CARTESIAN_POINT ( 'NONE', ( -20.49970531959032627, 138.0793279501024813, 92.05657955141926152 ) ) ; -#4293 = VECTOR ( 'NONE', #16958, 1000.000000000000000 ) ; -#4294 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927789170785, -0.0005734119022072707138 ) ) ; -#4295 = ORIENTED_EDGE ( 'NONE', *, *, #17129, .F. ) ; -#4296 = VERTEX_POINT ( 'NONE', #18801 ) ; -#4297 = CARTESIAN_POINT ( 'NONE', ( 38.34044226084490248, 118.6974003961651789, 90.05067387323349237 ) ) ; -#4298 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971576505 ) ) ; -#4299 = CARTESIAN_POINT ( 'NONE', ( -38.27190134952000022, 118.9739902352999934, 87.58185624361999544 ) ) ; -#4300 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#4301 = CARTESIAN_POINT ( 'NONE', ( 8.622920946291438682, 209.7096369262764597, 76.05329660143564752 ) ) ; -#4302 = ORIENTED_EDGE ( 'NONE', *, *, #26089, .T. ) ; -#4303 = DIRECTION ( 'NONE', ( 0.1706442583057913853, 1.252691005673331343E-14, 0.9853327037641987918 ) ) ; -#4304 = EDGE_CURVE ( 'NONE', #17992, #28125, #12484, .T. ) ; -#4305 = ORIENTED_EDGE ( 'NONE', *, *, #27778, .F. ) ; -#4306 = DIRECTION ( 'NONE', ( 2.734944080625583540E-13, -0.9743700558967669512, -0.2249510928440471014 ) ) ; -#4307 = CARTESIAN_POINT ( 'NONE', ( -2.938441476483304005, 191.9759150222000130, 101.9232220854011928 ) ) ; -#4308 = FACE_OUTER_BOUND ( 'NONE', #39346, .T. ) ; -#4309 = CARTESIAN_POINT ( 'NONE', ( -39.76913700811847718, 164.9864764582079033, 182.8973725837718121 ) ) ; -#4310 = ORIENTED_EDGE ( 'NONE', *, *, #19504, .F. ) ; -#4311 = ADVANCED_FACE ( 'NONE', ( #418 ), #19417, .T. ) ; -#4312 = CARTESIAN_POINT ( 'NONE', ( 35.54494089926004108, 209.7096602146001487, 73.03703587511542139 ) ) ; -#4313 = CARTESIAN_POINT ( 'NONE', ( 19.99933118494021755, 196.5785306413737601, 103.8628508136982731 ) ) ; -#4314 = EDGE_CURVE ( 'NONE', #36902, #30574, #3275, .T. ) ; -#4315 = VECTOR ( 'NONE', #22065, 1000.000000000000114 ) ; -#4316 = ORIENTED_EDGE ( 'NONE', *, *, #6163, .T. ) ; -#4317 = CARTESIAN_POINT ( 'NONE', ( -20.16545193449732309, 118.1202296371234581, 90.11267470310258432 ) ) ; -#4318 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391911088 ) ) ; -#4319 = CIRCLE ( 'NONE', #385, 2.500000720456942105 ) ; -#4320 = EDGE_CURVE ( 'NONE', #39497, #15288, #25587, .T. ) ; -#4321 = ORIENTED_EDGE ( 'NONE', *, *, #29941, .T. ) ; -#4322 = CIRCLE ( 'NONE', #32413, 2.499999999386279370 ) ; -#4323 = EDGE_CURVE ( 'NONE', #23972, #15470, #12279, .T. ) ; -#4324 = CIRCLE ( 'NONE', #37010, 59.40509898897001051 ) ; -#4325 = ORIENTED_EDGE ( 'NONE', *, *, #2686, .T. ) ; -#4326 = DIRECTION ( 'NONE', ( 1.387778780764727741E-15, 0.9743700557921591843, 0.2249510932971534038 ) ) ; -#4327 = ORIENTED_EDGE ( 'NONE', *, *, #4551, .F. ) ; -#4328 = AXIS2_PLACEMENT_3D ( 'NONE', #30847, #8149, #14496 ) ; -#4329 = CARTESIAN_POINT ( 'NONE', ( -26.03994625616386571, 191.1138689880127117, 103.7907643604723802 ) ) ; -#4330 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673776705, 151.8594835319893548, 95.21744457848066645 ) ) ; -#4331 = CARTESIAN_POINT ( 'NONE', ( -19.99292196337442107, 118.8155724060715812, 94.27986157945176160 ) ) ; -#4332 = ORIENTED_EDGE ( 'NONE', *, *, #20062, .F. ) ; -#4333 = CARTESIAN_POINT ( 'NONE', ( 26.01047000073999982, 120.4380107313999986, 90.52133411668999941 ) ) ; -#4334 = CARTESIAN_POINT ( 'NONE', ( -16.53940709779629259, 123.0792221378318203, 172.1887768675690040 ) ) ; -#4336 = CARTESIAN_POINT ( 'NONE', ( -10.60967616682832926, 153.7228291392860626, 95.14904155532032348 ) ) ; -#4335 = DIRECTION ( 'NONE', ( -0.0004161288024547640796, 0.8480480897973101673, -0.5299191110235157431 ) ) ; -#4337 = VERTEX_POINT ( 'NONE', #34739 ) ; -#4338 = CARTESIAN_POINT ( 'NONE', ( -2.287398478804171909, 189.4306113881276588, 103.3878077086402385 ) ) ; -#4339 = AXIS2_PLACEMENT_3D ( 'NONE', #4580, #32990, #563 ) ; -#4340 = CARTESIAN_POINT ( 'NONE', ( -36.11017946864552641, 191.9687029343600102, 104.4208442067391189 ) ) ; -#4341 = CARTESIAN_POINT ( 'NONE', ( 42.33356330404532031, 170.6397506934769126, 189.3563035634615233 ) ) ; -#4342 = EDGE_LOOP ( 'NONE', ( #22975, #28649, #9937, #2324 ) ) ; -#4343 = AXIS2_PLACEMENT_3D ( 'NONE', #35355, #7362, #1233 ) ; -#4344 = AXIS2_PLACEMENT_3D ( 'NONE', #10200, #21857, #18966 ) ; -#4345 = ORIENTED_EDGE ( 'NONE', *, *, #22172, .F. ) ; -#4346 = DIRECTION ( 'NONE', ( 0.0005884949961224280940, -0.2249510543439061094, 0.9743698870671263501 ) ) ; -#4347 = DIRECTION ( 'NONE', ( 0.0005884949961204437871, -0.2249510543439066645, 0.9743698870671262391 ) ) ; -#4348 = CARTESIAN_POINT ( 'NONE', ( -44.95738950158257552, 124.6557125506502359, 91.20127123669165314 ) ) ; -#4349 = DIRECTION ( 'NONE', ( 0.6087614883550946931, -0.7730004026499607273, -0.1785492307423602321 ) ) ; -#4350 = EDGE_CURVE ( 'NONE', #11228, #30753, #6948, .T. ) ; -#4351 = CIRCLE ( 'NONE', #26593, 4.500000000438258319 ) ; -#4352 = ORIENTED_EDGE ( 'NONE', *, *, #33118, .F. ) ; -#4353 = EDGE_CURVE ( 'NONE', #16874, #6030, #21, .T. ) ; -#4354 = VERTEX_POINT ( 'NONE', #6741 ) ; -#4355 = EDGE_CURVE ( 'NONE', #30329, #31352, #1542, .T. ) ; -#4356 = CARTESIAN_POINT ( 'NONE', ( -23.36055974375966571, 134.8407614670647661, 93.36323390285753021 ) ) ; -#4357 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#4358 = VERTEX_POINT ( 'NONE', #6542 ) ; -#4359 = EDGE_CURVE ( 'NONE', #20666, #7827, #20018, .T. ) ; -#4360 = DIRECTION ( 'NONE', ( -9.251858538484500274E-15, -1.000000000000000000, 1.387778780772674962E-14 ) ) ; -#4361 = EDGE_CURVE ( 'NONE', #6068, #15877, #40071, .T. ) ; -#4362 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825886666129127, 0.0005734119031577724354 ) ) ; -#4363 = CARTESIAN_POINT ( 'NONE', ( 3.080804039577430320, 190.8472066119958868, 106.8075773176640837 ) ) ; -#4364 = ORIENTED_EDGE ( 'NONE', *, *, #3230, .F. ) ; -#4365 = CARTESIAN_POINT ( 'NONE', ( -30.07323508668966738, 135.0961509773328544, 91.10847914731613173 ) ) ; -#4366 = EDGE_CURVE ( 'NONE', #19459, #14180, #30507, .T. ) ; -#4367 = CARTESIAN_POINT ( 'NONE', ( -45.92960031148149369, 125.5172539323009886, 88.65860258904321256 ) ) ; -#4368 = LINE ( 'NONE', #39934, #9801 ) ; -#4369 = CARTESIAN_POINT ( 'NONE', ( 44.84982446188305261, 177.0778658525795493, 147.7896410935606184 ) ) ; -#4370 = VECTOR ( 'NONE', #21150, 999.9999999999998863 ) ; -#4371 = ORIENTED_EDGE ( 'NONE', *, *, #37374, .F. ) ; -#4372 = VERTEX_POINT ( 'NONE', #37634 ) ; -#4373 = CARTESIAN_POINT ( 'NONE', ( -24.53767847806265223, 116.1139939875861131, 87.78242264549591312 ) ) ; -#4374 = CARTESIAN_POINT ( 'NONE', ( 21.15131189037067827, 213.4625898340589742, 73.04572922002022040 ) ) ; -#4375 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31981, #34803, #25454, #6606 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4376 = AXIS2_PLACEMENT_3D ( 'NONE', #14465, #23871, #33245 ) ; -#4377 = CARTESIAN_POINT ( 'NONE', ( 20.80759478759580361, 212.3488673824964792, 75.54571959206188581 ) ) ; -#4378 = ADVANCED_FACE ( 'NONE', ( #13301 ), #19013, .F. ) ; -#4379 = CARTESIAN_POINT ( 'NONE', ( -42.11868374227395861, 189.5899118835476713, 106.5956137111014499 ) ) ; -#4380 = ORIENTED_EDGE ( 'NONE', *, *, #308, .T. ) ; -#4381 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971568733 ) ) ; -#4382 = CARTESIAN_POINT ( 'NONE', ( -35.56838832268000061, 112.3995020750000009, 90.16785085327001070 ) ) ; -#4383 = VERTEX_POINT ( 'NONE', #31503 ) ; -#4384 = CARTESIAN_POINT ( 'NONE', ( 3.062676760973492840, 191.1124749746149121, 103.7728652720017095 ) ) ; -#4385 = EDGE_LOOP ( 'NONE', ( #17630, #21125, #38299, #2953 ) ) ; -#4386 = CARTESIAN_POINT ( 'NONE', ( 0.5459373229760942081, 209.0000000000000000, 76.05817489712759993 ) ) ; -#4387 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490320223031, 156.2427122711505092, 96.23754757942438687 ) ) ; -#4388 = CARTESIAN_POINT ( 'NONE', ( 29.35339269389225336, 109.9231769193005448, 185.5806642568865357 ) ) ; -#4389 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971553745 ) ) ; -#4390 = ORIENTED_EDGE ( 'NONE', *, *, #15280, .F. ) ; -#4391 = VERTEX_POINT ( 'NONE', #35136 ) ; -#4392 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#4393 = ORIENTED_EDGE ( 'NONE', *, *, #26223, .T. ) ; -#4394 = ORIENTED_EDGE ( 'NONE', *, *, #29168, .F. ) ; -#4395 = CARTESIAN_POINT ( 'NONE', ( -6.036111313236179221, 177.3878382371900955, 100.9543767415334230 ) ) ; -#4396 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457974481995, -32.89481530046831637, 142.2936922234670760 ) ) ; -#4397 = CARTESIAN_POINT ( 'NONE', ( 19.48130215079870453, 124.7230702991837319, 177.6103480138636428 ) ) ; -#4398 = ADVANCED_FACE ( 'NONE', ( #32112 ), #4067, .T. ) ; -#4399 = VECTOR ( 'NONE', #5574, 1000.000000000000114 ) ; -#4400 = ORIENTED_EDGE ( 'NONE', *, *, #5210, .T. ) ; -#4401 = LINE ( 'NONE', #3593, #31105 ) ; -#4402 = EDGE_CURVE ( 'NONE', #15440, #1631, #25185, .T. ) ; -#4403 = DIRECTION ( 'NONE', ( 0.7933535320750287889, -0.5931614265262138419, -0.1369295264925107780 ) ) ; -#4404 = LINE ( 'NONE', #17063, #24813 ) ; -#4405 = CARTESIAN_POINT ( 'NONE', ( 36.33629891371000298, 191.7501006589000383, 104.2401080745000002 ) ) ; -#4406 = ADVANCED_FACE ( 'NONE', ( #16541 ), #35900, .F. ) ; -#4407 = DIRECTION ( 'NONE', ( 0.6087116037913345989, -0.7730376917437173923, -0.1785578633197842657 ) ) ; -#4408 = AXIS2_PLACEMENT_3D ( 'NONE', #1178, #35913, #29811 ) ; -#4409 = ORIENTED_EDGE ( 'NONE', *, *, #7125, .F. ) ; -#4410 = LINE ( 'NONE', #10369, #18619 ) ; -#4411 = CARTESIAN_POINT ( 'NONE', ( -23.35926900925013427, 176.8944240928315708, 103.2853824253334523 ) ) ; -#4412 = ORIENTED_EDGE ( 'NONE', *, *, #2496, .T. ) ; -#4413 = EDGE_CURVE ( 'NONE', #6773, #25855, #22010, .T. ) ; -#4414 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#4415 = CARTESIAN_POINT ( 'NONE', ( 16.29673443576292513, 122.7881700461012571, 174.3527752401433872 ) ) ; -#4416 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474989196751357, 155.7928101624825672, 98.18628735359796167 ) ) ; -#4417 = CARTESIAN_POINT ( 'NONE', ( -21.82845865523656315, 182.3067054805563316, 104.3206871860773504 ) ) ; -#4418 = ORIENTED_EDGE ( 'NONE', *, *, #24760, .F. ) ; -#4420 = ADVANCED_FACE ( 'NONE', ( #29645 ), #25280, .F. ) ; -#4419 = CARTESIAN_POINT ( 'NONE', ( -15.10714335811488773, 183.0966620568070198, 101.9332428217494027 ) ) ; -#4421 = CARTESIAN_POINT ( 'NONE', ( 0.7148223346852035087, 189.0057347121541795, 103.6850123720776367 ) ) ; -#4422 = CARTESIAN_POINT ( 'NONE', ( 14.35428732803441321, 191.5259372390380292, 103.8615007246684172 ) ) ; -#4423 = DIRECTION ( 'NONE', ( -0.0002393071182786160318, -0.2252352986010024705, 0.9743043687658494711 ) ) ; -#4424 = VERTEX_POINT ( 'NONE', #4477 ) ; -#4425 = CARTESIAN_POINT ( 'NONE', ( -25.36091826042000008, 191.5596352517000014, 104.5375569756999994 ) ) ; -#4426 = EDGE_CURVE ( 'NONE', #29005, #14963, #10244, .T. ) ; -#4427 = CARTESIAN_POINT ( 'NONE', ( 15.59065710782569703, 147.2783093503222460, 179.8436489142887922 ) ) ; -#4428 = CARTESIAN_POINT ( 'NONE', ( 26.14599041829999848, 192.0602195719000065, 103.7684055290999936 ) ) ; -#4429 = EDGE_CURVE ( 'NONE', #17707, #35463, #14160, .T. ) ; -#4430 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #31692, #581 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4431 = LINE ( 'NONE', #19757, #29125 ) ; -#4432 = ORIENTED_EDGE ( 'NONE', *, *, #2034, .F. ) ; -#4433 = CARTESIAN_POINT ( 'NONE', ( -42.86870032173014522, 121.2410338499262537, 90.70283413665809746 ) ) ; -#4434 = AXIS2_PLACEMENT_3D ( 'NONE', #24567, #30892, #9016 ) ; -#4435 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29945, #32991, #33608, #11957 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.003684369078374031495, 0.004391610992028501664 ), - .UNSPECIFIED. ) ; -#4436 = AXIS2_PLACEMENT_3D ( 'NONE', #4997, #24447, #39746 ) ; -#4437 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 103.5647597712388261, 168.7177032462348620 ) ) ; -#4438 = ORIENTED_EDGE ( 'NONE', *, *, #35483, .T. ) ; -#4439 = CARTESIAN_POINT ( 'NONE', ( -38.04444379205944671, 118.4867705051282627, 87.71485106921780073 ) ) ; -#4440 = CARTESIAN_POINT ( 'NONE', ( -4.037441716908935163, 137.2418790766312782, 91.85329641515465937 ) ) ; -#4441 = CARTESIAN_POINT ( 'NONE', ( 37.85090698586000002, 191.1231049499999983, 106.1818745881000154 ) ) ; -#4442 = CARTESIAN_POINT ( 'NONE', ( 36.08395475670999986, 192.1923109830999863, 104.3567733717000010 ) ) ; -#4443 = CARTESIAN_POINT ( 'NONE', ( -16.52323579073919646, 152.1899771268108452, 181.4476381748975768 ) ) ; -#4444 = CARTESIAN_POINT ( 'NONE', ( 13.50189226125813846, 187.9430574696029907, 103.3793715338758972 ) ) ; -#4445 = EDGE_LOOP ( 'NONE', ( #20342, #20335, #2484, #38003, #14410, #25276, #18791, #16038 ) ) ; -#4446 = ORIENTED_EDGE ( 'NONE', *, *, #19041, .F. ) ; -#4447 = LINE ( 'NONE', #38588, #8859 ) ; -#4448 = CARTESIAN_POINT ( 'NONE', ( 35.81039908593225363, 115.0592316559111765, 87.24615570831635125 ) ) ; -#4449 = EDGE_LOOP ( 'NONE', ( #1491, #27730, #29795, #18220 ) ) ; -#4450 = DIRECTION ( 'NONE', ( -0.7075059890727370959, -1.651605043716707640E-15, -0.7067073477941262505 ) ) ; -#4451 = ADVANCED_FACE ( 'NONE', ( #32311 ), #28541, .F. ) ; -#4452 = CARTESIAN_POINT ( 'NONE', ( -45.01366707977943094, 130.2508973098130411, 92.82981015662352320 ) ) ; -#4453 = EDGE_CURVE ( 'NONE', #4711, #1188, #15254, .T. ) ; -#4454 = ORIENTED_EDGE ( 'NONE', *, *, #19388, .F. ) ; -#4455 = CARTESIAN_POINT ( 'NONE', ( 20.00013814902157350, 147.4939005714190046, 93.69263431585608259 ) ) ; -#4456 = ORIENTED_EDGE ( 'NONE', *, *, #12135, .T. ) ; -#4457 = LINE ( 'NONE', #2019, #35313 ) ; -#4458 = AXIS2_PLACEMENT_3D ( 'NONE', #11490, #23975, #36430 ) ; -#4459 = CARTESIAN_POINT ( 'NONE', ( -12.63649281425979254, 129.9703308616587947, 92.23232912629561042 ) ) ; -#4460 = CARTESIAN_POINT ( 'NONE', ( 23.36190162741788967, 177.7945445883550519, 100.6858769593398080 ) ) ; -#4461 = CARTESIAN_POINT ( 'NONE', ( 39.72744443561925465, 107.0407409438602855, 185.0027117538028278 ) ) ; -#4462 = ORIENTED_EDGE ( 'NONE', *, *, #29773, .F. ) ; -#4463 = FACE_OUTER_BOUND ( 'NONE', #8606, .T. ) ; -#4464 = CARTESIAN_POINT ( 'NONE', ( -30.07171558059459215, 177.1876876956736169, 101.0912387261568028 ) ) ; -#4465 = CARTESIAN_POINT ( 'NONE', ( -14.99989747112629068, 176.2176057258887454, 100.5160767531280328 ) ) ; -#4466 = ORIENTED_EDGE ( 'NONE', *, *, #7136, .F. ) ; -#4467 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #15857, #517 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4468 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#4469 = ORIENTED_EDGE ( 'NONE', *, *, #27304, .T. ) ; -#4470 = CARTESIAN_POINT ( 'NONE', ( 25.51935971830618399, 191.1026097824055796, 106.3227842531489671 ) ) ; -#4471 = CARTESIAN_POINT ( 'NONE', ( 4.404236726960877313, 130.7136275758185491, 89.82787981506024266 ) ) ; -#4472 = EDGE_CURVE ( 'NONE', #32173, #26941, #32706, .T. ) ; -#4473 = CARTESIAN_POINT ( 'NONE', ( 36.71352342385499412, 115.7387982162421025, 89.70104857119935104 ) ) ; -#4474 = CARTESIAN_POINT ( 'NONE', ( 1.447658035600616788, 152.0519508786576353, 130.6788418761141486 ) ) ; -#4475 = CARTESIAN_POINT ( 'NONE', ( 15.50147166558119594, 185.3474886484798390, 105.0001610792874942 ) ) ; -#4476 = CARTESIAN_POINT ( 'NONE', ( -25.99272572791733182, 191.9759150222000130, 101.9371462953202609 ) ) ; -#4477 = CARTESIAN_POINT ( 'NONE', ( 21.83022404666562366, 176.4985800024501259, 100.9007981789296053 ) ) ; -#4478 = AXIS2_PLACEMENT_3D ( 'NONE', #3298, #21732, #21329 ) ; -#4479 = CARTESIAN_POINT ( 'NONE', ( 38.29551853473000733, 119.2077387477000059, 87.35949975440999538 ) ) ; -#4480 = CARTESIAN_POINT ( 'NONE', ( 39.06524929025407999, 190.3639766107277751, 106.6572273908310677 ) ) ; -#4481 = CARTESIAN_POINT ( 'NONE', ( 38.48852289050999786, 118.5536772429999957, 89.80770094992000452 ) ) ; -#4482 = ORIENTED_EDGE ( 'NONE', *, *, #34053, .T. ) ; -#4483 = ADVANCED_FACE ( 'NONE', ( #29037 ), #13500, .F. ) ; -#4484 = CARTESIAN_POINT ( 'NONE', ( 40.67360545558243956, 184.2591260079552740, 105.2468408042174275 ) ) ; -#4485 = AXIS2_PLACEMENT_3D ( 'NONE', #38418, #22701, #16145 ) ; -#4486 = CARTESIAN_POINT ( 'NONE', ( 29.17699550212986637, 209.7096486318000075, 76.04088245540252444 ) ) ; -#4487 = CYLINDRICAL_SURFACE ( 'NONE', #724, 5.249999999999986677 ) ; -#4488 = AXIS2_PLACEMENT_3D ( 'NONE', #38285, #22766, #16006 ) ; -#4489 = VECTOR ( 'NONE', #20515, 999.9999999999998863 ) ; -#4490 = LINE ( 'NONE', #13909, #34944 ) ; -#4491 = ORIENTED_EDGE ( 'NONE', *, *, #17129, .T. ) ; -#4492 = ORIENTED_EDGE ( 'NONE', *, *, #37377, .T. ) ; -#4493 = ORIENTED_EDGE ( 'NONE', *, *, #31850, .F. ) ; -#4494 = CARTESIAN_POINT ( 'NONE', ( 26.03373140117899709, 191.5260202047026041, 103.8544635878054976 ) ) ; -#4495 = CARTESIAN_POINT ( 'NONE', ( -2.533214444037978907, 209.6150328728459442, 73.39336733046577876 ) ) ; -#4496 = DIRECTION ( 'NONE', ( 0.6087614810001754639, -0.7729390313185934280, -0.1788147452386056602 ) ) ; -#4497 = EDGE_CURVE ( 'NONE', #28807, #3459, #19570, .T. ) ; -#4498 = ORIENTED_EDGE ( 'NONE', *, *, #8836, .F. ) ; -#4499 = EDGE_CURVE ( 'NONE', #3242, #27979, #26918, .T. ) ; -#4500 = ORIENTED_EDGE ( 'NONE', *, *, #33577, .F. ) ; -#4501 = CARTESIAN_POINT ( 'NONE', ( 38.22623376675434059, 118.8155667128057615, 90.24469678293085906 ) ) ; -#4502 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#4503 = CARTESIAN_POINT ( 'NONE', ( -38.39793200855000066, 118.8574776149000058, 87.72185305345000472 ) ) ; -#4504 = CARTESIAN_POINT ( 'NONE', ( -35.92375300345999989, 114.4806295604000042, 87.65586600601000100 ) ) ; -#4505 = ORIENTED_EDGE ( 'NONE', *, *, #16051, .T. ) ; -#4506 = EDGE_CURVE ( 'NONE', #34607, #726, #27355, .T. ) ; -#4507 = CYLINDRICAL_SURFACE ( 'NONE', #21898, 48.00000000000002132 ) ; -#4508 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#4509 = DIRECTION ( 'NONE', ( 0.6087613186456907188, -0.7729176985478710682, -0.1789074850089337476 ) ) ; -#4510 = CARTESIAN_POINT ( 'NONE', ( -12.63718560774618105, 181.5628715657541079, 104.1854011749896216 ) ) ; -#4511 = ORIENTED_EDGE ( 'NONE', *, *, #27801, .T. ) ; -#4512 = CARTESIAN_POINT ( 'NONE', ( -0.6019272315500000525, 188.9987428910999938, 103.6847776933999938 ) ) ; -#4513 = LINE ( 'NONE', #7383, #17920 ) ; -#4514 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#4515 = CONICAL_SURFACE ( 'NONE', #16906, 2.502999999899097716, 0.7853981634646929333 ) ; -#4516 = VECTOR ( 'NONE', #29498, 999.9999999999998863 ) ; -#4517 = ORIENTED_EDGE ( 'NONE', *, *, #3230, .T. ) ; -#4518 = CARTESIAN_POINT ( 'NONE', ( -2.421663575686999970, 209.3771755197000175, 75.56751031131001639 ) ) ; -#4519 = CARTESIAN_POINT ( 'NONE', ( 19.98271455780751538, 210.1680415111135574, 76.04531988083382998 ) ) ; -#4520 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28746, #22626, #35050, #6857, #1125, #7057, #31828, #32023, #729, #3982, #19915, #28552, #25294, #37736, #16066, #19332, #9748 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999954481, 0.1874999999999938938, 0.2499999999999923395, 0.3749999999999933387, 0.4999999999999943379, 0.6249999999999953371, 0.7499999999999963363, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4521 = ORIENTED_EDGE ( 'NONE', *, *, #17086, .F. ) ; -#4522 = VECTOR ( 'NONE', #3729, 1000.000000000000114 ) ; -#4523 = VERTEX_POINT ( 'NONE', #17145 ) ; -#4524 = ORIENTED_EDGE ( 'NONE', *, *, #33158, .F. ) ; -#4525 = DIRECTION ( 'NONE', ( 5.741067343745209959E-12, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#4526 = FACE_OUTER_BOUND ( 'NONE', #28474, .T. ) ; -#4527 = ORIENTED_EDGE ( 'NONE', *, *, #32169, .F. ) ; -#4528 = LINE ( 'NONE', #10898, #19927 ) ; -#4529 = ORIENTED_EDGE ( 'NONE', *, *, #26306, .F. ) ; -#4530 = EDGE_CURVE ( 'NONE', #29413, #27492, #8789, .T. ) ; -#4531 = CARTESIAN_POINT ( 'NONE', ( 25.50082892276000024, 120.2986139677999944, 89.97792380045000016 ) ) ; -#4532 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #25498, #13018 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4533 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384972194 ) ) ; -#4535 = CARTESIAN_POINT ( 'NONE', ( -11.62476157916481512, 154.1189553150826725, 95.24110759181746744 ) ) ; -#4534 = CARTESIAN_POINT ( 'NONE', ( 20.48167212851781827, 208.5384972688564176, 75.82337149459281989 ) ) ; -#4536 = AXIS2_PLACEMENT_3D ( 'NONE', #7582, #38651, #16972 ) ; -#4537 = EDGE_CURVE ( 'NONE', #3655, #7336, #21257, .T. ) ; -#4538 = CIRCLE ( 'NONE', #15010, 7.499999999921035609 ) ; -#4539 = EDGE_LOOP ( 'NONE', ( #32447, #38436, #21477, #14127 ) ) ; -#4540 = VECTOR ( 'NONE', #9474, 1000.000000000000114 ) ; -#4541 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930882562 ) ) ; -#4542 = AXIS2_PLACEMENT_3D ( 'NONE', #23594, #26271, #4569 ) ; -#4543 = CARTESIAN_POINT ( 'NONE', ( -8.191411997281301538, 151.3128155192395354, 94.76223611369431410 ) ) ; -#4544 = EDGE_CURVE ( 'NONE', #10087, #30803, #30054, .T. ) ; -#4545 = EDGE_CURVE ( 'NONE', #7229, #34227, #12391, .T. ) ; -#4546 = VECTOR ( 'NONE', #24985, 999.9999999999998863 ) ; -#4547 = EDGE_LOOP ( 'NONE', ( #35614, #28333, #29158 ) ) ; -#4549 = ADVANCED_FACE ( 'NONE', ( #33503 ), #5711, .T. ) ; -#4548 = CARTESIAN_POINT ( 'NONE', ( 38.73814783011000173, 119.0754946943000050, 90.11438996249999889 ) ) ; -#4550 = CARTESIAN_POINT ( 'NONE', ( -36.73985734004195791, 117.5510141980808072, 87.28997424524052917 ) ) ; -#4551 = EDGE_CURVE ( 'NONE', #22040, #33315, #39127, .T. ) ; -#4552 = LINE ( 'NONE', #22586, #14830 ) ; -#4553 = FACE_OUTER_BOUND ( 'NONE', #29748, .T. ) ; -#4554 = CARTESIAN_POINT ( 'NONE', ( 36.32029408017999828, 191.7179464608000217, 104.1934018853000055 ) ) ; -#4555 = EDGE_LOOP ( 'NONE', ( #37973, #19035, #30475, #11294 ) ) ; -#4556 = ORIENTED_EDGE ( 'NONE', *, *, #16534, .F. ) ; -#4557 = CARTESIAN_POINT ( 'NONE', ( -12.63686179124978892, 177.3887316568832659, 100.9570573941570473 ) ) ; -#4558 = CARTESIAN_POINT ( 'NONE', ( 15.89469151744206421, 147.4449134593691610, 177.3586166299334650 ) ) ; -#4559 = EDGE_LOOP ( 'NONE', ( #9659, #25662, #38768, #1875, #32378, #37292, #37581, #10521, #4991, #31295 ) ) ; -#4560 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #31919, #10246, #818, #25985 ), - ( #7345, #32314, #25590, #34740 ), - ( #614, #13302, #28639, #19210 ), - ( #1015, #4277, #3467, #22316 ), - ( #10032, #22110, #419, #4070 ), - ( #10446, #16542, #25788, #25379 ), - ( #16751, #214, #38235, #19420 ), - ( #31504, #38428, #22714, #12695 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.1683202481699999919, 0.000000000000000000, 0.3333334569363999855, 0.6666668616933999481, 1.000000000000000000, 1.164202491116000049 ), - ( -3.140553228863999869E-07, 0.9999999710371000328 ), - .UNSPECIFIED. ) ; -#4561 = CARTESIAN_POINT ( 'NONE', ( -35.43083629604420537, 192.6084089038419904, 106.9106422785019959 ) ) ; -#4562 = CARTESIAN_POINT ( 'NONE', ( -39.42815928026088557, 120.3902238028007616, 87.47100753998802247 ) ) ; -#4563 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#4564 = ORIENTED_EDGE ( 'NONE', *, *, #9036, .F. ) ; -#4565 = CYLINDRICAL_SURFACE ( 'NONE', #1389, 4.999999999999994671 ) ; -#4566 = AXIS2_PLACEMENT_3D ( 'NONE', #21644, #40219, #21840 ) ; -#4567 = ADVANCED_FACE ( 'NONE', ( #2245 ), #35675, .F. ) ; -#4568 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#4569 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825889831406412, 0.0005734119030863655793 ) ) ; -#4570 = CARTESIAN_POINT ( 'NONE', ( -5.960622339528989677, 163.5635530557085247, 97.41814418763185301 ) ) ; -#4571 = AXIS2_PLACEMENT_3D ( 'NONE', #6649, #3784, #34847 ) ; -#4572 = ORIENTED_EDGE ( 'NONE', *, *, #29672, .F. ) ; -#4573 = AXIS2_PLACEMENT_3D ( 'NONE', #22055, #3224, #40234 ) ; -#4574 = CARTESIAN_POINT ( 'NONE', ( -25.50129508846853099, 118.1132512059233335, 87.78307593003776788 ) ) ; -#4575 = CARTESIAN_POINT ( 'NONE', ( -15.49823494792000034, 157.9289540101000284, 99.20196762495000087 ) ) ; -#4576 = CARTESIAN_POINT ( 'NONE', ( -12.63809828823728232, 131.0198806733800438, 89.90888323108799796 ) ) ; -#4577 = VERTEX_POINT ( 'NONE', #40238 ) ; -#4578 = ADVANCED_FACE ( 'NONE', ( #24123 ), #27613, .F. ) ; -#4579 = DIRECTION ( 'NONE', ( 0.2808154964431652245, -1.219838484668546832E-14, -0.9597617709397361363 ) ) ; -#4581 = CARTESIAN_POINT ( 'NONE', ( -37.93206066660999909, 118.8229955981000074, 90.44873202908000565 ) ) ; -#4580 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250093319, 179.6252109630997893, 101.6466942237284456 ) ) ; -#4583 = EDGE_LOOP ( 'NONE', ( #4900, #11547, #37783, #19485 ) ) ; -#4582 = EDGE_CURVE ( 'NONE', #8036, #7563, #24336, .T. ) ; -#4584 = VERTEX_POINT ( 'NONE', #30661 ) ; -#4585 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#4586 = EDGE_CURVE ( 'NONE', #17427, #15772, #27812, .T. ) ; -#4587 = CARTESIAN_POINT ( 'NONE', ( -12.63810005728112529, 131.0234914809575741, 89.90663177300498887 ) ) ; -#4588 = DIRECTION ( 'NONE', ( -0.0006039748319392047697, 6.984862132708257173E-19, -0.9999998176071845934 ) ) ; -#4589 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218858604, 82.27946979429611929, 297.5295786860745579 ) ) ; -#4590 = DIRECTION ( 'NONE', ( -0.0005884949961138158424, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#4591 = ORIENTED_EDGE ( 'NONE', *, *, #4129, .F. ) ; -#4592 = ORIENTED_EDGE ( 'NONE', *, *, #7931, .T. ) ; -#4593 = CARTESIAN_POINT ( 'NONE', ( -5.023244955357182739, 181.7489884665435511, 101.6160173790793664 ) ) ; -#4594 = VERTEX_POINT ( 'NONE', #2660 ) ; -#4595 = EDGE_LOOP ( 'NONE', ( #2154, #14283, #6161, #18251 ) ) ; -#4597 = EDGE_CURVE ( 'NONE', #12222, #22101, #23624, .T. ) ; -#4596 = CARTESIAN_POINT ( 'NONE', ( -25.99976593112455348, 118.8155677978001705, 90.28348901843737906 ) ) ; -#4599 = VECTOR ( 'NONE', #22797, 1000.000000000000114 ) ; -#4598 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265225566, -0.1368326740407719011 ) ) ; -#4600 = CARTESIAN_POINT ( 'NONE', ( 2.538357414086000130, 209.1910662834000050, 73.57953838714999506 ) ) ; -#4601 = ORIENTED_EDGE ( 'NONE', *, *, #8292, .F. ) ; -#4602 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21526, #2506, #39489, #27663 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4603 = CIRCLE ( 'NONE', #12440, 4.500000000381400689 ) ; -#4604 = EDGE_LOOP ( 'NONE', ( #33445, #38098, #5649, #26664 ) ) ; -#4605 = LINE ( 'NONE', #27124, #18663 ) ; -#4606 = VECTOR ( 'NONE', #15142, 1000.000000000000227 ) ; -#4607 = CARTESIAN_POINT ( 'NONE', ( -15.49852918272448576, 137.6306203012457843, 94.00257521259531757 ) ) ; -#4608 = CARTESIAN_POINT ( 'NONE', ( 38.07634149388000111, 118.5735798831999972, 87.56817451646001871 ) ) ; -#4609 = CARTESIAN_POINT ( 'NONE', ( 25.50067444836711772, 120.1830342791591733, 89.91912185905974297 ) ) ; -#4610 = CARTESIAN_POINT ( 'NONE', ( 2.945216860577655638, 209.7036681624458083, 76.05698929380193363 ) ) ; -#4611 = ORIENTED_EDGE ( 'NONE', *, *, #8001, .F. ) ; -#4612 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265228896, 0.1368326740407718456 ) ) ; -#4613 = FACE_OUTER_BOUND ( 'NONE', #7396, .T. ) ; -#4614 = EDGE_LOOP ( 'NONE', ( #23557, #6512, #5327, #22758 ) ) ; -#4615 = CARTESIAN_POINT ( 'NONE', ( 0.6034525440803617524, 188.6132189102335985, 103.1973517498306450 ) ) ; -#4616 = CARTESIAN_POINT ( 'NONE', ( 16.14434960484450343, 151.5098951869006783, 180.2135683096318246 ) ) ; -#4617 = CARTESIAN_POINT ( 'NONE', ( 20.49930103516235746, 196.1188360154283430, 103.6658478038365558 ) ) ; -#4618 = CARTESIAN_POINT ( 'NONE', ( 46.07705293508445266, 185.2595815743947014, 105.4745506663921475 ) ) ; -#4619 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #4904, #17360, #10657, #17162 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.994645287853319182, 6.088140294281147114 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9028133655217900344, 0.9028133655217900344, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#4620 = ORIENTED_EDGE ( 'NONE', *, *, #15228, .T. ) ; -#4621 = LINE ( 'NONE', #35889, #19368 ) ; -#4622 = DIRECTION ( 'NONE', ( 0.9808256175858699466, 0.000000000000000000, -0.1948874236252736147 ) ) ; -#4623 = PLANE ( 'NONE', #2591 ) ; -#4624 = VERTEX_POINT ( 'NONE', #36385 ) ; -#4625 = FACE_OUTER_BOUND ( 'NONE', #26882, .T. ) ; -#4626 = ORIENTED_EDGE ( 'NONE', *, *, #18612, .T. ) ; -#4627 = CARTESIAN_POINT ( 'NONE', ( -25.61315145657999892, 191.8113400482999964, 104.3089204063000039 ) ) ; -#4628 = DIRECTION ( 'NONE', ( -0.6087613186456907188, -0.7730177010543248795, -0.1784749023741044327 ) ) ; -#4629 = CARTESIAN_POINT ( 'NONE', ( -24.27915398407497705, 213.2748068212543444, 73.57307564708263214 ) ) ; -#4630 = CIRCLE ( 'NONE', #13146, 2.250000000041454840 ) ; -#4631 = CONICAL_SURFACE ( 'NONE', #24251, 2.503164102235868604, 0.7853981633414612862 ) ; -#4632 = CARTESIAN_POINT ( 'NONE', ( -37.54329503931378298, 86.59195937703771051, 280.9751938861189728 ) ) ; -#4633 = EDGE_CURVE ( 'NONE', #34336, #33189, #29370, .T. ) ; -#4634 = VERTEX_POINT ( 'NONE', #8382 ) ; -#4635 = CONICAL_SURFACE ( 'NONE', #22291, 2.502999999978117618, 0.7853981634080025032 ) ; -#4636 = CARTESIAN_POINT ( 'NONE', ( -14.99833314732373246, 182.5837072631661613, 104.7226143053096052 ) ) ; -#4637 = EDGE_CURVE ( 'NONE', #14862, #37986, #20592, .T. ) ; -#4638 = CONICAL_SURFACE ( 'NONE', #29458, 4.999996804348348256, 0.7853981633997131340 ) ; -#4639 = EDGE_CURVE ( 'NONE', #19409, #9106, #1079, .T. ) ; -#4640 = CARTESIAN_POINT ( 'NONE', ( -20.00000588364686038, 174.5066637885302896, 99.95304239614711150 ) ) ; -#4641 = LINE ( 'NONE', #14467, #19072 ) ; -#4642 = FACE_OUTER_BOUND ( 'NONE', #137, .T. ) ; -#4643 = CARTESIAN_POINT ( 'NONE', ( 5.664743062628560644, 181.1015080686150895, 104.4647125381774941 ) ) ; -#4644 = CARTESIAN_POINT ( 'NONE', ( 37.82160095445000536, 190.5065482114999895, 106.5662966441000208 ) ) ; -#4645 = CARTESIAN_POINT ( 'NONE', ( 31.07270177211735174, 177.5903766379979629, 100.6341249661810906 ) ) ; -#4646 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474989203096108, 155.7928101624825956, 98.18628735359794746 ) ) ; -#4647 = PLANE ( 'NONE', #12545 ) ; -#4648 = CARTESIAN_POINT ( 'NONE', ( -38.36244646033240002, 118.8225362708849389, 87.71978071755118833 ) ) ; -#4649 = ORIENTED_EDGE ( 'NONE', *, *, #9461, .F. ) ; -#4651 = EDGE_CURVE ( 'NONE', #9324, #37873, #32446, .T. ) ; -#4650 = CARTESIAN_POINT ( 'NONE', ( -5.668553076709809346, 181.6128662714581310, 104.1507415746884391 ) ) ; -#4652 = PLANE ( 'NONE', #13230 ) ; -#4653 = CARTESIAN_POINT ( 'NONE', ( 37.35926580955523946, 118.3178168644534196, 87.24522023162664652 ) ) ; -#4654 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501101346, 129.6135529957512063, 92.66635095646515197 ) ) ; -#4655 = ORIENTED_EDGE ( 'NONE', *, *, #9943, .T. ) ; -#4656 = LINE ( 'NONE', #10217, #33096 ) ; -#4657 = CARTESIAN_POINT ( 'NONE', ( 3.780283637447459100, 136.7368630678065529, 94.04685604330656190 ) ) ; -#4658 = VECTOR ( 'NONE', #34180, 1000.000000000000114 ) ; -#4659 = ORIENTED_EDGE ( 'NONE', *, *, #34319, .T. ) ; -#4660 = EDGE_CURVE ( 'NONE', #39586, #13672, #448, .T. ) ; -#4661 = CIRCLE ( 'NONE', #30777, 6.000000000000001776 ) ; -#4662 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394469186868, 3.303562273565746580E-12, 297.5584364845187224 ) ) ; -#4663 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748615030, 134.6026445760790295, 93.28327864748658271 ) ) ; -#4664 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825940274355384, 0.0005734119019191435528 ) ) ; -#4665 = EDGE_LOOP ( 'NONE', ( #36301, #1335, #30452, #34959 ) ) ; -#4666 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825940409482753, 0.0005734119019167828110 ) ) ; -#4667 = CARTESIAN_POINT ( 'NONE', ( 3.608059120702661104, 167.8427776935849636, 101.4051864878073559 ) ) ; -#4668 = CYLINDRICAL_SURFACE ( 'NONE', #27965, 4.999999999999990230 ) ; -#4669 = CARTESIAN_POINT ( 'NONE', ( 21.25891437287570440, 136.8714408223384567, 91.75249562560091476 ) ) ; -#4670 = CARTESIAN_POINT ( 'NONE', ( 15.75161875086000052, 184.8197207970999898, 105.1347412410000004 ) ) ; -#4671 = VERTEX_POINT ( 'NONE', #34695 ) ; -#4672 = CARTESIAN_POINT ( 'NONE', ( 16.56077817173662936, 151.9932236380383586, 182.4670194890501875 ) ) ; -#4673 = CARTESIAN_POINT ( 'NONE', ( 12.63727515886041175, 181.9878585597662948, 102.0677450848580463 ) ) ; -#4674 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; -#4675 = ORIENTED_EDGE ( 'NONE', *, *, #32407, .F. ) ; -#4676 = CYLINDRICAL_SURFACE ( 'NONE', #38623, 2.000000000000001332 ) ; -#4677 = ORIENTED_EDGE ( 'NONE', *, *, #5684, .T. ) ; -#4678 = CYLINDRICAL_SURFACE ( 'NONE', #27073, 1.999999999999999112 ) ; -#4679 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #16926, #599 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4680 = FACE_OUTER_BOUND ( 'NONE', #40139, .T. ) ; -#4681 = CARTESIAN_POINT ( 'NONE', ( -30.06407784565124430, 177.7873364699197793, 100.7165267053679969 ) ) ; -#4682 = CARTESIAN_POINT ( 'NONE', ( -19.28424117596089715, 124.3280322740279189, 178.4026130020181427 ) ) ; -#4683 = ADVANCED_FACE ( 'NONE', ( #28203 ), #31993, .F. ) ; -#4684 = AXIS2_PLACEMENT_3D ( 'NONE', #24970, #12085, #9019 ) ; -#4685 = EDGE_CURVE ( 'NONE', #8959, #25850, #7400, .T. ) ; -#4686 = CARTESIAN_POINT ( 'NONE', ( 18.98784741603935089, 148.4369364876176292, 183.7046361175107450 ) ) ; -#4687 = AXIS2_PLACEMENT_3D ( 'NONE', #20364, #26524, #32840 ) ; -#4688 = CARTESIAN_POINT ( 'NONE', ( -13.49823352275769395, 126.1251030033876361, 91.86135017785642276 ) ) ; -#4689 = AXIS2_PLACEMENT_3D ( 'NONE', #3178, #2794, #34250 ) ; -#4690 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#4691 = DIRECTION ( 'NONE', ( 0.0006039748319385316970, 1.156831349449291921E-15, 0.9999998176071845934 ) ) ; -#4692 = CARTESIAN_POINT ( 'NONE', ( 20.50147102596341853, 119.8278772368997380, 89.87074405082867656 ) ) ; -#4693 = ORIENTED_EDGE ( 'NONE', *, *, #39082, .F. ) ; -#4694 = CARTESIAN_POINT ( 'NONE', ( 3.499881480001497458, 128.5116462485979696, 89.66216756041531255 ) ) ; -#4695 = CARTESIAN_POINT ( 'NONE', ( -0.02805196447938418727, 127.1761617620222893, 297.5585619722723436 ) ) ; -#4696 = CARTESIAN_POINT ( 'NONE', ( -25.86970796406206574, 117.9463803759205405, 170.9998979181758614 ) ) ; -#4697 = FACE_OUTER_BOUND ( 'NONE', #24415, .T. ) ; -#4698 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8212, #16980, #23543, #1669 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 2.414395626052624255, 2.591408619140276759 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973905707491301786, 0.9973905707491301786, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#4699 = DIRECTION ( 'NONE', ( -0.6087611427445811518, -0.7731004622513006908, -0.1781166650011639374 ) ) ; -#4700 = ORIENTED_EDGE ( 'NONE', *, *, #10844, .T. ) ; -#4701 = ORIENTED_EDGE ( 'NONE', *, *, #8546, .T. ) ; -#4702 = ORIENTED_EDGE ( 'NONE', *, *, #28163, .F. ) ; -#4703 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971561239 ) ) ; -#4704 = CARTESIAN_POINT ( 'NONE', ( 15.83331839798551499, 138.4673770510489135, 91.78223853853539538 ) ) ; -#4705 = ORIENTED_EDGE ( 'NONE', *, *, #40044, .T. ) ; -#4706 = CARTESIAN_POINT ( 'NONE', ( -14.55129768904543930, 135.1122403316443581, 93.93374132341575944 ) ) ; -#4707 = EDGE_CURVE ( 'NONE', #24392, #26636, #5457, .T. ) ; -#4708 = CARTESIAN_POINT ( 'NONE', ( -13.49659569010611548, 187.5255899304984553, 105.8396958350310939 ) ) ; -#4709 = DIRECTION ( 'NONE', ( -0.0005884949961240770570, 0.2255194585872583313, -0.9742384859325510238 ) ) ; -#4710 = CARTESIAN_POINT ( 'NONE', ( -19.15235677364794142, 125.6631553015295992, 176.1837327014617358 ) ) ; -#4711 = VERTEX_POINT ( 'NONE', #28595 ) ; -#4712 = CARTESIAN_POINT ( 'NONE', ( -76.10866181110002060, 156.0153766034999876, 97.25733412651000265 ) ) ; -#4713 = ORIENTED_EDGE ( 'NONE', *, *, #4039, .F. ) ; -#4714 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858958, 183.1686750955933576, 104.5300206044594091 ) ) ; -#4715 = AXIS2_PLACEMENT_3D ( 'NONE', #31285, #34335, #28036 ) ; -#4716 = CARTESIAN_POINT ( 'NONE', ( 5.669295872926322311, 130.1822457206637296, 92.55708892453651515 ) ) ; -#4717 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384972194 ) ) ; -#4718 = CYLINDRICAL_SURFACE ( 'NONE', #28864, 6.000000000000008882 ) ; -#4719 = AXIS2_PLACEMENT_3D ( 'NONE', #12505, #30734, #27884 ) ; -#4720 = ORIENTED_EDGE ( 'NONE', *, *, #37380, .T. ) ; -#4721 = CARTESIAN_POINT ( 'NONE', ( -19.70071604027683065, 149.4445624503525778, 181.7665744593643637 ) ) ; -#4722 = VECTOR ( 'NONE', #26344, 1000.000000000000227 ) ; -#4723 = LINE ( 'NONE', #13139, #19202 ) ; -#4724 = CARTESIAN_POINT ( 'NONE', ( 28.46875780327905403, 130.1006733151145909, 92.40864205061642167 ) ) ; -#4725 = CARTESIAN_POINT ( 'NONE', ( 26.07306197714198248, 120.9961311236103541, 90.65024403513507423 ) ) ; -#4726 = EDGE_LOOP ( 'NONE', ( #39149, #865 ) ) ; -#4727 = ORIENTED_EDGE ( 'NONE', *, *, #16050, .F. ) ; -#4728 = CARTESIAN_POINT ( 'NONE', ( -20.33367336965308780, 118.1180462047051947, 87.61411334273522300 ) ) ; -#4729 = CARTESIAN_POINT ( 'NONE', ( -34.95638760651608834, 217.7719116314000019, 73.57961695566839921 ) ) ; -#4730 = ORIENTED_EDGE ( 'NONE', *, *, #12578, .T. ) ; -#4731 = VERTEX_POINT ( 'NONE', #22062 ) ; -#4732 = ORIENTED_EDGE ( 'NONE', *, *, #19926, .T. ) ; -#4733 = ORIENTED_EDGE ( 'NONE', *, *, #15698, .F. ) ; -#4734 = EDGE_CURVE ( 'NONE', #20205, #38824, #20073, .T. ) ; -#4735 = CARTESIAN_POINT ( 'NONE', ( 3.054829480853488377, 190.6506292567034677, 106.7451573915843284 ) ) ; -#4736 = ADVANCED_FACE ( 'NONE', ( #19161 ), #37004, .T. ) ; -#4737 = CARTESIAN_POINT ( 'NONE', ( -27.86428169786740128, 186.6957439683559699, 105.3359119473810068 ) ) ; -#4738 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714601725811, 0.5299193037554699170 ) ) ; -#4739 = CARTESIAN_POINT ( 'NONE', ( -15.10714335811488773, 183.0966620568070198, 101.9332428217494027 ) ) ; -#4740 = CIRCLE ( 'NONE', #19756, 2.499999999999997335 ) ; -#4741 = ORIENTED_EDGE ( 'NONE', *, *, #33856, .T. ) ; -#4742 = CARTESIAN_POINT ( 'NONE', ( 27.53514821939999990, 124.1339620642999932, 91.20273972887000014 ) ) ; -#4743 = FACE_OUTER_BOUND ( 'NONE', #21558, .T. ) ; -#4744 = VECTOR ( 'NONE', #12600, 1000.000000000000000 ) ; -#4746 = CARTESIAN_POINT ( 'NONE', ( -30.05378920129078679, 185.1945982732621303, 102.9397691308601566 ) ) ; -#4745 = DIRECTION ( 'NONE', ( 0.0004161288024550070493, -0.8480480897973143861, 0.5299191110235090818 ) ) ; -#4747 = ORIENTED_EDGE ( 'NONE', *, *, #12626, .T. ) ; -#4748 = CIRCLE ( 'NONE', #22430, 5.000000000000007994 ) ; -#4749 = ORIENTED_EDGE ( 'NONE', *, *, #37098, .F. ) ; -#4750 = ORIENTED_EDGE ( 'NONE', *, *, #25837, .F. ) ; -#4751 = CARTESIAN_POINT ( 'NONE', ( 29.05442967595000070, 110.6131156702000027, 88.75023641814000541 ) ) ; -#4752 = FACE_OUTER_BOUND ( 'NONE', #38629, .T. ) ; -#4753 = LINE ( 'NONE', #27071, #636 ) ; -#4754 = VERTEX_POINT ( 'NONE', #22268 ) ; -#4755 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25584, #212, #31718, #12692, #9237, #37830, #28835, #10029, #6541, #13300, #25184, #25376, #9434, #19011, #9841, #38030, #6740 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000004636014, 0.1875000000007515932, 0.2187500000008642531, 0.2343750000008895107, 0.2500000000009147683, 0.3750000000009675594, 0.4375000000009690582, 0.4687500000009482970, 0.5000000000009274803, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4756 = ORIENTED_EDGE ( 'NONE', *, *, #27221, .T. ) ; -#4757 = CARTESIAN_POINT ( 'NONE', ( -38.40287610445658117, 121.6088961281960366, 92.88326245006905424 ) ) ; -#4758 = VERTEX_POINT ( 'NONE', #31668 ) ; -#4759 = CARTESIAN_POINT ( 'NONE', ( -35.60095806785000860, 192.5993474919999926, 106.7397797018000034 ) ) ; -#4760 = AXIS2_PLACEMENT_3D ( 'NONE', #31564, #6797, #12961 ) ; -#4761 = ADVANCED_FACE ( 'NONE', ( #34891 ), #3628, .T. ) ; -#4762 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #316, #37938, #25694, #34837, #32213, #31822, #13402, #37729, #34646, #3778 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4763 = AXIS2_PLACEMENT_3D ( 'NONE', #17058, #14226, #17668 ) ; -#4764 = CARTESIAN_POINT ( 'NONE', ( 3.080804014109543854, 190.8472021536144609, 106.8075760281446236 ) ) ; -#4765 = ORIENTED_EDGE ( 'NONE', *, *, #31076, .F. ) ; -#4766 = DIRECTION ( 'NONE', ( -0.0006039748319390056018, -1.156901198131326670E-14, -0.9999998176071845934 ) ) ; -#4767 = ADVANCED_FACE ( 'NONE', ( #32265 ), #10396, .T. ) ; -#4768 = AXIS2_PLACEMENT_3D ( 'NONE', #37306, #34023, #27928 ) ; -#4769 = CARTESIAN_POINT ( 'NONE', ( 15.66685957430246212, 126.7291730765401638, 89.24329869400926896 ) ) ; -#4770 = DIRECTION ( 'NONE', ( 0.0005884949961203373185, -0.2249510543439093846, 0.9743698870671255730 ) ) ; -#4771 = CARTESIAN_POINT ( 'NONE', ( 40.67331120850098358, 184.3716013758799761, 104.7596565504592547 ) ) ; -#4772 = ORIENTED_EDGE ( 'NONE', *, *, #34850, .T. ) ; -#4773 = EDGE_CURVE ( 'NONE', #39471, #13855, #20683, .T. ) ; -#4774 = EDGE_CURVE ( 'NONE', #662, #23150, #33696, .T. ) ; -#4775 = LINE ( 'NONE', #2138, #40137 ) ; -#4776 = CARTESIAN_POINT ( 'NONE', ( 30.44722896069117724, 127.1067747388918434, 88.97944275832713856 ) ) ; -#4777 = ADVANCED_FACE ( 'NONE', ( #19965 ), #39185, .T. ) ; -#4778 = ADVANCED_FACE ( 'NONE', ( #4028 ), #26738, .F. ) ; -#4779 = VERTEX_POINT ( 'NONE', #7102 ) ; -#4780 = CARTESIAN_POINT ( 'NONE', ( 33.46336677059740339, 81.57552323989831677, 288.3251734967106472 ) ) ; -#4782 = CARTESIAN_POINT ( 'NONE', ( -36.24326983097000010, 115.8895241964000036, 90.15716172436000875 ) ) ; -#4781 = DIRECTION ( 'NONE', ( -0.000000000000000000, -1.000000000000000000, 0.000000000000000000 ) ) ; -#4783 = ORIENTED_EDGE ( 'NONE', *, *, #8463, .T. ) ; -#4784 = VECTOR ( 'NONE', #27425, 1000.000000000000000 ) ; -#4785 = ORIENTED_EDGE ( 'NONE', *, *, #25640, .T. ) ; -#4786 = CARTESIAN_POINT ( 'NONE', ( 16.88249520722548169, 148.9778306577506726, 176.8903484419645622 ) ) ; -#4787 = CARTESIAN_POINT ( 'NONE', ( -13.49987458194983425, 124.7394176591053423, 88.97259030931672896 ) ) ; -#4788 = CARTESIAN_POINT ( 'NONE', ( -13.49946409159211669, 123.8765466711892742, 91.17938207915341309 ) ) ; -#4790 = ORIENTED_EDGE ( 'NONE', *, *, #1742, .F. ) ; -#4789 = AXIS2_PLACEMENT_3D ( 'NONE', #29716, #23175, #10915 ) ; -#4791 = EDGE_LOOP ( 'NONE', ( #23565, #27285, #37128 ) ) ; -#4792 = DIRECTION ( 'NONE', ( -0.6087614115774880874, 0.7730004600455407937, 0.1785492440296698458 ) ) ; -#4793 = VERTEX_POINT ( 'NONE', #4640 ) ; -#4794 = ORIENTED_EDGE ( 'NONE', *, *, #22573, .F. ) ; -#4795 = ORIENTED_EDGE ( 'NONE', *, *, #13893, .F. ) ; -#4796 = CARTESIAN_POINT ( 'NONE', ( 14.35597858069445465, 190.8513438264349134, 106.7846703957270904 ) ) ; -#4797 = CIRCLE ( 'NONE', #15274, 5.500000707771594222 ) ; -#4798 = EDGE_CURVE ( 'NONE', #32100, #1393, #16497, .T. ) ; -#4799 = CARTESIAN_POINT ( 'NONE', ( 2.802951049184000176, 209.5843744970999865, 73.22346325304999937 ) ) ; -#4800 = ORIENTED_EDGE ( 'NONE', *, *, #34899, .F. ) ; -#4801 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#4802 = CARTESIAN_POINT ( 'NONE', ( -36.03544878659999995, 191.6081880703000024, 104.0158779490000001 ) ) ; -#4803 = CARTESIAN_POINT ( 'NONE', ( -26.00229023349000101, 120.8686760094000050, 87.57325582845000156 ) ) ; -#4804 = VERTEX_POINT ( 'NONE', #4833 ) ; -#4805 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; -#4806 = CARTESIAN_POINT ( 'NONE', ( 22.77977433793355999, 158.3069438176785582, 96.18720162681876218 ) ) ; -#4807 = DIRECTION ( 'NONE', ( 0.0005884949961228161299, -0.2249510543439076360, 0.9743698870671260170 ) ) ; -#4808 = VERTEX_POINT ( 'NONE', #10996 ) ; -#4809 = ADVANCED_FACE ( 'NONE', ( #32069 ), #7295, .T. ) ; -#4810 = CARTESIAN_POINT ( 'NONE', ( -20.51863885680050359, 209.7097602209678939, 75.57089512796630970 ) ) ; -#4811 = FACE_OUTER_BOUND ( 'NONE', #2519, .T. ) ; -#4812 = CARTESIAN_POINT ( 'NONE', ( 20.50021201310788044, 195.1792461124052522, 105.0717163744397595 ) ) ; -#4813 = CARTESIAN_POINT ( 'NONE', ( 45.47174799569548753, 185.9669337813575396, 105.9176514305813441 ) ) ; -#4814 = ORIENTED_EDGE ( 'NONE', *, *, #27015, .F. ) ; -#4815 = CARTESIAN_POINT ( 'NONE', ( 17.27337838772892553, 121.3064376902564589, 177.4324028043064345 ) ) ; -#4816 = EDGE_CURVE ( 'NONE', #7173, #5222, #12701, .T. ) ; -#4817 = CARTESIAN_POINT ( 'NONE', ( 5.674778016381245571, 131.0223034755605909, 89.89838139801142347 ) ) ; -#4818 = VECTOR ( 'NONE', #11603, 1000.000000000000000 ) ; -#4819 = CARTESIAN_POINT ( 'NONE', ( 31.60023222786816177, 135.4070683171111966, 90.89502048698429348 ) ) ; -#4820 = EDGE_CURVE ( 'NONE', #7212, #31691, #11776, .T. ) ; -#4821 = ORIENTED_EDGE ( 'NONE', *, *, #6904, .F. ) ; -#4822 = ORIENTED_EDGE ( 'NONE', *, *, #17708, .T. ) ; -#4823 = VECTOR ( 'NONE', #30884, 1000.000000000000000 ) ; -#4824 = CARTESIAN_POINT ( 'NONE', ( -26.12881852497000068, 191.7883093318000078, 103.7920838617999948 ) ) ; -#4825 = EDGE_CURVE ( 'NONE', #15715, #33368, #1573, .T. ) ; -#4826 = PLANE ( 'NONE', #15348 ) ; -#4827 = CARTESIAN_POINT ( 'NONE', ( -23.34729099692994936, 213.5902299287207029, 73.57263793552689890 ) ) ; -#4828 = CARTESIAN_POINT ( 'NONE', ( -6.612072173594106393E-14, 161.0393699423707972, 99.91070331020887352 ) ) ; -#4829 = AXIS2_PLACEMENT_3D ( 'NONE', #4662, #985, #25963 ) ; -#4830 = CARTESIAN_POINT ( 'NONE', ( 22.78190537993189224, 158.0318634473625536, 98.86050528674346083 ) ) ; -#4831 = ORIENTED_EDGE ( 'NONE', *, *, #15459, .T. ) ; -#4832 = CARTESIAN_POINT ( 'NONE', ( 20.00176513866536965, 118.9456690639568990, 90.18052439326535819 ) ) ; -#4833 = CARTESIAN_POINT ( 'NONE', ( -14.55129769642598703, 176.2445762652153007, 103.4298910492225616 ) ) ; -#4834 = CARTESIAN_POINT ( 'NONE', ( -15.46321445985169873, 124.1316392283082450, 152.4730753928283775 ) ) ; -#4835 = DIRECTION ( 'NONE', ( 0.0001358648856691746900, 0.9743700647852248098, 0.2249510133143870216 ) ) ; -#4836 = CARTESIAN_POINT ( 'NONE', ( 22.50059290207999396, 154.2095289565698124, 95.41246725570897524 ) ) ; -#4837 = CARTESIAN_POINT ( 'NONE', ( 36.42681392942999707, 191.0436009519999914, 106.6811892480999973 ) ) ; -#4838 = DIRECTION ( 'NONE', ( -0.0006039748319391919761, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#4839 = DIRECTION ( 'NONE', ( -0.0005884949961254009763, 0.2249510543439060262, -0.9743698870671263501 ) ) ; -#4840 = PLANE ( 'NONE', #39581 ) ; -#4841 = EDGE_LOOP ( 'NONE', ( #30503, #5723, #15797, #17645 ) ) ; -#4842 = VECTOR ( 'NONE', #35743, 1000.000000000000227 ) ; -#4843 = VECTOR ( 'NONE', #16490, 1000.000000000000114 ) ; -#4844 = DIRECTION ( 'NONE', ( 0.0006039748319395906373, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#4845 = CARTESIAN_POINT ( 'NONE', ( 3.585551889548043825, 144.2098241759302084, 92.99688381113877256 ) ) ; -#4846 = VECTOR ( 'NONE', #30654, 1000.000000000000114 ) ; -#4847 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709481474, 77.27946979429643193, 322.5205145037752459 ) ) ; -#4848 = AXIS2_PLACEMENT_3D ( 'NONE', #25316, #28769, #9768 ) ; -#4849 = ORIENTED_EDGE ( 'NONE', *, *, #25384, .F. ) ; -#4850 = DIRECTION ( 'NONE', ( 0.0005884949961258187194, -0.2249510543439062760, 0.9743698870671264611 ) ) ; -#4851 = VECTOR ( 'NONE', #2459, 1000.000000000000227 ) ; -#4852 = EDGE_LOOP ( 'NONE', ( #11713, #11540, #13674, #1694 ) ) ; -#4853 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #18008, #5133, #33760 ), - ( #17606, #9032, #27473 ), - ( #39895, #32947, #5759 ), - ( #30715, #14568, #11703 ) ), - .UNSPECIFIED., .F., .F., .T. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), - ( 3, 3 ), - ( 0.003213125900859597692, 0.003266714168266309296 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.7110173697362405232, 1.000000000000000000), - ( 1.000000000000000000, 0.7097605058162677061, 1.000000000000000000), - ( 1.000000000000000000, 0.7084892703251066681, 1.000000000000000000), - ( 1.000000000000000000, 0.7072031799626566917, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#4854 = DIRECTION ( 'NONE', ( 0.0002393071182785071779, 0.2252352986010040525, -0.9743043687658491381 ) ) ; -#4855 = CARTESIAN_POINT ( 'NONE', ( -17.26213291099019997, 152.2612616225560771, 183.6636115490260863 ) ) ; -#4856 = ORIENTED_EDGE ( 'NONE', *, *, #17035, .T. ) ; -#4857 = CARTESIAN_POINT ( 'NONE', ( 25.46575390506999881, 213.5902260771000272, 32.39311599089000282 ) ) ; -#4858 = EDGE_CURVE ( 'NONE', #23757, #3973, #13458, .T. ) ; -#4859 = ADVANCED_FACE ( 'NONE', ( #25941 ), #7704, .T. ) ; -#4860 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; -#4862 = ADVANCED_FACE ( 'NONE', ( #1367 ), #22682, .T. ) ; -#4861 = FACE_OUTER_BOUND ( 'NONE', #36235, .T. ) ; -#4863 = DIRECTION ( 'NONE', ( -0.0005884949961278631994, 0.2249510543439048327, -0.9743698870671267942 ) ) ; -#4865 = EDGE_CURVE ( 'NONE', #12760, #1525, #38997, .T. ) ; -#4864 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1691, #32953, #24191, #4950 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4866 = LINE ( 'NONE', #11414, #15044 ) ; -#4867 = CARTESIAN_POINT ( 'NONE', ( -3.669581230394507898, 185.7947741359049019, 103.0623953380812168 ) ) ; -#4868 = ORIENTED_EDGE ( 'NONE', *, *, #29196, .F. ) ; -#4869 = LINE ( 'NONE', #35119, #34924 ) ; -#4870 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#4871 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2427, #39813, #24917, #14891, #36754, #15094, #31226, #8762, #33677, #5685, #18132 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998300804, 0.3749999999997295497, 0.4374999999996792011, 0.4687499999996728728, 0.4999999999996664890, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4872 = CARTESIAN_POINT ( 'NONE', ( 47.95588533879620741, 89.40266445833195519, 291.5248371983224729 ) ) ; -#4873 = EDGE_CURVE ( 'NONE', #35062, #26640, #28569, .T. ) ; -#4874 = ORIENTED_EDGE ( 'NONE', *, *, #3431, .F. ) ; -#4875 = CARTESIAN_POINT ( 'NONE', ( -45.68381200445116264, 124.6973070541615414, 92.04274264343763434 ) ) ; -#4876 = ORIENTED_EDGE ( 'NONE', *, *, #22580, .F. ) ; -#4877 = CARTESIAN_POINT ( 'NONE', ( 3.666638755385807080, 126.6906504152049706, 89.41269982467663624 ) ) ; -#4878 = CARTESIAN_POINT ( 'NONE', ( -43.71968941974858325, 120.3868516857203872, 91.27386099642183126 ) ) ; -#4879 = AXIS2_PLACEMENT_3D ( 'NONE', #30339, #17032, #32986 ) ; -#4880 = CYLINDRICAL_SURFACE ( 'NONE', #16341, 2.500000000000002220 ) ; -#4881 = CARTESIAN_POINT ( 'NONE', ( -28.38456979805999936, 125.0358147611000135, 91.22736114040000643 ) ) ; -#4882 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#4883 = EDGE_CURVE ( 'NONE', #7762, #2748, #38330, .T. ) ; -#4884 = CIRCLE ( 'NONE', #10129, 6.500001087336261030 ) ; -#4885 = CONICAL_SURFACE ( 'NONE', #8855, 6.503080706119665599, 0.7853981633713218447 ) ; -#4886 = PLANE ( 'NONE', #23453 ) ; -#4887 = CARTESIAN_POINT ( 'NONE', ( -45.56069752896866731, 133.9656849080258496, 337.3347232553839490 ) ) ; -#4888 = AXIS2_PLACEMENT_3D ( 'NONE', #28157, #24292, #25095 ) ; -#4889 = CARTESIAN_POINT ( 'NONE', ( -19.99850934198748931, 160.0545621481389844, 99.69532483852709959 ) ) ; -#4890 = DIRECTION ( 'NONE', ( 0.0005884949961179900208, -0.2249510543439076360, 0.9743698870671260170 ) ) ; -#4891 = ADVANCED_FACE ( 'NONE', ( #27760 ), #39995, .F. ) ; -#4892 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319381716335 ) ) ; -#4893 = CARTESIAN_POINT ( 'NONE', ( 3.333080673702689456, 183.2502631384639074, 101.9575669988970645 ) ) ; -#4894 = ORIENTED_EDGE ( 'NONE', *, *, #37346, .F. ) ; -#4895 = CARTESIAN_POINT ( 'NONE', ( -1.237265163634357679, 156.7699511568839625, 100.9789453716980177 ) ) ; -#4896 = CARTESIAN_POINT ( 'NONE', ( -20.49957633237145060, 118.5814696803204384, 87.78009030275359237 ) ) ; -#4897 = CARTESIAN_POINT ( 'NONE', ( -23.36013443158915237, 136.6763330450122567, 94.30332275863374036 ) ) ; -#4899 = EDGE_LOOP ( 'NONE', ( #25926, #35599, #35510, #21481, #22707 ) ) ; -#4898 = CARTESIAN_POINT ( 'NONE', ( 37.28139794753688108, 124.9423866440358069, 93.60865750304402866 ) ) ; -#4900 = ORIENTED_EDGE ( 'NONE', *, *, #20691, .F. ) ; -#4901 = ORIENTED_EDGE ( 'NONE', *, *, #5947, .F. ) ; -#4902 = ORIENTED_EDGE ( 'NONE', *, *, #18297, .T. ) ; -#4903 = CARTESIAN_POINT ( 'NONE', ( -23.35526879455558813, 177.7631879465995723, 100.7283305276877172 ) ) ; -#4904 = CARTESIAN_POINT ( 'NONE', ( 29.37172806597842722, 112.1957651408767873, 175.8423023756299131 ) ) ; -#4905 = CYLINDRICAL_SURFACE ( 'NONE', #31141, 2.000000000000011546 ) ; -#4906 = ORIENTED_EDGE ( 'NONE', *, *, #7920, .T. ) ; -#4907 = AXIS2_PLACEMENT_3D ( 'NONE', #1930, #14400, #27907 ) ; -#4908 = DIRECTION ( 'NONE', ( -0.0005884949961246456127, 0.2249510543439063592, -0.9743698870671262391 ) ) ; -#4909 = CIRCLE ( 'NONE', #27803, 2.499999999994544364 ) ; -#4910 = CIRCLE ( 'NONE', #37579, 2.000000000004209522 ) ; -#4911 = CARTESIAN_POINT ( 'NONE', ( 26.73277628323574717, 120.3821797830261033, 171.5759152015846496 ) ) ; -#4912 = ORIENTED_EDGE ( 'NONE', *, *, #38928, .T. ) ; -#4913 = CIRCLE ( 'NONE', #13422, 2.000000000000011546 ) ; -#4914 = LINE ( 'NONE', #14337, #12744 ) ; -#4915 = EDGE_CURVE ( 'NONE', #28666, #24015, #39638, .T. ) ; -#4916 = ORIENTED_EDGE ( 'NONE', *, *, #35733, .T. ) ; -#4917 = EDGE_CURVE ( 'NONE', #29169, #21974, #33658, .T. ) ; -#4918 = CARTESIAN_POINT ( 'NONE', ( -27.80047107912594484, 149.4166296170034514, 291.5753347231419639 ) ) ; -#4919 = AXIS2_PLACEMENT_3D ( 'NONE', #31077, #31266, #40056 ) ; -#4920 = EDGE_CURVE ( 'NONE', #34430, #10571, #24288, .T. ) ; -#4921 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.894780628693970840E-14, 0.9999998176071847045 ) ) ; -#4922 = CARTESIAN_POINT ( 'NONE', ( -3.169795749769255711, 186.0607901153434511, 102.6103559709178654 ) ) ; -#4923 = CARTESIAN_POINT ( 'NONE', ( -35.93925692342736511, 191.9759150222000130, 101.9431537509079817 ) ) ; -#4924 = ORIENTED_EDGE ( 'NONE', *, *, #25161, .F. ) ; -#4925 = CARTESIAN_POINT ( 'NONE', ( -2.438021043067000182, 190.8225405149999858, 104.2122243419999990 ) ) ; -#4926 = CARTESIAN_POINT ( 'NONE', ( 0.6371225951570861357, 189.0073665696679655, 103.6986168510260029 ) ) ; -#4927 = CARTESIAN_POINT ( 'NONE', ( -35.95543229855000078, 209.7096535459000108, 75.16162026493999804 ) ) ; -#4928 = CARTESIAN_POINT ( 'NONE', ( 26.00087991994412917, 120.1719190573502090, 90.46000324774034596 ) ) ; -#4929 = EDGE_CURVE ( 'NONE', #33034, #15187, #8122, .T. ) ; -#4930 = ORIENTED_EDGE ( 'NONE', *, *, #25348, .T. ) ; -#4931 = CARTESIAN_POINT ( 'NONE', ( -2.454332449978999797, 209.0617968418999908, 75.63992803070000548 ) ) ; -#4932 = ORIENTED_EDGE ( 'NONE', *, *, #33295, .F. ) ; -#4933 = VERTEX_POINT ( 'NONE', #15072 ) ; -#4934 = EDGE_CURVE ( 'NONE', #15039, #19726, #30303, .T. ) ; -#4935 = ORIENTED_EDGE ( 'NONE', *, *, #22812, .T. ) ; -#4936 = AXIS2_PLACEMENT_3D ( 'NONE', #16718, #787, #22689 ) ; -#4937 = ORIENTED_EDGE ( 'NONE', *, *, #38025, .T. ) ; -#4938 = AXIS2_PLACEMENT_3D ( 'NONE', #30721, #4949, #5353 ) ; -#4939 = CARTESIAN_POINT ( 'NONE', ( -38.94691154124904386, 128.1851843107897650, 89.27032559287691527 ) ) ; -#4940 = CARTESIAN_POINT ( 'NONE', ( -39.75024793617362917, 128.4756217986020488, 92.41677646255658374 ) ) ; -#4941 = EDGE_CURVE ( 'NONE', #32409, #34827, #11803, .T. ) ; -#4942 = VERTEX_POINT ( 'NONE', #8534 ) ; -#4943 = CARTESIAN_POINT ( 'NONE', ( 25.99877525812749468, 118.1153592017238338, 87.25208168324967062 ) ) ; -#4944 = VECTOR ( 'NONE', #29797, 1000.000000000000114 ) ; -#4945 = VERTEX_POINT ( 'NONE', #2795 ) ; -#4946 = CIRCLE ( 'NONE', #19930, 2.000000000000011546 ) ; -#4947 = CARTESIAN_POINT ( 'NONE', ( 26.02941144344040580, 120.6378765363000269, 90.57112595491780382 ) ) ; -#4948 = CARTESIAN_POINT ( 'NONE', ( -43.27414346572250992, 128.2423119564918466, 92.36504097611086195 ) ) ; -#4950 = CARTESIAN_POINT ( 'NONE', ( -23.35464359634993770, 177.7881151143831744, 100.7126876897662697 ) ) ; -#4949 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#4951 = ORIENTED_EDGE ( 'NONE', *, *, #21619, .T. ) ; -#4952 = ORIENTED_EDGE ( 'NONE', *, *, #12729, .T. ) ; -#4953 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6962, #16762, #1431, #20232, #23124, #22926 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#4954 = VERTEX_POINT ( 'NONE', #17502 ) ; -#4955 = LINE ( 'NONE', #29916, #23090 ) ; -#4956 = CARTESIAN_POINT ( 'NONE', ( -21.82845856935587037, 135.5369429020799146, 93.52303473086848840 ) ) ; -#4957 = CARTESIAN_POINT ( 'NONE', ( 20.33347830596183314, 160.6696382356835500, 97.07619954612073343 ) ) ; -#4958 = ORIENTED_EDGE ( 'NONE', *, *, #170, .T. ) ; -#4959 = ORIENTED_EDGE ( 'NONE', *, *, #14903, .T. ) ; -#4960 = VECTOR ( 'NONE', #19342, 1000.000000000000000 ) ; -#4962 = ADVANCED_FACE ( 'NONE', ( #39787 ), #5659, .F. ) ; -#4961 = CARTESIAN_POINT ( 'NONE', ( -2.438083998875509639, 190.8225490817534933, 104.2121631052086315 ) ) ; -#4963 = DIRECTION ( 'NONE', ( -0.0006039748319388572829, -3.099784637799882324E-15, -0.9999998176071847045 ) ) ; -#4964 = EDGE_CURVE ( 'NONE', #19017, #35125, #7839, .T. ) ; -#4965 = VECTOR ( 'NONE', #7970, 1000.000000000000114 ) ; -#4966 = AXIS2_PLACEMENT_3D ( 'NONE', #32012, #1311, #13595 ) ; -#4967 = CARTESIAN_POINT ( 'NONE', ( 15.14910835783079079, 187.7483930415743316, 102.9889057178500735 ) ) ; -#4968 = ORIENTED_EDGE ( 'NONE', *, *, #21192, .T. ) ; -#4969 = CARTESIAN_POINT ( 'NONE', ( 30.06788789467000456, 135.1647620141970094, 91.17105285833032724 ) ) ; -#4970 = CARTESIAN_POINT ( 'NONE', ( -37.85985168709885329, 117.8113977611419187, 89.71713298447978957 ) ) ; -#4971 = AXIS2_PLACEMENT_3D ( 'NONE', #34610, #1084, #31579 ) ; -#4972 = AXIS2_PLACEMENT_3D ( 'NONE', #22992, #35615, #35415 ) ; -#4973 = CARTESIAN_POINT ( 'NONE', ( 3.074439616337855785, 190.7388267800502035, 106.7754277006573176 ) ) ; -#4974 = EDGE_LOOP ( 'NONE', ( #3301, #4821, #20854, #3357 ) ) ; -#4975 = CARTESIAN_POINT ( 'NONE', ( 39.10488449847447612, 118.9309680717053084, 89.68369243349377484 ) ) ; -#4976 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000094147, 179.7424522644965634, 101.1388664480874269 ) ) ; -#4977 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555133 ) ) ; -#4978 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825711345, 184.4051477319173955, 104.7783766748929821 ) ) ; -#4979 = ORIENTED_EDGE ( 'NONE', *, *, #405, .F. ) ; -#4980 = FACE_OUTER_BOUND ( 'NONE', #34228, .T. ) ; -#4981 = CARTESIAN_POINT ( 'NONE', ( 29.40506628721518112, 160.9732782815168832, 187.1184765030605774 ) ) ; -#4982 = EDGE_CURVE ( 'NONE', #27492, #39268, #27873, .T. ) ; -#4983 = ORIENTED_EDGE ( 'NONE', *, *, #31456, .F. ) ; -#4984 = FACE_OUTER_BOUND ( 'NONE', #41, .T. ) ; -#4985 = AXIS2_PLACEMENT_3D ( 'NONE', #13712, #20034, #32519 ) ; -#4986 = AXIS2_PLACEMENT_3D ( 'NONE', #6905, #9790, #9583 ) ; -#4988 = LINE ( 'NONE', #11328, #10941 ) ; -#4987 = CARTESIAN_POINT ( 'NONE', ( 13.73173069815889491, 135.3487696960925177, 90.89235331452654520 ) ) ; -#4989 = VERTEX_POINT ( 'NONE', #39382 ) ; -#4990 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24362, #36811, #6127, #18184 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0007138690537832477175, 0.0007171792812430367522 ), - .UNSPECIFIED. ) ; -#4991 = ORIENTED_EDGE ( 'NONE', *, *, #22290, .F. ) ; -#4993 = AXIS2_PLACEMENT_3D ( 'NONE', #6783, #13542, #23149 ) ; -#4992 = CARTESIAN_POINT ( 'NONE', ( 2.826471639010999848, 209.6751949233000403, 75.93526320658999396 ) ) ; -#4994 = ADVANCED_FACE ( 'NONE', ( #5861 ), #27271, .F. ) ; -#4995 = CARTESIAN_POINT ( 'NONE', ( 37.26718118745528585, 191.0824230493275309, 106.2979611257835728 ) ) ; -#4996 = VECTOR ( 'NONE', #20154, 1000.000000000000000 ) ; -#4997 = CARTESIAN_POINT ( 'NONE', ( 22.33189175409000171, 129.8624845047999941, 92.69946294856001145 ) ) ; -#4998 = EDGE_LOOP ( 'NONE', ( #32196, #39454, #5406, #33594, #984 ) ) ; -#4999 = ORIENTED_EDGE ( 'NONE', *, *, #4355, .T. ) ; -#5000 = DIRECTION ( 'NONE', ( -4.163336342379951730E-15, 0.9743700557921592953, 0.2249510932971524324 ) ) ; -#5001 = EDGE_LOOP ( 'NONE', ( #29660, #16036, #28721, #13477 ) ) ; -#5002 = ORIENTED_EDGE ( 'NONE', *, *, #22573, .T. ) ; -#5003 = CARTESIAN_POINT ( 'NONE', ( -20.89128718923779005, 182.4208812217193838, 104.8596338257292757 ) ) ; -#5004 = CARTESIAN_POINT ( 'NONE', ( 19.38724966413716189, 125.5510095562851234, 178.4140686402664642 ) ) ; -#5005 = CARTESIAN_POINT ( 'NONE', ( 37.33357129172325273, 105.3428449184722098, 178.5087748212203280 ) ) ; -#5006 = ORIENTED_EDGE ( 'NONE', *, *, #8236, .F. ) ; -#5007 = ORIENTED_EDGE ( 'NONE', *, *, #27898, .F. ) ; -#5008 = FACE_OUTER_BOUND ( 'NONE', #35108, .T. ) ; -#5009 = CARTESIAN_POINT ( 'NONE', ( -35.97269354704000222, 191.6488110232999986, 104.0237207920000060 ) ) ; -#5010 = CARTESIAN_POINT ( 'NONE', ( 38.06764886506999801, 191.3258868949000089, 104.1925984591000116 ) ) ; -#5011 = ADVANCED_FACE ( 'NONE', ( #30814 ), #20704, .T. ) ; -#5012 = CARTESIAN_POINT ( 'NONE', ( -25.84266698421999919, 121.0534836917999968, 87.78695595496000692 ) ) ; -#5013 = EDGE_CURVE ( 'NONE', #6603, #39814, #5239, .T. ) ; -#5014 = CARTESIAN_POINT ( 'NONE', ( 76.10630783111388098, 156.2604783515451743, 96.19568201158742227 ) ) ; -#5015 = ORIENTED_EDGE ( 'NONE', *, *, #20286, .F. ) ; -#5016 = DIRECTION ( 'NONE', ( -0.0005884949961208443998, 0.2249510543439059429, -0.9743698870671263501 ) ) ; -#5017 = CARTESIAN_POINT ( 'NONE', ( -23.35945886576643815, 176.9432781775398951, 103.3635654750831776 ) ) ; -#5018 = ORIENTED_EDGE ( 'NONE', *, *, #29815, .F. ) ; -#5019 = AXIS2_PLACEMENT_3D ( 'NONE', #37706, #22189, #5835 ) ; -#5020 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 132.9679238121742912, 90.36185680194377312 ) ) ; -#5021 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; -#5022 = AXIS2_PLACEMENT_3D ( 'NONE', #1189, #1385, #10612 ) ; -#5023 = CARTESIAN_POINT ( 'NONE', ( -6.273952199476604541, 148.6532986828639480, 94.48918149448384440 ) ) ; -#5024 = CARTESIAN_POINT ( 'NONE', ( 45.54189549626755706, 185.8919662543875688, 105.8359296185758751 ) ) ; -#5025 = VECTOR ( 'NONE', #34063, 1000.000000000000000 ) ; -#5026 = EDGE_LOOP ( 'NONE', ( #15933, #25656, #30106, #28174 ) ) ; -#5027 = CARTESIAN_POINT ( 'NONE', ( -19.39687658205970422, 126.0855016948991221, 176.0882538048638537 ) ) ; -#5028 = CARTESIAN_POINT ( 'NONE', ( 2.178827133561953122, 189.8211730161134767, 103.9204081209391006 ) ) ; -#5029 = FACE_OUTER_BOUND ( 'NONE', #35071, .T. ) ; -#5030 = ORIENTED_EDGE ( 'NONE', *, *, #37844, .T. ) ; -#5031 = FACE_OUTER_BOUND ( 'NONE', #5026, .T. ) ; -#5032 = PLANE ( 'NONE', #30343 ) ; -#5033 = FACE_OUTER_BOUND ( 'NONE', #33367, .T. ) ; -#5034 = CARTESIAN_POINT ( 'NONE', ( 26.19519609312000341, 191.4049078856000108, 103.6787492708999991 ) ) ; -#5035 = CARTESIAN_POINT ( 'NONE', ( 17.17610773255657719, 152.4992089640258826, 182.3747067827581532 ) ) ; -#5036 = CARTESIAN_POINT ( 'NONE', ( 6.027366378080522225, 134.9354931969997153, 90.82302421546900462 ) ) ; -#5037 = EDGE_LOOP ( 'NONE', ( #12728, #39319, #16071, #17387 ) ) ; -#5038 = CARTESIAN_POINT ( 'NONE', ( 2.562619485644860973, 196.1181876864285698, 103.6781880485148406 ) ) ; -#5039 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; -#5040 = CARTESIAN_POINT ( 'NONE', ( -3.631817828491611166, 137.3302548163418066, 91.45691583842069861 ) ) ; -#5041 = EDGE_CURVE ( 'NONE', #28826, #13796, #28356, .T. ) ; -#5042 = CIRCLE ( 'NONE', #38355, 6.000000000000001776 ) ; -#5043 = CARTESIAN_POINT ( 'NONE', ( -20.99003731125718986, 183.0888586945435463, 104.5007462684889248 ) ) ; -#5044 = CARTESIAN_POINT ( 'NONE', ( 21.24456206835106542, 171.9013578063823502, 152.1279856333677571 ) ) ; -#5045 = DIRECTION ( 'NONE', ( 0.0001408404346093821877, -0.2255194953558360971, 0.9742386449830559014 ) ) ; -#5046 = CARTESIAN_POINT ( 'NONE', ( 21.70855119580487269, 123.2009557436313401, 176.5136632602473981 ) ) ; -#5047 = CIRCLE ( 'NONE', #1796, 59.40509898823097501 ) ; -#5048 = ORIENTED_EDGE ( 'NONE', *, *, #27359, .T. ) ; -#5049 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142367503004439, 137.4659008082804519, 177.5714312369109393 ) ) ; -#5050 = EDGE_CURVE ( 'NONE', #38350, #1917, #39591, .T. ) ; -#5051 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; -#5052 = EDGE_LOOP ( 'NONE', ( #3303, #3213, #30735, #24751, #14796, #12802, #1867, #871, #33846, #11687, #32379, #37912, #38796, #5697, #7798, #9395, #18469, #25829, #2877, #24278, #13059, #32292, #8896, #36825, #4185, #25847, #37070 ) ) ; -#5053 = CARTESIAN_POINT ( 'NONE', ( 5.665157511863806228, 181.8548547649002387, 101.8603694440876950 ) ) ; -#5054 = EDGE_CURVE ( 'NONE', #32409, #5601, #3735, .T. ) ; -#5055 = EDGE_CURVE ( 'NONE', #17992, #36832, #22416, .T. ) ; -#5056 = ORIENTED_EDGE ( 'NONE', *, *, #30095, .T. ) ; -#5057 = ADVANCED_FACE ( 'NONE', ( #25491 ), #28348, .T. ) ; -#5058 = EDGE_CURVE ( 'NONE', #25194, #13591, #23945, .T. ) ; -#5059 = CARTESIAN_POINT ( 'NONE', ( 20.00028792540915035, 151.9820690596619102, 94.72877128701482263 ) ) ; -#5060 = DIRECTION ( 'NONE', ( -0.8135696865073147599, 0.000000000000000000, 0.5814674240199442234 ) ) ; -#5061 = ORIENTED_EDGE ( 'NONE', *, *, #16050, .T. ) ; -#5062 = DIRECTION ( 'NONE', ( -0.7942820423213359238, -0.5918950211223032998, -0.1370267171630252523 ) ) ; -#5063 = CARTESIAN_POINT ( 'NONE', ( -14.78462263661723597, 175.5939430572494757, 102.0824664216037263 ) ) ; -#5064 = CARTESIAN_POINT ( 'NONE', ( 3.064326251946869473, 190.8646446422509939, 106.7945608832239657 ) ) ; -#5065 = LINE ( 'NONE', #30443, #34591 ) ; -#5066 = CARTESIAN_POINT ( 'NONE', ( 6.042308921164076807, 177.7921139377573638, 100.6958234779730645 ) ) ; -#5067 = VERTEX_POINT ( 'NONE', #16060 ) ; -#5068 = VERTEX_POINT ( 'NONE', #28547 ) ; -#5069 = CARTESIAN_POINT ( 'NONE', ( -5.633767562759513403, 157.0637020868425395, 100.6797548176731993 ) ) ; -#5070 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31400, #19107, #6431, #3367 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.001173009038358866895, 0.007810755923537757509 ), - .UNSPECIFIED. ) ; -#5071 = DIRECTION ( 'NONE', ( 0.0005884949961254158299, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#5072 = CARTESIAN_POINT ( 'NONE', ( 44.99182355356327179, 85.19921574553130483, 291.3598206077773511 ) ) ; -#5073 = VERTEX_POINT ( 'NONE', #40195 ) ; -#5074 = CIRCLE ( 'NONE', #23370, 4.500000000002243539 ) ; -#5075 = CARTESIAN_POINT ( 'NONE', ( 17.25788849119799195, 152.5371962406647413, 182.4889206688251306 ) ) ; -#5076 = ORIENTED_EDGE ( 'NONE', *, *, #9461, .T. ) ; -#5077 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825951923653446, 0.0005734119016496685723 ) ) ; -#5078 = CARTESIAN_POINT ( 'NONE', ( -42.24295683378286981, 121.5717801413329653, 91.17935236647853969 ) ) ; -#5079 = VECTOR ( 'NONE', #19917, 1000.000000000000114 ) ; -#5080 = CARTESIAN_POINT ( 'NONE', ( 6.035541027891230925, 134.8446529991751390, 93.34637782540107764 ) ) ; -#5081 = PLANE ( 'NONE', #16284 ) ; -#5082 = CARTESIAN_POINT ( 'NONE', ( -20.02002437005085511, 209.7095682957761085, 73.07054393135327075 ) ) ; -#5083 = DIRECTION ( 'NONE', ( -0.0006039748319386378404, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#5084 = LINE ( 'NONE', #8581, #1915 ) ; -#5085 = CARTESIAN_POINT ( 'NONE', ( -25.64334719397065498, 209.7118774246391695, 73.44058178187695773 ) ) ; -#5086 = CARTESIAN_POINT ( 'NONE', ( 6.038444123889645354, 177.0265160856394004, 103.4736887629186270 ) ) ; -#5087 = FACE_OUTER_BOUND ( 'NONE', #38449, .T. ) ; -#5088 = CARTESIAN_POINT ( 'NONE', ( 39.12645029865999646, 118.7985587775000056, 89.52831436418999544 ) ) ; -#5089 = EDGE_LOOP ( 'NONE', ( #15011, #9465, #19436, #19453 ) ) ; -#5090 = CARTESIAN_POINT ( 'NONE', ( 26.07574513491999824, 130.1628104229000087, 92.50996139529000573 ) ) ; -#5091 = CARTESIAN_POINT ( 'NONE', ( -2.438441567505833518, 191.9759150222000130, 101.9229200979927867 ) ) ; -#5092 = EDGE_CURVE ( 'NONE', #12760, #40342, #18708, .T. ) ; -#5093 = CARTESIAN_POINT ( 'NONE', ( -25.84017946953396461, 190.8761128457341272, 106.6436155876561429 ) ) ; -#5094 = CYLINDRICAL_SURFACE ( 'NONE', #3235, 2.250000000000011102 ) ; -#5095 = ADVANCED_FACE ( 'NONE', ( #12586 ), #34648, .T. ) ; -#5096 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#5097 = ORIENTED_EDGE ( 'NONE', *, *, #37560, .T. ) ; -#5098 = EDGE_LOOP ( 'NONE', ( #2920, #4677, #40264, #7119 ) ) ; -#5099 = CARTESIAN_POINT ( 'NONE', ( -2.675754854896591262, 189.9858645893802986, 103.5162325917308834 ) ) ; -#5100 = EDGE_CURVE ( 'NONE', #26291, #37554, #26399, .T. ) ; -#5101 = EDGE_LOOP ( 'NONE', ( #30764, #29319, #8004, #29324 ) ) ; -#5102 = CARTESIAN_POINT ( 'NONE', ( 42.43787138009228244, 189.9416574239004376, 106.2771675705110823 ) ) ; -#5103 = EDGE_CURVE ( 'NONE', #1836, #19924, #13000, .T. ) ; -#5104 = CIRCLE ( 'NONE', #5764, 1.999999999874873424 ) ; -#5105 = CARTESIAN_POINT ( 'NONE', ( -28.42905095578378649, 115.9590670314987193, 152.9217692738434380 ) ) ; -#5106 = ORIENTED_EDGE ( 'NONE', *, *, #22858, .T. ) ; -#5107 = CARTESIAN_POINT ( 'NONE', ( -14.42373139518885417, 135.2541458085655961, 93.79537502748391375 ) ) ; -#5108 = ADVANCED_FACE ( 'NONE', ( #3182 ), #38502, .F. ) ; -#5109 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048997459, 187.6642686534307245, 106.0792573255209419 ) ) ; -#5110 = ORIENTED_EDGE ( 'NONE', *, *, #20677, .T. ) ; -#5111 = CARTESIAN_POINT ( 'NONE', ( -0.4540624946310913290, 209.0000000000000000, 76.05877887198174392 ) ) ; -#5112 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; -#5113 = CARTESIAN_POINT ( 'NONE', ( -6.611727627915328530E-14, 161.0393699423707972, 99.91070331020888773 ) ) ; -#5114 = DIRECTION ( 'NONE', ( 1.156372029607614051E-16, 0.9743043966640312359, 0.2252353050503803356 ) ) ; -#5115 = CARTESIAN_POINT ( 'NONE', ( -20.01839671862364867, 211.0902260915352429, 76.07059681904712534 ) ) ; -#5116 = VERTEX_POINT ( 'NONE', #1515 ) ; -#5117 = CARTESIAN_POINT ( 'NONE', ( -0.6435036550759100082, 188.6095499604300016, 103.1959319992260049 ) ) ; -#5118 = CARTESIAN_POINT ( 'NONE', ( 0.5626206141546249428, 189.0089373245590423, 103.6956312891909846 ) ) ; -#5119 = CARTESIAN_POINT ( 'NONE', ( -36.01634936736067516, 191.1431690495213616, 106.8733999024287300 ) ) ; -#5120 = VERTEX_POINT ( 'NONE', #19714 ) ; -#5121 = FACE_OUTER_BOUND ( 'NONE', #16820, .T. ) ; -#5122 = EDGE_LOOP ( 'NONE', ( #25480, #26834, #13359, #15133, #10111, #37567 ) ) ; -#5123 = CIRCLE ( 'NONE', #22141, 2.500000000003625988 ) ; -#5124 = VECTOR ( 'NONE', #6937, 1000.000000000000227 ) ; -#5125 = VERTEX_POINT ( 'NONE', #29150 ) ; -#5126 = AXIS2_PLACEMENT_3D ( 'NONE', #19266, #868, #7002 ) ; -#5127 = ORIENTED_EDGE ( 'NONE', *, *, #18751, .T. ) ; -#5128 = CARTESIAN_POINT ( 'NONE', ( 21.73156077531386288, 213.2744565895932851, 73.54538933777284626 ) ) ; -#5129 = VECTOR ( 'NONE', #26078, 1000.000000000000000 ) ; -#5130 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552150381, 77.14301703112145958, 291.5584375788748162 ) ) ; -#5131 = CARTESIAN_POINT ( 'NONE', ( -42.13403640304736086, 120.7957551389193185, 90.64517896386178109 ) ) ; -#5132 = EDGE_LOOP ( 'NONE', ( #18258, #22607, #18180, #13030 ) ) ; -#5133 = CARTESIAN_POINT ( 'NONE', ( 44.87338937966080010, 186.7839235692700868, 105.8491573445734133 ) ) ; -#5134 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 82.27946979429631824, 312.5857197240630967 ) ) ; -#5135 = ORIENTED_EDGE ( 'NONE', *, *, #30469, .T. ) ; -#5136 = EDGE_CURVE ( 'NONE', #34012, #38457, #14613, .T. ) ; -#5137 = CARTESIAN_POINT ( 'NONE', ( 25.73070893625000011, 121.0294910055999935, 90.31596527812001796 ) ) ; -#5138 = EDGE_CURVE ( 'NONE', #10571, #20739, #4988, .T. ) ; -#5139 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.274821093756980468E-14, 0.9999998176071847045 ) ) ; -#5140 = ADVANCED_FACE ( 'NONE', ( #18058 ), #36384, .T. ) ; -#5141 = EDGE_CURVE ( 'NONE', #38824, #30359, #24236, .T. ) ; -#5143 = CARTESIAN_POINT ( 'NONE', ( -42.99989013480271183, 189.1985352993988556, 106.4377309217844072 ) ) ; -#5142 = CARTESIAN_POINT ( 'NONE', ( 44.53164522189504737, 188.5976176822237278, 105.9040318422177194 ) ) ; -#5144 = ORIENTED_EDGE ( 'NONE', *, *, #32714, .F. ) ; -#5145 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27694, #2328, #33793, #14807 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0008896472904070360128, 0.004888313434849526212 ), - .UNSPECIFIED. ) ; -#5146 = ORIENTED_EDGE ( 'NONE', *, *, #35102, .F. ) ; -#5147 = ADVANCED_FACE ( 'NONE', ( #17655 ), #8061, .F. ) ; -#5148 = ORIENTED_EDGE ( 'NONE', *, *, #27987, .T. ) ; -#5149 = DIRECTION ( 'NONE', ( 0.9999998268367131793, 0.0001323826278427382556, -0.0005734120540847093992 ) ) ; -#5150 = EDGE_CURVE ( 'NONE', #21825, #34607, #27100, .T. ) ; -#5151 = CARTESIAN_POINT ( 'NONE', ( 22.78045900286101499, 164.6403492429683126, 97.64938332809994392 ) ) ; -#5152 = LINE ( 'NONE', #39099, #30509 ) ; -#5153 = CARTESIAN_POINT ( 'NONE', ( -25.50804057823069471, 190.9260211217805363, 106.3128357153982648 ) ) ; -#5154 = CARTESIAN_POINT ( 'NONE', ( 36.32716782976999781, 191.7164159702000177, 104.1917411218000069 ) ) ; -#5155 = VERTEX_POINT ( 'NONE', #15018 ) ; -#5156 = VECTOR ( 'NONE', #16638, 1000.000000000000114 ) ; -#5157 = ORIENTED_EDGE ( 'NONE', *, *, #28380, .T. ) ; -#5158 = AXIS2_PLACEMENT_3D ( 'NONE', #21674, #39646, #2846 ) ; -#5159 = CARTESIAN_POINT ( 'NONE', ( -2.437851586972803020, 194.2771770550226336, 102.8997479777824537 ) ) ; -#5160 = AXIS2_PLACEMENT_3D ( 'NONE', #4331, #32944, #16800 ) ; -#5161 = CARTESIAN_POINT ( 'NONE', ( 14.56365463500893398, 188.1150310587336776, 103.0739043884865396 ) ) ; -#5162 = ORIENTED_EDGE ( 'NONE', *, *, #35833, .F. ) ; -#5163 = EDGE_LOOP ( 'NONE', ( #34603, #37252, #7307, #1194, #4968, #20958, #19693, #38326, #14277 ) ) ; -#5164 = CARTESIAN_POINT ( 'NONE', ( 30.06796867041454746, 135.0793120097469568, 91.03430416376022549 ) ) ; -#5165 = ORIENTED_EDGE ( 'NONE', *, *, #14587, .F. ) ; -#5166 = CARTESIAN_POINT ( 'NONE', ( 19.46094516130095542, 125.6747539604571813, 178.4426934156100231 ) ) ; -#5167 = ORIENTED_EDGE ( 'NONE', *, *, #26064, .F. ) ; -#5168 = DIRECTION ( 'NONE', ( 0.0004161288024558960951, 0.5299192578740949955, 0.8480479980348919478 ) ) ; -#5169 = VERTEX_POINT ( 'NONE', #21151 ) ; -#5170 = CARTESIAN_POINT ( 'NONE', ( -20.51858740271092429, 206.4917143845494252, 74.92147872994014790 ) ) ; -#5171 = CARTESIAN_POINT ( 'NONE', ( -46.39481885264477512, 125.2269168869080431, 89.10500611615424305 ) ) ; -#5172 = CARTESIAN_POINT ( 'NONE', ( 46.05118615274398763, 124.8743111081185049, 91.53352630994533001 ) ) ; -#5173 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971546806 ) ) ; -#5174 = ORIENTED_EDGE ( 'NONE', *, *, #22841, .F. ) ; -#5175 = CARTESIAN_POINT ( 'NONE', ( 25.99051299129742887, 207.8021718666841764, 73.39534836237326942 ) ) ; -#5176 = CARTESIAN_POINT ( 'NONE', ( 2.563067459505969481, 191.9759150222000130, 104.4198997672286708 ) ) ; -#5177 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364886824597, 136.5649596138813706, 181.4686487119530511 ) ) ; -#5178 = VECTOR ( 'NONE', #22943, 1000.000000000000114 ) ; -#5179 = ORIENTED_EDGE ( 'NONE', *, *, #491, .T. ) ; -#5180 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10346, #4171, #16648, #3974, #7443, #28346, #15851, #25695, #22816, #29147 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5181 = CIRCLE ( 'NONE', #18233, 4.999999999999990230 ) ; -#5182 = CONICAL_SURFACE ( 'NONE', #28700, 3.003059068065875081, 0.7854054309186528915 ) ; -#5183 = CARTESIAN_POINT ( 'NONE', ( -2.938441474952925514, 191.9759150222000130, 101.9232220853079411 ) ) ; -#5184 = EDGE_CURVE ( 'NONE', #5512, #3137, #4435, .T. ) ; -#5185 = VECTOR ( 'NONE', #34738, 999.9999999999998863 ) ; -#5186 = CARTESIAN_POINT ( 'NONE', ( -13.49852954173680430, 160.1760870560666774, 99.20639934581299713 ) ) ; -#5187 = EDGE_LOOP ( 'NONE', ( #8760, #19564, #2157, #16227, #7379, #39558, #36903, #25790, #9273, #40122, #33208, #8498 ) ) ; -#5188 = ORIENTED_EDGE ( 'NONE', *, *, #14077, .T. ) ; -#5189 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#5190 = ORIENTED_EDGE ( 'NONE', *, *, #32956, .F. ) ; -#5191 = CARTESIAN_POINT ( 'NONE', ( 36.04675231538612223, 209.7096534091000137, 76.03673329443569173 ) ) ; -#5192 = CARTESIAN_POINT ( 'NONE', ( -13.73975480783703773, 149.7280840183275927, 179.8128424031955603 ) ) ; -#5193 = CARTESIAN_POINT ( 'NONE', ( -0.4375226734455109900, 188.8043241971669204, 103.4389957040046539 ) ) ; -#5194 = ORIENTED_EDGE ( 'NONE', *, *, #13343, .T. ) ; -#5195 = ORIENTED_EDGE ( 'NONE', *, *, #5376, .F. ) ; -#5196 = CARTESIAN_POINT ( 'NONE', ( 3.064505435595261229, 190.8915653482034998, 106.8005998850467222 ) ) ; -#5197 = ORIENTED_EDGE ( 'NONE', *, *, #13296, .T. ) ; -#5198 = ORIENTED_EDGE ( 'NONE', *, *, #37884, .T. ) ; -#5199 = ORIENTED_EDGE ( 'NONE', *, *, #39016, .T. ) ; -#5200 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#5201 = CARTESIAN_POINT ( 'NONE', ( 39.70674893776387648, 114.9516458920610660, 150.7368254606779772 ) ) ; -#5202 = CARTESIAN_POINT ( 'NONE', ( -2.851221542150457200, 209.7096659646922774, 76.06022685436926167 ) ) ; -#5203 = VERTEX_POINT ( 'NONE', #29747 ) ; -#5204 = ORIENTED_EDGE ( 'NONE', *, *, #40086, .T. ) ; -#5205 = FACE_OUTER_BOUND ( 'NONE', #32107, .T. ) ; -#5206 = CARTESIAN_POINT ( 'NONE', ( -35.63362683194999647, 191.6206829176000213, 103.7794803856000101 ) ) ; -#5207 = ORIENTED_EDGE ( 'NONE', *, *, #1595, .T. ) ; -#5208 = DIRECTION ( 'NONE', ( 0.0005884949961241434102, -0.2249510543439057764, 0.9743698870671265722 ) ) ; -#5209 = CIRCLE ( 'NONE', #37889, 7.500000206705061068 ) ; -#5210 = EDGE_CURVE ( 'NONE', #32100, #7892, #17450, .T. ) ; -#5211 = VERTEX_POINT ( 'NONE', #30348 ) ; -#5212 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319368615920 ) ) ; -#5213 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552156487, 3.781093664149108639E-12, 291.5584375788758393 ) ) ; -#5214 = LINE ( 'NONE', #17682, #9120 ) ; -#5215 = EDGE_LOOP ( 'NONE', ( #17258, #13683, #22093, #5897 ) ) ; -#5216 = CIRCLE ( 'NONE', #6530, 1.999999999967367437 ) ; -#5217 = CARTESIAN_POINT ( 'NONE', ( -6.037312566745338671, 134.5332731853788175, 93.54687357718964336 ) ) ; -#5218 = VECTOR ( 'NONE', #27412, 1000.000000000000000 ) ; -#5219 = CARTESIAN_POINT ( 'NONE', ( 25.49921019565536184, 118.1133140256443426, 87.75227232668940758 ) ) ; -#5220 = CARTESIAN_POINT ( 'NONE', ( 20.00004282447493864, 191.5259056233101091, 103.8580927373495371 ) ) ; -#5221 = CARTESIAN_POINT ( 'NONE', ( 14.17036435349962353, 176.4975660804189488, 100.9051904591885886 ) ) ; -#5222 = VERTEX_POINT ( 'NONE', #24019 ) ; -#5223 = CARTESIAN_POINT ( 'NONE', ( -48.18983608578390232, 82.56060091850311267, 289.7643016034785433 ) ) ; -#5224 = CARTESIAN_POINT ( 'NONE', ( 1.929693795520588839, 189.5261676399869089, 103.8354463821101064 ) ) ; -#5225 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19598, #19400, #32290, #16520 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5226 = CARTESIAN_POINT ( 'NONE', ( -13.83205090675506455, 124.7811071190511285, 174.0455584609973414 ) ) ; -#5227 = ORIENTED_EDGE ( 'NONE', *, *, #18892, .F. ) ; -#5228 = LINE ( 'NONE', #14453, #39945 ) ; -#5229 = EDGE_LOOP ( 'NONE', ( #34543, #3721, #9929, #35438 ) ) ; -#5230 = ORIENTED_EDGE ( 'NONE', *, *, #21051, .T. ) ; -#5231 = CARTESIAN_POINT ( 'NONE', ( 3.044059411013400940, 209.1882909079368744, 73.07656864438033040 ) ) ; -#5232 = CARTESIAN_POINT ( 'NONE', ( -35.62164487996323459, 209.7096534849600289, 75.91335251043651056 ) ) ; -#5233 = CARTESIAN_POINT ( 'NONE', ( 25.38734224913000048, 191.4305716074000259, 104.4940156361000021 ) ) ; -#5234 = DIRECTION ( 'NONE', ( -0.6319545750169662801, -0.7750053350989876133, 0.0003816847278651969611 ) ) ; -#5235 = ORIENTED_EDGE ( 'NONE', *, *, #35321, .T. ) ; -#5236 = CARTESIAN_POINT ( 'NONE', ( -15.10537787283572619, 182.4218088933851050, 104.8563524828814764 ) ) ; -#5237 = EDGE_CURVE ( 'NONE', #20022, #1098, #16152, .T. ) ; -#5238 = ADVANCED_FACE ( 'NONE', ( #30148 ), #5599, .F. ) ; -#5239 = LINE ( 'NONE', #36335, #5710 ) ; -#5240 = CONICAL_SURFACE ( 'NONE', #20273, 2.749999999949247709, 0.7853981633862016087 ) ; -#5241 = AXIS2_PLACEMENT_3D ( 'NONE', #28367, #18937, #31434 ) ; -#5242 = CYLINDRICAL_SURFACE ( 'NONE', #15296, 2.000000000000014655 ) ; -#5243 = CARTESIAN_POINT ( 'NONE', ( 3.667031087184732474, 183.8629715334667480, 103.2961752168644409 ) ) ; -#5244 = EDGE_CURVE ( 'NONE', #34253, #26260, #31815, .T. ) ; -#5245 = CONICAL_SURFACE ( 'NONE', #28136, 2.999999999884520374, 0.7853981634033615489 ) ; -#5246 = CARTESIAN_POINT ( 'NONE', ( 20.16676440252237157, 184.9321535431011228, 102.5067456869941651 ) ) ; -#5247 = FACE_OUTER_BOUND ( 'NONE', #29467, .T. ) ; -#5248 = CONICAL_SURFACE ( 'NONE', #22267, 2.502994210670941744, 0.7853981633984441491 ) ; -#5249 = CARTESIAN_POINT ( 'NONE', ( 13.46662727487878719, 154.4076626936201251, 95.29260641077831906 ) ) ; -#5250 = LINE ( 'NONE', #39390, #26002 ) ; -#5251 = DIRECTION ( 'NONE', ( -0.6087614115774878654, -0.7729348350621346730, -0.1788331191967953149 ) ) ; -#5252 = CARTESIAN_POINT ( 'NONE', ( 0.05300952315392960107, 83.21792371834001756, 87.76775236679999637 ) ) ; -#5253 = ORIENTED_EDGE ( 'NONE', *, *, #11627, .T. ) ; -#5254 = CARTESIAN_POINT ( 'NONE', ( -26.01077944034773282, 209.7097224531575534, 73.07398733611859143 ) ) ; -#5255 = CARTESIAN_POINT ( 'NONE', ( 3.952994205079280565, 144.1211950466918097, 93.35308613109434361 ) ) ; -#5256 = CARTESIAN_POINT ( 'NONE', ( -32.40504396064814330, 136.4748265295417582, 91.18018952198957550 ) ) ; -#5257 = EDGE_LOOP ( 'NONE', ( #14779, #6425, #5813, #25680 ) ) ; -#5258 = DIRECTION ( 'NONE', ( 0.0005884949961239157278, -0.2249510543439051935, 0.9743698870671265722 ) ) ; -#5259 = ORIENTED_EDGE ( 'NONE', *, *, #10906, .F. ) ; -#5260 = CARTESIAN_POINT ( 'NONE', ( -39.52796655470999809, 119.7636465605999945, 87.83956657257000700 ) ) ; -#5261 = CARTESIAN_POINT ( 'NONE', ( -16.42102836926336806, 151.9104391475223963, 184.3463035859948036 ) ) ; -#5262 = ORIENTED_EDGE ( 'NONE', *, *, #8756, .T. ) ; -#5263 = CARTESIAN_POINT ( 'NONE', ( 36.13238095029493735, 191.1563762242305131, 106.8320446025870893 ) ) ; -#5264 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33499, #39833, #14508, #26785 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5265 = CARTESIAN_POINT ( 'NONE', ( -5.669876942565291955, 126.8023652021145722, 88.92780583867599375 ) ) ; -#5266 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557957380992, -0.2249510932816513320 ) ) ; -#5267 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000094502, 179.7424522643958653, 101.1388664480904396 ) ) ; -#5268 = CARTESIAN_POINT ( 'NONE', ( 39.42035703641028022, 114.3667165859880015, 151.6079144922757109 ) ) ; -#5269 = CARTESIAN_POINT ( 'NONE', ( 6.039606680401115923, 177.7921203572399804, 100.6958205443672085 ) ) ; -#5270 = ORIENTED_EDGE ( 'NONE', *, *, #12049, .F. ) ; -#5271 = CIRCLE ( 'NONE', #3319, 2.499999999945343720 ) ; -#5272 = CARTESIAN_POINT ( 'NONE', ( 38.49152248112999786, 119.0204481247999979, 87.57880690499000309 ) ) ; -#5273 = AXIS2_PLACEMENT_3D ( 'NONE', #22791, #12982, #31796 ) ; -#5274 = DIRECTION ( 'NONE', ( -0.0005884949961250434064, 0.2249510543439061094, -0.9743698870671263501 ) ) ; -#5275 = CARTESIAN_POINT ( 'NONE', ( -35.96311564216326673, 218.5902260770998282, 61.08022271436995965 ) ) ; -#5276 = ADVANCED_FACE ( 'NONE', ( #27309 ), #19386, .T. ) ; -#5277 = CONICAL_SURFACE ( 'NONE', #11785, 6.499999999903893766, 0.7853981634197682027 ) ; -#5278 = VERTEX_POINT ( 'NONE', #26890 ) ; -#5279 = VECTOR ( 'NONE', #34277, 1000.000000000000114 ) ; -#5280 = DIRECTION ( 'NONE', ( -0.6087614115774879764, -0.7729348350621345620, -0.1788331191967953704 ) ) ; -#5281 = EDGE_LOOP ( 'NONE', ( #28177, #5863, #28718, #40358 ) ) ; -#5282 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; -#5283 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#5284 = DIRECTION ( 'NONE', ( 1.850371707731960504E-14, -1.000000000000000000, 1.387778780798970378E-14 ) ) ; -#5285 = CARTESIAN_POINT ( 'NONE', ( -41.29162907220920431, 121.2433985071746605, 87.66910399198238224 ) ) ; -#5286 = CARTESIAN_POINT ( 'NONE', ( -25.02141864464750753, 181.5306254107395887, 104.1434434358392735 ) ) ; -#5287 = EDGE_CURVE ( 'NONE', #25208, #21069, #25391, .T. ) ; -#5288 = CARTESIAN_POINT ( 'NONE', ( 36.05503269261969734, 112.4664341864257437, 89.74600809124632406 ) ) ; -#5289 = CARTESIAN_POINT ( 'NONE', ( -20.00017858637951207, 184.9560350789418237, 102.3655360699851400 ) ) ; -#5290 = CARTESIAN_POINT ( 'NONE', ( 3.499876110998302980, 184.0507947266270321, 102.4843871410976135 ) ) ; -#5291 = EDGE_CURVE ( 'NONE', #37651, #35508, #12227, .T. ) ; -#5292 = EDGE_CURVE ( 'NONE', #37091, #29223, #35033, .T. ) ; -#5293 = CARTESIAN_POINT ( 'NONE', ( -25.76767330085639429, 209.7106972169785877, 73.31640534608830251 ) ) ; -#5294 = EDGE_CURVE ( 'NONE', #25248, #7054, #40286, .T. ) ; -#5295 = CARTESIAN_POINT ( 'NONE', ( 6.037029121800269849, 176.9361410009001929, 103.3290594646711185 ) ) ; -#5296 = EDGE_CURVE ( 'NONE', #25074, #12430, #25045, .T. ) ; -#5297 = CARTESIAN_POINT ( 'NONE', ( -38.93814858684476121, 191.0388300950886560, 103.7812318162937686 ) ) ; -#5298 = CARTESIAN_POINT ( 'NONE', ( 38.96805248119999732, 118.9657793131000005, 89.82484713342999783 ) ) ; -#5299 = CARTESIAN_POINT ( 'NONE', ( 25.50964488085134008, 191.7826714808669237, 105.0633093220635033 ) ) ; -#5300 = CARTESIAN_POINT ( 'NONE', ( -42.47220679908992480, 189.9442792002049316, 106.2657712603332385 ) ) ; -#5301 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#5302 = FACE_OUTER_BOUND ( 'NONE', #2344, .T. ) ; -#5303 = AXIS2_PLACEMENT_3D ( 'NONE', #34869, #18730, #19547 ) ; -#5304 = CARTESIAN_POINT ( 'NONE', ( -20.49973909911777881, 191.9757886370473443, 104.4339460251406706 ) ) ; -#5305 = ORIENTED_EDGE ( 'NONE', *, *, #25685, .T. ) ; -#5306 = VERTEX_POINT ( 'NONE', #37486 ) ; -#5307 = CARTESIAN_POINT ( 'NONE', ( -16.55192910790513849, 122.5029194652213107, 174.6229610647038726 ) ) ; -#5308 = CONICAL_SURFACE ( 'NONE', #22315, 2.503000006812882816, 0.7853981634117586097 ) ; -#5309 = ORIENTED_EDGE ( 'NONE', *, *, #10406, .T. ) ; -#5310 = CARTESIAN_POINT ( 'NONE', ( -23.36089161421036309, 177.5428730706524334, 100.8660013147756302 ) ) ; -#5311 = DIRECTION ( 'NONE', ( 6.591949208711879581E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#5312 = ORIENTED_EDGE ( 'NONE', *, *, #23390, .T. ) ; -#5313 = ORIENTED_EDGE ( 'NONE', *, *, #34053, .F. ) ; -#5314 = LINE ( 'NONE', #36603, #33550 ) ; -#5315 = EDGE_CURVE ( 'NONE', #40156, #28075, #39048, .T. ) ; -#5316 = CARTESIAN_POINT ( 'NONE', ( -38.01211212650550664, 119.1971871873620472, 87.30118044812934386 ) ) ; -#5317 = CARTESIAN_POINT ( 'NONE', ( -23.36589107377781005, 134.9158523539519194, 90.81477344275025132 ) ) ; -#5318 = CARTESIAN_POINT ( 'NONE', ( 16.59040448417249891, 121.5622698803751121, 177.2309519810485767 ) ) ; -#5319 = ORIENTED_EDGE ( 'NONE', *, *, #28879, .T. ) ; -#5320 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620728018, 0.0004744508866335543488 ) ) ; -#5321 = ORIENTED_EDGE ( 'NONE', *, *, #16356, .T. ) ; -#5322 = DIRECTION ( 'NONE', ( -0.5988683521957647304, 0.8008474865655316188, 0.000000000000000000 ) ) ; -#5323 = CARTESIAN_POINT ( 'NONE', ( -44.77033340054011745, 167.6031324061906673, 188.6329174925582777 ) ) ; -#5324 = CARTESIAN_POINT ( 'NONE', ( -15.99998378297181745, 127.7446958148473186, 89.15477705487283799 ) ) ; -#5325 = CARTESIAN_POINT ( 'NONE', ( -12.63796699598845308, 181.2087211845504839, 104.4066993005394863 ) ) ; -#5326 = ORIENTED_EDGE ( 'NONE', *, *, #2009, .F. ) ; -#5327 = ORIENTED_EDGE ( 'NONE', *, *, #37158, .T. ) ; -#5328 = CARTESIAN_POINT ( 'NONE', ( -12.63662704360904065, 183.5606839279895155, 104.6046393389179059 ) ) ; -#5329 = CARTESIAN_POINT ( 'NONE', ( 0.7372372423313999779, 188.7528568893999932, 103.3644243068000179 ) ) ; -#5330 = CARTESIAN_POINT ( 'NONE', ( -35.46134654744881232, 192.4113187253241506, 106.9240966051354746 ) ) ; -#5331 = EDGE_CURVE ( 'NONE', #39755, #29108, #33098, .T. ) ; -#5332 = EDGE_LOOP ( 'NONE', ( #1258, #20466, #24460, #23207, #14639 ) ) ; -#5333 = CONICAL_SURFACE ( 'NONE', #749, 2.499989690268706877, 0.7853981633751526692 ) ; -#5334 = CARTESIAN_POINT ( 'NONE', ( 30.05533549523401149, 104.1131156702010969, 90.24963216969922541 ) ) ; -#5335 = VERTEX_POINT ( 'NONE', #34406 ) ; -#5336 = AXIS2_PLACEMENT_3D ( 'NONE', #38374, #37979, #19563 ) ; -#5337 = EDGE_CURVE ( 'NONE', #28941, #35790, #18547, .T. ) ; -#5338 = CONICAL_SURFACE ( 'NONE', #24957, 40.50000000000311928, 0.7853981633973105003 ) ; -#5339 = CARTESIAN_POINT ( 'NONE', ( -16.56444619814642394, 122.4978951069579125, 174.6020624745778491 ) ) ; -#5340 = EDGE_CURVE ( 'NONE', #6484, #407, #31167, .T. ) ; -#5341 = ORIENTED_EDGE ( 'NONE', *, *, #19591, .F. ) ; -#5342 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23527, #27021, #39659, #4708, #30077, #39256, #1855, #14334, #11461, #35763, #17979 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000003156364, 0.3750000000004984901, 0.4375000000005899170, 0.4687500000005980771, 0.5000000000006062928, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5343 = ORIENTED_EDGE ( 'NONE', *, *, #8121, .F. ) ; -#5344 = DIRECTION ( 'NONE', ( -0.0004161288024356094256, -0.5299192578742120130, -0.8480479980348188951 ) ) ; -#5345 = CARTESIAN_POINT ( 'NONE', ( -37.60604071504999979, 191.4600945531000207, 104.1578384304000053 ) ) ; -#5346 = DIRECTION ( 'NONE', ( -0.6087611427424929333, -0.7731004630501246977, -0.1781166615410725018 ) ) ; -#5347 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319384230599 ) ) ; -#5348 = ORIENTED_EDGE ( 'NONE', *, *, #25354, .F. ) ; -#5349 = CARTESIAN_POINT ( 'NONE', ( -6.035968307203201988, 174.6790541867032971, 103.0665008558034117 ) ) ; -#5350 = ORIENTED_EDGE ( 'NONE', *, *, #23458, .T. ) ; -#5351 = CARTESIAN_POINT ( 'NONE', ( 26.49737273317900232, 122.3640048392010016, 90.97099765724030362 ) ) ; -#5352 = CARTESIAN_POINT ( 'NONE', ( -35.55286435437628256, 191.9058181829571481, 103.9437009855516294 ) ) ; -#5354 = CARTESIAN_POINT ( 'NONE', ( -15.49852919254797179, 185.3436308334966895, 105.0179936564814511 ) ) ; -#5353 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927678092104, 0.0005734119022099723288 ) ) ; -#5355 = ORIENTED_EDGE ( 'NONE', *, *, #32402, .T. ) ; -#5356 = CARTESIAN_POINT ( 'NONE', ( 3.535986888874630196, 143.5554623264248733, 95.87208321593506355 ) ) ; -#5357 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26569, #23485, #39820, #3012, #11836, #27786, #27990, #5477, #30843, #27599, #27400, #30643 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000002464140, 0.3750000000003541056, 0.4375000000004172218, 0.4687500000004241607, 0.4843750000004030665, 0.5000000000003819167, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5358 = EDGE_LOOP ( 'NONE', ( #26687, #8427, #7870 ) ) ; -#5359 = CARTESIAN_POINT ( 'NONE', ( 19.99983023451520836, 117.9120932992704951, 87.25570489572297106 ) ) ; -#5360 = DIRECTION ( 'NONE', ( 0.0006039748319383107366, 1.234791622901071989E-14, 0.9999998176071845934 ) ) ; -#5361 = AXIS2_PLACEMENT_3D ( 'NONE', #12673, #33741, #33936 ) ; -#5362 = ORIENTED_EDGE ( 'NONE', *, *, #3858, .F. ) ; -#5364 = AXIS2_PLACEMENT_3D ( 'NONE', #21409, #28143, #6047 ) ; -#5363 = CARTESIAN_POINT ( 'NONE', ( -11.79201011660654785, 125.8410499982071400, 176.6171124943543873 ) ) ; -#5365 = AXIS2_PLACEMENT_3D ( 'NONE', #23608, #29545, #11549 ) ; -#5366 = DIRECTION ( 'NONE', ( -0.0005884950603321816021, 0.2249510543244929439, -0.9743698870715694627 ) ) ; -#5367 = CARTESIAN_POINT ( 'NONE', ( -33.33102413683000975, 226.1502260771000010, 73.32863523137000072 ) ) ; -#5368 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#5369 = ORIENTED_EDGE ( 'NONE', *, *, #15021, .F. ) ; -#5370 = VERTEX_POINT ( 'NONE', #28109 ) ; -#5371 = CARTESIAN_POINT ( 'NONE', ( -25.99272572791733182, 191.9759150222000130, 101.9371462953202609 ) ) ; -#5372 = CARTESIAN_POINT ( 'NONE', ( -38.93887205695440201, 183.6185768692615170, 102.5812822814675087 ) ) ; -#5373 = VERTEX_POINT ( 'NONE', #9900 ) ; -#5374 = FACE_OUTER_BOUND ( 'NONE', #3434, .T. ) ; -#5375 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35063, #740, #13621, #35456, #19932, #31839 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.006198667244160495360, 0.007464447912241703106, 0.008730228580322910853 ), - .UNSPECIFIED. ) ; -#5376 = EDGE_CURVE ( 'NONE', #16629, #21126, #5809, .T. ) ; -#5377 = EDGE_CURVE ( 'NONE', #39751, #27737, #9309, .T. ) ; -#5378 = EDGE_CURVE ( 'NONE', #33167, #3122, #16591, .T. ) ; -#5379 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22194, #38122, #6423, #34621, #3550, #10121, #35018, #3955, #19500, #31387 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5380 = ADVANCED_FACE ( 'NONE', ( #16010 ), #6597, .F. ) ; -#5381 = CARTESIAN_POINT ( 'NONE', ( 2.967800897092010448, 190.0831160609456276, 106.6319593653253719 ) ) ; -#5382 = ORIENTED_EDGE ( 'NONE', *, *, #23776, .T. ) ; -#5383 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#5384 = DIRECTION ( 'NONE', ( 0.0006039748319385908944, 1.293414132305980107E-14, 0.9999998176071845934 ) ) ; -#5385 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15923, #588, #28416, #12882, #19396, #29009, #25355, #16724, #3851, #19781, #29222, #25559, #37807, #9813, #34715, #6717, #32285, #1192, #19180, #16328 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999998811784, 0.1874999999998311906, 0.2187499999998049893, 0.2343749999998032130, 0.2499999999998014366, 0.4999999999998957501, 0.6249999999999429345, 0.6874999999999665823, 0.7187499999999783507, 0.7343749999999795719, 0.7499999999999809042, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5386 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; -#5387 = CARTESIAN_POINT ( 'NONE', ( 22.78281254372720355, 153.7346105515276804, 98.21050616309901216 ) ) ; -#5388 = ORIENTED_EDGE ( 'NONE', *, *, #15640, .T. ) ; -#5389 = AXIS2_PLACEMENT_3D ( 'NONE', #25102, #8755, #18927 ) ; -#5390 = LINE ( 'NONE', #20939, #13388 ) ; -#5391 = DIRECTION ( 'NONE', ( 0.6087614115774887535, 0.7729348350621332298, 0.1788331191967985623 ) ) ; -#5392 = EDGE_CURVE ( 'NONE', #22698, #5155, #21991, .T. ) ; -#5393 = AXIS2_PLACEMENT_3D ( 'NONE', #22025, #6066, #15281 ) ; -#5394 = ORIENTED_EDGE ( 'NONE', *, *, #34085, .F. ) ; -#5395 = CARTESIAN_POINT ( 'NONE', ( -5.668029527664558032, 188.1161524041082203, 103.2806162949214013 ) ) ; -#5396 = ORIENTED_EDGE ( 'NONE', *, *, #36012, .F. ) ; -#5398 = DIRECTION ( 'NONE', ( 0.1305262051638081400, -0.9658997602660276405, -0.2236080563923530939 ) ) ; -#5397 = FACE_OUTER_BOUND ( 'NONE', #11297, .T. ) ; -#5399 = ORIENTED_EDGE ( 'NONE', *, *, #19629, .F. ) ; -#5400 = EDGE_CURVE ( 'NONE', #10049, #4424, #15099, .T. ) ; -#5401 = ORIENTED_EDGE ( 'NONE', *, *, #395, .T. ) ; -#5402 = VERTEX_POINT ( 'NONE', #19272 ) ; -#5403 = CARTESIAN_POINT ( 'NONE', ( 2.351541002293000115, 209.4594558450999955, 75.42326402205000591 ) ) ; -#5404 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319380485765 ) ) ; -#5405 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#5406 = ORIENTED_EDGE ( 'NONE', *, *, #30788, .T. ) ; -#5407 = ORIENTED_EDGE ( 'NONE', *, *, #10705, .T. ) ; -#5408 = CARTESIAN_POINT ( 'NONE', ( 20.00192081821563761, 126.7670151487632353, 91.98617178303544506 ) ) ; -#5409 = ORIENTED_EDGE ( 'NONE', *, *, #7380, .F. ) ; -#5410 = VERTEX_POINT ( 'NONE', #1477 ) ; -#5411 = LINE ( 'NONE', #33008, #15249 ) ; -#5412 = FACE_OUTER_BOUND ( 'NONE', #8523, .T. ) ; -#5413 = DIRECTION ( 'NONE', ( 0.0005884949961299158110, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#5414 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319695600, 89.65051019401549581, 291.5295797804316180 ) ) ; -#5415 = VECTOR ( 'NONE', #18816, 1000.000000000000000 ) ; -#5416 = ORIENTED_EDGE ( 'NONE', *, *, #38665, .T. ) ; -#5417 = EDGE_LOOP ( 'NONE', ( #35754, #22565, #30953, #8626, #6229, #18770, #2772, #4800, #26250, #28550, #22265 ) ) ; -#5418 = DIRECTION ( 'NONE', ( -0.9999998268366113718, -0.0001323826667115919479, 0.0005734122222537812747 ) ) ; -#5419 = CARTESIAN_POINT ( 'NONE', ( -35.56489546672000301, 192.4169749659000104, 104.0136898731999935 ) ) ; -#5420 = DIRECTION ( 'NONE', ( -0.0005884949961251158311, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#5421 = ORIENTED_EDGE ( 'NONE', *, *, #28609, .F. ) ; -#5422 = VECTOR ( 'NONE', #18276, 1000.000000000000114 ) ; -#5423 = CARTESIAN_POINT ( 'NONE', ( -1.247069977563740384, 153.6904434798544514, 100.2674314307152628 ) ) ; -#5424 = FACE_OUTER_BOUND ( 'NONE', #31910, .T. ) ; -#5425 = ORIENTED_EDGE ( 'NONE', *, *, #17974, .T. ) ; -#5426 = CARTESIAN_POINT ( 'NONE', ( 2.607514698226610861, 189.6744051077729978, 103.4411355290657184 ) ) ; -#5427 = EDGE_CURVE ( 'NONE', #5601, #31792, #22968, .T. ) ; -#5428 = EDGE_CURVE ( 'NONE', #8771, #19923, #13963, .T. ) ; -#5429 = CARTESIAN_POINT ( 'NONE', ( 20.22996898690999856, 210.3997738015999914, 73.29629337437999936 ) ) ; -#5430 = CARTESIAN_POINT ( 'NONE', ( -3.857669709864375296, 167.8924508806730955, 101.1652248471848878 ) ) ; -#5431 = ORIENTED_EDGE ( 'NONE', *, *, #38889, .T. ) ; -#5432 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971546529 ) ) ; -#5433 = CARTESIAN_POINT ( 'NONE', ( 1.765308310976175799, 189.4019637521823824, 103.7997217045437992 ) ) ; -#5434 = PLANE ( 'NONE', #578 ) ; -#5435 = EDGE_CURVE ( 'NONE', #34827, #12793, #18467, .T. ) ; -#5436 = VERTEX_POINT ( 'NONE', #10699 ) ; -#5437 = CARTESIAN_POINT ( 'NONE', ( 35.93233219525675537, 108.6927157154615031, 168.7346187899305221 ) ) ; -#5438 = ORIENTED_EDGE ( 'NONE', *, *, #24583, .F. ) ; -#5439 = CARTESIAN_POINT ( 'NONE', ( 22.78222448783898813, 147.4012051316309737, 96.74832440307339709 ) ) ; -#5440 = CARTESIAN_POINT ( 'NONE', ( -2.373302774618340827, 209.5677226285648942, 73.55993759090392814 ) ) ; -#5441 = CARTESIAN_POINT ( 'NONE', ( 36.08146340137000152, 116.0255615537000011, 90.39360793564999597 ) ) ; -#5442 = EDGE_CURVE ( 'NONE', #35255, #30695, #32368, .T. ) ; -#5443 = CARTESIAN_POINT ( 'NONE', ( -21.48251327031369939, 213.0894491055004210, 75.57141013448118372 ) ) ; -#5444 = CIRCLE ( 'NONE', #4760, 2.499999999999997335 ) ; -#5445 = CARTESIAN_POINT ( 'NONE', ( -30.06407215524082943, 177.1126099298436714, 103.6397089757105192 ) ) ; -#5446 = ORIENTED_EDGE ( 'NONE', *, *, #27859, .F. ) ; -#5447 = CIRCLE ( 'NONE', #8042, 4.500000000492645036 ) ; -#5448 = CARTESIAN_POINT ( 'NONE', ( 2.896031416032872396, 196.4250263690624365, 103.8082216141275325 ) ) ; -#5449 = EDGE_CURVE ( 'NONE', #39374, #5743, #38038, .T. ) ; -#5450 = AXIS2_PLACEMENT_3D ( 'NONE', #12823, #37752, #31636 ) ; -#5451 = CARTESIAN_POINT ( 'NONE', ( -23.00078011532012212, 115.1133396198523968, 87.28167119284988473 ) ) ; -#5452 = PLANE ( 'NONE', #9462 ) ; -#5453 = FACE_OUTER_BOUND ( 'NONE', #29480, .T. ) ; -#5454 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; -#5455 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923337649, 151.9719590600774097, 94.73025963079751932 ) ) ; -#5456 = CARTESIAN_POINT ( 'NONE', ( -39.69719626944747404, 124.2805046067504122, 88.36931224150116293 ) ) ; -#5457 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25136, #3423, #28005, #37585 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5458 = DIRECTION ( 'NONE', ( 0.9999998176018447538, 2.041100424550427796E-09, -0.0006039836729574345631 ) ) ; -#5459 = DIRECTION ( 'NONE', ( 0.0002393071182784984501, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#5460 = ORIENTED_EDGE ( 'NONE', *, *, #32117, .T. ) ; -#5461 = CARTESIAN_POINT ( 'NONE', ( 27.07873119645540783, 119.5134203564188198, 171.3751642805570157 ) ) ; -#5462 = CARTESIAN_POINT ( 'NONE', ( -30.39593890779433494, 134.9159342868063902, 90.81907737499864197 ) ) ; -#5463 = ORIENTED_EDGE ( 'NONE', *, *, #21090, .T. ) ; -#5464 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999904787, 182.4172041435091955, 101.7781247866528531 ) ) ; -#5465 = VERTEX_POINT ( 'NONE', #28894 ) ; -#5466 = CARTESIAN_POINT ( 'NONE', ( -39.51669770417000649, 120.2152126645000010, 87.60169382661999293 ) ) ; -#5467 = CARTESIAN_POINT ( 'NONE', ( 25.51044001015309703, 191.4790671403759745, 106.3785283636754855 ) ) ; -#5468 = DIRECTION ( 'NONE', ( -0.0004161288024657918251, 0.8480480897829454356, -0.5299191110465040211 ) ) ; -#5469 = ORIENTED_EDGE ( 'NONE', *, *, #16529, .F. ) ; -#5470 = FACE_OUTER_BOUND ( 'NONE', #8860, .T. ) ; -#5471 = CARTESIAN_POINT ( 'NONE', ( 20.16676685501600019, 138.4782451641996488, 91.78201644681476523 ) ) ; -#5472 = DIRECTION ( 'NONE', ( -0.7856637149787868424, 0.6186538021912832974, 0.000000000000000000 ) ) ; -#5473 = ADVANCED_FACE ( 'NONE', ( #34994 ), #10303, .T. ) ; -#5474 = AXIS2_PLACEMENT_3D ( 'NONE', #28, #30719, #12490 ) ; -#5475 = EDGE_CURVE ( 'NONE', #16595, #23382, #30226, .T. ) ; -#5476 = CARTESIAN_POINT ( 'NONE', ( -12.16667563857975942, 125.0476480134844195, 178.7711262641263659 ) ) ; -#5477 = CARTESIAN_POINT ( 'NONE', ( -5.670789482781440682, 124.5559286933783483, 88.67279856817222594 ) ) ; -#5478 = VERTEX_POINT ( 'NONE', #29500 ) ; -#5479 = CARTESIAN_POINT ( 'NONE', ( 39.24285237467999821, 119.6631188639999976, 87.65313480276999769 ) ) ; -#5480 = CONICAL_SURFACE ( 'NONE', #33554, 2.503000000093201560, 0.7853981634628647290 ) ; -#5481 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; -#5482 = DIRECTION ( 'NONE', ( -0.7075229215369958080, -9.360719863004943371E-05, -0.7066903895889957710 ) ) ; -#5483 = DIRECTION ( 'NONE', ( 0.5635853613747644486, -0.8260577610420147820, -0.0003403914359935476352 ) ) ; -#5484 = ORIENTED_EDGE ( 'NONE', *, *, #19094, .F. ) ; -#5485 = FACE_OUTER_BOUND ( 'NONE', #276, .T. ) ; -#5486 = FACE_OUTER_BOUND ( 'NONE', #1489, .T. ) ; -#5487 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#5488 = CARTESIAN_POINT ( 'NONE', ( 2.941278393888057341, 209.7096877029368613, 73.05672770647804271 ) ) ; -#5489 = CARTESIAN_POINT ( 'NONE', ( -23.79325425886786505, 213.9958348113663646, 73.07287461175785381 ) ) ; -#5490 = DIRECTION ( 'NONE', ( -0.0005122663767566810198, 0.5297425686469459105, -0.8481583275229307439 ) ) ; -#5491 = CARTESIAN_POINT ( 'NONE', ( -25.63717913679842297, 209.7120637380510857, 73.44674248724354015 ) ) ; -#5492 = CARTESIAN_POINT ( 'NONE', ( 20.14857755624994340, 209.7095273962098645, 75.87932221801115418 ) ) ; -#5493 = EDGE_CURVE ( 'NONE', #20878, #37162, #10093, .T. ) ; -#5494 = CALENDAR_DATE ( 2025, 24, 6 ) ; -#5495 = CARTESIAN_POINT ( 'NONE', ( -23.05439898571000512, 211.0902260770999987, 13.53038997162000001 ) ) ; -#5496 = AXIS2_PLACEMENT_3D ( 'NONE', #14488, #26973, #10818 ) ; -#5497 = CARTESIAN_POINT ( 'NONE', ( 30.31510162847516909, 185.4752933756049629, 102.6260100505549104 ) ) ; -#5498 = CARTESIAN_POINT ( 'NONE', ( 25.50924745143719718, 191.9344736266071436, 104.4056993596765039 ) ) ; -#5499 = CARTESIAN_POINT ( 'NONE', ( -39.05638795867287882, 135.6127962752709095, 291.5821330148877450 ) ) ; -#5500 = CARTESIAN_POINT ( 'NONE', ( 2.547144911090980735, 209.7096538831000032, 78.05696658266604970 ) ) ; -#5501 = AXIS2_PLACEMENT_3D ( 'NONE', #29042, #22717, #619 ) ; -#5502 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971546529 ) ) ; -#5503 = VERTEX_POINT ( 'NONE', #7205 ) ; -#5504 = ORIENTED_EDGE ( 'NONE', *, *, #12830, .T. ) ; -#5505 = CARTESIAN_POINT ( 'NONE', ( -16.54674137764969899, 122.5082657265542849, 174.6175140616275883 ) ) ; -#5506 = VERTEX_POINT ( 'NONE', #26041 ) ; -#5507 = CARTESIAN_POINT ( 'NONE', ( 38.46700359482129272, 118.8212168396402717, 87.67371270529410765 ) ) ; -#5508 = EDGE_CURVE ( 'NONE', #15039, #13511, #7004, .T. ) ; -#5509 = FACE_OUTER_BOUND ( 'NONE', #27066, .T. ) ; -#5510 = CARTESIAN_POINT ( 'NONE', ( 56.51967809335915405, 71.57350793124206234, 282.5210433287024898 ) ) ; -#5511 = EDGE_LOOP ( 'NONE', ( #25686, #16343, #12509, #141 ) ) ; -#5512 = VERTEX_POINT ( 'NONE', #35595 ) ; -#5513 = CARTESIAN_POINT ( 'NONE', ( 15.50147166925602527, 127.1825504195482353, 91.57172455528431954 ) ) ; -#5514 = EDGE_CURVE ( 'NONE', #2544, #31532, #7612, .T. ) ; -#5515 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#5516 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#5517 = CARTESIAN_POINT ( 'NONE', ( 0.5641566756163646223, 188.3875244735902470, 106.2241826918301228 ) ) ; -#5518 = ORIENTED_EDGE ( 'NONE', *, *, #20373, .T. ) ; -#5519 = CARTESIAN_POINT ( 'NONE', ( 23.68458193633980713, 135.2968916886795228, 91.38751720632359365 ) ) ; -#5520 = DIRECTION ( 'NONE', ( 0.0004161288024633573576, -0.8480480897834431486, 0.5299191110457075471 ) ) ; -#5521 = CARTESIAN_POINT ( 'NONE', ( 23.36642197761798911, 177.0299567763120194, 103.4655879047946456 ) ) ; -#5522 = ADVANCED_FACE ( 'NONE', ( #23374 ), #39671, .F. ) ; -#5523 = EDGE_CURVE ( 'NONE', #35141, #5410, #20957, .T. ) ; -#5524 = DIRECTION ( 'NONE', ( 0.0005884949961229730140, -0.2249510543439056098, 0.9743698870671265722 ) ) ; -#5525 = CARTESIAN_POINT ( 'NONE', ( 36.37174737416455628, 116.2078075011454530, 90.24581721519344057 ) ) ; -#5526 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749105660, 132.4103119505516872, 92.77713868769167505 ) ) ; -#5527 = LOCAL_TIME ( 14, 25, 27.00000000000000000, #11652 ) ; -#5528 = VECTOR ( 'NONE', #34244, 999.9999999999998863 ) ; -#5529 = ADVANCED_FACE ( 'NONE', ( #39493 ), #11501, .F. ) ; -#5530 = VERTEX_POINT ( 'NONE', #11097 ) ; -#5531 = CARTESIAN_POINT ( 'NONE', ( -25.36909684671000065, 191.4049634124000079, 104.5096523423000008 ) ) ; -#5532 = FACE_OUTER_BOUND ( 'NONE', #2520, .T. ) ; -#5533 = VECTOR ( 'NONE', #31656, 1000.000000000000000 ) ; -#5534 = VECTOR ( 'NONE', #10677, 1000.000000000000114 ) ; -#5535 = CARTESIAN_POINT ( 'NONE', ( 26.00089628489983085, 120.1297184594761518, 90.45026046038573497 ) ) ; -#5536 = VERTEX_POINT ( 'NONE', #39290 ) ; -#5537 = VECTOR ( 'NONE', #39191, 1000.000000000000000 ) ; -#5538 = ORIENTED_EDGE ( 'NONE', *, *, #26400, .T. ) ; -#5539 = LINE ( 'NONE', #17998, #6776 ) ; -#5540 = ORIENTED_EDGE ( 'NONE', *, *, #27419, .T. ) ; -#5541 = EDGE_LOOP ( 'NONE', ( #2777, #5135, #30651, #13342 ) ) ; -#5542 = CARTESIAN_POINT ( 'NONE', ( -38.72644908288000209, 118.7070105194000007, 89.71289965706000658 ) ) ; -#5543 = ORIENTED_EDGE ( 'NONE', *, *, #29558, .F. ) ; -#5544 = CARTESIAN_POINT ( 'NONE', ( -35.95650388587999657, 192.3880382931000383, 106.6208529457999958 ) ) ; -#5545 = CARTESIAN_POINT ( 'NONE', ( 13.50012729195547934, 124.7429919913152929, 88.95710818440272760 ) ) ; -#5546 = CARTESIAN_POINT ( 'NONE', ( 35.54675198585685791, 209.7096512551739238, 76.03703539298859937 ) ) ; -#5547 = EDGE_CURVE ( 'NONE', #31532, #29127, #12923, .T. ) ; -#5548 = ORIENTED_EDGE ( 'NONE', *, *, #4917, .T. ) ; -#5549 = CARTESIAN_POINT ( 'NONE', ( 37.23595206341339292, 125.7280132836212090, 91.73594320339621788 ) ) ; -#5550 = ORIENTED_EDGE ( 'NONE', *, *, #40413, .F. ) ; -#5551 = CARTESIAN_POINT ( 'NONE', ( 26.34089362906999909, 122.4733679560000041, 90.82008448493999708 ) ) ; -#5552 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250100069, 179.6252109631261646, 101.6466942236143041 ) ) ; -#5554 = PLANE ( 'NONE', #20730 ) ; -#5553 = DIRECTION ( 'NONE', ( 0.0005884949961187157857, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#5555 = CONICAL_SURFACE ( 'NONE', #36255, 6.500000447167895601, 0.7853981634102744636 ) ; -#5556 = ORIENTED_EDGE ( 'NONE', *, *, #29532, .T. ) ; -#5557 = DIRECTION ( 'NONE', ( -0.7933533411653341805, -0.5931840316264885837, -0.1368326740407639630 ) ) ; -#5558 = CIRCLE ( 'NONE', #21249, 2.499999999950359264 ) ; -#5559 = CIRCLE ( 'NONE', #39499, 5.000000000000007994 ) ; -#5560 = ORIENTED_EDGE ( 'NONE', *, *, #12785, .F. ) ; -#5561 = EDGE_CURVE ( 'NONE', #4634, #29235, #20431, .T. ) ; -#5562 = CARTESIAN_POINT ( 'NONE', ( -25.50117313779839279, 120.2777482656007493, 87.94978106211669910 ) ) ; -#5563 = VECTOR ( 'NONE', #31686, 1000.000000000000114 ) ; -#5564 = ORIENTED_EDGE ( 'NONE', *, *, #1574, .F. ) ; -#5565 = CARTESIAN_POINT ( 'NONE', ( 0.04412548967591382182, 271.9029643396000324, 73.05847743168912700 ) ) ; -#5566 = EDGE_CURVE ( 'NONE', #35793, #21265, #21489, .T. ) ; -#5567 = DIRECTION ( 'NONE', ( 1.067522139063650355E-15, 0.9743700557921582961, 0.2249510932971566790 ) ) ; -#5568 = DIRECTION ( 'NONE', ( 0.0005884949961218503226, -0.2249510543439091348, 0.9743698870671257950 ) ) ; -#5569 = CARTESIAN_POINT ( 'NONE', ( 3.534327104360340588, 144.2236672556986434, 92.94748474794259607 ) ) ; -#5570 = CARTESIAN_POINT ( 'NONE', ( -12.64096629072132671, 135.0031918988153734, 90.94602447020258751 ) ) ; -#5571 = ADVANCED_FACE ( 'NONE', ( #21111 ), #20698, .T. ) ; -#5572 = ORIENTED_EDGE ( 'NONE', *, *, #124, .T. ) ; -#5573 = ORIENTED_EDGE ( 'NONE', *, *, #1047, .T. ) ; -#5574 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#5575 = EDGE_CURVE ( 'NONE', #5306, #28078, #9649, .T. ) ; -#5576 = CARTESIAN_POINT ( 'NONE', ( 26.90034969837000034, 124.4338129124000005, 88.87781188249999786 ) ) ; -#5577 = EDGE_CURVE ( 'NONE', #3576, #15604, #4864, .T. ) ; -#5578 = ORIENTED_EDGE ( 'NONE', *, *, #12097, .T. ) ; -#5579 = CARTESIAN_POINT ( 'NONE', ( 14.78718619285897518, 182.9114187639047486, 104.4381813414848779 ) ) ; -#5580 = EDGE_CURVE ( 'NONE', #14577, #5875, #3074, .T. ) ; -#5581 = CARTESIAN_POINT ( 'NONE', ( 1.064777206855000102, 189.0415535920000139, 105.7486712733000047 ) ) ; -#5582 = AXIS2_PLACEMENT_3D ( 'NONE', #9248, #27874, #21918 ) ; -#5583 = LINE ( 'NONE', #24005, #722 ) ; -#5584 = AXIS2_PLACEMENT_3D ( 'NONE', #36217, #1261, #20270 ) ; -#5585 = CARTESIAN_POINT ( 'NONE', ( 13.49905878177554364, 124.6099297501443317, 88.74416486964138073 ) ) ; -#5586 = CIRCLE ( 'NONE', #26415, 6.500001099658025083 ) ; -#5587 = FACE_OUTER_BOUND ( 'NONE', #3068, .T. ) ; -#5588 = DIRECTION ( 'NONE', ( -0.7947985590179719173, 0.5913221741348984040, 0.1365039814779489546 ) ) ; -#5589 = AXIS2_PLACEMENT_3D ( 'NONE', #15679, #29780, #7273 ) ; -#5590 = EDGE_LOOP ( 'NONE', ( #18035, #24839, #8901, #9170 ) ) ; -#5591 = FACE_OUTER_BOUND ( 'NONE', #2999, .T. ) ; -#5592 = VECTOR ( 'NONE', #30790, 1000.000000000000114 ) ; -#5593 = CARTESIAN_POINT ( 'NONE', ( 15.99974815555098218, 138.5019114137554936, 91.61902897505088106 ) ) ; -#5594 = CARTESIAN_POINT ( 'NONE', ( -31.70415073521903082, 226.4002260770974715, 75.57765305100397768 ) ) ; -#5595 = EDGE_LOOP ( 'NONE', ( #35106, #28631, #35319 ) ) ; -#5596 = CARTESIAN_POINT ( 'NONE', ( 29.77977117171763055, 126.9465717267340352, 89.45601389182257890 ) ) ; -#5597 = ORIENTED_EDGE ( 'NONE', *, *, #14768, .T. ) ; -#5599 = PLANE ( 'NONE', #1767 ) ; -#5598 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#5600 = ORIENTED_EDGE ( 'NONE', *, *, #13285, .F. ) ; -#5601 = VERTEX_POINT ( 'NONE', #5354 ) ; -#5602 = CARTESIAN_POINT ( 'NONE', ( -39.04920027559904838, 183.0116935643604563, 105.0069995834368228 ) ) ; -#5603 = ORIENTED_EDGE ( 'NONE', *, *, #5895, .T. ) ; -#5604 = EDGE_CURVE ( 'NONE', #1116, #8838, #14787, .T. ) ; -#5605 = CARTESIAN_POINT ( 'NONE', ( 2.828495721917000161, 209.6693846176999898, 75.93556339497999375 ) ) ; -#5606 = ADVANCED_FACE ( 'NONE', ( #1896 ), #28594, .F. ) ; -#5607 = AXIS2_PLACEMENT_3D ( 'NONE', #34076, #18522, #31031 ) ; -#5608 = FACE_OUTER_BOUND ( 'NONE', #32326, .T. ) ; -#5609 = CARTESIAN_POINT ( 'NONE', ( -19.73768723704201378, 124.3505960279316014, 178.1528323905962452 ) ) ; -#5610 = ADVANCED_FACE ( 'NONE', ( #2104 ), #5554, .T. ) ; -#5611 = CARTESIAN_POINT ( 'NONE', ( 3.534086375177905914, 137.3581944094399603, 91.36238397499714381 ) ) ; -#5612 = VERTEX_POINT ( 'NONE', #27060 ) ; -#5613 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #11736, #24222 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5614 = AXIS2_PLACEMENT_3D ( 'NONE', #21213, #33868, #33665 ) ; -#5615 = ORIENTED_EDGE ( 'NONE', *, *, #7829, .T. ) ; -#5616 = CARTESIAN_POINT ( 'NONE', ( -43.94897559503611717, 113.3760414272567658, 85.85438615327556988 ) ) ; -#5617 = VERTEX_POINT ( 'NONE', #17810 ) ; -#5618 = EDGE_LOOP ( 'NONE', ( #3910, #37937, #40251, #23418, #39200 ) ) ; -#5619 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -3.519737326604822600E-16, 0.0006039748319386522603 ) ) ; -#5620 = EDGE_CURVE ( 'NONE', #26666, #2464, #32764, .T. ) ; -#5621 = CARTESIAN_POINT ( 'NONE', ( -15.49970618472456074, 126.6879451655382809, 89.42365126055415203 ) ) ; -#5622 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#5623 = AXIS2_PLACEMENT_3D ( 'NONE', #21167, #33622, #15235 ) ; -#5624 = ADVANCED_FACE ( 'NONE', ( #14179 ), #26649, .T. ) ; -#5625 = VERTEX_POINT ( 'NONE', #9249 ) ; -#5626 = ORIENTED_EDGE ( 'NONE', *, *, #17035, .F. ) ; -#5627 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#5628 = CARTESIAN_POINT ( 'NONE', ( 37.31639193983529879, 111.9096183688354245, 150.0649592369359766 ) ) ; -#5629 = CARTESIAN_POINT ( 'NONE', ( -35.99558150418999958, 191.6334676936000108, 104.0208552518000005 ) ) ; -#5630 = ORIENTED_EDGE ( 'NONE', *, *, #22122, .T. ) ; -#5631 = CARTESIAN_POINT ( 'NONE', ( -14.31241256655965621, 191.5260885035135061, 103.8788496152396306 ) ) ; -#5632 = ORIENTED_EDGE ( 'NONE', *, *, #4188, .F. ) ; -#5633 = ADVANCED_FACE ( 'NONE', ( #37248 ), #21721, .T. ) ; -#5634 = ORIENTED_EDGE ( 'NONE', *, *, #14347, .F. ) ; -#5635 = LINE ( 'NONE', #15448, #13456 ) ; -#5636 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#5637 = ORIENTED_EDGE ( 'NONE', *, *, #13151, .F. ) ; -#5638 = CARTESIAN_POINT ( 'NONE', ( -0.4376666143244844487, 188.6124751099401351, 103.1978086576974221 ) ) ; -#5639 = CARTESIAN_POINT ( 'NONE', ( -14.46549242823763670, 124.5535847925790591, 88.41711846462007429 ) ) ; -#5640 = ADVANCED_FACE ( 'NONE', ( #33965 ), #2717, .F. ) ; -#5641 = PLANE ( 'NONE', #34833 ) ; -#5642 = CARTESIAN_POINT ( 'NONE', ( -38.95171367412964258, 118.8959113292413008, 89.72644992023717236 ) ) ; -#5643 = CARTESIAN_POINT ( 'NONE', ( 20.50086710772547249, 118.1127836709285077, 88.42196848232048012 ) ) ; -#5644 = VECTOR ( 'NONE', #37114, 1000.000000000000000 ) ; -#5645 = VERTEX_POINT ( 'NONE', #33768 ) ; -#5646 = DIRECTION ( 'NONE', ( 0.0006039748319378514686, 1.190362635753271326E-14, 0.9999998176071847045 ) ) ; -#5647 = ORIENTED_EDGE ( 'NONE', *, *, #14388, .T. ) ; -#5648 = VERTEX_POINT ( 'NONE', #11914 ) ; -#5649 = ORIENTED_EDGE ( 'NONE', *, *, #10944, .T. ) ; -#5650 = CARTESIAN_POINT ( 'NONE', ( -14.16977587005254158, 182.7576216332787737, 102.3675551592481696 ) ) ; -#5651 = VECTOR ( 'NONE', #22329, 1000.000000000000000 ) ; -#5652 = CARTESIAN_POINT ( 'NONE', ( -77.86614104348858234, 192.3476576144325350, 194.3451165138085912 ) ) ; -#5653 = VECTOR ( 'NONE', #3570, 999.9999999999998863 ) ; -#5654 = CARTESIAN_POINT ( 'NONE', ( 36.79269875112999699, 115.7237157444999980, 89.55271142270001405 ) ) ; -#5655 = CARTESIAN_POINT ( 'NONE', ( -27.41839611513448460, 124.6006531081595341, 91.00156934076623827 ) ) ; -#5656 = ORIENTED_EDGE ( 'NONE', *, *, #36113, .T. ) ; -#5657 = FACE_OUTER_BOUND ( 'NONE', #34842, .T. ) ; -#5658 = VECTOR ( 'NONE', #9172, 1000.000000000000000 ) ; -#5659 = PLANE ( 'NONE', #18726 ) ; -#5660 = ORIENTED_EDGE ( 'NONE', *, *, #23966, .F. ) ; -#5661 = CARTESIAN_POINT ( 'NONE', ( 37.40434350968867250, 145.4460227941551409, 282.5393146728916918 ) ) ; -#5662 = EDGE_CURVE ( 'NONE', #9884, #7887, #5822, .T. ) ; -#5663 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971581223 ) ) ; -#5664 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422595305, 173.8425259979994166, 102.8583906001885140 ) ) ; -#5665 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38855, #10871, #26614, #37021 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5666 = EDGE_CURVE ( 'NONE', #19822, #27218, #31263, .T. ) ; -#5667 = CARTESIAN_POINT ( 'NONE', ( 13.49999901743118969, 185.9104161957919530, 102.5624987652265645 ) ) ; -#5668 = EDGE_CURVE ( 'NONE', #39268, #17481, #11184, .T. ) ; -#5669 = CARTESIAN_POINT ( 'NONE', ( -39.52795649239820364, 119.7636651699444172, 87.83955215443023690 ) ) ; -#5670 = VERTEX_POINT ( 'NONE', #18218 ) ; -#5671 = VERTEX_POINT ( 'NONE', #25749 ) ; -#5672 = CARTESIAN_POINT ( 'NONE', ( 5.696483686681999892, 176.3366685932843154, 152.9217693939943388 ) ) ; -#5673 = DIRECTION ( 'NONE', ( 0.0005884949961234528818, -0.2249510543439066368, 0.9743698870671262391 ) ) ; -#5674 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10720, #26875, #33173, #32587 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5675 = CARTESIAN_POINT ( 'NONE', ( -19.32883136058536522, 148.6341161399039379, 180.6975394149132796 ) ) ; -#5676 = CARTESIAN_POINT ( 'NONE', ( -30.07831637853678686, 134.9151858147922667, 90.81876078434068233 ) ) ; -#5677 = CIRCLE ( 'NONE', #22675, 6.000000000000007994 ) ; -#5678 = ORIENTED_EDGE ( 'NONE', *, *, #37060, .T. ) ; -#5679 = DIRECTION ( 'NONE', ( 0.0005559617641631810821, -0.3907311284876849311, 0.9205046855596428212 ) ) ; -#5680 = CARTESIAN_POINT ( 'NONE', ( -22.99922046160000022, 115.1130721137993191, 90.28167579205376114 ) ) ; -#5681 = ORIENTED_EDGE ( 'NONE', *, *, #13249, .T. ) ; -#5682 = CARTESIAN_POINT ( 'NONE', ( -38.17065836694000325, 119.3614639495999938, 87.31205330151000510 ) ) ; -#5683 = AXIS2_PLACEMENT_3D ( 'NONE', #28790, #770, #32849 ) ; -#5684 = EDGE_CURVE ( 'NONE', #37846, #15841, #18416, .T. ) ; -#5685 = CARTESIAN_POINT ( 'NONE', ( -5.668533004880120352, 130.5151097924451733, 90.22088404420168217 ) ) ; -#5686 = VERTEX_POINT ( 'NONE', #15181 ) ; -#5687 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559851 ) ) ; -#5688 = VECTOR ( 'NONE', #2116, 1000.000000000000114 ) ; -#5689 = FACE_OUTER_BOUND ( 'NONE', #28900, .T. ) ; -#5690 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#5691 = CARTESIAN_POINT ( 'NONE', ( -19.99984748064912665, 127.7403057018771904, 89.15611954941233819 ) ) ; -#5692 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567068 ) ) ; -#5693 = EDGE_LOOP ( 'NONE', ( #10719, #10088, #39604, #40167 ) ) ; -#5694 = CARTESIAN_POINT ( 'NONE', ( 38.45096419866000304, 119.7540675949999951, 87.16908489566000640 ) ) ; -#5695 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#5696 = CARTESIAN_POINT ( 'NONE', ( 36.80935782333227735, 191.6100133775751146, 104.3431987054480459 ) ) ; -#5697 = ORIENTED_EDGE ( 'NONE', *, *, #20109, .F. ) ; -#5698 = CARTESIAN_POINT ( 'NONE', ( -46.07067374065479015, 125.2897427003481567, 91.71631631010059493 ) ) ; -#5699 = ORIENTED_EDGE ( 'NONE', *, *, #33075, .F. ) ; -#5700 = ORIENTED_EDGE ( 'NONE', *, *, #1156, .F. ) ; -#5701 = CARTESIAN_POINT ( 'NONE', ( 15.83511149127399698, 173.8757477943649974, 102.6937136768388257 ) ) ; -#5702 = CARTESIAN_POINT ( 'NONE', ( -43.37573184873028964, 120.5133568975543312, 91.89801145053407083 ) ) ; -#5703 = CARTESIAN_POINT ( 'NONE', ( 3.667815739887069881, 126.2406713584936568, 91.36142183053807742 ) ) ; -#5704 = DIRECTION ( 'NONE', ( 0.7933531821873445189, -0.5930539082291854669, -0.1373964710147356216 ) ) ; -#5705 = DIRECTION ( 'NONE', ( 0.0004161288024593278660, -0.8480480897937284768, 0.5299191110292476026 ) ) ; -#5706 = LINE ( 'NONE', #2656, #13641 ) ; -#5707 = VECTOR ( 'NONE', #8459, 1000.000000000000114 ) ; -#5708 = CARTESIAN_POINT ( 'NONE', ( 20.49908935505346719, 194.2769733015968541, 102.8866291927022303 ) ) ; -#5709 = CARTESIAN_POINT ( 'NONE', ( -35.44629553207012407, 109.6131156415000021, 90.28919351360151779 ) ) ; -#5710 = VECTOR ( 'NONE', #17709, 1000.000000000000000 ) ; -#5711 = PLANE ( 'NONE', #9594 ) ; -#5712 = DATE_AND_TIME ( #33504, #33599 ) ; -#5713 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; -#5714 = CARTESIAN_POINT ( 'NONE', ( -35.45668950278280818, 209.7096538831000032, 73.07991903448129278 ) ) ; -#5715 = CARTESIAN_POINT ( 'NONE', ( 16.85259243521460704, 122.7321277142430063, 172.1167388318093572 ) ) ; -#5716 = CARTESIAN_POINT ( 'NONE', ( -20.29046413099899127, 184.3514851594299273, 105.0052445737425586 ) ) ; -#5717 = CARTESIAN_POINT ( 'NONE', ( 25.99214295446221357, 205.1071317750680123, 76.08915132579089402 ) ) ; -#5718 = CARTESIAN_POINT ( 'NONE', ( 37.18342556898939932, 191.4809961130700344, 104.2937016655759805 ) ) ; -#5719 = EDGE_CURVE ( 'NONE', #27492, #31838, #18614, .T. ) ; -#5720 = VERTEX_POINT ( 'NONE', #36846 ) ; -#5721 = CARTESIAN_POINT ( 'NONE', ( 36.30754780179999841, 190.7605496600999970, 106.8997039823000108 ) ) ; -#5722 = ORIENTED_EDGE ( 'NONE', *, *, #17043, .F. ) ; -#5723 = ORIENTED_EDGE ( 'NONE', *, *, #10947, .T. ) ; -#5724 = DIRECTION ( 'NONE', ( -0.6087614115774880874, -0.7729348350621346730, -0.1788331191967949541 ) ) ; -#5725 = ORIENTED_EDGE ( 'NONE', *, *, #36215, .F. ) ; -#5726 = CARTESIAN_POINT ( 'NONE', ( 5.668111463870241451, 127.9108406804157454, 92.26213812171604900 ) ) ; -#5727 = FACE_BOUND ( 'NONE', #36456, .T. ) ; -#5728 = CARTESIAN_POINT ( 'NONE', ( 17.17601495924390775, 152.1789494465686516, 183.7587347276876812 ) ) ; -#5729 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#5730 = EDGE_LOOP ( 'NONE', ( #26613, #22029, #19134, #17066, #32985 ) ) ; -#5731 = CARTESIAN_POINT ( 'NONE', ( -39.44182108252999797, 119.8420607383000061, 90.56257358771001975 ) ) ; -#5732 = DIRECTION ( 'NONE', ( 1.156504871743948528E-16, 0.9743043966640312359, 0.2252353050503803078 ) ) ; -#5733 = CARTESIAN_POINT ( 'NONE', ( -20.51767729163077547, 205.5669979433283743, 76.31342074382325791 ) ) ; -#5734 = DIRECTION ( 'NONE', ( -0.0005884949961230158400, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#5735 = CARTESIAN_POINT ( 'NONE', ( -14.55294119842380063, 130.1498083917327904, 89.70916153464222020 ) ) ; -#5736 = ORIENTED_EDGE ( 'NONE', *, *, #2090, .T. ) ; -#5737 = CARTESIAN_POINT ( 'NONE', ( -35.95435800709800844, 218.5902260770999987, 75.58022006963935269 ) ) ; -#5738 = VECTOR ( 'NONE', #1810, 1000.000000000000114 ) ; -#5739 = CARTESIAN_POINT ( 'NONE', ( -19.46367937371129742, 126.2449231135791052, 175.9963188856066267 ) ) ; -#5740 = CYLINDRICAL_SURFACE ( 'NONE', #18928, 1.650000000000002798 ) ; -#5741 = VECTOR ( 'NONE', #16807, 1000.000000000000000 ) ; -#5742 = DIRECTION ( 'NONE', ( -0.1305262051639064502, 0.9658997602660150950, 0.2236080563923502629 ) ) ; -#5743 = VERTEX_POINT ( 'NONE', #16505 ) ; -#5744 = EDGE_LOOP ( 'NONE', ( #6873, #31869, #9717, #23290 ) ) ; -#5745 = EDGE_CURVE ( 'NONE', #34643, #29469, #35734, .T. ) ; -#5746 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498903273, 181.7471167548486903, 104.6805916159352137 ) ) ; -#5747 = CARTESIAN_POINT ( 'NONE', ( 0.5732654918656009402, 188.9939624363879886, 103.6998360806250048 ) ) ; -#5748 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#5749 = VERTEX_POINT ( 'NONE', #21531 ) ; -#5750 = ORIENTED_EDGE ( 'NONE', *, *, #40363, .F. ) ; -#5751 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391913256 ) ) ; -#5752 = ORIENTED_EDGE ( 'NONE', *, *, #36644, .F. ) ; -#5753 = CARTESIAN_POINT ( 'NONE', ( 25.49064341928363220, 210.1701501020666853, 73.54307249209045949 ) ) ; -#5754 = EDGE_CURVE ( 'NONE', #15470, #9488, #35067, .T. ) ; -#5755 = CARTESIAN_POINT ( 'NONE', ( -36.54980801557999825, 191.4575972176000391, 105.7985015051000062 ) ) ; -#5756 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173593504, 151.8558615133134708, 95.23291569143458446 ) ) ; -#5757 = CARTESIAN_POINT ( 'NONE', ( 21.33595229338290622, 124.0143879427035642, 174.3475635039766587 ) ) ; -#5758 = ORIENTED_EDGE ( 'NONE', *, *, #36505, .F. ) ; -#5759 = CARTESIAN_POINT ( 'NONE', ( 44.87942421866700471, 186.3432610492434662, 107.7775111143619142 ) ) ; -#5760 = CARTESIAN_POINT ( 'NONE', ( -3.169881662145332513, 128.5839160399947332, 89.34077473205128683 ) ) ; -#5761 = CARTESIAN_POINT ( 'NONE', ( -25.50006458888940131, 118.8155663869242886, 89.78318340809063614 ) ) ; -#5762 = ORIENTED_EDGE ( 'NONE', *, *, #18024, .F. ) ; -#5763 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#5764 = AXIS2_PLACEMENT_3D ( 'NONE', #37562, #6881, #748 ) ; -#5765 = CARTESIAN_POINT ( 'NONE', ( -35.66122680783149690, 191.7745722628655187, 103.9336186430080176 ) ) ; -#5766 = EDGE_CURVE ( 'NONE', #39184, #26493, #37039, .T. ) ; -#5767 = EDGE_CURVE ( 'NONE', #8220, #38190, #12305, .T. ) ; -#5768 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20427, #32907, #29857, #1839 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.003684369075596064403, 0.004391610989047198960 ), - .UNSPECIFIED. ) ; -#5770 = CARTESIAN_POINT ( 'NONE', ( 37.82238896534387607, 118.1203242141574918, 87.67403663391523594 ) ) ; -#5769 = DIRECTION ( 'NONE', ( 0.9999998268368104348, 0.0001323825905645391462, -0.0005734118926139947789 ) ) ; -#5771 = VERTEX_POINT ( 'NONE', #12496 ) ; -#5772 = ORIENTED_EDGE ( 'NONE', *, *, #34404, .T. ) ; -#5773 = CARTESIAN_POINT ( 'NONE', ( -37.56217811679143637, 145.6431275960571838, 282.5778664123586168 ) ) ; -#5774 = ORIENTED_EDGE ( 'NONE', *, *, #8636, .T. ) ; -#5775 = ORIENTED_EDGE ( 'NONE', *, *, #29219, .F. ) ; -#5776 = CARTESIAN_POINT ( 'NONE', ( 39.09835378390000216, 119.0620695200999961, 89.83136319784000534 ) ) ; -#5777 = LINE ( 'NONE', #24605, #25703 ) ; -#5778 = CARTESIAN_POINT ( 'NONE', ( -14.62254490296892406, 128.1170529630574606, 179.5121082275731794 ) ) ; -#5779 = DIRECTION ( 'NONE', ( 4.163336342344344915E-15, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#5780 = CARTESIAN_POINT ( 'NONE', ( 30.11206992270177807, 130.4288502407819692, 89.74660688778928375 ) ) ; -#5781 = CARTESIAN_POINT ( 'NONE', ( 25.50039747045966365, 119.1573732123225113, 89.75239197219917742 ) ) ; -#5782 = VERTEX_POINT ( 'NONE', #37446 ) ; -#5783 = EDGE_LOOP ( 'NONE', ( #38464, #33748, #26417, #34769 ) ) ; -#5784 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#5785 = FACE_OUTER_BOUND ( 'NONE', #34693, .T. ) ; -#5786 = ORIENTED_EDGE ( 'NONE', *, *, #25535, .F. ) ; -#5787 = AXIS2_PLACEMENT_3D ( 'NONE', #15726, #11879, #40261 ) ; -#5788 = CARTESIAN_POINT ( 'NONE', ( 35.63003517211246418, 209.7096550727324598, 75.95365185415883502 ) ) ; -#5789 = AXIS2_PLACEMENT_3D ( 'NONE', #2874, #15354, #40277 ) ; -#5790 = AXIS2_PLACEMENT_3D ( 'NONE', #18456, #15605, #12532 ) ; -#5791 = CARTESIAN_POINT ( 'NONE', ( 0.5640584298180999490, 188.5916829849000180, 106.0617877117999939 ) ) ; -#5792 = FACE_OUTER_BOUND ( 'NONE', #16554, .T. ) ; -#5793 = AXIS2_PLACEMENT_3D ( 'NONE', #18465, #15428, #12353 ) ; -#5794 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385907860 ) ) ; -#5795 = CARTESIAN_POINT ( 'NONE', ( -19.99799082025366204, 173.8313734241264967, 102.8761342917995734 ) ) ; -#5796 = CARTESIAN_POINT ( 'NONE', ( -24.30274708465592326, 117.2756935949167314, 170.8452364414067688 ) ) ; -#5797 = ADVANCED_FACE ( 'NONE', ( #21919 ), #7678, .T. ) ; -#5798 = ORIENTED_EDGE ( 'NONE', *, *, #12471, .T. ) ; -#5799 = CARTESIAN_POINT ( 'NONE', ( 25.99030006218819366, 209.2225090305980473, 73.04280209862368167 ) ) ; -#5800 = CARTESIAN_POINT ( 'NONE', ( -19.99827944177191341, 118.8155627782461181, 90.27982142893266371 ) ) ; -#5801 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142367503004439, 137.4659008082804519, 177.5714312369109393 ) ) ; -#5802 = ADVANCED_FACE ( 'NONE', ( #38395 ), #10799, .F. ) ; -#5803 = ORIENTED_EDGE ( 'NONE', *, *, #398, .F. ) ; -#5804 = CARTESIAN_POINT ( 'NONE', ( 28.46561332783693743, 183.4529609800732146, 105.0712386042130646 ) ) ; -#5805 = ORIENTED_EDGE ( 'NONE', *, *, #32312, .F. ) ; -#5806 = ADVANCED_FACE ( 'NONE', ( #32668 ), #24678, .T. ) ; -#5807 = EDGE_CURVE ( 'NONE', #15536, #14606, #26343, .T. ) ; -#5809 = LINE ( 'NONE', #18460, #25310 ) ; -#5808 = LINE ( 'NONE', #36273, #12221 ) ; -#5810 = ADVANCED_FACE ( 'NONE', ( #13658 ), #8991, .F. ) ; -#5811 = EDGE_LOOP ( 'NONE', ( #23345, #24443, #13633, #12618 ) ) ; -#5812 = AXIS2_PLACEMENT_3D ( 'NONE', #38795, #16914, #7724 ) ; -#5813 = ORIENTED_EDGE ( 'NONE', *, *, #35630, .F. ) ; -#5814 = CARTESIAN_POINT ( 'NONE', ( 25.49121397285902191, 206.8604079607866595, 74.53252332260622381 ) ) ; -#5815 = EDGE_CURVE ( 'NONE', #20529, #12363, #36414, .T. ) ; -#5816 = ORIENTED_EDGE ( 'NONE', *, *, #411, .F. ) ; -#5817 = CARTESIAN_POINT ( 'NONE', ( 3.183378028902000167, 209.2131121278000023, 76.25807972613000629 ) ) ; -#5818 = AXIS2_PLACEMENT_3D ( 'NONE', #8932, #39985, #30800 ) ; -#5819 = LINE ( 'NONE', #27716, #7876 ) ; -#5820 = CARTESIAN_POINT ( 'NONE', ( 12.64462803911309408, 177.7679548982654865, 100.7076870104759223 ) ) ; -#5821 = ORIENTED_EDGE ( 'NONE', *, *, #19804, .T. ) ; -#5822 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24399, #28797, #5770, #34167, #38203, #16314, #5965, #31123 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 4 ), - ( 0.000000000000000000, 1.269409900111855138E-06, 0.2500142417030432607, 0.5000095022491750640, 0.7500047627954068430, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5823 = EDGE_LOOP ( 'NONE', ( #2305, #5394 ) ) ; -#5824 = VECTOR ( 'NONE', #35739, 1000.000000000000114 ) ; -#5825 = EDGE_LOOP ( 'NONE', ( #36942, #1535, #20911, #38405, #1058, #19499 ) ) ; -#5826 = ORIENTED_EDGE ( 'NONE', *, *, #19600, .T. ) ; -#5827 = CARTESIAN_POINT ( 'NONE', ( -76.10777906860100472, 155.6779500220206387, 98.71888895707797928 ) ) ; -#5828 = CARTESIAN_POINT ( 'NONE', ( -15.49852919137054741, 126.2381079287689403, 91.37240600825562353 ) ) ; -#5829 = CARTESIAN_POINT ( 'NONE', ( -15.03362232203068771, 151.2943605774707407, 177.4366870137986609 ) ) ; -#5830 = ORIENTED_EDGE ( 'NONE', *, *, #11301, .F. ) ; -#5831 = EDGE_LOOP ( 'NONE', ( #30957, #11071, #12403, #5989 ) ) ; -#5832 = ORIENTED_EDGE ( 'NONE', *, *, #6211, .T. ) ; -#5833 = FACE_OUTER_BOUND ( 'NONE', #30484, .T. ) ; -#5834 = CARTESIAN_POINT ( 'NONE', ( -35.95668941153999754, 211.4999999999000124, 73.08022102179994306 ) ) ; -#5835 = DIRECTION ( 'NONE', ( 0.6773442687123943928, 0.7356661890031861439, 0.000000000000000000 ) ) ; -#5836 = CARTESIAN_POINT ( 'NONE', ( -27.65267440593000003, 124.6459337409000057, 88.44632915393999895 ) ) ; -#5837 = ORIENTED_EDGE ( 'NONE', *, *, #35780, .F. ) ; -#5838 = ORIENTED_EDGE ( 'NONE', *, *, #26407, .F. ) ; -#5839 = ADVANCED_FACE ( 'NONE', ( #7303 ), #37057, .T. ) ; -#5840 = CARTESIAN_POINT ( 'NONE', ( -21.10564552771868918, 182.7447230726116914, 104.5924260504270222 ) ) ; -#5841 = PLANE ( 'NONE', #27454 ) ; -#5842 = ORIENTED_EDGE ( 'NONE', *, *, #28086, .T. ) ; -#5843 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; -#5844 = CARTESIAN_POINT ( 'NONE', ( -15.99999440082457447, 126.8010213445309660, 88.93691041956509480 ) ) ; -#5845 = CARTESIAN_POINT ( 'NONE', ( 40.29675614866165745, 187.8287955346809213, 108.1243603913822824 ) ) ; -#5846 = CARTESIAN_POINT ( 'NONE', ( -15.49852918272448576, 137.6306203012457843, 94.00257521259531757 ) ) ; -#5847 = EDGE_CURVE ( 'NONE', #1172, #4372, #959, .T. ) ; -#5848 = VECTOR ( 'NONE', #8377, 1000.000000000000227 ) ; -#5849 = ORIENTED_EDGE ( 'NONE', *, *, #18889, .F. ) ; -#5850 = CARTESIAN_POINT ( 'NONE', ( 23.78175299703032408, 115.1895619078190833, 90.25342125631841839 ) ) ; -#5851 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#5852 = PLANE ( 'NONE', #10127 ) ; -#5853 = AXIS2_PLACEMENT_3D ( 'NONE', #10494, #22961, #26237 ) ; -#5854 = CARTESIAN_POINT ( 'NONE', ( 38.21082481197999670, 118.9849248355999976, 90.40249913504000290 ) ) ; -#5855 = EDGE_CURVE ( 'NONE', #5116, #13604, #19413, .T. ) ; -#5856 = CARTESIAN_POINT ( 'NONE', ( -29.66394945108131864, 181.9788733209050520, 101.6839728573242070 ) ) ; -#5857 = EDGE_LOOP ( 'NONE', ( #33533, #32165, #35246, #8949 ) ) ; -#5858 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#5859 = VERTEX_POINT ( 'NONE', #23068 ) ; -#5860 = EDGE_CURVE ( 'NONE', #3824, #3701, #5047, .T. ) ; -#5861 = FACE_OUTER_BOUND ( 'NONE', #33148, .T. ) ; -#5862 = ADVANCED_FACE ( 'NONE', ( #10402 ), #1374, .T. ) ; -#5863 = ORIENTED_EDGE ( 'NONE', *, *, #4453, .F. ) ; -#5864 = CARTESIAN_POINT ( 'NONE', ( 0.5623190733617040582, 188.6124699482102756, 103.1972064621602527 ) ) ; -#5865 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825881520, 173.9561929685035011, 102.3660449494794875 ) ) ; -#5866 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749098554, 132.4103119504792119, 92.77713868755240867 ) ) ; -#5867 = DIRECTION ( 'NONE', ( 0.0005884949961248158324, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#5868 = LINE ( 'NONE', #6262, #33683 ) ; -#5869 = VERTEX_POINT ( 'NONE', #36125 ) ; -#5871 = AXIS2_PLACEMENT_3D ( 'NONE', #29226, #6932, #16332 ) ; -#5870 = CARTESIAN_POINT ( 'NONE', ( -22.49975369487818710, 158.6756590294297382, 96.81282609783636417 ) ) ; -#5872 = CIRCLE ( 'NONE', #9151, 2.500000000000002220 ) ; -#5873 = CARTESIAN_POINT ( 'NONE', ( -26.74382575616715130, 120.3580507813137075, 171.5572023280520000 ) ) ; -#5874 = AXIS2_PLACEMENT_3D ( 'NONE', #30004, #20382, #4838 ) ; -#5875 = VERTEX_POINT ( 'NONE', #32272 ) ; -#5876 = CARTESIAN_POINT ( 'NONE', ( 30.06786877912685441, 134.3922893418122442, 93.61725361227318842 ) ) ; -#5877 = AXIS2_PLACEMENT_3D ( 'NONE', #33509, #36998, #39437 ) ; -#5878 = CARTESIAN_POINT ( 'NONE', ( -21.15906699444968453, 115.7109002682168466, 90.28056438547068296 ) ) ; -#5879 = ORIENTED_EDGE ( 'NONE', *, *, #38382, .T. ) ; -#5880 = CARTESIAN_POINT ( 'NONE', ( -2.937322199011638268, 191.1124755427409809, 103.7764892006471058 ) ) ; -#5881 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173423507, 174.4013293029843794, 100.4379480074635751 ) ) ; -#5882 = ORIENTED_EDGE ( 'NONE', *, *, #3615, .T. ) ; -#5883 = CARTESIAN_POINT ( 'NONE', ( -45.25641640995738868, 187.0376772300918162, 105.9402203223797585 ) ) ; -#5884 = FACE_OUTER_BOUND ( 'NONE', #10332, .T. ) ; -#5885 = CARTESIAN_POINT ( 'NONE', ( -38.16347685272999968, 118.8553488218999945, 90.29083592950999559 ) ) ; -#5886 = CARTESIAN_POINT ( 'NONE', ( 18.86495409459369199, 125.7426432556772937, 175.2080514493007399 ) ) ; -#5887 = CARTESIAN_POINT ( 'NONE', ( 3.312914662172945945, 125.9807902387186687, 88.73587715203963455 ) ) ; -#5888 = ORIENTED_EDGE ( 'NONE', *, *, #26086, .T. ) ; -#5889 = CARTESIAN_POINT ( 'NONE', ( 39.65541091293999898, 120.3034690318000060, 87.52491919870999482 ) ) ; -#5890 = CARTESIAN_POINT ( 'NONE', ( 30.80503333159449042, 110.6131156702000027, 89.74917927975997145 ) ) ; -#5891 = DIRECTION ( 'NONE', ( 0.0002267487151011638629, 0.6230052038431761474, 0.7822176580526309930 ) ) ; -#5892 = EDGE_CURVE ( 'NONE', #8895, #34116, #20384, .T. ) ; -#5893 = ADVANCED_FACE ( 'NONE', ( #29603 ), #25981, .F. ) ; -#5894 = CARTESIAN_POINT ( 'NONE', ( -16.26675888613999277, 147.1900965690931571, 179.8154315105366265 ) ) ; -#5895 = EDGE_CURVE ( 'NONE', #23591, #6503, #16102, .T. ) ; -#5896 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #2579, #9312 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5897 = ORIENTED_EDGE ( 'NONE', *, *, #15367, .F. ) ; -#5898 = PLANE ( 'NONE', #21189 ) ; -#5899 = ADVANCED_FACE ( 'NONE', ( #35492 ), #29410, .F. ) ; -#5900 = FACE_OUTER_BOUND ( 'NONE', #31378, .T. ) ; -#5901 = CARTESIAN_POINT ( 'NONE', ( -38.90873939381000213, 209.7096538831000032, 152.4718672074000381 ) ) ; -#5902 = CONICAL_SURFACE ( 'NONE', #34, 6.500002405954553808, 0.7853981634096851572 ) ; -#5903 = CARTESIAN_POINT ( 'NONE', ( -38.93887205695098430, 183.6185768681206696, 102.5812822866380429 ) ) ; -#5904 = EDGE_CURVE ( 'NONE', #37986, #38350, #30819, .T. ) ; -#5905 = CIRCLE ( 'NONE', #28758, 6.000000000022998492 ) ; -#5906 = VECTOR ( 'NONE', #24118, 999.9999999999998863 ) ; -#5907 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29608, #35502, #13861, #1185 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5908 = CARTESIAN_POINT ( 'NONE', ( 20.31497364642072512, 209.7094416523713107, 75.71273011267322772 ) ) ; -#5909 = EDGE_CURVE ( 'NONE', #8706, #15284, #24894, .T. ) ; -#5910 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 181.0156285263394409, 104.5149534146525951 ) ) ; -#5911 = CARTESIAN_POINT ( 'NONE', ( -14.16977588484152939, 129.7240516297933368, 90.12378855087145268 ) ) ; -#5912 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; -#5913 = CARTESIAN_POINT ( 'NONE', ( -20.51958837602166952, 211.0905570355220391, 74.23756124933424871 ) ) ; -#5914 = CARTESIAN_POINT ( 'NONE', ( 36.67803983362900055, 191.3737267936979833, 106.3776180154320201 ) ) ; -#5915 = CARTESIAN_POINT ( 'NONE', ( 36.74530222242999855, 191.5590816579000091, 106.2291238966000009 ) ) ; -#5916 = ORIENTED_EDGE ( 'NONE', *, *, #21926, .T. ) ; -#5917 = EDGE_LOOP ( 'NONE', ( #38129, #4733, #22457, #38667 ) ) ; -#5918 = EDGE_CURVE ( 'NONE', #37217, #22040, #33867, .T. ) ; -#5919 = FACE_OUTER_BOUND ( 'NONE', #31099, .T. ) ; -#5920 = FACE_OUTER_BOUND ( 'NONE', #39683, .T. ) ; -#5921 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#5922 = CARTESIAN_POINT ( 'NONE', ( 16.88646150490552955, 151.9945395218822739, 184.0188689872561554 ) ) ; -#5923 = CARTESIAN_POINT ( 'NONE', ( -32.07406512675382970, 176.8455996186746404, 100.5003186764579368 ) ) ; -#5924 = ORIENTED_EDGE ( 'NONE', *, *, #16133, .F. ) ; -#5925 = CARTESIAN_POINT ( 'NONE', ( -39.48405827645999722, 119.1504450973999951, 89.61452043577999405 ) ) ; -#5926 = CONICAL_SURFACE ( 'NONE', #35288, 2.503075499750329502, 0.7853981633711295540 ) ; -#5927 = CIRCLE ( 'NONE', #22923, 59.40509898897000340 ) ; -#5928 = CARTESIAN_POINT ( 'NONE', ( -22.49970497326267349, 138.0793299450762106, 92.05778796167568601 ) ) ; -#5929 = DIRECTION ( 'NONE', ( -0.6087611427445811518, -0.7731004622513008018, -0.1781166650011639652 ) ) ; -#5930 = EDGE_LOOP ( 'NONE', ( #34742, #3478, #32070, #14518 ) ) ; -#5931 = CARTESIAN_POINT ( 'NONE', ( 29.37172806597842722, 112.1957651408767873, 175.8423023756299131 ) ) ; -#5932 = AXIS2_PLACEMENT_3D ( 'NONE', #36897, #430, #21374 ) ; -#5933 = AXIS2_PLACEMENT_3D ( 'NONE', #27565, #31006, #2972 ) ; -#5934 = LINE ( 'NONE', #18389, #34819 ) ; -#5935 = DIRECTION ( 'NONE', ( 0.0004161288024595938208, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#5936 = DIRECTION ( 'NONE', ( 0.0004161288024539961934, 0.5299192578740949955, 0.8480479980348919478 ) ) ; -#5937 = LINE ( 'NONE', #15346, #16399 ) ; -#5938 = CARTESIAN_POINT ( 'NONE', ( 26.00352093159665756, 118.1131156702000169, 90.25513476933149093 ) ) ; -#5939 = ORIENTED_EDGE ( 'NONE', *, *, #22108, .F. ) ; -#5940 = ORIENTED_EDGE ( 'NONE', *, *, #15806, .F. ) ; -#5941 = CARTESIAN_POINT ( 'NONE', ( -27.97052338342000155, 187.2447426445999952, 103.2870855110000008 ) ) ; -#5942 = CARTESIAN_POINT ( 'NONE', ( 2.028511351659660455, 189.6362499608300141, 103.8782587184760189 ) ) ; -#5943 = FACE_OUTER_BOUND ( 'NONE', #5831, .T. ) ; -#5944 = EDGE_CURVE ( 'NONE', #33123, #28125, #6366, .T. ) ; -#5945 = VERTEX_POINT ( 'NONE', #39598 ) ; -#5946 = CARTESIAN_POINT ( 'NONE', ( -3.824228238827691584, 136.7434104837603002, 94.00818167131841108 ) ) ; -#5947 = EDGE_CURVE ( 'NONE', #14526, #11101, #2611, .T. ) ; -#5948 = EDGE_LOOP ( 'NONE', ( #12381, #36746, #36957, #22814 ) ) ; -#5949 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8368, #14710, #5072, #4872 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.749868521873144678, 3.288573094609483327 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8122409435129915867, 0.8122409435129915867, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#5950 = CC_DESIGN_PERSON_AND_ORGANIZATION_ASSIGNMENT ( #18158, #12060, ( #37519 ) ) ; -#5951 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921577410, 0.2249510932971593713 ) ) ; -#5952 = AXIS2_PLACEMENT_3D ( 'NONE', #27984, #24920, #5687 ) ; -#5953 = CARTESIAN_POINT ( 'NONE', ( 35.04675250840001155, 225.9002260768477583, 76.03733726937247184 ) ) ; -#5954 = CARTESIAN_POINT ( 'NONE', ( 42.46126417412090603, 102.4384360438650674, 173.5898619844123516 ) ) ; -#5955 = CARTESIAN_POINT ( 'NONE', ( 39.14109227172561134, 77.12646253814384067, 290.6753325472866436 ) ) ; -#5956 = CONICAL_SURFACE ( 'NONE', #19661, 7.003070832701193460, 0.7853905227103019637 ) ; -#5957 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749900286, 179.6299767372254621, 101.6260513916172670 ) ) ; -#5958 = CARTESIAN_POINT ( 'NONE', ( -36.13007122617000277, 190.7921904634999919, 106.9513591670999944 ) ) ; -#5959 = EDGE_LOOP ( 'NONE', ( #10864, #16900, #28610, #34071 ) ) ; -#5960 = CARTESIAN_POINT ( 'NONE', ( 13.49481983871936386, 124.3681642032378534, 88.35737770391504853 ) ) ; -#5961 = AXIS2_PLACEMENT_3D ( 'NONE', #12721, #15981, #446 ) ; -#5962 = FACE_OUTER_BOUND ( 'NONE', #30271, .T. ) ; -#5963 = CARTESIAN_POINT ( 'NONE', ( -14.55306305638819886, 182.5568561273574630, 101.8082842025129366 ) ) ; -#5965 = CARTESIAN_POINT ( 'NONE', ( 36.05207512480546939, 113.4195156597768062, 87.73930006848613061 ) ) ; -#5964 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -3.486209987973606947E-16, -0.0006039748319386279742 ) ) ; -#5966 = EDGE_LOOP ( 'NONE', ( #14795, #539, #18872, #2125, #28676 ) ) ; -#5967 = ORIENTED_EDGE ( 'NONE', *, *, #18525, .F. ) ; -#5968 = EDGE_CURVE ( 'NONE', #4945, #26517, #34068, .T. ) ; -#5969 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28853, #19632, #7767, #32128 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5970 = ORIENTED_EDGE ( 'NONE', *, *, #6163, .F. ) ; -#5971 = CARTESIAN_POINT ( 'NONE', ( 21.02805964049290210, 115.8422386153537218, 87.25508387092705220 ) ) ; -#5972 = EDGE_LOOP ( 'NONE', ( #33639, #39478, #3992, #39684 ) ) ; -#5973 = CARTESIAN_POINT ( 'NONE', ( -11.79202345736525892, 125.7774812735008254, 176.8918472601677365 ) ) ; -#5974 = CARTESIAN_POINT ( 'NONE', ( -40.95517856246386401, 220.4002260740000168, 75.58324044005986764 ) ) ; -#5975 = CARTESIAN_POINT ( 'NONE', ( 35.04645051036201409, 220.4002260771000010, 75.53733736045833780 ) ) ; -#5976 = CARTESIAN_POINT ( 'NONE', ( 25.50042068489791092, 119.4947997981225143, 89.79082806718720633 ) ) ; -#5977 = EDGE_LOOP ( 'NONE', ( #26616, #7154, #889, #26715 ) ) ; -#5978 = EDGE_LOOP ( 'NONE', ( #9525, #33678, #28269, #23564 ) ) ; -#5979 = CARTESIAN_POINT ( 'NONE', ( 33.42108704067000247, 226.1502260771000010, 75.78831908486999680 ) ) ; -#5980 = AXIS2_PLACEMENT_3D ( 'NONE', #9871, #7584, #34768 ) ; -#5981 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10044, #36690, #9856, #22327 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5982 = CARTESIAN_POINT ( 'NONE', ( 47.95588533879620741, 89.40266445833195519, 291.5248371983224729 ) ) ; -#5983 = ORIENTED_EDGE ( 'NONE', *, *, #8065, .T. ) ; -#5984 = CARTESIAN_POINT ( 'NONE', ( -36.51249493859999973, 191.4347527150000303, 106.3954561580000018 ) ) ; -#5985 = AXIS2_PLACEMENT_3D ( 'NONE', #4887, #29241, #1213 ) ; -#5986 = DIRECTION ( 'NONE', ( 0.0006039748319389448864, 1.387638830454547823E-14, 0.9999998176071845934 ) ) ; -#5987 = CARTESIAN_POINT ( 'NONE', ( -23.36052865740974838, 181.6105241605473282, 104.1608863659234885 ) ) ; -#5988 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39858, #36804, #8806, #21275, #933, #4397, #32232 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 4 ), - ( 0.0005016376834197731199, 0.001216693642771546954, 0.002475153169198318886 ), - .UNSPECIFIED. ) ; -#5989 = ORIENTED_EDGE ( 'NONE', *, *, #12151, .T. ) ; -#5990 = EDGE_CURVE ( 'NONE', #35941, #6111, #5250, .T. ) ; -#5991 = CARTESIAN_POINT ( 'NONE', ( 1.796908679885000026, 188.6799599361000048, 106.2909706032000088 ) ) ; -#5992 = EDGE_CURVE ( 'NONE', #28895, #9915, #36540, .T. ) ; -#5993 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#5994 = CARTESIAN_POINT ( 'NONE', ( -45.01543256409814120, 130.9257504736116289, 89.90670049556989341 ) ) ; -#5995 = DIRECTION ( 'NONE', ( -0.0005884949961203977085, 0.2249510542986902784, -0.9743698870775652221 ) ) ; -#5996 = DIRECTION ( 'NONE', ( 0.7764773693108221186, -0.5342314611987211137, -0.3341850397812930473 ) ) ; -#5997 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36541, #8340, #30420, #2207 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#5998 = VERTEX_POINT ( 'NONE', #11392 ) ; -#5999 = CARTESIAN_POINT ( 'NONE', ( -2.853038766185818087, 209.7096500570610544, 73.06022702708840200 ) ) ; -#6000 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#6001 = CARTESIAN_POINT ( 'NONE', ( -85.24348513260991922, 108.2328939675489039, 25.03902193712222513 ) ) ; -#6002 = EDGE_LOOP ( 'NONE', ( #14338, #13408, #4466 ) ) ; -#6003 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7730, #7327, #38603, #38799 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6004 = CARTESIAN_POINT ( 'NONE', ( 16.37235661304711698, 121.4990984041977669, 177.3555196612732914 ) ) ; -#6005 = ORIENTED_EDGE ( 'NONE', *, *, #2632, .F. ) ; -#6007 = CARTESIAN_POINT ( 'NONE', ( -3.169886429704571462, 127.9892485439772543, 89.20349298771401436 ) ) ; -#6006 = DIRECTION ( 'NONE', ( -0.0005884949961255136249, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#6008 = ORIENTED_EDGE ( 'NONE', *, *, #38008, .F. ) ; -#6009 = CIRCLE ( 'NONE', #19684, 2.000000000000011546 ) ; -#6010 = ORIENTED_EDGE ( 'NONE', *, *, #17784, .F. ) ; -#6011 = ADVANCED_FACE ( 'NONE', ( #12216 ), #24701, .T. ) ; -#6012 = AXIS2_PLACEMENT_3D ( 'NONE', #40396, #21420, #15075 ) ; -#6013 = LINE ( 'NONE', #37296, #28812 ) ; -#6014 = ORIENTED_EDGE ( 'NONE', *, *, #6613, .T. ) ; -#6015 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048993906, 181.0091974213519848, 104.5428127881224043 ) ) ; -#6016 = CARTESIAN_POINT ( 'NONE', ( -31.70566062302000887, 225.9002260770971873, 73.07765350693868811 ) ) ; -#6017 = CARTESIAN_POINT ( 'NONE', ( -3.786117645261999787, 171.3070458651999957, 102.0268941565000205 ) ) ; -#6018 = ORIENTED_EDGE ( 'NONE', *, *, #16645, .T. ) ; -#6019 = VERTEX_POINT ( 'NONE', #21628 ) ; -#6020 = EDGE_LOOP ( 'NONE', ( #29186, #25965, #2146, #40316 ) ) ; -#6021 = CARTESIAN_POINT ( 'NONE', ( 2.519724450483999956, 189.0000000000000000, 32.65697486330000032 ) ) ; -#6022 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#6023 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -3.869599770875634371E-16, -0.0006039748319386379488 ) ) ; -#6024 = CYLINDRICAL_SURFACE ( 'NONE', #30699, 1.749999999999998446 ) ; -#6025 = EDGE_LOOP ( 'NONE', ( #33784, #4352, #6859, #5399 ) ) ; -#6026 = EDGE_CURVE ( 'NONE', #12880, #18436, #34124, .T. ) ; -#6027 = ORIENTED_EDGE ( 'NONE', *, *, #21424, .T. ) ; -#6028 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319385907860 ) ) ; -#6029 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; -#6030 = VERTEX_POINT ( 'NONE', #30418 ) ; -#6031 = CARTESIAN_POINT ( 'NONE', ( 45.16687593781013277, 180.7102929186874576, 104.0827134509707719 ) ) ; -#6032 = EDGE_CURVE ( 'NONE', #8808, #1228, #6064, .T. ) ; -#6033 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364886824597, 136.5649596138813706, 181.4686487119530511 ) ) ; -#6034 = CARTESIAN_POINT ( 'NONE', ( -40.53910299374540926, 190.0772126196563931, 106.7391449377395958 ) ) ; -#6035 = ORIENTED_EDGE ( 'NONE', *, *, #15409, .T. ) ; -#6036 = AXIS2_PLACEMENT_3D ( 'NONE', #12035, #37175, #24518 ) ; -#6037 = CARTESIAN_POINT ( 'NONE', ( 0.2289920495087351959, 188.6124736079447928, 103.1974058479635374 ) ) ; -#6038 = EDGE_CURVE ( 'NONE', #32912, #7007, #11644, .T. ) ; -#6039 = CARTESIAN_POINT ( 'NONE', ( -15.69890139841092669, 125.5937060352607944, 88.65799436637878728 ) ) ; -#6040 = EDGE_CURVE ( 'NONE', #3145, #6533, #39049, .T. ) ; -#6041 = VECTOR ( 'NONE', #34175, 1000.000000000000114 ) ; -#6042 = EDGE_CURVE ( 'NONE', #27010, #30572, #24295, .T. ) ; -#6043 = CONICAL_SURFACE ( 'NONE', #28898, 2.250000000020516921, 0.7853981633778843729 ) ; -#6044 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#6045 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#6046 = ORIENTED_EDGE ( 'NONE', *, *, #7180, .F. ) ; -#6047 = DIRECTION ( 'NONE', ( 0.0006039748319386249384, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#6048 = VERTEX_POINT ( 'NONE', #12015 ) ; -#6049 = ORIENTED_EDGE ( 'NONE', *, *, #12450, .F. ) ; -#6050 = DIRECTION ( 'NONE', ( 4.139050213799733023E-13, 0.9743700557921592953, 0.2249510932971530708 ) ) ; -#6051 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; -#6052 = CARTESIAN_POINT ( 'NONE', ( 35.67718874540000229, 112.3973804366000167, 90.12490527673999452 ) ) ; -#6053 = CARTESIAN_POINT ( 'NONE', ( -29.47137614685608753, 181.8899047795460717, 101.6633165379169697 ) ) ; -#6054 = DIRECTION ( 'NONE', ( -0.7075227796380204603, 0.1590644278876734985, -0.6885564784925463089 ) ) ; -#6055 = ORIENTED_EDGE ( 'NONE', *, *, #5287, .F. ) ; -#6056 = CARTESIAN_POINT ( 'NONE', ( -37.83658322688275888, 190.9636381155321203, 106.3289620680116343 ) ) ; -#6057 = ORIENTED_EDGE ( 'NONE', *, *, #28657, .F. ) ; -#6058 = CARTESIAN_POINT ( 'NONE', ( -23.36190171889898082, 184.1216419186661710, 102.1748637788190450 ) ) ; -#6059 = CARTESIAN_POINT ( 'NONE', ( -38.03412148675000282, 118.9059103988000174, 90.43955447022000271 ) ) ; -#6060 = CARTESIAN_POINT ( 'NONE', ( 13.50029502672841275, 127.6322554542020100, 89.62414723470079991 ) ) ; -#6061 = ORIENTED_EDGE ( 'NONE', *, *, #9506, .F. ) ; -#6062 = FACE_OUTER_BOUND ( 'NONE', #6980, .T. ) ; -#6063 = DIRECTION ( 'NONE', ( -0.0005884949961236305826, 0.2249510543439055266, -0.9743698870671265722 ) ) ; -#6064 = LINE ( 'NONE', #33461, #28620 ) ; -#6065 = VECTOR ( 'NONE', #16464, 1000.000000000000114 ) ; -#6066 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#6067 = CARTESIAN_POINT ( 'NONE', ( -36.36961419606605972, 116.4217524378240824, 90.28975117483606994 ) ) ; -#6068 = VERTEX_POINT ( 'NONE', #36341 ) ; -#6069 = CARTESIAN_POINT ( 'NONE', ( -5.639490866605999742, 172.5096616001999905, 152.4718672074000381 ) ) ; -#6070 = FACE_OUTER_BOUND ( 'NONE', #33628, .T. ) ; -#6071 = ADVANCED_FACE ( 'NONE', ( #8339 ), #31900, .T. ) ; -#6072 = ORIENTED_EDGE ( 'NONE', *, *, #17515, .T. ) ; -#6073 = CARTESIAN_POINT ( 'NONE', ( 22.78079777786205540, 154.0096890380606851, 95.53720361524960936 ) ) ; -#6074 = DIRECTION ( 'NONE', ( -0.0005884949961279498272, 0.2249510543439066645, -0.9743698870671262391 ) ) ; -#6075 = ORIENTED_EDGE ( 'NONE', *, *, #36215, .T. ) ; -#6076 = DIRECTION ( 'NONE', ( -0.0005734119072324118244, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#6077 = ADVANCED_FACE ( 'NONE', ( #11812 ), #26670, .T. ) ; -#6078 = CARTESIAN_POINT ( 'NONE', ( -3.658524238769305548, 143.5629147409079849, 95.75245122380474072 ) ) ; -#6079 = ORIENTED_EDGE ( 'NONE', *, *, #10743, .T. ) ; -#6080 = CARTESIAN_POINT ( 'NONE', ( -38.54565956053704667, 119.1564759897554211, 90.30561907418552892 ) ) ; -#6081 = ADVANCED_FACE ( 'NONE', ( #33664 ), #6396, .F. ) ; -#6082 = CARTESIAN_POINT ( 'NONE', ( 3.645681218333928442, 167.8503244431992982, 101.3682716064896141 ) ) ; -#6083 = CARTESIAN_POINT ( 'NONE', ( -25.61249488107000261, 191.4936735446000000, 106.5346214470000064 ) ) ; -#6084 = CARTESIAN_POINT ( 'NONE', ( 30.07074129078960922, 176.7765392974760630, 103.0547703579528189 ) ) ; -#6085 = EDGE_CURVE ( 'NONE', #40349, #23346, #39479, .T. ) ; -#6086 = CARTESIAN_POINT ( 'NONE', ( 3.166350953592421025, 126.8041585549839709, 88.92605846951083493 ) ) ; -#6087 = ADVANCED_FACE ( 'NONE', ( #13015 ), #40402, .F. ) ; -#6088 = ORIENTED_EDGE ( 'NONE', *, *, #14347, .T. ) ; -#6089 = CARTESIAN_POINT ( 'NONE', ( 3.534327104360340588, 144.2236672556986434, 92.94748474794259607 ) ) ; -#6090 = CARTESIAN_POINT ( 'NONE', ( 37.34687875379296429, 164.7440994830517411, 197.7708186323690995 ) ) ; -#6091 = CIRCLE ( 'NONE', #22419, 2.000000001263195770 ) ; -#6092 = CARTESIAN_POINT ( 'NONE', ( -15.94446068766880487, 121.2107412334159591, 177.4020268254936923 ) ) ; -#6093 = CARTESIAN_POINT ( 'NONE', ( 20.33359772957916789, 151.9013818374707796, 95.05201010367687786 ) ) ; -#6094 = ORIENTED_EDGE ( 'NONE', *, *, #27288, .T. ) ; -#6095 = CIRCLE ( 'NONE', #222, 6.500001124525312868 ) ; -#6096 = LINE ( 'NONE', #30453, #3530 ) ; -#6097 = CARTESIAN_POINT ( 'NONE', ( 19.62707591446529065, 149.3912708485596568, 181.6576907650956230 ) ) ; -#6098 = CARTESIAN_POINT ( 'NONE', ( 24.26115219290281644, 213.8084469570644046, 73.04385095440355258 ) ) ; -#6099 = CARTESIAN_POINT ( 'NONE', ( 19.98059076253610300, 209.7097557544199162, 73.04669817794425057 ) ) ; -#6100 = VECTOR ( 'NONE', #17581, 1000.000000000000000 ) ; -#6101 = CARTESIAN_POINT ( 'NONE', ( -25.50198239243739806, 190.9621235434596542, 106.3177461849878114 ) ) ; -#6102 = CARTESIAN_POINT ( 'NONE', ( 44.91030012776904812, 180.8423815822312974, 104.4554649243456339 ) ) ; -#6103 = CARTESIAN_POINT ( 'NONE', ( -12.63885905074691252, 181.8641958648152013, 101.8896919015048042 ) ) ; -#6104 = DATE_AND_TIME ( #30247, #9447 ) ; -#6105 = CYLINDRICAL_SURFACE ( 'NONE', #27887, 4.999999999999990230 ) ; -#6106 = CARTESIAN_POINT ( 'NONE', ( 25.05527577951534468, 181.6921585128408765, 101.5847744912912418 ) ) ; -#6107 = LINE ( 'NONE', #15520, #18535 ) ; -#6108 = CARTESIAN_POINT ( 'NONE', ( 20.00016034875645943, 127.4394136103090887, 89.06260552501319694 ) ) ; -#6109 = CARTESIAN_POINT ( 'NONE', ( 37.18424073381000028, 191.2020551955000087, 105.6433944051999987 ) ) ; -#6110 = CARTESIAN_POINT ( 'NONE', ( 35.79896412904000158, 191.3773265435000042, 107.0072713659999977 ) ) ; -#6111 = VERTEX_POINT ( 'NONE', #3189 ) ; -#6112 = VERTEX_POINT ( 'NONE', #3580 ) ; -#6113 = CARTESIAN_POINT ( 'NONE', ( 15.95616423589712340, 121.8747789553152785, 174.5819126748912709 ) ) ; -#6114 = VECTOR ( 'NONE', #7998, 1000.000000000000000 ) ; -#6115 = CARTESIAN_POINT ( 'NONE', ( -20.18830040110167090, 184.9181145972527531, 102.5501949385248679 ) ) ; -#6116 = VECTOR ( 'NONE', #177, 1000.000000000000227 ) ; -#6117 = EDGE_CURVE ( 'NONE', #20878, #32946, #37742, .T. ) ; -#6118 = EDGE_CURVE ( 'NONE', #1973, #30537, #9662, .T. ) ; -#6119 = FACE_OUTER_BOUND ( 'NONE', #9003, .T. ) ; -#6120 = CARTESIAN_POINT ( 'NONE', ( -29.91365887524281320, 126.3524082176346610, 91.57855139315392989 ) ) ; -#6121 = EDGE_CURVE ( 'NONE', #24812, #12942, #34258, .T. ) ; -#6122 = AXIS2_PLACEMENT_3D ( 'NONE', #4196, #15532, #29369 ) ; -#6123 = VERTEX_POINT ( 'NONE', #3785 ) ; -#6124 = CARTESIAN_POINT ( 'NONE', ( 16.84438044484771879, 125.8148033517563249, 178.9876133819932136 ) ) ; -#6125 = CARTESIAN_POINT ( 'NONE', ( -42.36701999636228777, 171.7704926474248737, 184.4650328233902599 ) ) ; -#6126 = CARTESIAN_POINT ( 'NONE', ( -20.00074514949506010, 193.6646176325368458, 103.0738027862439310 ) ) ; -#6127 = CARTESIAN_POINT ( 'NONE', ( 17.33132192515028436, 121.2638944594648791, 177.4233360669502133 ) ) ; -#6128 = VERTEX_POINT ( 'NONE', #25497 ) ; -#6129 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6130 = DIRECTION ( 'NONE', ( -0.0004161288024517756931, 0.8480480897992000999, -0.5299191110204911626 ) ) ; -#6131 = CARTESIAN_POINT ( 'NONE', ( 20.53365435870338018, 147.8783930214090390, 152.4730821390034805 ) ) ; -#6132 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17996, #14151, #39881, #5330, #24168, #11477, #30500, #2282, #33339, #36623, #7791, #36206, #8208, #27037, #20676, #17788, #20258, #5119, #33135, #39272, #23961, #17590, #30283 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 2, 1, 2, 2, 2, 2, 2, 1, 4 ), - ( 0.000000000000000000, 0.1249999999999444888, 0.1874999999999157618, 0.2499999999998870348, 0.3749999999998629430, 0.4374999999998688827, 0.4687499999998721023, 0.4999999999998753220, 0.7499999999998643307, 0.7812499999998687716, 0.8124999999998732125, 0.8749999999999034106, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6133 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#6134 = ADVANCED_FACE ( 'NONE', ( #16262 ), #3385, .F. ) ; -#6135 = VERTEX_POINT ( 'NONE', #2992 ) ; -#6136 = LINE ( 'NONE', #28823, #37642 ) ; -#6137 = CARTESIAN_POINT ( 'NONE', ( 2.723234776511000099, 191.0360723070999995, 104.1040072879000036 ) ) ; -#6138 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#6139 = ORIENTED_EDGE ( 'NONE', *, *, #863, .F. ) ; -#6140 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#6141 = ORIENTED_EDGE ( 'NONE', *, *, #34991, .T. ) ; -#6142 = EDGE_CURVE ( 'NONE', #29201, #38952, #11620, .T. ) ; -#6143 = LINE ( 'NONE', #809, #7390 ) ; -#6144 = VECTOR ( 'NONE', #10434, 1000.000000000000114 ) ; -#6145 = AXIS2_PLACEMENT_3D ( 'NONE', #11195, #5039, #30000 ) ; -#6146 = CARTESIAN_POINT ( 'NONE', ( 20.00118831922474527, 194.3293166618819612, 106.3477151517464421 ) ) ; -#6147 = CIRCLE ( 'NONE', #31648, 1.999999999520721161 ) ; -#6148 = CARTESIAN_POINT ( 'NONE', ( -36.23924049691999727, 191.8477165461999903, 104.2143108436000034 ) ) ; -#6149 = CARTESIAN_POINT ( 'NONE', ( -17.09037752892578865, 152.4702182831101709, 182.2569833114785069 ) ) ; -#6150 = DIRECTION ( 'NONE', ( 0.0006039748319382907873, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#6151 = CARTESIAN_POINT ( 'NONE', ( 23.67998985452990368, 134.9222885997251637, 90.78792508986444432 ) ) ; -#6152 = CARTESIAN_POINT ( 'NONE', ( -37.02430110774999861, 191.2881234072000041, 106.2406684328999944 ) ) ; -#6153 = EDGE_LOOP ( 'NONE', ( #24792, #36700, #3111, #30133 ) ) ; -#6154 = FACE_OUTER_BOUND ( 'NONE', #5823, .T. ) ; -#6155 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13702, #10645, #7553, #33102, #7752, #20023, #38826, #30249, #34110, #27208 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999995559, 0.4999999999999991118, 0.7499999999999995559, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6156 = CARTESIAN_POINT ( 'NONE', ( -35.98778029410813417, 191.5265872904686830, 103.8920147005603951 ) ) ; -#6157 = CARTESIAN_POINT ( 'NONE', ( 33.97007310651787293, 92.28421717967789561, 297.5380279566514901 ) ) ; -#6159 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#6158 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; -#6160 = EDGE_LOOP ( 'NONE', ( #6817, #37546, #40431 ) ) ; -#6161 = ORIENTED_EDGE ( 'NONE', *, *, #21370, .T. ) ; -#6162 = EDGE_CURVE ( 'NONE', #33088, #39067, #17248, .T. ) ; -#6163 = EDGE_CURVE ( 'NONE', #26442, #30446, #32421, .T. ) ; -#6164 = ORIENTED_EDGE ( 'NONE', *, *, #7353, .F. ) ; -#6165 = EDGE_CURVE ( 'NONE', #12599, #15031, #11144, .T. ) ; -#6166 = EDGE_LOOP ( 'NONE', ( #14043, #29546, #20434, #25121 ) ) ; -#6167 = CARTESIAN_POINT ( 'NONE', ( 8.330750903747036418, 160.8464898286100322, 99.51904042281638851 ) ) ; -#6168 = CARTESIAN_POINT ( 'NONE', ( 26.71438282722398938, 124.3231695455690442, 88.85220642046358819 ) ) ; -#6169 = LINE ( 'NONE', #15573, #25898 ) ; -#6170 = CARTESIAN_POINT ( 'NONE', ( 39.31311957223007880, 119.5494579213072370, 87.74834752111200942 ) ) ; -#6171 = CARTESIAN_POINT ( 'NONE', ( 30.81681382182493678, 129.4130655731118509, 89.51166882856213647 ) ) ; -#6172 = AXIS2_PLACEMENT_3D ( 'NONE', #13397, #17031, #25885 ) ; -#6173 = CIRCLE ( 'NONE', #4848, 2.499999999897516645 ) ; -#6174 = CARTESIAN_POINT ( 'NONE', ( -12.63880466802784319, 135.2324181042121438, 91.31286148751507881 ) ) ; -#6175 = VERTEX_POINT ( 'NONE', #23416 ) ; -#6176 = DIRECTION ( 'NONE', ( 0.0005884949961226190220, -0.2249510543439057486, 0.9743698870671265722 ) ) ; -#6177 = VERTEX_POINT ( 'NONE', #32025 ) ; -#6178 = CARTESIAN_POINT ( 'NONE', ( 1.222756100067673213, 143.4876838778120884, 158.5675586475568366 ) ) ; -#6179 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #10193, #32258, #16696, #29197 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.712388980384698556, 6.103777378942509380 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8450726411000299976, 0.8450726411000299976, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#6180 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#6181 = ADVANCED_FACE ( 'NONE', ( #4180 ), #35855, .F. ) ; -#6182 = ORIENTED_EDGE ( 'NONE', *, *, #12041, .F. ) ; -#6183 = CARTESIAN_POINT ( 'NONE', ( 35.91764861553071597, 209.7096530691624139, 75.66569077816501476 ) ) ; -#6184 = CARTESIAN_POINT ( 'NONE', ( 2.623782561446397654, 189.6978541430437417, 103.4465393410279717 ) ) ; -#6185 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191947214049181, 0.8480481395922153665 ) ) ; -#6186 = FACE_OUTER_BOUND ( 'NONE', #23889, .T. ) ; -#6187 = ORIENTED_EDGE ( 'NONE', *, *, #123, .F. ) ; -#6188 = CARTESIAN_POINT ( 'NONE', ( 2.325038912688802473, 189.0644929844613387, 106.3859680065207982 ) ) ; -#6189 = VERTEX_POINT ( 'NONE', #19720 ) ; -#6190 = EDGE_CURVE ( 'NONE', #40149, #7358, #32599, .T. ) ; -#6191 = CARTESIAN_POINT ( 'NONE', ( 41.04524146632582671, 220.4002260741250154, 73.53371387615798938 ) ) ; -#6192 = CARTESIAN_POINT ( 'NONE', ( 36.15379333015832941, 191.4992728616623765, 103.8421784115979563 ) ) ; -#6193 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6194 = ORIENTED_EDGE ( 'NONE', *, *, #18740, .T. ) ; -#6195 = CARTESIAN_POINT ( 'NONE', ( 23.35635955975471134, 181.6919812636757285, 101.5857449861623110 ) ) ; -#6196 = CARTESIAN_POINT ( 'NONE', ( -20.04876416055233435, 127.0750181908596517, 92.02969372391483205 ) ) ; -#6197 = AXIS2_PLACEMENT_3D ( 'NONE', #26274, #38711, #23198 ) ; -#6198 = AXIS2_PLACEMENT_3D ( 'NONE', #20566, #29984, #14449 ) ; -#6199 = ORIENTED_EDGE ( 'NONE', *, *, #27291, .T. ) ; -#6200 = CARTESIAN_POINT ( 'NONE', ( -5.668307419685251425, 188.0500116628189744, 103.3219457577105800 ) ) ; -#6201 = ORIENTED_EDGE ( 'NONE', *, *, #35683, .F. ) ; -#6202 = CIRCLE ( 'NONE', #29067, 6.500000000014392043 ) ; -#6204 = CARTESIAN_POINT ( 'NONE', ( 0.5625159773845863631, 188.8708249854730354, 103.5219946925948591 ) ) ; -#6203 = DIRECTION ( 'NONE', ( -0.0005884949961159111715, 0.2249510543439030286, -0.9743698870671271273 ) ) ; -#6205 = EDGE_LOOP ( 'NONE', ( #2441, #25111, #24247, #24960, #2468, #33938, #10568, #296, #15964, #3962, #13991 ) ) ; -#6206 = VERTEX_POINT ( 'NONE', #7865 ) ; -#6207 = ORIENTED_EDGE ( 'NONE', *, *, #35203, .F. ) ; -#6208 = CARTESIAN_POINT ( 'NONE', ( 2.584181958089999842, 209.5884796122000182, 75.67830153580999308 ) ) ; -#6209 = CARTESIAN_POINT ( 'NONE', ( 41.83291673182624493, 184.0748290677734929, 107.2083188323588132 ) ) ; -#6210 = PLANE ( 'NONE', #35796 ) ; -#6211 = EDGE_CURVE ( 'NONE', #14392, #39304, #23018, .T. ) ; -#6212 = VERTEX_POINT ( 'NONE', #38727 ) ; -#6213 = ADVANCED_FACE ( 'NONE', ( #26695 ), #7058, .F. ) ; -#6214 = ORIENTED_EDGE ( 'NONE', *, *, #9410, .T. ) ; -#6215 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#6216 = CARTESIAN_POINT ( 'NONE', ( -19.73786857073881151, 124.3510898702264171, 178.1525024657645986 ) ) ; -#6217 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; -#6218 = CARTESIAN_POINT ( 'NONE', ( -23.36170564740000088, 182.0604262666973341, 102.2121465930607371 ) ) ; -#6219 = ORIENTED_EDGE ( 'NONE', *, *, #27501, .F. ) ; -#6220 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15174, #11493, #31308, #22109 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6221 = ORIENTED_EDGE ( 'NONE', *, *, #27831, .T. ) ; -#6222 = CARTESIAN_POINT ( 'NONE', ( -23.36013623391100325, 183.4467887557270842, 105.0979734400102217 ) ) ; -#6223 = CARTESIAN_POINT ( 'NONE', ( 76.10777906860903386, 155.6827192487146760, 98.62805563713385482 ) ) ; -#6224 = CARTESIAN_POINT ( 'NONE', ( 14.55294048017762698, 182.5605668518259392, 101.7915615195478409 ) ) ; -#6225 = AXIS2_PLACEMENT_3D ( 'NONE', #18451, #34398, #2922 ) ; -#6226 = ORIENTED_EDGE ( 'NONE', *, *, #3255, .T. ) ; -#6227 = FACE_OUTER_BOUND ( 'NONE', #9719, .T. ) ; -#6228 = CARTESIAN_POINT ( 'NONE', ( -40.71505848696708085, 189.9242018305782551, 106.7973272910517863 ) ) ; -#6229 = ORIENTED_EDGE ( 'NONE', *, *, #4254, .T. ) ; -#6230 = AXIS2_PLACEMENT_3D ( 'NONE', #17803, #1890, #36221 ) ; -#6231 = VECTOR ( 'NONE', #18643, 1000.000000000000114 ) ; -#6232 = VECTOR ( 'NONE', #17880, 1000.000000000000114 ) ; -#6233 = CARTESIAN_POINT ( 'NONE', ( -35.43807705578637268, 196.5784392935932203, 103.8965070399753614 ) ) ; -#6234 = CARTESIAN_POINT ( 'NONE', ( -5.666773900267269681, 187.4652808147925214, 105.7370325349066320 ) ) ; -#6235 = EDGE_CURVE ( 'NONE', #34668, #16043, #10681, .T. ) ; -#6236 = CARTESIAN_POINT ( 'NONE', ( 42.43787138009228244, 189.9416574239004376, 106.2771675705110823 ) ) ; -#6237 = CARTESIAN_POINT ( 'NONE', ( 26.03373140117899709, 191.5260202047026041, 103.8544635878054976 ) ) ; -#6238 = EDGE_LOOP ( 'NONE', ( #14738, #36571, #22603, #2015 ) ) ; -#6239 = CARTESIAN_POINT ( 'NONE', ( 21.72603247161529438, 129.4256177271351760, 92.59897021125679828 ) ) ; -#6240 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26425, #29890, #10882, #7386 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6241 = ORIENTED_EDGE ( 'NONE', *, *, #3518, .F. ) ; -#6242 = CARTESIAN_POINT ( 'NONE', ( 19.98483764167631094, 211.0849390754169974, 73.04592155476974824 ) ) ; -#6243 = FACE_OUTER_BOUND ( 'NONE', #14533, .T. ) ; -#6244 = CARTESIAN_POINT ( 'NONE', ( 38.55824950455000533, 118.6163727090000037, 89.80334989176999727 ) ) ; -#6245 = ORIENTED_EDGE ( 'NONE', *, *, #18916, .T. ) ; -#6246 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#6247 = VERTEX_POINT ( 'NONE', #28949 ) ; -#6248 = EDGE_CURVE ( 'NONE', #1973, #14528, #7662, .T. ) ; -#6249 = VECTOR ( 'NONE', #35506, 1000.000000000000114 ) ; -#6250 = VECTOR ( 'NONE', #4699, 1000.000000000000000 ) ; -#6251 = CONICAL_SURFACE ( 'NONE', #28483, 6.000000000213348450, 0.7853981633778843729 ) ; -#6252 = CARTESIAN_POINT ( 'NONE', ( -38.17814356823000566, 118.7082741531000067, 90.14969561450999436 ) ) ; -#6253 = ORIENTED_EDGE ( 'NONE', *, *, #10117, .F. ) ; -#6255 = VECTOR ( 'NONE', #7862, 1000.000000000000000 ) ; -#6254 = CARTESIAN_POINT ( 'NONE', ( 37.23701003965144452, 122.4655498436707859, 105.8628478846491987 ) ) ; -#6256 = CYLINDRICAL_SURFACE ( 'NONE', #13724, 2.000000000000014655 ) ; -#6257 = CARTESIAN_POINT ( 'NONE', ( -33.60903683397481956, 163.7527748289998328, 189.3325253559470696 ) ) ; -#6258 = AXIS2_PLACEMENT_3D ( 'NONE', #23639, #16330, #4612 ) ; -#6259 = CARTESIAN_POINT ( 'NONE', ( -21.65625503477336977, 158.4439038514896936, 96.24565958992596393 ) ) ; -#6260 = ADVANCED_FACE ( 'NONE', ( #10356 ), #29262, .T. ) ; -#6261 = EDGE_CURVE ( 'NONE', #16791, #20537, #21463, .T. ) ; -#6262 = CARTESIAN_POINT ( 'NONE', ( -30.01596277575672289, 112.8237990546615066, 152.1988939502894880 ) ) ; -#6263 = ORIENTED_EDGE ( 'NONE', *, *, #12922, .T. ) ; -#6264 = EDGE_CURVE ( 'NONE', #20739, #1497, #20099, .T. ) ; -#6265 = CARTESIAN_POINT ( 'NONE', ( 1.145067044774861653, 189.0860242507255009, 105.7614945720849846 ) ) ; -#6266 = CARTESIAN_POINT ( 'NONE', ( 26.00071577175129889, 119.4206015363792517, 90.28654347840240746 ) ) ; -#6267 = EDGE_LOOP ( 'NONE', ( #39503, #6312, #7454, #9969 ) ) ; -#6268 = CARTESIAN_POINT ( 'NONE', ( -29.78271245060107830, 185.5388541528431290, 103.0190830191734648 ) ) ; -#6269 = CARTESIAN_POINT ( 'NONE', ( -22.49783753475205472, 153.7286132221404955, 98.23646823715600362 ) ) ; -#6270 = VERTEX_POINT ( 'NONE', #23215 ) ; -#6271 = FACE_OUTER_BOUND ( 'NONE', #26555, .T. ) ; -#6272 = FACE_OUTER_BOUND ( 'NONE', #39393, .T. ) ; -#6273 = LINE ( 'NONE', #37362, #35174 ) ; -#6274 = ORIENTED_EDGE ( 'NONE', *, *, #28574, .F. ) ; -#6275 = FACE_OUTER_BOUND ( 'NONE', #23756, .T. ) ; -#6276 = LINE ( 'NONE', #40216, #38141 ) ; -#6277 = CARTESIAN_POINT ( 'NONE', ( 42.97429946896744468, 67.83849343097567441, 322.0145824706445978 ) ) ; -#6278 = CARTESIAN_POINT ( 'NONE', ( 30.07353398222051055, 177.0661537567726782, 103.5182483147875985 ) ) ; -#6279 = CARTESIAN_POINT ( 'NONE', ( -37.56217811679143637, 145.6431275960571838, 282.5778664123586168 ) ) ; -#6280 = AXIS2_PLACEMENT_3D ( 'NONE', #15267, #25285, #16054 ) ; -#6281 = ORIENTED_EDGE ( 'NONE', *, *, #30615, .F. ) ; -#6282 = CARTESIAN_POINT ( 'NONE', ( 29.19927575800447173, 163.6433483284885426, 97.41533068389654204 ) ) ; -#6283 = CARTESIAN_POINT ( 'NONE', ( -37.67574118798827243, 118.8155645602721222, 87.29053938956874958 ) ) ; -#6284 = PLANE ( 'NONE', #551 ) ; -#6285 = CIRCLE ( 'NONE', #21346, 2.249999999963659292 ) ; -#6286 = CARTESIAN_POINT ( 'NONE', ( -16.53001031479427141, 121.8780329720448066, 177.6173573199974953 ) ) ; -#6287 = CIRCLE ( 'NONE', #33050, 59.40509992922265781 ) ; -#6288 = ORIENTED_EDGE ( 'NONE', *, *, #5604, .F. ) ; -#6289 = FACE_OUTER_BOUND ( 'NONE', #2289, .T. ) ; -#6290 = CARTESIAN_POINT ( 'NONE', ( 17.03953122770531081, 121.4984955427919431, 177.4945558973374204 ) ) ; -#6291 = CARTESIAN_POINT ( 'NONE', ( 23.37288949314423192, 214.0898084988432686, 73.04438744281617346 ) ) ; -#6292 = FACE_OUTER_BOUND ( 'NONE', #9846, .T. ) ; -#6293 = CARTESIAN_POINT ( 'NONE', ( -27.26501486794000328, 187.3490569909000101, 105.6591404369000031 ) ) ; -#6294 = ORIENTED_EDGE ( 'NONE', *, *, #12041, .T. ) ; -#6295 = EDGE_CURVE ( 'NONE', #14325, #37725, #32809, .T. ) ; -#6296 = CARTESIAN_POINT ( 'NONE', ( -19.44534545229788591, 148.3863058741690679, 180.5858969458773515 ) ) ; -#6297 = ADVANCED_FACE ( 'NONE', ( #17052 ), #29908, .T. ) ; -#6298 = PLANE ( 'NONE', #31471 ) ; -#6299 = PLANE ( 'NONE', #12195 ) ; -#6300 = LINE ( 'NONE', #40242, #6116 ) ; -#6301 = CARTESIAN_POINT ( 'NONE', ( -39.35534632512823805, 129.4524480647742450, 89.54659771444076455 ) ) ; -#6302 = AXIS2_PLACEMENT_3D ( 'NONE', #18080, #34034, #21987 ) ; -#6303 = FACE_OUTER_BOUND ( 'NONE', #39372, .T. ) ; -#6304 = CARTESIAN_POINT ( 'NONE', ( 36.18931669942080021, 192.0080903167539930, 104.3523514206140135 ) ) ; -#6305 = EDGE_CURVE ( 'NONE', #1726, #29530, #7703, .T. ) ; -#6306 = CIRCLE ( 'NONE', #29182, 2.250000000000011102 ) ; -#6307 = EDGE_CURVE ( 'NONE', #17938, #4160, #8702, .T. ) ; -#6308 = VERTEX_POINT ( 'NONE', #27718 ) ; -#6310 = ORIENTED_EDGE ( 'NONE', *, *, #14619, .T. ) ; -#6309 = CARTESIAN_POINT ( 'NONE', ( 36.64635057513000049, 191.2562995250000029, 106.4472677424000011 ) ) ; -#6311 = VECTOR ( 'NONE', #7911, 999.9999999999998863 ) ; -#6312 = ORIENTED_EDGE ( 'NONE', *, *, #31768, .T. ) ; -#6313 = ORIENTED_EDGE ( 'NONE', *, *, #29519, .T. ) ; -#6314 = ADVANCED_FACE ( 'NONE', ( #24242 ), #20762, .F. ) ; -#6315 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173122415, 160.6259891653180034, 97.25765956939861212 ) ) ; -#6316 = EDGE_CURVE ( 'NONE', #39083, #23549, #36067, .T. ) ; -#6317 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#6318 = AXIS2_PLACEMENT_3D ( 'NONE', #1284, #38494, #32185 ) ; -#6319 = FACE_OUTER_BOUND ( 'NONE', #7371, .T. ) ; -#6320 = CARTESIAN_POINT ( 'NONE', ( 26.00056762447263026, 118.1139028608674408, 90.25209678512123901 ) ) ; -#6321 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25928, #10581, #38562, #13440 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6322 = ORIENTED_EDGE ( 'NONE', *, *, #30652, .T. ) ; -#6323 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640293485, -0.2252353050503884957 ) ) ; -#6324 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -7.822507694019388974E-18, -0.0006039748319385908944 ) ) ; -#6325 = FACE_OUTER_BOUND ( 'NONE', #30263, .T. ) ; -#6326 = ORIENTED_EDGE ( 'NONE', *, *, #39907, .T. ) ; -#6327 = CARTESIAN_POINT ( 'NONE', ( -35.62767240713339589, 77.14301703112144537, 291.5800621566117456 ) ) ; -#6328 = DIRECTION ( 'NONE', ( 0.9999998176071900335, 9.143184980527326943E-12, -0.0006039748227977436356 ) ) ; -#6329 = DIRECTION ( 'NONE', ( -0.0005884949961206199700, 0.2249510543439050825, -0.9743698870671266832 ) ) ; -#6330 = FACE_OUTER_BOUND ( 'NONE', #30773, .T. ) ; -#6331 = CARTESIAN_POINT ( 'NONE', ( 15.50029467836134778, 127.6324160061193567, 89.62297635127647766 ) ) ; -#6332 = ORIENTED_EDGE ( 'NONE', *, *, #16578, .T. ) ; -#6333 = CARTESIAN_POINT ( 'NONE', ( -25.50870663471662780, 209.7066555246269104, 75.57407794464953099 ) ) ; -#6334 = EDGE_CURVE ( 'NONE', #26262, #16596, #22091, .T. ) ; -#6335 = CARTESIAN_POINT ( 'NONE', ( 2.504779437822759913, 190.4797426592519969, 104.1230114428459927 ) ) ; -#6336 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; -#6337 = AXIS2_PLACEMENT_3D ( 'NONE', #36680, #8693, #18057 ) ; -#6338 = VERTEX_POINT ( 'NONE', #1947 ) ; -#6339 = ORIENTED_EDGE ( 'NONE', *, *, #36327, .F. ) ; -#6340 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775999513 ) ) ; -#6341 = ORIENTED_EDGE ( 'NONE', *, *, #28562, .F. ) ; -#6342 = VECTOR ( 'NONE', #8331, 1000.000000000000000 ) ; -#6343 = CARTESIAN_POINT ( 'NONE', ( 15.10714335843527145, 176.3834766976846993, 100.3651329064352922 ) ) ; -#6344 = CARTESIAN_POINT ( 'NONE', ( -17.26183278765846651, 121.5203170840806024, 176.4533299693686956 ) ) ; -#6345 = CARTESIAN_POINT ( 'NONE', ( -77.81044467944656162, 193.2853083808247163, 188.4036545891195544 ) ) ; -#6346 = ADVANCED_FACE ( 'NONE', ( #33000 ), #27528, .T. ) ; -#6347 = CARTESIAN_POINT ( 'NONE', ( 35.54795982457387993, 209.7096538831000032, 78.03703491738708919 ) ) ; -#6348 = CARTESIAN_POINT ( 'NONE', ( -16.54861044420561100, 152.4810896450478879, 181.7854491407948672 ) ) ; -#6349 = CARTESIAN_POINT ( 'NONE', ( -3.503014828629882782, 185.8319201473011901, 102.8998220731232749 ) ) ; -#6350 = EDGE_CURVE ( 'NONE', #2177, #16493, #33151, .T. ) ; -#6351 = CARTESIAN_POINT ( 'NONE', ( -12.63675505126982657, 134.8421811116586753, 93.35708474409203461 ) ) ; -#6352 = CARTESIAN_POINT ( 'NONE', ( 25.49062502244311190, 209.7098837966309475, 73.54308088453358039 ) ) ; -#6353 = ORIENTED_EDGE ( 'NONE', *, *, #11756, .T. ) ; -#6354 = EDGE_CURVE ( 'NONE', #27892, #6456, #12955, .T. ) ; -#6355 = LINE ( 'NONE', #24596, #40089 ) ; -#6356 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6413, #15436, #40353, #9302, #21779, #3348, #9912, #18672, #15622, #22381 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998718248, 0.3749999999998139266, 0.4374999999998159805, 0.4999999999998180344, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6357 = CARTESIAN_POINT ( 'NONE', ( -20.01839195877885302, 210.6282793158955258, 76.07066396527223162 ) ) ; -#6358 = LINE ( 'NONE', #37048, #37920 ) ; -#6359 = DIRECTION ( 'NONE', ( -0.0006039748319386279742, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#6360 = VERTEX_POINT ( 'NONE', #11335 ) ; -#6361 = ADVANCED_FACE ( 'NONE', ( #30358 ), #31215, .F. ) ; -#6362 = ORIENTED_EDGE ( 'NONE', *, *, #37178, .T. ) ; -#6363 = VECTOR ( 'NONE', #22343, 1000.000000000000000 ) ; -#6364 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319364164186 ) ) ; -#6365 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971580945 ) ) ; -#6366 = CIRCLE ( 'NONE', #20074, 2.250000000024274360 ) ; -#6367 = ORIENTED_EDGE ( 'NONE', *, *, #18349, .F. ) ; -#6368 = DIRECTION ( 'NONE', ( 0.0006039748319382295299, -5.238646599373848640E-18, 0.9999998176071845934 ) ) ; -#6369 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37762, #951, #28972, #34679, #6883, #32056, #28579, #157, #348, #35278, #7280, #19145, #751, #12617 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999976685, 0.2499999999999953371, 0.4999999999999906741, 0.6249999999999947820, 0.7499999999999988898, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6370 = CARTESIAN_POINT ( 'NONE', ( 23.68575892633012003, 134.8469895808620436, 93.33625697840975022 ) ) ; -#6371 = CARTESIAN_POINT ( 'NONE', ( -30.45075997731206030, 185.6036007986156449, 102.5212824999076986 ) ) ; -#6372 = CARTESIAN_POINT ( 'NONE', ( 26.00891783773975874, 196.5784392904109836, 103.8593946022765522 ) ) ; -#6373 = ORIENTED_EDGE ( 'NONE', *, *, #10986, .T. ) ; -#6374 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363196006660E-14, -0.9999998176071844824 ) ) ; -#6375 = ORIENTED_EDGE ( 'NONE', *, *, #23032, .F. ) ; -#6376 = PLANE ( 'NONE', #16147 ) ; -#6377 = CARTESIAN_POINT ( 'NONE', ( 39.06385346265498981, 191.4135374074515994, 104.3337792663689072 ) ) ; -#6378 = EDGE_LOOP ( 'NONE', ( #27072, #21920, #21904, #21195, #15708 ) ) ; -#6379 = CARTESIAN_POINT ( 'NONE', ( -13.50000077923288977, 160.7384646933283250, 96.77047462218374108 ) ) ; -#6380 = CARTESIAN_POINT ( 'NONE', ( 0.8004895499858137864, 188.6246619147358672, 103.1998745706487455 ) ) ; -#6381 = PLANE ( 'NONE', #33172 ) ; -#6382 = ORIENTED_EDGE ( 'NONE', *, *, #16404, .F. ) ; -#6383 = CARTESIAN_POINT ( 'NONE', ( -3.503014745918749728, 128.5096117803557263, 89.66592193050738047 ) ) ; -#6384 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#6385 = ORIENTED_EDGE ( 'NONE', *, *, #2931, .F. ) ; -#6386 = CARTESIAN_POINT ( 'NONE', ( -37.19447980817694344, 79.23804072928820119, 291.5810084690210715 ) ) ; -#6387 = CARTESIAN_POINT ( 'NONE', ( 36.47675288263859983, 191.3241625203926617, 103.8015559370109884 ) ) ; -#6388 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#6389 = EDGE_CURVE ( 'NONE', #16772, #28262, #8375, .T. ) ; -#6390 = EDGE_CURVE ( 'NONE', #28118, #38719, #33817, .T. ) ; -#6391 = VECTOR ( 'NONE', #1445, 1000.000000000000227 ) ; -#6392 = ORIENTED_EDGE ( 'NONE', *, *, #29404, .F. ) ; -#6393 = EDGE_CURVE ( 'NONE', #1613, #29278, #26756, .T. ) ; -#6394 = CARTESIAN_POINT ( 'NONE', ( -4.037441716916447376, 168.3837378232288131, 99.04296232367518371 ) ) ; -#6395 = CARTESIAN_POINT ( 'NONE', ( 3.535986888874630196, 143.5554623264248733, 95.87208321593506355 ) ) ; -#6396 = CONICAL_SURFACE ( 'NONE', #1169, 2.502993757559606625, 0.7853981634100110076 ) ; -#6397 = DIRECTION ( 'NONE', ( -0.0006039748319401620118, -1.156691652267356444E-14, -0.9999998176071847045 ) ) ; -#6398 = ORIENTED_EDGE ( 'NONE', *, *, #37836, .F. ) ; -#6399 = EDGE_CURVE ( 'NONE', #12650, #1917, #34533, .T. ) ; -#6400 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921598504, 0.2249510932971504895 ) ) ; -#6401 = CARTESIAN_POINT ( 'NONE', ( -4.081258675555402782, 191.9912574625914488, 28.07874682001180489 ) ) ; -#6402 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28221, #28018, #18767, #187 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6403 = CARTESIAN_POINT ( 'NONE', ( -16.04815022346086906, 121.3122077256701630, 177.4254579244168042 ) ) ; -#6404 = ORIENTED_EDGE ( 'NONE', *, *, #14552, .T. ) ; -#6405 = ORIENTED_EDGE ( 'NONE', *, *, #8658, .F. ) ; -#6406 = CARTESIAN_POINT ( 'NONE', ( 39.71730849539001440, 182.4927982134933302, 106.8443253198619374 ) ) ; -#6407 = FACE_OUTER_BOUND ( 'NONE', #21966, .T. ) ; -#6408 = DIRECTION ( 'NONE', ( 0.1305262860326017182, 0.9659620395529877612, 0.2233388161452626308 ) ) ; -#6409 = EDGE_LOOP ( 'NONE', ( #13560, #26454, #7385, #6373 ) ) ; -#6410 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #8781, #33697, #11849 ), - ( #36375, #36573, #7389 ), - ( #10489, #2444, #19850 ), - ( #24329, #39829, #8374 ), - ( #4878, #17744, #35384 ), - ( #17336, #23917, #36772 ), - ( #8160, #30238, #21245 ), - ( #5702, #2649, #1822 ), - ( #20835, #26778, #21044 ), - ( #39227, #27197, #11230 ), - ( #23705, #2237, #30454 ), - ( #36158, #20626, #11643 ), - ( #24117, #5078, #30039 ), - ( #26988, #39423, #8577 ), - ( #34690, #18356, #359 ), - ( #33900, #15510, #28197 ) ), - .UNSPECIFIED., .F., .F., .T. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 2, 2, 2, 2, 2, 2, 4 ), - ( 3, 3 ), - ( 0.000000000000000000, 0.0004331055251506400771, 0.0008662110503012801542, 0.001299316575451920286, 0.001732422100602560308, 0.002165527625753200548, 0.002598633150903840571, 0.003464844201205120617 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.9092867158778993320, 1.000000000000000000), - ( 1.000000000000000000, 0.9092804009989405856, 1.000000000000000000), - ( 1.000000000000000000, 0.9074037354123881682, 1.000000000000000000), - ( 1.000000000000000000, 0.9002689965790705573, 1.000000000000000000), - ( 1.000000000000000000, 0.8949769825019651126, 1.000000000000000000), - ( 1.000000000000000000, 0.8820425834865006642, 1.000000000000000000), - ( 1.000000000000000000, 0.8742515007032405361, 1.000000000000000000), - ( 1.000000000000000000, 0.8572113049951757269, 1.000000000000000000), - ( 1.000000000000000000, 0.8479470991237200161, 1.000000000000000000), - ( 1.000000000000000000, 0.8282165362286774135, 1.000000000000000000), - ( 1.000000000000000000, 0.8177144993102715143, 1.000000000000000000), - ( 1.000000000000000000, 0.7963522215910799895, 1.000000000000000000), - ( 1.000000000000000000, 0.7854072817249182492, 1.000000000000000000), - ( 1.000000000000000000, 0.7518798169611724536, 1.000000000000000000), - ( 1.000000000000000000, 0.7291766701141920715, 1.000000000000000000), - ( 1.000000000000000000, 0.7071067811880478171, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#6411 = ORIENTED_EDGE ( 'NONE', *, *, #15634, .T. ) ; -#6412 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#6413 = CARTESIAN_POINT ( 'NONE', ( 13.50164015315887411, 187.2961052408047067, 105.4512425975207464 ) ) ; -#6414 = LINE ( 'NONE', #18473, #26784 ) ; -#6415 = ORIENTED_EDGE ( 'NONE', *, *, #29362, .F. ) ; -#6416 = VECTOR ( 'NONE', #22144, 1000.000000000000114 ) ; -#6417 = ORIENTED_EDGE ( 'NONE', *, *, #5860, .F. ) ; -#6418 = CARTESIAN_POINT ( 'NONE', ( -5.669636259340673945, 124.1935939972654666, 90.97742688201675776 ) ) ; -#6419 = CARTESIAN_POINT ( 'NONE', ( -39.03036842917153137, 121.1728496031133631, 123.5553118490634432 ) ) ; -#6420 = CARTESIAN_POINT ( 'NONE', ( -26.15780381216999828, 122.1014796219999994, 87.85799570823000693 ) ) ; -#6421 = VECTOR ( 'NONE', #10703, 999.9999999999998863 ) ; -#6422 = ORIENTED_EDGE ( 'NONE', *, *, #10435, .F. ) ; -#6423 = CARTESIAN_POINT ( 'NONE', ( -20.58515596502575562, 211.7448734286233503, 73.57093710791899355 ) ) ; -#6424 = CARTESIAN_POINT ( 'NONE', ( -21.21399091017794802, 175.8930158889867528, 100.7869902896899816 ) ) ; -#6425 = ORIENTED_EDGE ( 'NONE', *, *, #23203, .T. ) ; -#6426 = DIRECTION ( 'NONE', ( -0.0004161288024436979533, 0.8480480898119694411, -0.5299191110000558425 ) ) ; -#6427 = CARTESIAN_POINT ( 'NONE', ( -44.50693014258958158, 206.7304000571328118, 28.20407784316371647 ) ) ; -#6428 = LINE ( 'NONE', #9121, #2304 ) ; -#6429 = CARTESIAN_POINT ( 'NONE', ( -18.59070810293174603, 148.9276284220111393, 180.2165354988448200 ) ) ; -#6430 = VERTEX_POINT ( 'NONE', #5611 ) ; -#6431 = CARTESIAN_POINT ( 'NONE', ( -42.96540792352757876, 112.9275286064121104, 127.4010142069958675 ) ) ; -#6432 = ORIENTED_EDGE ( 'NONE', *, *, #13071, .T. ) ; -#6433 = EDGE_CURVE ( 'NONE', #4210, #38012, #27316, .T. ) ; -#6434 = CARTESIAN_POINT ( 'NONE', ( 28.90184376448340942, 77.14301703112161590, 291.5410879458182762 ) ) ; -#6435 = EDGE_CURVE ( 'NONE', #18083, #32425, #12759, .T. ) ; -#6436 = CARTESIAN_POINT ( 'NONE', ( -38.37150668424000344, 119.0019429191000029, 87.62653263106000168 ) ) ; -#6437 = CARTESIAN_POINT ( 'NONE', ( 42.70335351170635363, 189.5620346758765038, 106.3836115623159344 ) ) ; -#6438 = CIRCLE ( 'NONE', #29312, 2.000000000021789237 ) ; -#6439 = CARTESIAN_POINT ( 'NONE', ( 15.99999439207489615, 185.9093013714976053, 102.5638074086867846 ) ) ; -#6440 = ORIENTED_EDGE ( 'NONE', *, *, #14301, .F. ) ; -#6441 = LINE ( 'NONE', #37936, #1711 ) ; -#6442 = EDGE_LOOP ( 'NONE', ( #2576, #9139, #16922, #11968 ) ) ; -#6443 = CIRCLE ( 'NONE', #37139, 1.999999999999994893 ) ; -#6444 = CONICAL_SURFACE ( 'NONE', #29320, 2.499999999987272403, 0.7853981633679723018 ) ; -#6445 = CARTESIAN_POINT ( 'NONE', ( -25.89015350293919582, 209.7107532057999606, 73.19407301408074318 ) ) ; -#6446 = AXIS2_PLACEMENT_3D ( 'NONE', #23006, #17650, #8266 ) ; -#6447 = CARTESIAN_POINT ( 'NONE', ( 46.23034675843089758, 142.4471217300238663, 290.2939289711846413 ) ) ; -#6448 = CARTESIAN_POINT ( 'NONE', ( 3.667815741532966189, 126.2406713581920599, 91.36142183184406917 ) ) ; -#6449 = ORIENTED_EDGE ( 'NONE', *, *, #25404, .F. ) ; -#6450 = DIRECTION ( 'NONE', ( 0.0004270881509380666254, 0.7071067811865995312, 0.7071066522071742799 ) ) ; -#6451 = CARTESIAN_POINT ( 'NONE', ( 28.18739088310087482, 186.6040837889091506, 105.2826068624289064 ) ) ; -#6452 = CARTESIAN_POINT ( 'NONE', ( -4.037441716908935163, 137.2418790766312782, 91.85329641515465937 ) ) ; -#6453 = CARTESIAN_POINT ( 'NONE', ( -20.30306764003320552, 159.5691140880819034, 96.50461759798676553 ) ) ; -#6454 = LINE ( 'NONE', #15862, #21731 ) ; -#6455 = CARTESIAN_POINT ( 'NONE', ( 39.06393364112096123, 183.1686747593891198, 104.4829110315198193 ) ) ; -#6456 = VERTEX_POINT ( 'NONE', #16216 ) ; -#6457 = EDGE_LOOP ( 'NONE', ( #16423, #25540, #22112, #38273, #21588, #4288, #25727, #22848, #30400, #2047, #32913, #6294, #12775, #17451, #39434 ) ) ; -#6458 = CARTESIAN_POINT ( 'NONE', ( 5.668069803484447888, 187.9566418269450878, 103.3747270639725997 ) ) ; -#6459 = CARTESIAN_POINT ( 'NONE', ( -26.00800983458967508, 191.5260122442129216, 103.8858970416150385 ) ) ; -#6460 = EDGE_CURVE ( 'NONE', #31838, #32027, #31572, .T. ) ; -#6461 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971550137 ) ) ; -#6462 = ORIENTED_EDGE ( 'NONE', *, *, #23332, .T. ) ; -#6463 = CARTESIAN_POINT ( 'NONE', ( 19.98129031103842479, 206.1771145815928321, 74.47467027735100942 ) ) ; -#6464 = ORIENTED_EDGE ( 'NONE', *, *, #26080, .F. ) ; -#6465 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971547361 ) ) ; -#6466 = CIRCLE ( 'NONE', #9761, 2.000000000000000000 ) ; -#6467 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#6468 = LINE ( 'NONE', #3599, #1366 ) ; -#6469 = ORIENTED_EDGE ( 'NONE', *, *, #9328, .F. ) ; -#6470 = CARTESIAN_POINT ( 'NONE', ( -39.42639396830977461, 119.7153704062085353, 90.39411697856569106 ) ) ; -#6471 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6472 = AXIS2_PLACEMENT_3D ( 'NONE', #7810, #23561, #14175 ) ; -#6473 = LINE ( 'NONE', #346, #17501 ) ; -#6474 = CARTESIAN_POINT ( 'NONE', ( 18.99767128196905830, 125.6058446513852118, 175.3475295528536151 ) ) ; -#6475 = VECTOR ( 'NONE', #11699, 1000.000000000000114 ) ; -#6476 = CARTESIAN_POINT ( 'NONE', ( 19.99976926757112849, 160.7481248081381295, 96.75239270071580222 ) ) ; -#6477 = EDGE_LOOP ( 'NONE', ( #7425, #31736 ) ) ; -#6478 = DIRECTION ( 'NONE', ( -6.775747579923947991E-13, 0.9743700560511913134, 0.2249510921751617376 ) ) ; -#6479 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; -#6480 = CARTESIAN_POINT ( 'NONE', ( -1.095994359663330364, 188.4547440274937173, 106.2407042419200138 ) ) ; -#6481 = CARTESIAN_POINT ( 'NONE', ( -11.79202345736525892, 125.7774812735008254, 176.8918472601677365 ) ) ; -#6482 = APPLICATION_CONTEXT ( 'configuration controlled 3d designs of mechanical parts and assemblies' ) ; -#6483 = ADVANCED_FACE ( 'NONE', ( #21972 ), #37141, .F. ) ; -#6484 = VERTEX_POINT ( 'NONE', #273 ) ; -#6485 = LINE ( 'NONE', #15508, #8165 ) ; -#6486 = EDGE_CURVE ( 'NONE', #31222, #34652, #12983, .T. ) ; -#6487 = LINE ( 'NONE', #6290, #11463 ) ; -#6488 = CARTESIAN_POINT ( 'NONE', ( 15.50029467836134778, 127.6324160061193567, 89.62297635127647766 ) ) ; -#6489 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; -#6490 = CARTESIAN_POINT ( 'NONE', ( -15.03362232196302095, 125.0996412702250211, 171.3811097074177212 ) ) ; -#6491 = ORIENTED_EDGE ( 'NONE', *, *, #26519, .T. ) ; -#6492 = EDGE_CURVE ( 'NONE', #20699, #7741, #12966, .T. ) ; -#6493 = CARTESIAN_POINT ( 'NONE', ( -16.29619488456271981, 121.9866529957326691, 177.9438470153492631 ) ) ; -#6494 = CONICAL_SURFACE ( 'NONE', #20180, 5.999999999758604652, 0.7853981633778843729 ) ; -#6495 = LINE ( 'NONE', #31063, #27212 ) ; -#6496 = CARTESIAN_POINT ( 'NONE', ( -35.94780306588808116, 112.9281708003797036, 87.78949364045074333 ) ) ; -#6497 = CARTESIAN_POINT ( 'NONE', ( 31.49993145514000403, 120.4394921222999955, 88.97899963669999579 ) ) ; -#6498 = VECTOR ( 'NONE', #27508, 1000.000000000000114 ) ; -#6499 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560684 ) ) ; -#6500 = FACE_OUTER_BOUND ( 'NONE', #19558, .T. ) ; -#6501 = AXIS2_PLACEMENT_3D ( 'NONE', #7957, #29644, #35948 ) ; -#6503 = VERTEX_POINT ( 'NONE', #37695 ) ; -#6502 = CARTESIAN_POINT ( 'NONE', ( 36.44567169039000021, 191.8783867296999972, 106.2558788317000023 ) ) ; -#6504 = VERTEX_POINT ( 'NONE', #31782 ) ; -#6505 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2252353050503803633, -0.9743043966640312359 ) ) ; -#6506 = ADVANCED_FACE ( 'NONE', ( #9297 ), #21581, .T. ) ; -#6507 = CARTESIAN_POINT ( 'NONE', ( -34.43835868710999648, 129.8549691105999955, 92.73201569149999557 ) ) ; -#6508 = CARTESIAN_POINT ( 'NONE', ( 31.82998378949513452, 157.8941376960632397, 186.4072502462622367 ) ) ; -#6509 = CARTESIAN_POINT ( 'NONE', ( 42.53628601435023171, 136.4453753212296760, 337.8539966295136310 ) ) ; -#6510 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12907, #3679, #13502, #22914, #16161, #3877, #29039, #13105, #22517, #34934, #6950, #16351, #28839, #35340, #8384, #17553, #17149, #36168, #2045, #38822 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999146516, 0.1874999999998761824, 0.2187499999998555877, 0.2343749999998484546, 0.2499999999998413491, 0.4999999999998435696, 0.6249999999998382405, 0.6874999999998356870, 0.7187499999998402389, 0.7343749999998437916, 0.7499999999998472333, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6511 = CARTESIAN_POINT ( 'NONE', ( -35.45668950309346457, 209.7097078344999943, 73.07991903445761750 ) ) ; -#6512 = ORIENTED_EDGE ( 'NONE', *, *, #12097, .F. ) ; -#6513 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10186, #37769, #28979, #3612 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6514 = CARTESIAN_POINT ( 'NONE', ( 3.666638755385807080, 126.6906504152049706, 89.41269982467663624 ) ) ; -#6515 = CARTESIAN_POINT ( 'NONE', ( -12.64386474322367526, 181.0124094291204528, 104.5294403572958544 ) ) ; -#6516 = CARTESIAN_POINT ( 'NONE', ( -37.24902032432657961, 191.4390922065653626, 104.3803261539560481 ) ) ; -#6517 = ORIENTED_EDGE ( 'NONE', *, *, #32442, .T. ) ; -#6518 = CARTESIAN_POINT ( 'NONE', ( -31.70566066713798037, 220.4002260770999726, 73.07765350697074780 ) ) ; -#6519 = EDGE_CURVE ( 'NONE', #6030, #27038, #6805, .T. ) ; -#6520 = FACE_OUTER_BOUND ( 'NONE', #29515, .T. ) ; -#6521 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452351231, -0.1781166614240801693 ) ) ; -#6522 = CARTESIAN_POINT ( 'NONE', ( -39.69379533597580689, 119.8651493286000687, 87.86309706269757669 ) ) ; -#6523 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -1.238758140229870101E-30, 0.0006039748319385906776 ) ) ; -#6524 = ORIENTED_EDGE ( 'NONE', *, *, #10172, .F. ) ; -#6525 = EDGE_CURVE ( 'NONE', #978, #6030, #24651, .T. ) ; -#6526 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#6527 = VECTOR ( 'NONE', #16222, 1000.000000000000227 ) ; -#6528 = CARTESIAN_POINT ( 'NONE', ( 2.554510955381000148, 190.8274375100000100, 104.2205350602999943 ) ) ; -#6529 = CARTESIAN_POINT ( 'NONE', ( 43.17764363794253768, 121.2864334425410533, 90.70693487989220216 ) ) ; -#6530 = AXIS2_PLACEMENT_3D ( 'NONE', #5865, #2801, #40401 ) ; -#6531 = CONICAL_SURFACE ( 'NONE', #29408, 2.503011087841876758, 0.7854316141493700165 ) ; -#6532 = ADVANCED_FACE ( 'NONE', ( #6602 ), #6210, .T. ) ; -#6533 = VERTEX_POINT ( 'NONE', #9094 ) ; -#6534 = CYLINDRICAL_SURFACE ( 'NONE', #25753, 2.000000000000001332 ) ; -#6535 = ORIENTED_EDGE ( 'NONE', *, *, #35262, .F. ) ; -#6536 = ADVANCED_FACE ( 'NONE', ( #37904 ), #14937, .F. ) ; -#6537 = EDGE_CURVE ( 'NONE', #21584, #10351, #28647, .T. ) ; -#6538 = PLANE ( 'NONE', #28191 ) ; -#6539 = ADVANCED_FACE ( 'NONE', ( #19077 ), #34018, .T. ) ; -#6540 = CARTESIAN_POINT ( 'NONE', ( -77.81044467944656162, 193.2853083808247163, 188.4036545891195544 ) ) ; -#6541 = CARTESIAN_POINT ( 'NONE', ( -12.63453555434205100, 177.0107181004119354, 103.4630699979715018 ) ) ; -#6542 = CARTESIAN_POINT ( 'NONE', ( -35.44810745619992787, 112.9281708664996984, 87.28919406064997588 ) ) ; -#6543 = CARTESIAN_POINT ( 'NONE', ( -35.95487748704000097, 225.9002260771000010, 76.08022047461976456 ) ) ; -#6544 = CARTESIAN_POINT ( 'NONE', ( -36.16414195531000075, 190.7651570079000010, 106.9447890395999963 ) ) ; -#6545 = ORIENTED_EDGE ( 'NONE', *, *, #35357, .T. ) ; -#6546 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 9.251858538542969067E-15, 0.0006039748319391911088 ) ) ; -#6547 = CARTESIAN_POINT ( 'NONE', ( -39.78547281363039900, 190.3169928286148718, 106.6940055862042271 ) ) ; -#6548 = DIRECTION ( 'NONE', ( -9.423264860246663790E-14, -0.9743700557562335884, -0.2249510934527640116 ) ) ; -#6549 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8105, #17080, #26937, #26521 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6550 = CARTESIAN_POINT ( 'NONE', ( 14.78617723117088190, 128.6760556706539091, 91.91695949461106352 ) ) ; -#6551 = EDGE_LOOP ( 'NONE', ( #21114, #12897, #23476, #34686 ) ) ; -#6552 = ORIENTED_EDGE ( 'NONE', *, *, #19374, .T. ) ; -#6553 = AXIS2_PLACEMENT_3D ( 'NONE', #32199, #37924, #295 ) ; -#6554 = EDGE_CURVE ( 'NONE', #30696, #36900, #15566, .T. ) ; -#6555 = CONICAL_SURFACE ( 'NONE', #39864, 22.50000000000906653, 0.7853981633972855203 ) ; -#6556 = ORIENTED_EDGE ( 'NONE', *, *, #3762, .F. ) ; -#6557 = CARTESIAN_POINT ( 'NONE', ( -21.44517147737999707, 135.1113278520462586, 93.93769420648519031 ) ) ; -#6558 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30520, #27869, #23981, #5352, #5765, #40298, #11708, #15179, #20899, #17807, #21718, #24188, #14782, #9245, #34163, #27477, #11910, #6156, #33766 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 0.000000000000000000, 0.2499828855947091033, 0.4999852515029006295, 0.6249864344569463492, 0.7499876174109920690, 0.8124897471729031206, 0.8749918769346138880, 0.9062429418155193428, 0.9374940066964148055, 0.9531195391368775249, 0.9687450715773302523, 0.9765578377975616675, 0.9843706040177829797, 0.9921833702380082887, 0.9960897533481199995, 0.9980448766740599442, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6559 = LINE ( 'NONE', #37649, #18055 ) ; -#6560 = ORIENTED_EDGE ( 'NONE', *, *, #39640, .F. ) ; -#6561 = CARTESIAN_POINT ( 'NONE', ( 37.79442059176063395, 218.5902260770999987, 73.53567729060368663 ) ) ; -#6562 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552144553, 153.0051697192221241, 291.5584375788738498 ) ) ; -#6563 = CARTESIAN_POINT ( 'NONE', ( -38.24329037062999959, 118.9457152731000065, 87.57826822584999604 ) ) ; -#6564 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#6565 = ORIENTED_EDGE ( 'NONE', *, *, #24808, .F. ) ; -#6566 = LINE ( 'NONE', #37459, #40171 ) ; -#6567 = EDGE_CURVE ( 'NONE', #13948, #17976, #3341, .T. ) ; -#6568 = ORIENTED_EDGE ( 'NONE', *, *, #22208, .F. ) ; -#6569 = CARTESIAN_POINT ( 'NONE', ( -5.668109638568818553, 181.0132057329783493, 104.5254508863806393 ) ) ; -#6570 = ORIENTED_EDGE ( 'NONE', *, *, #30878, .F. ) ; -#6571 = ORIENTED_EDGE ( 'NONE', *, *, #39539, .T. ) ; -#6572 = ADVANCED_FACE ( 'NONE', ( #34212 ), #16017, .T. ) ; -#6573 = CARTESIAN_POINT ( 'NONE', ( -19.99929890231679153, 195.2358628576933199, 105.7690483904409149 ) ) ; -#6574 = CARTESIAN_POINT ( 'NONE', ( 2.910282181199090878, 190.2536080120511031, 103.5746722162875244 ) ) ; -#6575 = CARTESIAN_POINT ( 'NONE', ( 25.50041447495308233, 118.1134306400200416, 89.75249416949174019 ) ) ; -#6576 = EDGE_CURVE ( 'NONE', #189, #12858, #25049, .T. ) ; -#6577 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21020, #18523, #40017, #11619 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6578 = VERTEX_POINT ( 'NONE', #31978 ) ; -#6579 = CARTESIAN_POINT ( 'NONE', ( -20.61617605269181297, 212.9284424379133611, 73.07095573613224815 ) ) ; -#6580 = CARTESIAN_POINT ( 'NONE', ( -20.02016821360482268, 211.0854730039747267, 73.07052224373646254 ) ) ; -#6581 = ORIENTED_EDGE ( 'NONE', *, *, #11018, .T. ) ; -#6582 = ADVANCED_FACE ( 'NONE', ( #1076 ), #38684, .T. ) ; -#6583 = CIRCLE ( 'NONE', #37941, 22.00000000001092815 ) ; -#6584 = AXIS2_PLACEMENT_3D ( 'NONE', #10647, #29450, #16757 ) ; -#6585 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6586 = FACE_OUTER_BOUND ( 'NONE', #25051, .T. ) ; -#6587 = CARTESIAN_POINT ( 'NONE', ( 16.78949468225133046, 151.7806215848595457, 184.1646548055863093 ) ) ; -#6588 = AXIS2_PLACEMENT_3D ( 'NONE', #27380, #21220, #30010 ) ; -#6589 = VERTEX_POINT ( 'NONE', #10509 ) ; -#6590 = AXIS2_PLACEMENT_3D ( 'NONE', #11215, #35924, #1597 ) ; -#6591 = CARTESIAN_POINT ( 'NONE', ( 2.877595498296891208, 208.9474331469267554, 73.28391261355885433 ) ) ; -#6592 = CARTESIAN_POINT ( 'NONE', ( 13.85386899117346182, 129.1332408048698710, 155.2444354684493533 ) ) ; -#6593 = ORIENTED_EDGE ( 'NONE', *, *, #24713, .F. ) ; -#6594 = LINE ( 'NONE', #28495, #1913 ) ; -#6595 = CARTESIAN_POINT ( 'NONE', ( -20.49852834086299325, 137.6294258426618455, 94.00531932011546132 ) ) ; -#6597 = PLANE ( 'NONE', #7649 ) ; -#6596 = CARTESIAN_POINT ( 'NONE', ( -28.34546150099999906, 186.5535928724000030, 105.4761456043000010 ) ) ; -#6598 = ORIENTED_EDGE ( 'NONE', *, *, #6567, .F. ) ; -#6599 = DIRECTION ( 'NONE', ( 0.0005884949961258899515, -0.2249510543438812404, 0.9743698870671320122 ) ) ; -#6600 = ORIENTED_EDGE ( 'NONE', *, *, #34721, .T. ) ; -#6601 = DIRECTION ( 'NONE', ( -0.0005884951729871207987, 0.2249510544218079611, -0.9743698870490344888 ) ) ; -#6602 = FACE_OUTER_BOUND ( 'NONE', #9956, .T. ) ; -#6603 = VERTEX_POINT ( 'NONE', #19677 ) ; -#6604 = AXIS2_PLACEMENT_3D ( 'NONE', #3055, #16329, #22886 ) ; -#6605 = ORIENTED_EDGE ( 'NONE', *, *, #34846, .F. ) ; -#6606 = CARTESIAN_POINT ( 'NONE', ( 16.00175042068614317, 126.1291850884666559, 91.84138073825745607 ) ) ; -#6607 = CONICAL_SURFACE ( 'NONE', #31447, 3.000000000067766681, 0.7853981634062662254 ) ; -#6608 = DIRECTION ( 'NONE', ( 0.5987319967475644988, 0.8009494341534142414, 0.000000000000000000 ) ) ; -#6609 = CARTESIAN_POINT ( 'NONE', ( -15.99970515225999179, 151.9770228117144484, 94.74935186622352035 ) ) ; -#6610 = CARTESIAN_POINT ( 'NONE', ( 36.21188721582999648, 191.6197133759999929, 104.0153071847000064 ) ) ; -#6611 = EDGE_CURVE ( 'NONE', #15440, #20595, #29503, .T. ) ; -#6612 = EDGE_LOOP ( 'NONE', ( #15870, #19910, #12738, #37323 ) ) ; -#6613 = EDGE_CURVE ( 'NONE', #35621, #35766, #7687, .T. ) ; -#6614 = ORIENTED_EDGE ( 'NONE', *, *, #39919, .F. ) ; -#6615 = CARTESIAN_POINT ( 'NONE', ( -34.98386828774999913, 217.7719116314000019, 28.07991271570000080 ) ) ; -#6616 = EDGE_CURVE ( 'NONE', #3120, #5945, #29106, .T. ) ; -#6617 = CARTESIAN_POINT ( 'NONE', ( 2.519724450483999956, 211.0000000000000000, 32.65697486330000032 ) ) ; -#6618 = EDGE_CURVE ( 'NONE', #17879, #20244, #17448, .T. ) ; -#6619 = CARTESIAN_POINT ( 'NONE', ( -26.02655135031000100, 121.3050034530999994, 87.67404182062000473 ) ) ; -#6620 = VERTEX_POINT ( 'NONE', #16811 ) ; -#6621 = FACE_OUTER_BOUND ( 'NONE', #39456, .T. ) ; -#6622 = ORIENTED_EDGE ( 'NONE', *, *, #947, .F. ) ; -#6623 = EDGE_CURVE ( 'NONE', #28881, #32839, #31602, .T. ) ; -#6624 = CYLINDRICAL_SURFACE ( 'NONE', #24250, 22.50000000000000000 ) ; -#6625 = CARTESIAN_POINT ( 'NONE', ( -13.46391575659845685, 154.4039982810205629, 95.30803284751881677 ) ) ; -#6626 = ORIENTED_EDGE ( 'NONE', *, *, #8913, .F. ) ; -#6627 = DIRECTION ( 'NONE', ( 0.7763856147932154395, -0.5343480027610235661, -0.3342118924985555406 ) ) ; -#6628 = EDGE_CURVE ( 'NONE', #16791, #8036, #13172, .T. ) ; -#6629 = CARTESIAN_POINT ( 'NONE', ( -0.3747130585439999995, 189.1668057001000136, 105.6062578476999931 ) ) ; -#6630 = DIRECTION ( 'NONE', ( -3.474730790243325680E-10, -0.9743700557140873020, -0.2249510936353195101 ) ) ; -#6631 = ORIENTED_EDGE ( 'NONE', *, *, #21429, .F. ) ; -#6632 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; -#6633 = CARTESIAN_POINT ( 'NONE', ( 39.86430758302872590, 77.39023996490196566, 290.9329938034825318 ) ) ; -#6634 = AXIS2_PLACEMENT_3D ( 'NONE', #32144, #1046, #10673 ) ; -#6635 = DIRECTION ( 'NONE', ( 0.0005884949961228156962, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6636 = DIRECTION ( 'NONE', ( -0.0006039748319356123742, 6.151140898304641511E-15, -0.9999998176071847045 ) ) ; -#6637 = AXIS2_PLACEMENT_3D ( 'NONE', #1612, #11227, #2234 ) ; -#6638 = EDGE_CURVE ( 'NONE', #36135, #11474, #23173, .T. ) ; -#6639 = CONICAL_SURFACE ( 'NONE', #9944, 6.500000000082215124, 0.7853981634430716730 ) ; -#6640 = CARTESIAN_POINT ( 'NONE', ( 15.12415969602515986, 146.0659008074709106, 180.8278994957862551 ) ) ; -#6641 = ORIENTED_EDGE ( 'NONE', *, *, #9135, .T. ) ; -#6642 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319398847813 ) ) ; -#6643 = CARTESIAN_POINT ( 'NONE', ( -38.54368346761000197, 118.3571362795999988, 89.55295134938000956 ) ) ; -#6644 = EDGE_LOOP ( 'NONE', ( #14153, #18544, #1231, #20412 ) ) ; -#6645 = LINE ( 'NONE', #725, #22956 ) ; -#6646 = ORIENTED_EDGE ( 'NONE', *, *, #14587, .T. ) ; -#6647 = CARTESIAN_POINT ( 'NONE', ( 8.955013101272822240, 160.1620528194969211, 96.62383716770308695 ) ) ; -#6648 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561517 ) ) ; -#6649 = CARTESIAN_POINT ( 'NONE', ( -31.70415073005799300, 220.4002260771000010, 75.57765305097055375 ) ) ; -#6650 = CARTESIAN_POINT ( 'NONE', ( -3.870368579862465630, 174.7537207775617674, 102.7362565340363005 ) ) ; -#6651 = ORIENTED_EDGE ( 'NONE', *, *, #39033, .T. ) ; -#6652 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265227786, -0.1368326740407719844 ) ) ; -#6653 = VERTEX_POINT ( 'NONE', #32566 ) ; -#6654 = ORIENTED_EDGE ( 'NONE', *, *, #40131, .T. ) ; -#6655 = ORIENTED_EDGE ( 'NONE', *, *, #5136, .T. ) ; -#6656 = CARTESIAN_POINT ( 'NONE', ( 28.90951000791340064, 225.0820812894944822, 76.04104400993735169 ) ) ; -#6657 = CARTESIAN_POINT ( 'NONE', ( -45.01366707977943094, 130.2508973098130411, 92.82981015662352320 ) ) ; -#6658 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; -#6659 = EDGE_CURVE ( 'NONE', #32574, #11409, #13361, .T. ) ; -#6660 = EDGE_LOOP ( 'NONE', ( #20133, #4316, #8903, #8090, #8843, #34201, #10132, #20276 ) ) ; -#6661 = CARTESIAN_POINT ( 'NONE', ( 19.98210856654580780, 205.1070970766282358, 76.09272704596726555 ) ) ; -#6662 = EDGE_CURVE ( 'NONE', #37725, #39374, #28211, .T. ) ; -#6663 = CARTESIAN_POINT ( 'NONE', ( -28.81763517994743751, 225.0820812896716632, 76.07590975914473574 ) ) ; -#6664 = AXIS2_PLACEMENT_3D ( 'NONE', #23344, #1866, #10875 ) ; -#6665 = ADVANCED_FACE ( 'NONE', ( #38293 ), #7408, .F. ) ; -#6666 = ORIENTED_EDGE ( 'NONE', *, *, #9608, .F. ) ; -#6667 = DIRECTION ( 'NONE', ( 0.9999998268368220922, 0.0001323826147821730395, -0.0005734118669949963198 ) ) ; -#6668 = AXIS2_PLACEMENT_3D ( 'NONE', #19510, #15840, #16044 ) ; -#6669 = CONICAL_SURFACE ( 'NONE', #26935, 2.750000000007442491, 0.7853981633308424470 ) ; -#6670 = CARTESIAN_POINT ( 'NONE', ( -40.71080201233111495, 190.8841207850421995, 103.7465862286444178 ) ) ; -#6671 = EDGE_LOOP ( 'NONE', ( #9299, #24254, #4935, #28445, #10488, #25744, #16023, #3980, #7132, #38873, #36627, #18281, #36839 ) ) ; -#6672 = CARTESIAN_POINT ( 'NONE', ( 28.30326266966000048, 125.4564572028999976, 88.94198821295999835 ) ) ; -#6673 = EDGE_CURVE ( 'NONE', #24826, #21867, #35995, .T. ) ; -#6674 = FACE_OUTER_BOUND ( 'NONE', #21790, .T. ) ; -#6675 = PLANE ( 'NONE', #39714 ) ; -#6676 = CARTESIAN_POINT ( 'NONE', ( 3.534343284623258974, 175.3621990150981276, 100.1363906404241675 ) ) ; -#6677 = CARTESIAN_POINT ( 'NONE', ( 5.341513311928848040, 124.3682655131192831, 88.36237119484185598 ) ) ; -#6678 = ORIENTED_EDGE ( 'NONE', *, *, #28897, .F. ) ; -#6680 = EDGE_CURVE ( 'NONE', #2594, #11261, #14076, .T. ) ; -#6679 = CARTESIAN_POINT ( 'NONE', ( -28.46346214431096655, 130.6180201592175933, 90.16776375064561933 ) ) ; -#6681 = FACE_OUTER_BOUND ( 'NONE', #691, .T. ) ; -#6682 = CARTESIAN_POINT ( 'NONE', ( -37.83810969319355166, 191.0388331516561777, 103.7805696149103909 ) ) ; -#6683 = CARTESIAN_POINT ( 'NONE', ( 42.44089075944981460, 185.1190886577203685, 127.1660040187822318 ) ) ; -#6684 = VERTEX_POINT ( 'NONE', #4341 ) ; -#6685 = DIRECTION ( 'NONE', ( 0.0004161288024547961178, 0.5299192578740949955, 0.8480479980348919478 ) ) ; -#6686 = LINE ( 'NONE', #36987, #3622 ) ; -#6687 = FACE_OUTER_BOUND ( 'NONE', #5098, .T. ) ; -#6688 = CARTESIAN_POINT ( 'NONE', ( 19.98197889682855788, 210.1681488827333339, 73.04643546784730290 ) ) ; -#6689 = ADVANCED_FACE ( 'NONE', ( #21708 ), #34737, .T. ) ; -#6690 = CIRCLE ( 'NONE', #10654, 1.999999999512996451 ) ; -#6691 = CARTESIAN_POINT ( 'NONE', ( -26.72558658360999928, 188.4929050110000333, 106.2649942106999958 ) ) ; -#6692 = VERTEX_POINT ( 'NONE', #25374 ) ; -#6693 = CARTESIAN_POINT ( 'NONE', ( 22.50176470575690857, 173.8437174413195123, 102.8532298930652047 ) ) ; -#6694 = VECTOR ( 'NONE', #23269, 999.9999999999998863 ) ; -#6695 = CARTESIAN_POINT ( 'NONE', ( -12.63890180163353527, 181.8404537192973294, 101.8516965491096897 ) ) ; -#6696 = VECTOR ( 'NONE', #25283, 1000.000000000000000 ) ; -#6697 = CARTESIAN_POINT ( 'NONE', ( -29.78271232893557041, 185.5388540720573189, 103.0190829539931059 ) ) ; -#6698 = ORIENTED_EDGE ( 'NONE', *, *, #895, .T. ) ; -#6699 = CARTESIAN_POINT ( 'NONE', ( 15.59065710780900638, 127.6518116318376457, 175.3064835098809056 ) ) ; -#6700 = DIRECTION ( 'NONE', ( 3.053113317596056969E-14, 0.9743700557921590732, 0.2249510932971532096 ) ) ; -#6701 = CARTESIAN_POINT ( 'NONE', ( -2.937264483321980979, 191.5260295968394928, 103.8719657109621295 ) ) ; -#6702 = DIRECTION ( 'NONE', ( 0.0006039748319401620118, 1.156691652267356444E-14, 0.9999998176071847045 ) ) ; -#6703 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34472, #32054, #22845, #31440 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6704 = CARTESIAN_POINT ( 'NONE', ( 36.19631487654000068, 192.5993829527999992, 106.2212666058999986 ) ) ; -#6705 = ORIENTED_EDGE ( 'NONE', *, *, #1074, .T. ) ; -#6706 = ORIENTED_EDGE ( 'NONE', *, *, #11086, .T. ) ; -#6707 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971550969 ) ) ; -#6708 = LINE ( 'NONE', #28603, #18990 ) ; -#6709 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3274, #6947, #6149, #37436, #813, #6348, #12905, #20, #611, #18799 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.0004303995929816994254, 0.0008607991859633988508, 0.001291198778945098222, 0.001721598371926797702 ), - .UNSPECIFIED. ) ; -#6710 = CARTESIAN_POINT ( 'NONE', ( 40.67213421873967860, 184.8215033964496001, 102.8109171582487278 ) ) ; -#6711 = DIRECTION ( 'NONE', ( -0.0005959781126671458411, -0.1621881766265671210, -0.9867596668756980494 ) ) ; -#6712 = VERTEX_POINT ( 'NONE', #9837 ) ; -#6713 = CARTESIAN_POINT ( 'NONE', ( -32.57213854657648255, 175.6744114851244376, 100.2302293651451492 ) ) ; -#6714 = ADVANCED_FACE ( 'NONE', ( #37434 ), #16347, .T. ) ; -#6715 = EDGE_CURVE ( 'NONE', #468, #26246, #15942, .T. ) ; -#6716 = ORIENTED_EDGE ( 'NONE', *, *, #38401, .F. ) ; -#6717 = CARTESIAN_POINT ( 'NONE', ( -4.704802962633507057, 130.8321230753525981, 89.86073829340300279 ) ) ; -#6718 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#6719 = AXIS2_PLACEMENT_3D ( 'NONE', #26438, #4745, #38481 ) ; -#6720 = VERTEX_POINT ( 'NONE', #12903 ) ; -#6721 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; -#6722 = CARTESIAN_POINT ( 'NONE', ( 24.53469179835996172, 103.6131156702607257, 89.75296640900927514 ) ) ; -#6723 = CARTESIAN_POINT ( 'NONE', ( -23.35399029200872079, 130.2187140253622601, 92.63824150152402126 ) ) ; -#6724 = EDGE_CURVE ( 'NONE', #40272, #16030, #11698, .T. ) ; -#6725 = CIRCLE ( 'NONE', #38084, 2.250000000025557778 ) ; -#6726 = CARTESIAN_POINT ( 'NONE', ( -30.06587742563253585, 177.0744528912911733, 103.5787552974134087 ) ) ; -#6727 = LINE ( 'NONE', #38011, #23003 ) ; -#6728 = ORIENTED_EDGE ( 'NONE', *, *, #13005, .F. ) ; -#6729 = CARTESIAN_POINT ( 'NONE', ( -35.93878493987469369, 193.8169247291205863, 102.7246158654084098 ) ) ; -#6730 = AXIS2_PLACEMENT_3D ( 'NONE', #30827, #36748, #27775 ) ; -#6731 = CARTESIAN_POINT ( 'NONE', ( 1.973863911711999819, 189.2113471865000065, 103.4772481592000020 ) ) ; -#6732 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6733 = CARTESIAN_POINT ( 'NONE', ( -37.09244532070999867, 190.9712090824999962, 103.6176582474000014 ) ) ; -#6734 = ORIENTED_EDGE ( 'NONE', *, *, #23204, .T. ) ; -#6735 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#6736 = ORIENTED_EDGE ( 'NONE', *, *, #37601, .F. ) ; -#6737 = CARTESIAN_POINT ( 'NONE', ( 14.78600926606004862, 175.8977815190944796, 100.7663474239818839 ) ) ; -#6738 = CARTESIAN_POINT ( 'NONE', ( -20.02002437005085511, 209.7095682957761085, 73.07054393135327075 ) ) ; -#6739 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#6740 = CARTESIAN_POINT ( 'NONE', ( -12.63650000504985549, 176.7400935515184131, 103.0299816119349714 ) ) ; -#6741 = CARTESIAN_POINT ( 'NONE', ( 25.49063000826092562, 211.0902260967494897, 73.54299573436949800 ) ) ; -#6742 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498900786, 129.6183187699468249, 92.64570812446403636 ) ) ; -#6743 = CARTESIAN_POINT ( 'NONE', ( -37.68723907529999906, 190.5064451007000059, 106.6118794326999932 ) ) ; -#6744 = VECTOR ( 'NONE', #25745, 999.9999999999998863 ) ; -#6745 = ORIENTED_EDGE ( 'NONE', *, *, #12587, .T. ) ; -#6746 = ADVANCED_FACE ( 'NONE', ( #28048 ), #28244, .F. ) ; -#6747 = DIRECTION ( 'NONE', ( -0.0005884949961269576738, 0.2249510543439059429, -0.9743698870671263501 ) ) ; -#6748 = CARTESIAN_POINT ( 'NONE', ( 26.00611526003149621, 118.8155664120999973, 94.25207852681757004 ) ) ; -#6749 = DIRECTION ( 'NONE', ( 0.0005884949961236033691, -0.2249510543439074417, 0.9743698870671260170 ) ) ; -#6750 = AXIS2_PLACEMENT_3D ( 'NONE', #31526, #28460, #3487 ) ; -#6751 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387072293 ) ) ; -#6752 = ORIENTED_EDGE ( 'NONE', *, *, #5475, .T. ) ; -#6753 = EDGE_CURVE ( 'NONE', #9411, #10112, #21907, .T. ) ; -#6754 = CONICAL_SURFACE ( 'NONE', #17198, 59.40509898898601904, 0.7853981633972927368 ) ; -#6755 = EDGE_LOOP ( 'NONE', ( #38697, #11356, #36490, #13350 ) ) ; -#6756 = CARTESIAN_POINT ( 'NONE', ( 5.671965847892154855, 131.0223101898201605, 89.89837914816251896 ) ) ; -#6757 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#6758 = EDGE_CURVE ( 'NONE', #5402, #3978, #19415, .T. ) ; -#6759 = ORIENTED_EDGE ( 'NONE', *, *, #7500, .T. ) ; -#6760 = ADVANCED_FACE ( 'NONE', ( #37630 ), #14967, .F. ) ; -#6761 = ORIENTED_EDGE ( 'NONE', *, *, #40359, .T. ) ; -#6762 = ADVANCED_FACE ( 'NONE', ( #28634 ), #34507, .T. ) ; -#6763 = CARTESIAN_POINT ( 'NONE', ( 15.99970520780110483, 160.7332544674666508, 96.75156078672274873 ) ) ; -#6764 = CYLINDRICAL_SURFACE ( 'NONE', #7722, 1.650000000000002798 ) ; -#6765 = CARTESIAN_POINT ( 'NONE', ( -38.13219187549999845, 119.0756271369999979, 87.44113924395999504 ) ) ; -#6766 = FACE_OUTER_BOUND ( 'NONE', #9867, .T. ) ; -#6767 = DIRECTION ( 'NONE', ( 1.387778780793648170E-15, 0.9743700557921585181, 0.2249510932971560961 ) ) ; -#6768 = ORIENTED_EDGE ( 'NONE', *, *, #5050, .T. ) ; -#6769 = CARTESIAN_POINT ( 'NONE', ( -19.46394955521238401, 125.6772987183395998, 178.4491578239381511 ) ) ; -#6770 = DIRECTION ( 'NONE', ( -0.0005884949961231158034, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#6771 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560684 ) ) ; -#6772 = CARTESIAN_POINT ( 'NONE', ( 3.882702609145003869, 148.9606115484091617, 129.9617790688395473 ) ) ; -#6773 = VERTEX_POINT ( 'NONE', #22310 ) ; -#6774 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999904787, 179.7376864901910949, 101.1595092801111377 ) ) ; -#6775 = CARTESIAN_POINT ( 'NONE', ( 1.135325133094777561, 188.6789995793503749, 103.2122171789744840 ) ) ; -#6776 = VECTOR ( 'NONE', #39681, 1000.000000000000114 ) ; -#6777 = AXIS2_PLACEMENT_3D ( 'NONE', #2021, #38798, #14086 ) ; -#6778 = CARTESIAN_POINT ( 'NONE', ( 39.72739263165712487, 107.0606345199744283, 184.9165446084303426 ) ) ; -#6779 = CARTESIAN_POINT ( 'NONE', ( -16.49952091330321480, 137.4667901650724389, 177.5675841302929712 ) ) ; -#6780 = AXIS2_PLACEMENT_3D ( 'NONE', #32822, #17472, #39349 ) ; -#6781 = ORIENTED_EDGE ( 'NONE', *, *, #8357, .F. ) ; -#6782 = CARTESIAN_POINT ( 'NONE', ( -20.01953265211073685, 211.4835721071765704, 73.07059537846892283 ) ) ; -#6783 = CARTESIAN_POINT ( 'NONE', ( -28.94629671773202162, 110.6131156702000027, 90.28526767707491274 ) ) ; -#6784 = EDGE_LOOP ( 'NONE', ( #12899, #31611, #36886, #18447 ) ) ; -#6785 = CARTESIAN_POINT ( 'NONE', ( -35.95487748704000097, 211.5000000000000000, 76.08022047461994930 ) ) ; -#6786 = DIRECTION ( 'NONE', ( 0.7075235667960845243, -0.1533501899574517824, 0.6898507966713961492 ) ) ; -#6787 = CARTESIAN_POINT ( 'NONE', ( -26.40985164038999855, 123.6457726243000081, 90.64157144546000211 ) ) ; -#6788 = ORIENTED_EDGE ( 'NONE', *, *, #31200, .F. ) ; -#6789 = CARTESIAN_POINT ( 'NONE', ( -25.02259365761911880, 130.4982697376238718, 90.30908595312290288 ) ) ; -#6790 = CARTESIAN_POINT ( 'NONE', ( 26.00067918362605468, 118.8155664802563791, 90.25207353690788636 ) ) ; -#6791 = CARTESIAN_POINT ( 'NONE', ( -34.95668959393816522, 217.7719116313999734, 73.07961704668733205 ) ) ; -#6792 = ORIENTED_EDGE ( 'NONE', *, *, #29342, .F. ) ; -#6793 = ADVANCED_FACE ( 'NONE', ( #25581 ), #12688, .F. ) ; -#6794 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34039, #37507, #6031, #18482 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6795 = CARTESIAN_POINT ( 'NONE', ( -22.78222448642306119, 147.3951726449005264, 96.77445396919445386 ) ) ; -#6796 = CARTESIAN_POINT ( 'NONE', ( 35.56355292868355633, 196.5784392900514206, 103.8536238432368037 ) ) ; -#6798 = CARTESIAN_POINT ( 'NONE', ( 21.44693881909371669, 176.9241929811547038, 100.4861407201621120 ) ) ; -#6797 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.271205363195980628E-14, -0.9999998176071845934 ) ) ; -#6799 = EDGE_CURVE ( 'NONE', #32791, #21410, #3462, .T. ) ; -#6800 = CONICAL_SURFACE ( 'NONE', #15940, 2.499999999883616653, 0.7853981633241470250 ) ; -#6801 = AXIS2_PLACEMENT_3D ( 'NONE', #32879, #39014, #4870 ) ; -#6802 = ORIENTED_EDGE ( 'NONE', *, *, #19560, .T. ) ; -#6803 = FACE_OUTER_BOUND ( 'NONE', #6457, .T. ) ; -#6804 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178617807513E-05, -0.0002331579774917555924 ) ) ; -#6805 = LINE ( 'NONE', #25450, #34485 ) ; -#6807 = ORIENTED_EDGE ( 'NONE', *, *, #26835, .T. ) ; -#6806 = VECTOR ( 'NONE', #23460, 1000.000000000000000 ) ; -#6808 = EDGE_CURVE ( 'NONE', #22688, #38213, #12585, .T. ) ; -#6809 = VERTEX_POINT ( 'NONE', #34931 ) ; -#6810 = EDGE_CURVE ( 'NONE', #16126, #38935, #3869, .T. ) ; -#6811 = CARTESIAN_POINT ( 'NONE', ( 37.34006930806268088, 163.4882083427749819, 203.2693587385582248 ) ) ; -#6812 = EDGE_CURVE ( 'NONE', #35125, #30572, #35170, .T. ) ; -#6813 = CARTESIAN_POINT ( 'NONE', ( 15.89503781251914027, 146.8918091207503949, 179.7543742911328479 ) ) ; -#6814 = CARTESIAN_POINT ( 'NONE', ( 38.65471576631835404, 119.1564763279458816, 90.25899222980254422 ) ) ; -#6815 = CARTESIAN_POINT ( 'NONE', ( 36.41383768445999891, 191.8230841522999981, 104.3713742736999990 ) ) ; -#6816 = ORIENTED_EDGE ( 'NONE', *, *, #31967, .T. ) ; -#6817 = ORIENTED_EDGE ( 'NONE', *, *, #6118, .F. ) ; -#6818 = EDGE_LOOP ( 'NONE', ( #1881, #28724, #18742, #13725 ) ) ; -#6819 = FACE_OUTER_BOUND ( 'NONE', #31979, .T. ) ; -#6820 = CARTESIAN_POINT ( 'NONE', ( -15.49823494792000034, 122.6567579780000017, 91.05873804473000632 ) ) ; -#6821 = PLANE ( 'NONE', #63 ) ; -#6822 = ORIENTED_EDGE ( 'NONE', *, *, #31375, .F. ) ; -#6823 = DIRECTION ( 'NONE', ( 0.6087611434179115433, -0.7728348325624404547, -0.1792657018023851023 ) ) ; -#6824 = ORIENTED_EDGE ( 'NONE', *, *, #31112, .T. ) ; -#6825 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #22009, #31005, #309, #12200 ), - ( #36937, #2971, #9330, #34442 ), - ( #34055, #114, #15843, #15067 ), - ( #21806, #2788, #21199, #12797 ), - ( #2598, #37133, #6436, #27751 ), - ( #24486, #40185, #24686, #28337 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 4 ), - ( 4, 4 ), - ( -0.4155797443374000255, 0.000000000000000000, 1.000000000000000000, 1.415579535702000014 ), - ( -0.2939753932881999932, 1.293974227719999925 ), - .UNSPECIFIED. ) ; -#6826 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971554578 ) ) ; -#6827 = ORIENTED_EDGE ( 'NONE', *, *, #26519, .F. ) ; -#6828 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749898510, 132.8602140592310548, 90.82839891331310866 ) ) ; -#6829 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2945, #12765, #24459, #21587, #15623, #9303, #3349, #15821, #8711, #15035, #40160 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000137668, 0.6250000000000154321, 0.6875000000000102141, 0.7500000000000051070, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6830 = ORIENTED_EDGE ( 'NONE', *, *, #25691, .F. ) ; -#6831 = DIRECTION ( 'NONE', ( 0.0005884949961187157857, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6832 = CIRCLE ( 'NONE', #10762, 5.499999999656733252 ) ; -#6833 = CARTESIAN_POINT ( 'NONE', ( -0.3055502478852999970, 188.2261792854999953, 106.3573352107000005 ) ) ; -#6834 = AXIS2_PLACEMENT_3D ( 'NONE', #29796, #26326, #25933 ) ; -#6835 = AXIS2_PLACEMENT_3D ( 'NONE', #8931, #2782, #12192 ) ; -#6836 = CARTESIAN_POINT ( 'NONE', ( -34.02658427073158975, 128.5584679906816064, 291.5790951394965873 ) ) ; -#6837 = ORIENTED_EDGE ( 'NONE', *, *, #25040, .T. ) ; -#6838 = DIRECTION ( 'NONE', ( 0.0004270746993313995362, -0.7071067811864992780, 0.7071066522153991452 ) ) ; -#6839 = AXIS2_PLACEMENT_3D ( 'NONE', #19121, #35249, #22821 ) ; -#6840 = CARTESIAN_POINT ( 'NONE', ( 35.74718174663996706, 80.85208185161215511, 289.9785332225363277 ) ) ; -#6841 = CARTESIAN_POINT ( 'NONE', ( 22.01449759622806823, 213.9333678484432255, 73.04520787748346322 ) ) ; -#6842 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23024, #3585, #931, #22232, #10362, #32229, #35451, #16663, #4395, #330, #7064 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000004762302, 0.3750000000006487033, 0.4375000000007172596, 0.4687500000007325807, 0.5000000000007478462, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6843 = CARTESIAN_POINT ( 'NONE', ( 19.45344668381049402, 148.4806125025154699, 180.1225407165339050 ) ) ; -#6844 = CARTESIAN_POINT ( 'NONE', ( -41.49855576315250261, 120.6354435048598788, 90.60778428571630627 ) ) ; -#6845 = ADVANCED_FACE ( 'NONE', ( #35130 ), #26733, .T. ) ; -#6846 = ORIENTED_EDGE ( 'NONE', *, *, #39953, .T. ) ; -#6847 = EDGE_CURVE ( 'NONE', #16126, #27040, #10438, .T. ) ; -#6849 = EDGE_CURVE ( 'NONE', #29516, #9324, #21877, .T. ) ; -#6848 = CARTESIAN_POINT ( 'NONE', ( -45.21443695202828650, 123.9403496629249872, 93.41837760747816333 ) ) ; -#6850 = DIRECTION ( 'NONE', ( -0.0004161288024408846113, 0.8480480898094411302, -0.5299191110041020503 ) ) ; -#6852 = ORIENTED_EDGE ( 'NONE', *, *, #36677, .F. ) ; -#6851 = ADVANCED_FACE ( 'NONE', ( #17141 ), #4886, .F. ) ; -#6853 = FACE_OUTER_BOUND ( 'NONE', #8421, .T. ) ; -#6854 = VERTEX_POINT ( 'NONE', #38422 ) ; -#6855 = CARTESIAN_POINT ( 'NONE', ( 37.50056788730638857, 112.0004321268064302, 150.7364408029844469 ) ) ; -#6856 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15236, #34806, #25054, #483 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6857 = CARTESIAN_POINT ( 'NONE', ( -27.81698282089157814, 124.7490784083306607, 88.47031569593407596 ) ) ; -#6858 = CARTESIAN_POINT ( 'NONE', ( 12.63956951859597488, 183.5640300569467342, 104.5901456648895902 ) ) ; -#6859 = ORIENTED_EDGE ( 'NONE', *, *, #7634, .T. ) ; -#6860 = FACE_BOUND ( 'NONE', #988, .T. ) ; -#6861 = ORIENTED_EDGE ( 'NONE', *, *, #12233, .T. ) ; -#6862 = VECTOR ( 'NONE', #40333, 1000.000000000000114 ) ; -#6863 = ORIENTED_EDGE ( 'NONE', *, *, #6994, .F. ) ; -#6864 = EDGE_CURVE ( 'NONE', #8845, #13129, #16742, .T. ) ; -#6865 = CARTESIAN_POINT ( 'NONE', ( 1.706989674805065693, 189.3575274026192119, 105.8396631625953574 ) ) ; -#6866 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; -#6867 = FACE_OUTER_BOUND ( 'NONE', #35880, .T. ) ; -#6868 = ORIENTED_EDGE ( 'NONE', *, *, #3985, .T. ) ; -#6869 = CIRCLE ( 'NONE', #12118, 6.000000000000007994 ) ; -#6870 = ORIENTED_EDGE ( 'NONE', *, *, #1096, .F. ) ; -#6871 = CARTESIAN_POINT ( 'NONE', ( -25.50819987922450238, 205.5673820219388688, 76.31562095576882143 ) ) ; -#6872 = AXIS2_PLACEMENT_3D ( 'NONE', #33718, #33111, #23939 ) ; -#6873 = ORIENTED_EDGE ( 'NONE', *, *, #32737, .T. ) ; -#6874 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178570903572E-05, -0.0002331579774915885982 ) ) ; -#6875 = EDGE_CURVE ( 'NONE', #29957, #21784, #32577, .T. ) ; -#6876 = CARTESIAN_POINT ( 'NONE', ( -20.00083443091425650, 118.1225346402999037, 87.27986429484819553 ) ) ; -#6877 = CARTESIAN_POINT ( 'NONE', ( -22.82371426798999892, 163.2545600168000135, 28.07991271570000080 ) ) ; -#6878 = ORIENTED_EDGE ( 'NONE', *, *, #28837, .F. ) ; -#6879 = CARTESIAN_POINT ( 'NONE', ( 28.04365811438999856, 124.9477242110999953, 88.48236039207999681 ) ) ; -#6880 = DIRECTION ( 'NONE', ( 0.0005884949961166157945, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6881 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6882 = DIRECTION ( 'NONE', ( 0.0005884949961249829080, -0.2249510543439062205, 0.9743698870671264611 ) ) ; -#6883 = CARTESIAN_POINT ( 'NONE', ( 3.661323151892192929, 136.5728955213519100, 91.18104735487531798 ) ) ; -#6884 = ORIENTED_EDGE ( 'NONE', *, *, #1360, .T. ) ; -#6885 = CARTESIAN_POINT ( 'NONE', ( -20.49852830656245928, 127.1805961887959029, 91.59301651814030265 ) ) ; -#6886 = CARTESIAN_POINT ( 'NONE', ( -25.02141666792893560, 130.0483676884890656, 92.25782546781267968 ) ) ; -#6887 = LINE ( 'NONE', #756, #24131 ) ; -#6888 = CIRCLE ( 'NONE', #27826, 5.999999999955290875 ) ; -#6889 = CARTESIAN_POINT ( 'NONE', ( 39.77206948006279674, 161.5605239982007504, 197.5119495795953810 ) ) ; -#6890 = ORIENTED_EDGE ( 'NONE', *, *, #27660, .T. ) ; -#6891 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971552357 ) ) ; -#6892 = CIRCLE ( 'NONE', #19955, 5.000000000044655835 ) ; -#6893 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6894 = DIRECTION ( 'NONE', ( -0.6087611427424929333, -0.7731004630501246977, -0.1781166615410725018 ) ) ; -#6895 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16070, #37741, #38538, #28556 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6896 = CARTESIAN_POINT ( 'NONE', ( -25.71743419941340392, 189.5946358309539903, 106.0021668375359951 ) ) ; -#6897 = EDGE_CURVE ( 'NONE', #38290, #8778, #36481, .T. ) ; -#6898 = ORIENTED_EDGE ( 'NONE', *, *, #6165, .T. ) ; -#6899 = CONICAL_SURFACE ( 'NONE', #30410, 5.999999999954211738, 0.7853981634347277918 ) ; -#6900 = FACE_OUTER_BOUND ( 'NONE', #13969, .T. ) ; -#6901 = EDGE_CURVE ( 'NONE', #18015, #1910, #17933, .T. ) ; -#6902 = EDGE_CURVE ( 'NONE', #39810, #24997, #38232, .T. ) ; -#6903 = CONICAL_SURFACE ( 'NONE', #8254, 2.502994749725878876, 0.7853981634296968162 ) ; -#6904 = EDGE_CURVE ( 'NONE', #9285, #8110, #16441, .T. ) ; -#6905 = CARTESIAN_POINT ( 'NONE', ( 0.5444273858962908053, 208.9999999999988631, 73.55817535324572987 ) ) ; -#6906 = CARTESIAN_POINT ( 'NONE', ( 22.78045900286115000, 164.6403492429171820, 97.64938332832134904 ) ) ; -#6907 = LINE ( 'NONE', #38390, #17190 ) ; -#6908 = DIRECTION ( 'NONE', ( 0.0006039748319385908944, 1.293414132305980107E-14, 0.9999998176071845934 ) ) ; -#6909 = EDGE_CURVE ( 'NONE', #32422, #13026, #16935, .T. ) ; -#6910 = CARTESIAN_POINT ( 'NONE', ( 20.10661668407306735, 127.4128641808344184, 89.16571173669045436 ) ) ; -#6911 = CARTESIAN_POINT ( 'NONE', ( 36.08394249776021212, 192.1905234492190004, 104.3364764196000039 ) ) ; -#6912 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#6913 = LINE ( 'NONE', #3834, #24586 ) ; -#6914 = ORIENTED_EDGE ( 'NONE', *, *, #35275, .T. ) ; -#6915 = ADVANCED_FACE ( 'NONE', ( #20418 ), #16254, .T. ) ; -#6916 = CARTESIAN_POINT ( 'NONE', ( -2.390862647930000140, 209.5043720128000189, 75.55992074799000591 ) ) ; -#6917 = CARTESIAN_POINT ( 'NONE', ( 36.91298638867539239, 117.6615514768335657, 87.24548977321406085 ) ) ; -#6918 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33241, #4827, #1359, #4629, #23863, #26529, #8115, #17291, #11379, #14667 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6919 = CARTESIAN_POINT ( 'NONE', ( 28.36925001313300143, 160.2013931541194722, 186.9397811580082021 ) ) ; -#6920 = CONICAL_SURFACE ( 'NONE', #37599, 59.40509898907522768, 0.7853981633972503262 ) ; -#6921 = EDGE_LOOP ( 'NONE', ( #14187, #2221, #30065, #39110 ) ) ; -#6922 = CARTESIAN_POINT ( 'NONE', ( 5.666806155083023988, 187.7449703091009781, 103.5069947386187295 ) ) ; -#6923 = VECTOR ( 'NONE', #9953, 1000.000000000000114 ) ; -#6924 = EDGE_LOOP ( 'NONE', ( #17680, #5382, #4393, #7373 ) ) ; -#6925 = CARTESIAN_POINT ( 'NONE', ( -42.43581683406742400, 94.00600134306105815, 291.5841741052475413 ) ) ; -#6926 = CARTESIAN_POINT ( 'NONE', ( -28.94659870514799849, 110.6131156702000027, 89.78526776826356581 ) ) ; -#6927 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; -#6928 = CARTESIAN_POINT ( 'NONE', ( -25.75022655317000186, 199.6921533858000259, 89.51711465924999800 ) ) ; -#6929 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971573174 ) ) ; -#6930 = CARTESIAN_POINT ( 'NONE', ( -1.458415330454428283, 144.9404864492411207, 129.0359332385636151 ) ) ; -#6931 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366368657916, 137.4659008082770697, 177.5714312369256049 ) ) ; -#6932 = DIRECTION ( 'NONE', ( 0.0006039748319384539597, 1.295170900108887039E-14, 0.9999998176071845934 ) ) ; -#6933 = CARTESIAN_POINT ( 'NONE', ( 21.98720601892291882, 135.9708336155091501, 91.37308817621079982 ) ) ; -#6934 = ORIENTED_EDGE ( 'NONE', *, *, #7651, .F. ) ; -#6935 = CARTESIAN_POINT ( 'NONE', ( 20.00016034875645943, 127.4394136103090887, 89.06260552501319694 ) ) ; -#6936 = CARTESIAN_POINT ( 'NONE', ( -3.703375335444472949, 176.2270507236910078, 100.3403802001799932 ) ) ; -#6937 = DIRECTION ( 'NONE', ( -0.0006039748319382906789, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#6938 = PLANE ( 'NONE', #34025 ) ; -#6939 = ORIENTED_EDGE ( 'NONE', *, *, #13434, .F. ) ; -#6940 = FACE_OUTER_BOUND ( 'NONE', #14692, .T. ) ; -#6941 = VERTEX_POINT ( 'NONE', #32895 ) ; -#6942 = CARTESIAN_POINT ( 'NONE', ( -20.24971313286999930, 118.4645066358000065, 87.53000830311999891 ) ) ; -#6943 = CONICAL_SURFACE ( 'NONE', #29817, 2.499999999745661228, 0.7853981633575387589 ) ; -#6944 = EDGE_CURVE ( 'NONE', #25826, #20447, #9098, .T. ) ; -#6945 = CARTESIAN_POINT ( 'NONE', ( 23.64615935046051121, 213.5251573336125546, 75.54441360651122750 ) ) ; -#6946 = CIRCLE ( 'NONE', #35672, 8.499999910073746889 ) ; -#6947 = CARTESIAN_POINT ( 'NONE', ( -17.18067142873831443, 152.4961243885515501, 182.3657930501721864 ) ) ; -#6948 = CIRCLE ( 'NONE', #21339, 2.000000000000011546 ) ; -#6949 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6950 = CARTESIAN_POINT ( 'NONE', ( 20.48087218850230329, 207.4145945196426055, 74.16884525731691724 ) ) ; -#6951 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385906776 ) ) ; -#6952 = ORIENTED_EDGE ( 'NONE', *, *, #19491, .T. ) ; -#6953 = AXIS2_PLACEMENT_3D ( 'NONE', #29081, #13144, #12520 ) ; -#6954 = CARTESIAN_POINT ( 'NONE', ( -3.669581230394507898, 185.7947741359049019, 103.0623953380812168 ) ) ; -#6955 = CARTESIAN_POINT ( 'NONE', ( -16.53001031479427141, 121.8780329720448066, 177.6173573199974953 ) ) ; -#6956 = DIRECTION ( 'NONE', ( -0.0005884949961216892102, 0.2249510543439063592, -0.9743698870671262391 ) ) ; -#6957 = VECTOR ( 'NONE', #19000, 1000.000000000000000 ) ; -#6958 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971582333 ) ) ; -#6959 = ORIENTED_EDGE ( 'NONE', *, *, #6399, .F. ) ; -#6960 = VERTEX_POINT ( 'NONE', #20211 ) ; -#6961 = ORIENTED_EDGE ( 'NONE', *, *, #33229, .T. ) ; -#6962 = CARTESIAN_POINT ( 'NONE', ( -26.00898928064792059, 209.7096528057114710, 76.07444037909847623 ) ) ; -#6963 = FACE_OUTER_BOUND ( 'NONE', #24652, .T. ) ; -#6964 = CARTESIAN_POINT ( 'NONE', ( -5.669748535203316564, 124.7404542330243800, 88.96810042129679630 ) ) ; -#6965 = ORIENTED_EDGE ( 'NONE', *, *, #9141, .T. ) ; -#6966 = CARTESIAN_POINT ( 'NONE', ( 0.5444273898015423718, 211.0000000000153761, 73.55817535318051625 ) ) ; -#6967 = ADVANCED_FACE ( 'NONE', ( #20011 ), #32502, .T. ) ; -#6968 = CARTESIAN_POINT ( 'NONE', ( -20.01841854128525711, 211.0875725380936103, 76.07063535483980843 ) ) ; -#6969 = CARTESIAN_POINT ( 'NONE', ( -38.01148413917999846, 119.1977134487000001, 87.30055639309000526 ) ) ; -#6970 = CARTESIAN_POINT ( 'NONE', ( 24.53318186138201185, 109.6131156702000027, 87.25296686492356457 ) ) ; -#6971 = ORIENTED_EDGE ( 'NONE', *, *, #7029, .F. ) ; -#6972 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 82.27946979429644614, 322.5967026918628449 ) ) ; -#6973 = VECTOR ( 'NONE', #34892, 1000.000000000000114 ) ; -#6974 = ORIENTED_EDGE ( 'NONE', *, *, #36984, .T. ) ; -#6975 = DIRECTION ( 'NONE', ( -0.0002393071182776102175, -0.2252352986010028590, 0.9743043687658493601 ) ) ; -#6976 = AXIS2_PLACEMENT_3D ( 'NONE', #25151, #37211, #24555 ) ; -#6977 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#6978 = AXIS2_PLACEMENT_3D ( 'NONE', #33809, #23605, #8484 ) ; -#6979 = DIRECTION ( 'NONE', ( -0.0005884949961212082581, 0.2249510543439042498, -0.9743698870671267942 ) ) ; -#6980 = EDGE_LOOP ( 'NONE', ( #26896, #29395, #16553, #21445, #8056, #24653 ) ) ; -#6981 = DIRECTION ( 'NONE', ( -0.0005884949961213717558, 0.2249510543439036392, -0.9743698870671270162 ) ) ; -#6982 = DIRECTION ( 'NONE', ( -0.0005884949961247530571, 0.2249510543439059984, -0.9743698870671264611 ) ) ; -#6983 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2249510911124609769, 0.9743700461176366678 ) ) ; -#6984 = CARTESIAN_POINT ( 'NONE', ( 2.428754671134000009, 191.0208418608000045, 106.1781663985999984 ) ) ; -#6985 = ORIENTED_EDGE ( 'NONE', *, *, #12704, .F. ) ; -#6986 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#6987 = CARTESIAN_POINT ( 'NONE', ( 22.50109425295000420, 153.5098312371554812, 96.96142690451516444 ) ) ; -#6988 = ORIENTED_EDGE ( 'NONE', *, *, #536, .T. ) ; -#6989 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#6990 = CARTESIAN_POINT ( 'NONE', ( 36.14023722679998230, 191.5080921624359860, 103.8442226955327072 ) ) ; -#6991 = CARTESIAN_POINT ( 'NONE', ( -27.38672108596999877, 124.3235127633000019, 91.06231056098999943 ) ) ; -#6992 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5080, #38276, #30239, #2238, #32892, #36376, #17337, #35735, #2039, #33496 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998623323, 0.3749999999997778999, 0.4374999999998006595, 0.4999999999998234745, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#6993 = EDGE_LOOP ( 'NONE', ( #9081, #29946, #21769, #12557 ) ) ; -#6994 = EDGE_CURVE ( 'NONE', #21808, #37550, #5264, .T. ) ; -#6995 = ADVANCED_FACE ( 'NONE', ( #21252 ), #11648, .T. ) ; -#6996 = CARTESIAN_POINT ( 'NONE', ( 40.92026568131703357, 127.3697701066096357, 89.54698672994854292 ) ) ; -#6997 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971540977 ) ) ; -#6998 = VERTEX_POINT ( 'NONE', #24121 ) ; -#6999 = VERTEX_POINT ( 'NONE', #36580 ) ; -#7000 = ADVANCED_FACE ( 'NONE', ( #33701 ), #28680, .T. ) ; -#7001 = CARTESIAN_POINT ( 'NONE', ( 25.83552483359000007, 120.2784135862000028, 90.31309258643000248 ) ) ; -#7002 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971551525 ) ) ; -#7003 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#7004 = CIRCLE ( 'NONE', #39022, 5.000000000000007994 ) ; -#7006 = CARTESIAN_POINT ( 'NONE', ( -8.050307605157906110, 151.4365984322141117, 94.61967771673485572 ) ) ; -#7005 = LINE ( 'NONE', #3934, #27012 ) ; -#7007 = VERTEX_POINT ( 'NONE', #27200 ) ; -#7008 = FACE_OUTER_BOUND ( 'NONE', #8021, .T. ) ; -#7009 = CARTESIAN_POINT ( 'NONE', ( -35.94137855478952304, 192.3005220655173844, 104.4216532017527612 ) ) ; -#7010 = CARTESIAN_POINT ( 'NONE', ( 25.50924745143719718, 191.9344736266071436, 104.4056993596765039 ) ) ; -#7011 = ORIENTED_EDGE ( 'NONE', *, *, #7634, .F. ) ; -#7012 = EDGE_LOOP ( 'NONE', ( #14743, #29107, #38169, #20035 ) ) ; -#7013 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858247, 183.1686750955933292, 104.5300206044594091 ) ) ; -#7014 = EDGE_CURVE ( 'NONE', #18757, #39205, #5084, .T. ) ; -#7015 = DIRECTION ( 'NONE', ( 0.7857167650892389332, -0.6185862428610306996, -0.0004745532376930883104 ) ) ; -#7016 = CARTESIAN_POINT ( 'NONE', ( -2.300294511845000223, 191.0029775200999893, 106.1754856335000028 ) ) ; -#7017 = ORIENTED_EDGE ( 'NONE', *, *, #5378, .F. ) ; -#7018 = ORIENTED_EDGE ( 'NONE', *, *, #17793, .F. ) ; -#7019 = CARTESIAN_POINT ( 'NONE', ( 31.91041242450083004, 174.4868366864082532, 100.4302623719975571 ) ) ; -#7020 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11494, #23556, #30105, #36435 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7021 = CARTESIAN_POINT ( 'NONE', ( 20.00201742172724551, 173.8530216436687965, 102.8568040933565300 ) ) ; -#7022 = DIRECTION ( 'NONE', ( 0.7933533411653059808, 0.5931840316265239998, 0.1368326740407735942 ) ) ; -#7023 = CARTESIAN_POINT ( 'NONE', ( 30.06862072249006346, 137.3596426728894642, 91.34358413054317793 ) ) ; -#7024 = CARTESIAN_POINT ( 'NONE', ( 20.66773077360686983, 151.6559761831365734, 197.7415732814573630 ) ) ; -#7025 = ORIENTED_EDGE ( 'NONE', *, *, #35039, .F. ) ; -#7026 = CARTESIAN_POINT ( 'NONE', ( -20.00002391410913560, 191.9758546681010785, 103.9335315410770448 ) ) ; -#7027 = ORIENTED_EDGE ( 'NONE', *, *, #26681, .T. ) ; -#7028 = CARTESIAN_POINT ( 'NONE', ( -36.98896915103596683, 116.5316256593857673, 89.73479078397426179 ) ) ; -#7029 = EDGE_CURVE ( 'NONE', #31968, #456, #3773, .T. ) ; -#7030 = AXIS2_PLACEMENT_3D ( 'NONE', #16971, #27028, #5322 ) ; -#7031 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971565125 ) ) ; -#7032 = EDGE_LOOP ( 'NONE', ( #30278, #1295 ) ) ; -#7033 = CARTESIAN_POINT ( 'NONE', ( -13.49852954175317343, 126.2382556819623431, 91.37123216989357388 ) ) ; -#7034 = VECTOR ( 'NONE', #2758, 999.9999999999998863 ) ; -#7035 = EDGE_CURVE ( 'NONE', #12087, #29541, #31273, .T. ) ; -#7036 = CARTESIAN_POINT ( 'NONE', ( -0.5804629561866000431, 188.8452874369000085, 105.8546174481000008 ) ) ; -#7037 = LINE ( 'NONE', #31598, #11718 ) ; -#7038 = VERTEX_POINT ( 'NONE', #39231 ) ; -#7039 = FACE_OUTER_BOUND ( 'NONE', #238, .T. ) ; -#7040 = ORIENTED_EDGE ( 'NONE', *, *, #4651, .T. ) ; -#7042 = EDGE_CURVE ( 'NONE', #23715, #13773, #14561, .T. ) ; -#7041 = FACE_OUTER_BOUND ( 'NONE', #24238, .T. ) ; -#7043 = EDGE_CURVE ( 'NONE', #38112, #2346, #36162, .T. ) ; -#7044 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319402998139 ) ) ; -#7045 = CARTESIAN_POINT ( 'NONE', ( -14.08011580147661235, 129.1601492223334446, 176.8499123979196099 ) ) ; -#7046 = EDGE_CURVE ( 'NONE', #35577, #8041, #5706, .T. ) ; -#7047 = EDGE_CURVE ( 'NONE', #27835, #36593, #24332, .T. ) ; -#7048 = LINE ( 'NONE', #15465, #6696 ) ; -#7049 = DIRECTION ( 'NONE', ( -2.775557561577051799E-15, 0.9743700557921594063, 0.2249510932971529320 ) ) ; -#7050 = ORIENTED_EDGE ( 'NONE', *, *, #32495, .T. ) ; -#7051 = CARTESIAN_POINT ( 'NONE', ( -15.99999440082457447, 126.8010213445309660, 88.93691041956509480 ) ) ; -#7052 = CARTESIAN_POINT ( 'NONE', ( -38.20570836422999861, 118.3771204103999963, 89.85183920540001168 ) ) ; -#7053 = EDGE_LOOP ( 'NONE', ( #31357, #37960, #30571, #36092, #16256, #16402, #20128, #11284 ) ) ; -#7054 = VERTEX_POINT ( 'NONE', #8167 ) ; -#7055 = CARTESIAN_POINT ( 'NONE', ( 30.77698552351368022, 157.1445057580154696, 186.2336950731475156 ) ) ; -#7056 = CIRCLE ( 'NONE', #20095, 2.499999999912043247 ) ; -#7057 = CARTESIAN_POINT ( 'NONE', ( -27.57376195191087476, 124.5212553516985992, 88.41757169004912953 ) ) ; -#7058 = PLANE ( 'NONE', #18781 ) ; -#7059 = VERTEX_POINT ( 'NONE', #36778 ) ; -#7060 = FACE_OUTER_BOUND ( 'NONE', #18874, .T. ) ; -#7061 = VERTEX_POINT ( 'NONE', #30242 ) ; -#7062 = ORIENTED_EDGE ( 'NONE', *, *, #1407, .F. ) ; -#7063 = ORIENTED_EDGE ( 'NONE', *, *, #28889, .F. ) ; -#7064 = CARTESIAN_POINT ( 'NONE', ( -6.037299711039155525, 177.1908694358191099, 101.0774571033729785 ) ) ; -#7065 = CARTESIAN_POINT ( 'NONE', ( -20.49854424914517281, 188.7751534032917675, 105.8132267661662524 ) ) ; -#7066 = ORIENTED_EDGE ( 'NONE', *, *, #18073, .T. ) ; -#7067 = VERTEX_POINT ( 'NONE', #18151 ) ; -#7068 = LINE ( 'NONE', #19537, #8898 ) ; -#7069 = CARTESIAN_POINT ( 'NONE', ( 20.14930667494123639, 207.7151874268069776, 77.19983650213306703 ) ) ; -#7070 = CARTESIAN_POINT ( 'NONE', ( -0.03375341898833555260, -31.76863880746333280, 137.4221703796379188 ) ) ; -#7071 = FACE_OUTER_BOUND ( 'NONE', #20509, .T. ) ; -#7072 = CARTESIAN_POINT ( 'NONE', ( 19.99924631025479727, 193.7259939488269822, 102.9050502291709819 ) ) ; -#7073 = DIRECTION ( 'NONE', ( -0.0004161288024746329518, 0.8480480897661252238, -0.5299191110734220445 ) ) ; -#7074 = CARTESIAN_POINT ( 'NONE', ( 6.035971956738691802, 136.6802200559948517, 94.28648626696401891 ) ) ; -#7075 = ORIENTED_EDGE ( 'NONE', *, *, #4065, .F. ) ; -#7076 = CARTESIAN_POINT ( 'NONE', ( 28.22782016780999825, 125.5652517269000015, 89.13792513741999812 ) ) ; -#7077 = EDGE_CURVE ( 'NONE', #1845, #29762, #39886, .T. ) ; -#7078 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27802, #27609, #37188, #9182, #26330, #13051, #25937, #7292, #764, #19157 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7079 = CARTESIAN_POINT ( 'NONE', ( 30.77440290267000123, 127.9840126060999808, 90.72122795244999338 ) ) ; -#7080 = CARTESIAN_POINT ( 'NONE', ( 17.23194045394322416, 152.8507688340616824, 180.9169451015856396 ) ) ; -#7081 = CARTESIAN_POINT ( 'NONE', ( 16.50035848822895801, 137.3523938021837409, 178.0624305279299335 ) ) ; -#7082 = DIRECTION ( 'NONE', ( -0.000000000000000000, 1.000000000000000000, -1.110223024625155594E-14 ) ) ; -#7083 = ORIENTED_EDGE ( 'NONE', *, *, #16731, .T. ) ; -#7084 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; -#7085 = CIRCLE ( 'NONE', #29947, 22.50000000000899902 ) ; -#7086 = EDGE_CURVE ( 'NONE', #39699, #5211, #2242, .T. ) ; -#7087 = CARTESIAN_POINT ( 'NONE', ( 0.5795578794631678354, 189.0001590438989751, 103.6953544543183483 ) ) ; -#7088 = CARTESIAN_POINT ( 'NONE', ( 36.40558664052492333, 191.8188463803718093, 104.3612499972096117 ) ) ; -#7089 = EDGE_CURVE ( 'NONE', #6247, #20818, #36963, .T. ) ; -#7090 = VECTOR ( 'NONE', #33943, 1000.000000000000114 ) ; -#7091 = CARTESIAN_POINT ( 'NONE', ( 3.501239660417288402, 183.5259502247448893, 104.7579320029620931 ) ) ; -#7092 = AXIS2_PLACEMENT_3D ( 'NONE', #6795, #28892, #34989 ) ; -#7093 = CARTESIAN_POINT ( 'NONE', ( -30.07068226051780613, 136.7886132718092540, 93.81698375422377012 ) ) ; -#7094 = CARTESIAN_POINT ( 'NONE', ( -25.51388077191477066, 211.0902258580313742, 75.57405363378009611 ) ) ; -#7095 = VECTOR ( 'NONE', #19613, 1000.000000000000227 ) ; -#7096 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971594823 ) ) ; -#7097 = CARTESIAN_POINT ( 'NONE', ( -25.50804057823069471, 190.9260211217805363, 106.3128357153982648 ) ) ; -#7098 = EDGE_CURVE ( 'NONE', #11249, #33342, #9206, .T. ) ; -#7099 = CARTESIAN_POINT ( 'NONE', ( 25.75600378562127091, 122.1627709945768601, 90.40662719960204186 ) ) ; -#7100 = ORIENTED_EDGE ( 'NONE', *, *, #27097, .T. ) ; -#7101 = CARTESIAN_POINT ( 'NONE', ( -15.49970617728509481, 174.4013312752846900, 100.4391564138297497 ) ) ; -#7102 = CARTESIAN_POINT ( 'NONE', ( 25.99199080364422443, 211.0901596425212574, 76.04279652306830428 ) ) ; -#7103 = CARTESIAN_POINT ( 'NONE', ( -45.39773774286052088, 124.2994142384970218, 88.45363130071420699 ) ) ; -#7104 = CARTESIAN_POINT ( 'NONE', ( 22.49999746303471682, 151.9741732817970217, 94.72226965095939022 ) ) ; -#7105 = FACE_OUTER_BOUND ( 'NONE', #6477, .T. ) ; -#7106 = CARTESIAN_POINT ( 'NONE', ( 38.04164538826000097, 190.5102620719000015, 106.5668313176000055 ) ) ; -#7107 = CARTESIAN_POINT ( 'NONE', ( 36.08518473800659621, 192.3716602159279887, 106.3932342325000064 ) ) ; -#7108 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950524827, 137.3532831589782006, 178.0585834213013072 ) ) ; -#7109 = CARTESIAN_POINT ( 'NONE', ( -20.89286847790088331, 136.3261294211067138, 91.13890976780785991 ) ) ; -#7110 = ORIENTED_EDGE ( 'NONE', *, *, #23307, .T. ) ; -#7112 = VECTOR ( 'NONE', #22493, 1000.000000000000000 ) ; -#7111 = CARTESIAN_POINT ( 'NONE', ( -2.620872023761000147, 209.0473112116000038, 75.82273478259000399 ) ) ; -#7113 = CARTESIAN_POINT ( 'NONE', ( -15.56603823806943332, 147.4087826307038824, 179.2784924189821822 ) ) ; -#7114 = DIRECTION ( 'NONE', ( 0.5988683521957610667, -0.8008474865655346164, 0.000000000000000000 ) ) ; -#7115 = ORIENTED_EDGE ( 'NONE', *, *, #38518, .F. ) ; -#7116 = DIRECTION ( 'NONE', ( -0.0004161288024542070707, 0.8480480897973143861, -0.5299191110235090818 ) ) ; -#7117 = AXIS2_PLACEMENT_3D ( 'NONE', #28644, #15756, #28058 ) ; -#7118 = VECTOR ( 'NONE', #3130, 1000.000000000000227 ) ; -#7119 = ORIENTED_EDGE ( 'NONE', *, *, #34713, .F. ) ; -#7120 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#7121 = FACE_OUTER_BOUND ( 'NONE', #37080, .T. ) ; -#7122 = CARTESIAN_POINT ( 'NONE', ( -14.29616515061532489, 182.1658140207151462, 104.4546612231253846 ) ) ; -#7123 = EDGE_CURVE ( 'NONE', #19459, #35621, #18439, .T. ) ; -#7124 = EDGE_CURVE ( 'NONE', #1289, #10706, #37804, .T. ) ; -#7125 = EDGE_CURVE ( 'NONE', #25706, #1172, #22153, .T. ) ; -#7126 = CARTESIAN_POINT ( 'NONE', ( -23.35081975911714380, 130.3436102262665486, 92.83812635286813020 ) ) ; -#7127 = EDGE_CURVE ( 'NONE', #21013, #28306, #2139, .T. ) ; -#7128 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9322, #30799, #36717, #22000, #5642, #28140 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 4 ), - ( 0.000000000000000000, 0.3333335430186030734, 0.6666667714093976738, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7129 = CARTESIAN_POINT ( 'NONE', ( -30.06953855927680408, 176.7983674875579538, 103.1369290433998032 ) ) ; -#7130 = CARTESIAN_POINT ( 'NONE', ( 21.72804141255551968, 135.8412665901933281, 91.00123227078390187 ) ) ; -#7131 = ORIENTED_EDGE ( 'NONE', *, *, #30055, .T. ) ; -#7132 = ORIENTED_EDGE ( 'NONE', *, *, #26731, .T. ) ; -#7133 = CARTESIAN_POINT ( 'NONE', ( 16.56083240327746253, 152.2213612066225323, 181.4810637892755381 ) ) ; -#7134 = CARTESIAN_POINT ( 'NONE', ( -5.032525950256758307, 177.5851188099599653, 100.6547177535344133 ) ) ; -#7135 = CARTESIAN_POINT ( 'NONE', ( 3.853642445162356545, 176.5899727902160521, 100.4196031271038976 ) ) ; -#7136 = EDGE_CURVE ( 'NONE', #37750, #36032, #23320, .T. ) ; -#7137 = CARTESIAN_POINT ( 'NONE', ( -35.98473264158000262, 191.6464846952000016, 104.0240790657999952 ) ) ; -#7138 = ORIENTED_EDGE ( 'NONE', *, *, #15184, .T. ) ; -#7139 = FACE_OUTER_BOUND ( 'NONE', #8235, .T. ) ; -#7140 = ORIENTED_EDGE ( 'NONE', *, *, #31296, .T. ) ; -#7141 = EDGE_CURVE ( 'NONE', #2805, #11248, #7438, .T. ) ; -#7142 = VECTOR ( 'NONE', #29069, 1000.000000000000114 ) ; -#7143 = CARTESIAN_POINT ( 'NONE', ( 36.71933013359660691, 115.7525949145573207, 89.70085851803463584 ) ) ; -#7144 = CARTESIAN_POINT ( 'NONE', ( 2.544444642232003950, 209.0637104426000121, 73.60054458572000158 ) ) ; -#7145 = AXIS2_PLACEMENT_3D ( 'NONE', #20344, #19539, #936 ) ; -#7146 = CARTESIAN_POINT ( 'NONE', ( -15.74985326587000145, 127.2158021103000038, 89.28909166873999936 ) ) ; -#7147 = CONICAL_SURFACE ( 'NONE', #11103, 4.999999999912411397, 0.7853981633778838178 ) ; -#7148 = CARTESIAN_POINT ( 'NONE', ( -38.94514605625099080, 127.5103311478221428, 92.19343525405152207 ) ) ; -#7149 = CARTESIAN_POINT ( 'NONE', ( -25.99272582769830819, 191.9759150222000130, 101.9371462954573673 ) ) ; -#7150 = EDGE_CURVE ( 'NONE', #21029, #3248, #14322, .T. ) ; -#7151 = CYLINDRICAL_SURFACE ( 'NONE', #19047, 2.000000000000000000 ) ; -#7152 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#7153 = CARTESIAN_POINT ( 'NONE', ( -37.71819034619999655, 191.1230216278999876, 106.2274880251000013 ) ) ; -#7154 = ORIENTED_EDGE ( 'NONE', *, *, #24808, .T. ) ; -#7155 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#7156 = CARTESIAN_POINT ( 'NONE', ( -36.38117854302612386, 191.5685604296012912, 106.4115501805643476 ) ) ; -#7157 = DIRECTION ( 'NONE', ( 0.6087614115774887535, 0.7729348350621332298, 0.1788331191967985623 ) ) ; -#7158 = CARTESIAN_POINT ( 'NONE', ( 30.07038801304316777, 174.6845315262252143, 103.0427758964743816 ) ) ; -#7159 = VERTEX_POINT ( 'NONE', #32794 ) ; -#7160 = EDGE_LOOP ( 'NONE', ( #23324, #8068, #8182, #1080, #18474, #9596 ) ) ; -#7161 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #7993, #20456, #9225, #2485 ), - ( #12287, #17994, #30698, #5531 ), - ( #36416, #18396, #21697, #20880 ), - ( #27243, #30088, #39464, #34141 ), - ( #9021, #21504, #37226, #30498 ), - ( #15158, #33743, #2277, #27455 ), - ( #30281, #24773, #5941, #14951 ), - ( #40275, #14759, #33337, #33940 ), - ( #39674, #17785, #30898, #36621 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.01895079535701999982, 0.000000000000000000, 0.2500000606983999729, 0.5000001337900999987, 0.7500002068818999446, 1.000000000000000000, 1.019135236371000008 ), - ( 2.695796517459999933E-06, 0.9999450311894000354 ), - .UNSPECIFIED. ) ; -#7162 = ORIENTED_EDGE ( 'NONE', *, *, #29765, .F. ) ; -#7163 = CARTESIAN_POINT ( 'NONE', ( 31.30533522779878908, 110.6131156702000027, 90.24887720121222401 ) ) ; -#7164 = CARTESIAN_POINT ( 'NONE', ( 15.50029466867484551, 138.3983482085316723, 92.10848809867536602 ) ) ; -#7165 = VERTEX_POINT ( 'NONE', #17034 ) ; -#7166 = VERTEX_POINT ( 'NONE', #1309 ) ; -#7167 = CARTESIAN_POINT ( 'NONE', ( -35.95366953732082749, 209.7096538831000032, 78.08022010984795713 ) ) ; -#7168 = VECTOR ( 'NONE', #27678, 999.9999999999998863 ) ; -#7169 = CARTESIAN_POINT ( 'NONE', ( -38.23160862004999672, 118.6973730046999975, 90.09692188751000685 ) ) ; -#7170 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#7171 = CARTESIAN_POINT ( 'NONE', ( -21.79303016557126327, 121.9945052680030670, 152.1817659228955222 ) ) ; -#7172 = DIRECTION ( 'NONE', ( 0.6088160902985568779, -0.7729595817128234181, -0.1785397805306046803 ) ) ; -#7173 = VERTEX_POINT ( 'NONE', #1510 ) ; -#7174 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#7175 = VECTOR ( 'NONE', #21626, 1000.000000000000000 ) ; -#7176 = ORIENTED_EDGE ( 'NONE', *, *, #12369, .F. ) ; -#7178 = EDGE_CURVE ( 'NONE', #11556, #1872, #7851, .T. ) ; -#7177 = CARTESIAN_POINT ( 'NONE', ( -15.10713178427481651, 176.3794795624077096, 100.3824614381103828 ) ) ; -#7179 = FACE_OUTER_BOUND ( 'NONE', #31560, .T. ) ; -#7180 = EDGE_CURVE ( 'NONE', #20943, #7260, #12332, .T. ) ; -#7181 = CARTESIAN_POINT ( 'NONE', ( 20.12333278077425192, 184.3221617671313197, 105.1489674529760237 ) ) ; -#7182 = CARTESIAN_POINT ( 'NONE', ( 30.05382551872783736, 109.6131156702000027, 87.74963262544588360 ) ) ; -#7183 = CARTESIAN_POINT ( 'NONE', ( 41.55515210090072742, 120.2182341932538776, 89.94814927363270840 ) ) ; -#7184 = ORIENTED_EDGE ( 'NONE', *, *, #20540, .T. ) ; -#7185 = CARTESIAN_POINT ( 'NONE', ( -19.99825438583805237, 190.8509747501094580, 106.8052823956111013 ) ) ; -#7186 = DIRECTION ( 'NONE', ( -0.0005884949961246487568, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#7187 = FACE_OUTER_BOUND ( 'NONE', #10825, .T. ) ; -#7188 = EDGE_LOOP ( 'NONE', ( #19763, #9100 ) ) ; -#7189 = ORIENTED_EDGE ( 'NONE', *, *, #7223, .F. ) ; -#7190 = CARTESIAN_POINT ( 'NONE', ( -25.50827005986327478, 207.9228675525097003, 76.25894037447334028 ) ) ; -#7191 = CARTESIAN_POINT ( 'NONE', ( 23.39351881373000097, 165.2216646563843199, 152.9217693939943388 ) ) ; -#7192 = ORIENTED_EDGE ( 'NONE', *, *, #18247, .F. ) ; -#7193 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748320902236156 ) ) ; -#7194 = ORIENTED_EDGE ( 'NONE', *, *, #32269, .F. ) ; -#7195 = CARTESIAN_POINT ( 'NONE', ( 28.46551015877975033, 129.9757720508976888, 92.20876074269682476 ) ) ; -#7196 = CARTESIAN_POINT ( 'NONE', ( 35.88952463556218930, 77.14301703112145958, 291.5368675616688279 ) ) ; -#7197 = AXIS2_PLACEMENT_3D ( 'NONE', #29133, #5168, #36041 ) ; -#7198 = EDGE_CURVE ( 'NONE', #24067, #8293, #17236, .T. ) ; -#7199 = AXIS2_PLACEMENT_3D ( 'NONE', #27777, #22037, #6076 ) ; -#7200 = VERTEX_POINT ( 'NONE', #13994 ) ; -#7201 = CIRCLE ( 'NONE', #8541, 8.499999999972331466 ) ; -#7202 = CARTESIAN_POINT ( 'NONE', ( 26.00781598993299681, 120.3026641870980029, 90.49382190704038464 ) ) ; -#7203 = CYLINDRICAL_SURFACE ( 'NONE', #4488, 59.40509898897001051 ) ; -#7205 = CARTESIAN_POINT ( 'NONE', ( -30.17789690918193202, 185.2730303678106623, 105.5237128568702047 ) ) ; -#7204 = CARTESIAN_POINT ( 'NONE', ( 20.48149273625410061, 209.0618706960821385, 75.63135123663742831 ) ) ; -#7206 = ORIENTED_EDGE ( 'NONE', *, *, #23351, .F. ) ; -#7207 = ORIENTED_EDGE ( 'NONE', *, *, #14624, .F. ) ; -#7208 = LINE ( 'NONE', #3533, #36925 ) ; -#7209 = FACE_OUTER_BOUND ( 'NONE', #26092, .T. ) ; -#7210 = DIRECTION ( 'NONE', ( -0.0005734119072279676797, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#7211 = CARTESIAN_POINT ( 'NONE', ( -35.94740272817028170, 109.6131156707333361, 88.45616250159258698 ) ) ; -#7212 = VERTEX_POINT ( 'NONE', #33182 ) ; -#7213 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1603, #26765, #38800, #20402, #39211, #39409, #8145, #23481, #30025, #17732, #4459 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000001563194, 0.3750000000001783018, 0.4375000000001543765, 0.4687500000001424416, 0.5000000000001304512, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7214 = ORIENTED_EDGE ( 'NONE', *, *, #37738, .F. ) ; -#7215 = CARTESIAN_POINT ( 'NONE', ( 22.78070441975003391, 158.6816533748419147, 96.78686173997256503 ) ) ; -#7216 = CARTESIAN_POINT ( 'NONE', ( 5.669749815053078734, 187.5280698745357881, 105.8286138481728358 ) ) ; -#7217 = FACE_OUTER_BOUND ( 'NONE', #14454, .T. ) ; -#7218 = ORIENTED_EDGE ( 'NONE', *, *, #3079, .T. ) ; -#7219 = ORIENTED_EDGE ( 'NONE', *, *, #17081, .T. ) ; -#7220 = CARTESIAN_POINT ( 'NONE', ( -42.84606607935617006, 121.9225652775318167, 87.84153733356382077 ) ) ; -#7221 = CARTESIAN_POINT ( 'NONE', ( -12.63584100919595876, 177.6275380978030114, 100.8078340518252674 ) ) ; -#7222 = CARTESIAN_POINT ( 'NONE', ( 22.78045900286095815, 148.0760582945906663, 93.82521474193295319 ) ) ; -#7223 = EDGE_CURVE ( 'NONE', #4758, #23777, #1353, .T. ) ; -#7224 = LINE ( 'NONE', #25464, #30748 ) ; -#7225 = CIRCLE ( 'NONE', #22922, 2.499999999942582818 ) ; -#7226 = EDGE_LOOP ( 'NONE', ( #17398, #36910, #8637, #15929 ) ) ; -#7227 = DIRECTION ( 'NONE', ( 0.6075492010474008442, -0.7738441339353225867, -0.1790229724939112477 ) ) ; -#7228 = CIRCLE ( 'NONE', #30103, 4.750000613335879862 ) ; -#7229 = VERTEX_POINT ( 'NONE', #38923 ) ; -#7230 = VECTOR ( 'NONE', #6866, 1000.000000000000227 ) ; -#7231 = VERTEX_POINT ( 'NONE', #8054 ) ; -#7232 = CARTESIAN_POINT ( 'NONE', ( -13.48798776821729639, 154.4042536791194493, 95.30809926299690460 ) ) ; -#7233 = ORIENTED_EDGE ( 'NONE', *, *, #36578, .F. ) ; -#7234 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#7235 = CARTESIAN_POINT ( 'NONE', ( -0.3183892827599000275, 188.5403529200000037, 106.1071648710999966 ) ) ; -#7236 = CARTESIAN_POINT ( 'NONE', ( -30.05378918480198180, 127.2828694672463712, 89.56979071655838709 ) ) ; -#7237 = PLANE ( 'NONE', #18201 ) ; -#7238 = VERTEX_POINT ( 'NONE', #32987 ) ; -#7239 = CARTESIAN_POINT ( 'NONE', ( 10.30723277641929947, 181.6902071446141065, 101.5932328223857439 ) ) ; -#7240 = CARTESIAN_POINT ( 'NONE', ( 21.38683321223914646, 213.6392524122032910, 73.04558697104342002 ) ) ; -#7241 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #12878, #21487, #37410, #21880 ), - .UNSPECIFIED., .F., .F. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.571531679975004536, 3.141592653589798445 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8049111466635359147, 0.8049111466635359147, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#7242 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; -#7243 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24865, #286, #31586, #25060, #31381, #490, #15826, #12180, #33834, #34617, #37115 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000524025, 0.6250000000000566214, 0.6875000000000587308, 0.7500000000000608402, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7244 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#7245 = VERTEX_POINT ( 'NONE', #4981 ) ; -#7246 = CARTESIAN_POINT ( 'NONE', ( 40.07613110354596131, 77.14301703112144537, 291.5343389562696643 ) ) ; -#7247 = VECTOR ( 'NONE', #15096, 1000.000000000000000 ) ; -#7248 = CARTESIAN_POINT ( 'NONE', ( -38.11161765677999824, 118.6427780456999983, 90.14970056747002047 ) ) ; -#7249 = ORIENTED_EDGE ( 'NONE', *, *, #9279, .F. ) ; -#7250 = VECTOR ( 'NONE', #28899, 1000.000000000000114 ) ; -#7251 = ORIENTED_EDGE ( 'NONE', *, *, #13742, .T. ) ; -#7252 = CARTESIAN_POINT ( 'NONE', ( 5.957091414655063311, 149.1468224720344438, 94.08258114083251655 ) ) ; -#7253 = ADVANCED_FACE ( 'NONE', ( #17444 ), #39321, .T. ) ; -#7254 = CARTESIAN_POINT ( 'NONE', ( 35.48442776063147619, 88.13433118093483642, 282.5337480928039895 ) ) ; -#7255 = CARTESIAN_POINT ( 'NONE', ( -13.49977439033965432, 124.1657361220545397, 90.99867658793307612 ) ) ; -#7256 = ORIENTED_EDGE ( 'NONE', *, *, #6142, .F. ) ; -#7257 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3489, #639, #4092, #31530 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7258 = CARTESIAN_POINT ( 'NONE', ( -2.935232621041004020, 190.8511156531020276, 106.7950609103722286 ) ) ; -#7259 = VERTEX_POINT ( 'NONE', #40136 ) ; -#7260 = VERTEX_POINT ( 'NONE', #33598 ) ; -#7261 = CARTESIAN_POINT ( 'NONE', ( 2.563994175896955774, 190.9709097722040099, 106.3045652864306874 ) ) ; -#7262 = EDGE_CURVE ( 'NONE', #19980, #16610, #27399, .T. ) ; -#7263 = DIRECTION ( 'NONE', ( 7.677760455957277161E-18, -1.000000000000000000, 1.271205131337255403E-14 ) ) ; -#7264 = ORIENTED_EDGE ( 'NONE', *, *, #34149, .F. ) ; -#7265 = EDGE_LOOP ( 'NONE', ( #37212, #495, #5048, #5188 ) ) ; -#7266 = CARTESIAN_POINT ( 'NONE', ( -22.49975369487818710, 158.6756590294297382, 96.81282609783636417 ) ) ; -#7268 = EDGE_CURVE ( 'NONE', #36214, #4109, #21356, .T. ) ; -#7267 = DIRECTION ( 'NONE', ( 0.0002393071182782299474, 0.2252352986010034697, -0.9743043687658493601 ) ) ; -#7269 = CARTESIAN_POINT ( 'NONE', ( 43.53526136507346678, 121.9496774062499043, 88.05073105187337035 ) ) ; -#7270 = ADVANCED_FACE ( 'NONE', ( #21760 ), #30642, .F. ) ; -#7271 = CARTESIAN_POINT ( 'NONE', ( 2.943860253156593387, 209.7081874491304063, 76.05616958207551193 ) ) ; -#7272 = EDGE_CURVE ( 'NONE', #8707, #38178, #27513, .T. ) ; -#7273 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#7274 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971574284 ) ) ; -#7275 = VERTEX_POINT ( 'NONE', #11741 ) ; -#7276 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748612898, 181.3724072540864540, 104.0809311256944909 ) ) ; -#7277 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#7278 = CYLINDRICAL_SURFACE ( 'NONE', #32550, 2.000000000000011546 ) ; -#7279 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#7280 = CARTESIAN_POINT ( 'NONE', ( 4.915911327427738620, 135.1711131658586851, 90.85666259926293264 ) ) ; -#7281 = EDGE_LOOP ( 'NONE', ( #19922, #450, #32586, #1005 ) ) ; -#7282 = AXIS2_PLACEMENT_3D ( 'NONE', #36317, #1565, #14252 ) ; -#7283 = CARTESIAN_POINT ( 'NONE', ( -13.46991461394048706, 153.3545038370762654, 97.63149519329859061 ) ) ; -#7284 = AXIS2_PLACEMENT_3D ( 'NONE', #22710, #18797, #19010 ) ; -#7285 = CYLINDRICAL_SURFACE ( 'NONE', #16636, 10.00000000000000533 ) ; -#7286 = LINE ( 'NONE', #25930, #39777 ) ; -#7287 = CARTESIAN_POINT ( 'NONE', ( 12.63725699762741250, 130.1064011942611387, 92.43024055530932515 ) ) ; -#7288 = CARTESIAN_POINT ( 'NONE', ( -25.87061325811000145, 191.8108095213000013, 104.0515899184999995 ) ) ; -#7289 = CARTESIAN_POINT ( 'NONE', ( 20.50029381496701930, 120.2778657622999958, 87.92202511309000101 ) ) ; -#7290 = DIRECTION ( 'NONE', ( 0.0005884949961181263050, -0.2249510543439084131, 0.9743698870671259060 ) ) ; -#7291 = EDGE_CURVE ( 'NONE', #17219, #37866, #34504, .T. ) ; -#7292 = CARTESIAN_POINT ( 'NONE', ( -20.49856733782493379, 192.0038685806965475, 106.4640362600384549 ) ) ; -#7293 = CARTESIAN_POINT ( 'NONE', ( -28.26126760785277625, 125.3518701206620705, 90.14920593263850890 ) ) ; -#7294 = VERTEX_POINT ( 'NONE', #14609 ) ; -#7295 = CYLINDRICAL_SURFACE ( 'NONE', #23969, 59.40509898897001051 ) ; -#7296 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9821, #6933, #16521, #7130 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7297 = VERTEX_POINT ( 'NONE', #33803 ) ; -#7298 = CARTESIAN_POINT ( 'NONE', ( 24.53348384866000131, 103.6131156702000027, 87.75296677360999809 ) ) ; -#7299 = CARTESIAN_POINT ( 'NONE', ( -26.00043888416333004, 191.6093710626577149, 103.9038991438749235 ) ) ; -#7300 = EDGE_CURVE ( 'NONE', #11012, #34614, #13008, .T. ) ; -#7301 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.702666754117757870E-16, 0.0006039748319385827629 ) ) ; -#7302 = CARTESIAN_POINT ( 'NONE', ( 36.08436338837000079, 192.2518954457999882, 105.0333384416999962 ) ) ; -#7303 = FACE_OUTER_BOUND ( 'NONE', #16413, .T. ) ; -#7304 = AXIS2_PLACEMENT_3D ( 'NONE', #994, #3452, #3654 ) ; -#7305 = CARTESIAN_POINT ( 'NONE', ( 35.94834476972000203, 192.8406908178000094, 106.4387586362000064 ) ) ; -#7306 = VERTEX_POINT ( 'NONE', #37084 ) ; -#7307 = ORIENTED_EDGE ( 'NONE', *, *, #12890, .F. ) ; -#7308 = CONICAL_SURFACE ( 'NONE', #806, 2.500001241545478869, 0.7853981633776581095 ) ; -#7309 = CARTESIAN_POINT ( 'NONE', ( -5.669506394645257963, 181.2845812425110523, 104.3558773153669250 ) ) ; -#7310 = CARTESIAN_POINT ( 'NONE', ( -2.787474291791000258, 209.1564175354999975, 75.96280436173999817 ) ) ; -#7311 = ADVANCED_FACE ( 'NONE', ( #11949 ), #27092, .F. ) ; -#7312 = CARTESIAN_POINT ( 'NONE', ( -16.15354643035712812, 122.9157560190214156, 174.2038265287079071 ) ) ; -#7313 = ADVANCED_FACE ( 'NONE', ( #39527 ), #34004, .T. ) ; -#7314 = LINE ( 'NONE', #17111, #35617 ) ; -#7315 = PLANE ( 'NONE', #31117 ) ; -#7316 = VERTEX_POINT ( 'NONE', #2540 ) ; -#7317 = DIRECTION ( 'NONE', ( 0.0005884949961240270753, -0.2249510543439049992, 0.9743698870671265722 ) ) ; -#7318 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #17734, #20404, #14705, #33079 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.612409811267536242, 4.712390161299671476 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9991671675941976583, 0.9991671675941976583, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#7319 = EDGE_CURVE ( 'NONE', #4201, #39778, #11724, .T. ) ; -#7320 = ORIENTED_EDGE ( 'NONE', *, *, #28791, .T. ) ; -#7321 = EDGE_CURVE ( 'NONE', #16953, #9311, #29643, .T. ) ; -#7322 = EDGE_CURVE ( 'NONE', #2067, #32425, #15008, .T. ) ; -#7323 = CARTESIAN_POINT ( 'NONE', ( -28.94810864222802849, 110.6131156702000027, 87.28526822420690223 ) ) ; -#7324 = CARTESIAN_POINT ( 'NONE', ( 29.78035931491814026, 126.7216206972648109, 90.43038213919562907 ) ) ; -#7325 = ORIENTED_EDGE ( 'NONE', *, *, #23176, .T. ) ; -#7326 = CARTESIAN_POINT ( 'NONE', ( -19.99999816303952471, 191.5261162992163690, 103.8822987450886046 ) ) ; -#7327 = CARTESIAN_POINT ( 'NONE', ( 25.83230247200966545, 118.1154253885978278, 87.41886792823243013 ) ) ; -#7328 = LINE ( 'NONE', #19785, #496 ) ; -#7329 = CARTESIAN_POINT ( 'NONE', ( -5.663464557155529988, 131.0206703453534374, 89.90489628355439322 ) ) ; -#7330 = DIRECTION ( 'NONE', ( 0.7933535320750288999, 0.5930759023596230417, 0.1372994799130531074 ) ) ; -#7331 = ORIENTED_EDGE ( 'NONE', *, *, #31677, .T. ) ; -#7332 = DIRECTION ( 'NONE', ( 0.0006039748319356123742, -6.151140898304641511E-15, 0.9999998176071847045 ) ) ; -#7333 = CARTESIAN_POINT ( 'NONE', ( -30.07070568945121281, 177.4624532118801596, 100.9195456647180151 ) ) ; -#7334 = DIRECTION ( 'NONE', ( -0.0004161288024612937414, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#7335 = CARTESIAN_POINT ( 'NONE', ( 38.12150922002388143, 153.0051697192221241, 291.5355194989076608 ) ) ; -#7336 = VERTEX_POINT ( 'NONE', #39938 ) ; -#7337 = AXIS2_PLACEMENT_3D ( 'NONE', #21034, #2637, #17937 ) ; -#7338 = CARTESIAN_POINT ( 'NONE', ( 25.51042451852513082, 191.2901597426282194, 106.3556975140922702 ) ) ; -#7339 = AXIS2_PLACEMENT_3D ( 'NONE', #12274, #31278, #24562 ) ; -#7340 = VECTOR ( 'NONE', #3273, 1000.000000000000000 ) ; -#7341 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#7342 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178587041921E-05, -0.0002331579774917524482 ) ) ; -#7343 = CARTESIAN_POINT ( 'NONE', ( -6.000829975801000415, 123.2470639583000178, 152.4718672074000381 ) ) ; -#7344 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#7345 = CARTESIAN_POINT ( 'NONE', ( -2.957808003804000219, 209.8402624482000078, 72.92550096166999651 ) ) ; -#7346 = CARTESIAN_POINT ( 'NONE', ( 38.36127927543999760, 118.7741772839000163, 90.10271768068000142 ) ) ; -#7347 = ORIENTED_EDGE ( 'NONE', *, *, #3029, .F. ) ; -#7348 = EDGE_CURVE ( 'NONE', #17938, #13095, #8687, .T. ) ; -#7349 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971558741 ) ) ; -#7350 = EDGE_CURVE ( 'NONE', #3701, #9728, #22180, .T. ) ; -#7351 = CARTESIAN_POINT ( 'NONE', ( -20.89282324149344561, 183.0959377177359215, 101.9365769416837253 ) ) ; -#7352 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#7353 = EDGE_CURVE ( 'NONE', #13602, #25001, #30956, .T. ) ; -#7354 = CARTESIAN_POINT ( 'NONE', ( -35.93807696457238166, 196.5784392899485340, 103.8968090359679479 ) ) ; -#7355 = EDGE_LOOP ( 'NONE', ( #36172, #22186, #28510, #35150 ) ) ; -#7356 = ORIENTED_EDGE ( 'NONE', *, *, #14062, .F. ) ; -#7357 = ADVANCED_FACE ( 'NONE', ( #12338 ), #26757, .F. ) ; -#7358 = VERTEX_POINT ( 'NONE', #28292 ) ; -#7359 = DIRECTION ( 'NONE', ( 0.0006039748319373442788, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#7360 = AXIS2_PLACEMENT_3D ( 'NONE', #26743, #23879, #14678 ) ; -#7361 = EDGE_CURVE ( 'NONE', #28042, #28075, #32085, .T. ) ; -#7362 = DIRECTION ( 'NONE', ( 0.0005884949961245723206, -0.2249510543439059984, 0.9743698870671263501 ) ) ; -#7363 = VECTOR ( 'NONE', #39340, 1000.000000000000114 ) ; -#7364 = EDGE_LOOP ( 'NONE', ( #11778, #24765, #33818 ) ) ; -#7365 = CARTESIAN_POINT ( 'NONE', ( 38.45464856030794465, 118.5792329893091051, 89.85665017623614403 ) ) ; -#7366 = EDGE_CURVE ( 'NONE', #9960, #16388, #19061, .T. ) ; -#7367 = AXIS2_PLACEMENT_3D ( 'NONE', #11397, #21217, #14476 ) ; -#7368 = CARTESIAN_POINT ( 'NONE', ( 10.03420395425108680, 168.4982496180414273, 98.54774839040621259 ) ) ; -#7369 = CARTESIAN_POINT ( 'NONE', ( -38.24533459185000339, 118.9468119104000010, 87.58145080328000631 ) ) ; -#7370 = CARTESIAN_POINT ( 'NONE', ( 3.168110071476895495, 118.9434405806654240, 90.19017701310959012 ) ) ; -#7371 = EDGE_LOOP ( 'NONE', ( #37862, #29900, #24267, #8644, #28228, #35190 ) ) ; -#7372 = DIRECTION ( 'NONE', ( 0.0006039748319386177827, 1.312069532538339473E-14, 0.9999998176071847045 ) ) ; -#7373 = ORIENTED_EDGE ( 'NONE', *, *, #11651, .F. ) ; -#7374 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319379440594 ) ) ; -#7375 = CARTESIAN_POINT ( 'NONE', ( -3.168110071482259205, 118.9426017752647766, 90.19381027778268844 ) ) ; -#7376 = CARTESIAN_POINT ( 'NONE', ( 20.19176146692526430, 184.3365261251356344, 105.0819723774979906 ) ) ; -#7377 = CARTESIAN_POINT ( 'NONE', ( -45.68157572959258772, 116.8137947612332681, 122.5502833297559135 ) ) ; -#7378 = CARTESIAN_POINT ( 'NONE', ( 36.05533436145224613, 118.8155634790891355, 90.24600832072235335 ) ) ; -#7379 = ORIENTED_EDGE ( 'NONE', *, *, #3288, .T. ) ; -#7380 = EDGE_CURVE ( 'NONE', #28951, #8754, #22365, .T. ) ; -#7381 = ORIENTED_EDGE ( 'NONE', *, *, #3454, .F. ) ; -#7382 = CARTESIAN_POINT ( 'NONE', ( -0.9823828506576001152, 188.9161183472000118, 103.5350258649999944 ) ) ; -#7383 = CARTESIAN_POINT ( 'NONE', ( -13.63173874120965401, 135.9869460838498583, 148.6427343181233311 ) ) ; -#7384 = CARTESIAN_POINT ( 'NONE', ( 8.329377750328216479, 161.3713756194757991, 97.24551068566299250 ) ) ; -#7385 = ORIENTED_EDGE ( 'NONE', *, *, #25340, .F. ) ; -#7386 = CARTESIAN_POINT ( 'NONE', ( 22.50071842841086678, 154.4094130781474803, 95.28756121982962668 ) ) ; -#7387 = CARTESIAN_POINT ( 'NONE', ( 39.06349078196001301, 191.0388279120988670, 103.7341189576915355 ) ) ; -#7388 = VERTEX_POINT ( 'NONE', #665 ) ; -#7389 = CARTESIAN_POINT ( 'NONE', ( -42.22551659325709750, 120.8118849317876595, 90.64895807725147847 ) ) ; -#7390 = VECTOR ( 'NONE', #25580, 1000.000000000000114 ) ; -#7391 = EDGE_LOOP ( 'NONE', ( #34075, #4097, #9117, #7540, #1463, #24226, #5550, #27776 ) ) ; -#7392 = CIRCLE ( 'NONE', #6750, 2.499999999979839238 ) ; -#7393 = CARTESIAN_POINT ( 'NONE', ( -13.46279686986694202, 157.6279356061011185, 99.13124279942860539 ) ) ; -#7394 = DIRECTION ( 'NONE', ( 0.0005884949961658158049, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#7395 = CONICAL_SURFACE ( 'NONE', #30266, 2.503203150234936114, 0.7853981633958105890 ) ; -#7396 = EDGE_LOOP ( 'NONE', ( #16236, #6088, #24714, #21593, #27351 ) ) ; -#7397 = CARTESIAN_POINT ( 'NONE', ( 25.50043922912999861, 120.2537800310000193, 89.96303717399999300 ) ) ; -#7398 = CARTESIAN_POINT ( 'NONE', ( -21.21399079302519652, 183.3565551017309190, 102.5100844002234197 ) ) ; -#7399 = EDGE_CURVE ( 'NONE', #2188, #24453, #25639, .T. ) ; -#7401 = EDGE_CURVE ( 'NONE', #19373, #27237, #35188, .T. ) ; -#7400 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31460, #37779, #6493, #16110 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 3.763891609993758226E-05, 0.0006616524122018222496 ), - .UNSPECIFIED. ) ; -#7403 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7071067167008887600, -0.7071068456722005013 ) ) ; -#7402 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858958, 190.9636369981938913, 106.3296296870415887 ) ) ; -#7404 = DIRECTION ( 'NONE', ( 0.0005884949961259158639, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#7405 = ORIENTED_EDGE ( 'NONE', *, *, #19791, .T. ) ; -#7406 = DIRECTION ( 'NONE', ( -0.0001358593331183317757, -0.9743721449820399449, -0.2249420028037008579 ) ) ; -#7407 = EDGE_CURVE ( 'NONE', #3978, #5503, #38282, .T. ) ; -#7408 = CYLINDRICAL_SURFACE ( 'NONE', #27366, 2.000000000000014655 ) ; -#7409 = EDGE_LOOP ( 'NONE', ( #36009, #39462, #8813, #20350 ) ) ; -#7410 = EDGE_LOOP ( 'NONE', ( #6545, #9890, #23902, #28764, #34619 ) ) ; -#7411 = CARTESIAN_POINT ( 'NONE', ( 38.60331107998000277, 119.2723712158999945, 90.41971974563000458 ) ) ; -#7412 = CARTESIAN_POINT ( 'NONE', ( 22.78080448403245839, 154.4094593426142978, 95.28739704982865533 ) ) ; -#7413 = EDGE_CURVE ( 'NONE', #24067, #32727, #10144, .T. ) ; -#7414 = DIRECTION ( 'NONE', ( 0.0005884949961219661154, -0.2249510543439071364, 0.9743698870671262391 ) ) ; -#7415 = CARTESIAN_POINT ( 'NONE', ( -16.26709548037662145, 127.8724464670249148, 174.7626211946546277 ) ) ; -#7416 = VECTOR ( 'NONE', #13942, 1000.000000000000227 ) ; -#7417 = VECTOR ( 'NONE', #30667, 1000.000000000000114 ) ; -#7418 = ORIENTED_EDGE ( 'NONE', *, *, #18855, .F. ) ; -#7419 = ORIENTED_EDGE ( 'NONE', *, *, #23671, .F. ) ; -#7420 = CARTESIAN_POINT ( 'NONE', ( -12.63653284181130410, 177.5932570882007155, 100.8292555457751121 ) ) ; -#7421 = CARTESIAN_POINT ( 'NONE', ( 20.16823359922518932, 160.1106230620535484, 99.51315612356997065 ) ) ; -#7422 = CIRCLE ( 'NONE', #23118, 2.000000001207042466 ) ; -#7423 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#7424 = EDGE_CURVE ( 'NONE', #21974, #802, #24275, .T. ) ; -#7425 = ORIENTED_EDGE ( 'NONE', *, *, #5855, .T. ) ; -#7426 = VECTOR ( 'NONE', #37214, 1000.000000000000114 ) ; -#7427 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#7428 = ORIENTED_EDGE ( 'NONE', *, *, #4982, .T. ) ; -#7429 = CARTESIAN_POINT ( 'NONE', ( 3.069838397726039503, 190.8629629326576946, 106.8006141407937122 ) ) ; -#7430 = ORIENTED_EDGE ( 'NONE', *, *, #39169, .T. ) ; -#7431 = CARTESIAN_POINT ( 'NONE', ( 38.97204648811698036, 118.8228816124465368, 89.67376701884533929 ) ) ; -#7432 = CARTESIAN_POINT ( 'NONE', ( -45.59279413748385679, 146.2345503595622347, 284.1924382399986939 ) ) ; -#7433 = CARTESIAN_POINT ( 'NONE', ( 39.72394661644089098, 108.3778670559899524, 179.2109846985112540 ) ) ; -#7434 = CARTESIAN_POINT ( 'NONE', ( -6.273952178503699351, 163.8304651410298334, 97.99310710002680480 ) ) ; -#7435 = ORIENTED_EDGE ( 'NONE', *, *, #32263, .F. ) ; -#7436 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319386088922 ) ) ; -#7437 = CARTESIAN_POINT ( 'NONE', ( 20.92535880089854672, 213.2684201652496370, 73.04586569002432839 ) ) ; -#7438 = LINE ( 'NONE', #29742, #5129 ) ; -#7439 = VECTOR ( 'NONE', #1470, 1000.000000000000227 ) ; -#7440 = AXIS2_PLACEMENT_3D ( 'NONE', #28575, #6471, #28371 ) ; -#7441 = DIRECTION ( 'NONE', ( -0.0005884949961260158274, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#7442 = ORIENTED_EDGE ( 'NONE', *, *, #42, .F. ) ; -#7443 = CARTESIAN_POINT ( 'NONE', ( 24.53687191662514522, 116.1140267896956999, 89.75313255931047252 ) ) ; -#7444 = EDGE_CURVE ( 'NONE', #27950, #31729, #22763, .T. ) ; -#7445 = CONICAL_SURFACE ( 'NONE', #28373, 4.999999999925270444, 0.7853981634119230337 ) ; -#7446 = EDGE_CURVE ( 'NONE', #18386, #11331, #32600, .T. ) ; -#7447 = CARTESIAN_POINT ( 'NONE', ( -35.39949828460999726, 113.9650867045999973, 90.42993924146999518 ) ) ; -#7448 = ORIENTED_EDGE ( 'NONE', *, *, #28664, .T. ) ; -#7449 = ORIENTED_EDGE ( 'NONE', *, *, #4265, .F. ) ; -#7450 = CARTESIAN_POINT ( 'NONE', ( 19.99976926757112849, 160.7481248081381295, 96.75239270071580222 ) ) ; -#7451 = CARTESIAN_POINT ( 'NONE', ( 28.46284161542680025, 187.5721379928345129, 102.9401731420402939 ) ) ; -#7452 = CARTESIAN_POINT ( 'NONE', ( -43.56994142101562062, 121.4012961811330626, 90.41976514615660676 ) ) ; -#7453 = DIRECTION ( 'NONE', ( -0.0005884949961224831714, 0.2249510543439058596, -0.9743698870671263501 ) ) ; -#7454 = ORIENTED_EDGE ( 'NONE', *, *, #11935, .T. ) ; -#7455 = ORIENTED_EDGE ( 'NONE', *, *, #20665, .T. ) ; -#7456 = FACE_BOUND ( 'NONE', #19879, .T. ) ; -#7457 = ORIENTED_EDGE ( 'NONE', *, *, #22633, .T. ) ; -#7458 = EDGE_LOOP ( 'NONE', ( #20616, #13379, #15426, #31316 ) ) ; -#7459 = CARTESIAN_POINT ( 'NONE', ( 1.948921012460900659, 189.5571036615277762, 105.8967624099965263 ) ) ; -#7460 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555410 ) ) ; -#7461 = ORIENTED_EDGE ( 'NONE', *, *, #31431, .T. ) ; -#7462 = ORIENTED_EDGE ( 'NONE', *, *, #29295, .F. ) ; -#7463 = CARTESIAN_POINT ( 'NONE', ( 16.56091750598266543, 123.0789174470862406, 172.1968364805972271 ) ) ; -#7464 = CARTESIAN_POINT ( 'NONE', ( -13.49823340920320724, 157.6238447846168640, 99.13360705319831823 ) ) ; -#7465 = CARTESIAN_POINT ( 'NONE', ( 37.69036451307999869, 118.9411325438999967, 87.11195371982000779 ) ) ; -#7466 = CARTESIAN_POINT ( 'NONE', ( 36.02746032641000085, 191.4413277058000347, 103.6991758580000038 ) ) ; -#7467 = CARTESIAN_POINT ( 'NONE', ( -36.07211921651516917, 123.3571268225337008, 93.28546566300038023 ) ) ; -#7468 = APPROVAL_PERSON_ORGANIZATION ( #21858, #17932, #31062 ) ; -#7469 = AXIS2_PLACEMENT_3D ( 'NONE', #38185, #20163, #35086 ) ; -#7470 = EDGE_CURVE ( 'NONE', #3379, #12341, #11084, .T. ) ; -#7471 = ORIENTED_EDGE ( 'NONE', *, *, #11819, .F. ) ; -#7472 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; -#7473 = DIRECTION ( 'NONE', ( -0.0006039748319385906776, -1.261220487827980362E-14, -0.9999998176071844824 ) ) ; -#7474 = ORIENTED_EDGE ( 'NONE', *, *, #25927, .F. ) ; -#7475 = AXIS2_PLACEMENT_3D ( 'NONE', #37981, #9982, #6891 ) ; -#7476 = CARTESIAN_POINT ( 'NONE', ( -17.26213291099019997, 152.2612616225560771, 183.6636115490260863 ) ) ; -#7477 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; -#7478 = CARTESIAN_POINT ( 'NONE', ( -25.63990465300122779, 116.6810637759212170, 90.28327069913609648 ) ) ; -#7479 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -7.822507694019387433E-18, -0.0006039748319385908944 ) ) ; -#7480 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #32951, #23771, #39087, #17611 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 2.962146847938709193, 4.533316785306447549 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8046497850432340337, 0.8046497850432340337, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#7481 = ORIENTED_EDGE ( 'NONE', *, *, #8546, .F. ) ; -#7482 = PLANE ( 'NONE', #26566 ) ; -#7483 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#7484 = CARTESIAN_POINT ( 'NONE', ( -23.32500208832000155, 123.2470639583000178, 152.4718672074000381 ) ) ; -#7485 = EDGE_CURVE ( 'NONE', #37703, #28359, #16288, .T. ) ; -#7486 = CARTESIAN_POINT ( 'NONE', ( 15.50147166300774160, 151.4095604232323069, 97.16497154471535680 ) ) ; -#7487 = CARTESIAN_POINT ( 'NONE', ( -25.35581857957999929, 191.7922573250999960, 104.5649157546000083 ) ) ; -#7488 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26149, #10205, #28599, #19166, #13462, #29206, #19970, #4231, #1176, #13657 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999945599, 0.3750000000000179301, 0.4375000000000243139, 0.5000000000000307532, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7489 = FACE_OUTER_BOUND ( 'NONE', #35052, .T. ) ; -#7490 = CARTESIAN_POINT ( 'NONE', ( -3.701323146539070130, 168.4576286693920224, 98.71465524754557919 ) ) ; -#7491 = DIRECTION ( 'NONE', ( -0.6087613186456907188, -0.7730177010543248795, -0.1784749023741044327 ) ) ; -#7492 = EDGE_CURVE ( 'NONE', #23221, #6123, #27431, .T. ) ; -#7493 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #23189, #27083, #39514, #13779, #38913, #29521, #26266 ), - ( #35419, #11315, #38703, #32784, #20720, #23796, #13985 ), - ( #11527, #23590, #7429, #19890, #32396, #26462, #39118 ), - ( #4363, #10929, #17227, #36252, #23393, #35830, #7840 ), - ( #4764, #29731, #8256, #1717, #14200, #11122, #20502 ), - ( #32974, #4973, #24421, #60, #36666, #31149, #3121 ), - ( #37074, #15594, #12331, #11939, #30947, #37271, #33588 ), - ( #5381, #28094, #2327, #15400, #27900, #24002, #36872 ), - ( #21552, #40126, #11734, #36459, #18440, #9070, #8466 ), - ( #21349, #2915, #6188, #8674, #39717, #40326, #21750 ), - ( #24217, #24827, #2528, #5991, #27502, #20928, #12139 ), - ( #33792, #33384, #14998, #24625, #21135, #17833, #5581 ), - ( #18042, #8876, #9272, #34192, #30332, #14806, #27289 ), - ( #30543, #18641, #39929, #15205, #5791, #18245, #30744 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 3, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 3, 4 ), - ( -0.009999999139057998490, -4.027722043288000136E-12, 3.385156030728000000E-06, 0.08333638693828999966, 0.1666693887204999946, 0.3333354752625000139, 0.5000015618047000121, 0.6666676483468999548, 0.8333337348888999463, 0.9999999134989999705 ), - ( 0.1539537836571530649, 0.1754433755481999979, 0.8245457737757000416 ), - .UNSPECIFIED. ) ; -#7494 = CARTESIAN_POINT ( 'NONE', ( -13.50000077688951450, 188.3420892684051751, 103.1432776901117307 ) ) ; -#7495 = CARTESIAN_POINT ( 'NONE', ( -35.69616828627999894, 201.9934155195000187, 90.49994975821999788 ) ) ; -#7496 = EDGE_LOOP ( 'NONE', ( #15446, #10627, #27722, #4438 ) ) ; -#7497 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #40447, #22068 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7498 = CARTESIAN_POINT ( 'NONE', ( 20.48231950984458649, 205.5677633305384120, 76.28703242847967658 ) ) ; -#7499 = EDGE_CURVE ( 'NONE', #22046, #28881, #19469, .T. ) ; -#7500 = EDGE_CURVE ( 'NONE', #39778, #25997, #16401, .T. ) ; -#7501 = VECTOR ( 'NONE', #15262, 1000.000000000000227 ) ; -#7502 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999898748, 179.7376864902705904, 101.1595092802000835 ) ) ; -#7503 = CARTESIAN_POINT ( 'NONE', ( -43.95866919468323886, 185.6592565981171390, 107.3047072462908460 ) ) ; -#7504 = CONICAL_SURFACE ( 'NONE', #30381, 2.500000720456969194, 0.7853981633184845546 ) ; -#7505 = ORIENTED_EDGE ( 'NONE', *, *, #20087, .T. ) ; -#7506 = CARTESIAN_POINT ( 'NONE', ( 16.56199388762211200, 121.7260791789329062, 178.0423311718324157 ) ) ; -#7507 = CARTESIAN_POINT ( 'NONE', ( 46.20652635966656163, 124.8532258200277454, 91.35751384932866870 ) ) ; -#7508 = ADVANCED_FACE ( 'NONE', ( #37887 ), #15796, .T. ) ; -#7509 = CARTESIAN_POINT ( 'NONE', ( 38.02566647473999950, 191.1265785857000026, 106.1815786465000002 ) ) ; -#7510 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#7511 = AXIS2_PLACEMENT_3D ( 'NONE', #9204, #40252, #27626 ) ; -#7512 = CARTESIAN_POINT ( 'NONE', ( -17.26247767858138005, 152.5342161776122225, 182.4800534808789791 ) ) ; -#7513 = CARTESIAN_POINT ( 'NONE', ( 35.94569070589000148, 192.8022039118000066, 106.4463298239000153 ) ) ; -#7514 = ORIENTED_EDGE ( 'NONE', *, *, #11121, .T. ) ; -#7515 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 82.27946979429634666, 315.0857197240630967 ) ) ; -#7516 = CARTESIAN_POINT ( 'NONE', ( 20.16596632773250874, 196.4252918348997525, 103.7971211491498167 ) ) ; -#7517 = CARTESIAN_POINT ( 'NONE', ( 25.51044001015309703, 191.4790671403759745, 106.3785283636754855 ) ) ; -#7518 = ORIENTED_EDGE ( 'NONE', *, *, #32564, .F. ) ; -#7519 = CARTESIAN_POINT ( 'NONE', ( -29.42789445533455961, 116.9990604785378423, 176.9382643005241107 ) ) ; -#7520 = CARTESIAN_POINT ( 'NONE', ( -20.49588002752788185, 118.8155058231674701, 94.28014998164199767 ) ) ; -#7521 = ORIENTED_EDGE ( 'NONE', *, *, #29397, .F. ) ; -#7522 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#7523 = ORIENTED_EDGE ( 'NONE', *, *, #4139, .F. ) ; -#7524 = CARTESIAN_POINT ( 'NONE', ( 36.47845471365634751, 191.6031860892433087, 106.3715631444863448 ) ) ; -#7525 = DIRECTION ( 'NONE', ( -0.0005884931264925925961, 0.2249510545839476794, -0.9743698870128375544 ) ) ; -#7526 = FACE_OUTER_BOUND ( 'NONE', #16659, .T. ) ; -#7527 = CARTESIAN_POINT ( 'NONE', ( 21.68400888405614779, 177.1994660713384349, 100.5495466695472544 ) ) ; -#7528 = CARTESIAN_POINT ( 'NONE', ( 3.668109984895000508, 187.1823278903000016, 105.9440663766999933 ) ) ; -#7529 = ORIENTED_EDGE ( 'NONE', *, *, #39391, .T. ) ; -#7530 = EDGE_LOOP ( 'NONE', ( #19431, #18918, #25330, #11893 ) ) ; -#7531 = CARTESIAN_POINT ( 'NONE', ( -2.937261516931815919, 196.5784392894775010, 103.8768773714908775 ) ) ; -#7532 = CARTESIAN_POINT ( 'NONE', ( 30.06995732875381577, 177.2926437816356042, 100.9961439531841165 ) ) ; -#7533 = AXIS2_PLACEMENT_3D ( 'NONE', #9633, #7152, #37635 ) ; -#7534 = CIRCLE ( 'NONE', #15380, 2.249999999967385644 ) ; -#7535 = CARTESIAN_POINT ( 'NONE', ( 4.502832686075696422, 177.3080769709184210, 100.5849984759426405 ) ) ; -#7536 = VECTOR ( 'NONE', #13214, 999.9999999999998863 ) ; -#7537 = CARTESIAN_POINT ( 'NONE', ( -20.51791727788598152, 205.7357679558956534, 75.91561672826185259 ) ) ; -#7538 = VERTEX_POINT ( 'NONE', #26032 ) ; -#7539 = AXIS2_PLACEMENT_3D ( 'NONE', #20979, #23233, #20348 ) ; -#7540 = ORIENTED_EDGE ( 'NONE', *, *, #24549, .T. ) ; -#7541 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989908600, -0.1373964268091705798 ) ) ; -#7542 = ADVANCED_FACE ( 'NONE', ( #23765 ), #9130, .T. ) ; -#7543 = CARTESIAN_POINT ( 'NONE', ( 37.25545905135366098, 116.8164260177301799, 89.68586038215327960 ) ) ; -#7544 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265225566, -0.1368326740407719844 ) ) ; -#7545 = EDGE_CURVE ( 'NONE', #4372, #37091, #1888, .T. ) ; -#7546 = LINE ( 'NONE', #7746, #22212 ) ; -#7547 = EDGE_CURVE ( 'NONE', #8481, #23937, #35433, .T. ) ; -#7548 = CARTESIAN_POINT ( 'NONE', ( -75.99035305782904004, 156.3451282303881555, 95.79393540400390350 ) ) ; -#7549 = ADVANCED_FACE ( 'NONE', ( #13547 ), #36008, .T. ) ; -#7550 = CARTESIAN_POINT ( 'NONE', ( 0.5441253984803264832, 208.9999999999999716, 73.05817544431644706 ) ) ; -#7551 = CARTESIAN_POINT ( 'NONE', ( 38.16277029721000247, 118.9305731983999976, 90.39763992500999734 ) ) ; -#7552 = VERTEX_POINT ( 'NONE', #11283 ) ; -#7553 = CARTESIAN_POINT ( 'NONE', ( 14.14634404124179134, 124.4291101105236095, 88.37110038241654308 ) ) ; -#7554 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#7555 = CONICAL_SURFACE ( 'NONE', #30438, 5.999999999954156671, 0.7853981634347416696 ) ; -#7556 = FACE_OUTER_BOUND ( 'NONE', #6671, .T. ) ; -#7557 = CARTESIAN_POINT ( 'NONE', ( -34.95638760651606702, 220.4002260771005695, 73.57961695570443794 ) ) ; -#7558 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #13130, #22338, #6769 ), - ( #31745, #29877, #1240 ), - ( #1859, #39056, #38646 ), - ( #23529, #19830, #22740 ) ), - .UNSPECIFIED., .F., .F., .F. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), - ( 3, 3 ), - ( 0.5323285496897337543, 0.5323359952438722065 ), - ( 0.3705134913875697822, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 0.8839414210850555786, 0.8433814400653724119, 1.000000000000000000), - ( 0.8839429408946146705, 0.8433834910157350651, 1.000000000000000000), - ( 0.8839444606899004020, 0.8433855419468362369, 1.000000000000000000), - ( 0.8839459804709337565, 0.8433875928587041271, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#7559 = AXIS2_PLACEMENT_3D ( 'NONE', #23774, #11500, #8648 ) ; -#7560 = CARTESIAN_POINT ( 'NONE', ( -39.68966504267002193, 159.7604226669166110, 205.3090077686758832 ) ) ; -#7561 = AXIS2_PLACEMENT_3D ( 'NONE', #7700, #3823, #765 ) ; -#7562 = ORIENTED_EDGE ( 'NONE', *, *, #39994, .F. ) ; -#7563 = VERTEX_POINT ( 'NONE', #4940 ) ; -#7564 = ORIENTED_EDGE ( 'NONE', *, *, #12494, .F. ) ; -#7565 = LINE ( 'NONE', #13711, #24225 ) ; -#7566 = VECTOR ( 'NONE', #26691, 1000.000000000000227 ) ; -#7567 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#7568 = CARTESIAN_POINT ( 'NONE', ( -6.031620047117566052, 177.7903949882438042, 100.7027583919079063 ) ) ; -#7569 = VECTOR ( 'NONE', #21944, 999.9999999999998863 ) ; -#7570 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12193, #12379, #30391, #15258 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.002377699347871517228 ), - .UNSPECIFIED. ) ; -#7571 = ORIENTED_EDGE ( 'NONE', *, *, #33080, .T. ) ; -#7572 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#7573 = EDGE_CURVE ( 'NONE', #33368, #27991, #37435, .T. ) ; -#7574 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#7575 = CARTESIAN_POINT ( 'NONE', ( -39.25194077172999840, 120.2741315228000047, 87.44405325520000360 ) ) ; -#7576 = CARTESIAN_POINT ( 'NONE', ( -35.30228731257000163, 112.8193765062000011, 87.14170685835999564 ) ) ; -#7577 = ORIENTED_EDGE ( 'NONE', *, *, #24220, .F. ) ; -#7578 = CARTESIAN_POINT ( 'NONE', ( 19.41633238111709758, 148.7715877831155069, 183.2842058909355387 ) ) ; -#7579 = ORIENTED_EDGE ( 'NONE', *, *, #8352, .F. ) ; -#7580 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#7581 = CARTESIAN_POINT ( 'NONE', ( -20.51745969899640087, 207.4083551867479116, 77.09396086730279762 ) ) ; -#7582 = CARTESIAN_POINT ( 'NONE', ( -38.93740081958814159, 183.0561992808241882, 105.0172067937131999 ) ) ; -#7583 = CARTESIAN_POINT ( 'NONE', ( -39.73451189162042141, 125.2083021951255262, 106.5273060498917488 ) ) ; -#7584 = DIRECTION ( 'NONE', ( 0.0005884949961206773243, -0.2249510543439054433, 0.9743698870671265722 ) ) ; -#7585 = ORIENTED_EDGE ( 'NONE', *, *, #19775, .F. ) ; -#7586 = CARTESIAN_POINT ( 'NONE', ( -1.024403596856999998, 188.7904093113999977, 103.3726356948999978 ) ) ; -#7587 = CARTESIAN_POINT ( 'NONE', ( 3.666638755385807080, 126.6906504152049706, 89.41269982467663624 ) ) ; -#7588 = CARTESIAN_POINT ( 'NONE', ( -42.84985459258451357, 114.0190886146663587, 121.9014590159802509 ) ) ; -#7589 = DIRECTION ( 'NONE', ( 0.0005884949961239980187, -0.2249510543439088572, 0.9743698870671256840 ) ) ; -#7590 = ADVANCED_FACE ( 'NONE', ( #23552 ), #32164, .F. ) ; -#7591 = AXIS2_PLACEMENT_3D ( 'NONE', #12770, #18880, #33629 ) ; -#7592 = VERTEX_POINT ( 'NONE', #13953 ) ; -#7593 = CARTESIAN_POINT ( 'NONE', ( -6.273363704495623416, 148.4283476285271774, 95.46355138143680108 ) ) ; -#7594 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#7595 = AXIS2_PLACEMENT_3D ( 'NONE', #37994, #10000, #13464 ) ; -#7596 = ORIENTED_EDGE ( 'NONE', *, *, #9028, .F. ) ; -#7597 = AXIS2_PLACEMENT_3D ( 'NONE', #40189, #34248, #28543 ) ; -#7598 = ADVANCED_FACE ( 'NONE', ( #17197 ), #40424, .T. ) ; -#7599 = CIRCLE ( 'NONE', #8945, 6.000000000000001776 ) ; -#7600 = EDGE_CURVE ( 'NONE', #15042, #14325, #18867, .T. ) ; -#7601 = ORIENTED_EDGE ( 'NONE', *, *, #25524, .F. ) ; -#7602 = ORIENTED_EDGE ( 'NONE', *, *, #28574, .T. ) ; -#7603 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000092726, 177.0629346109330982, 100.5202509414855712 ) ) ; -#7604 = DIRECTION ( 'NONE', ( 0.0005884949961244984864, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#7605 = ADVANCED_FACE ( 'NONE', ( #4526 ), #24136, .T. ) ; -#7606 = ORIENTED_EDGE ( 'NONE', *, *, #7125, .T. ) ; -#7607 = CARTESIAN_POINT ( 'NONE', ( 25.99876818124551292, 118.1164810761916470, 87.25208046938912787 ) ) ; -#7608 = VERTEX_POINT ( 'NONE', #1064 ) ; -#7609 = CARTESIAN_POINT ( 'NONE', ( 25.99935010583338268, 120.0781821002242111, 90.41881030976217914 ) ) ; -#7610 = CARTESIAN_POINT ( 'NONE', ( -16.11981483123442871, 151.5072451358702210, 180.2250316836006050 ) ) ; -#7612 = LINE ( 'NONE', #32562, #33802 ) ; -#7611 = CARTESIAN_POINT ( 'NONE', ( -53.43553862205013871, 4.776739081468993398, 161.2530495364081560 ) ) ; -#7613 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4617, #26515, #10975, #35885, #32831, #4812, #17278, #29787, #17484, #17885, #34233, #39769, #2779, #3162, #21796, #39979 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 1, 2, 2, 1, 2, 4 ), - ( 0.000000000000000000, 0.2080649981249293456, 0.2600812476561621955, 0.3120974971873950454, 0.4161299962498555827, 0.5201624953123160644, 0.6241949943747765461, 0.7282274934372370279, 0.8322599924996976206 ), - .UNSPECIFIED. ) ; -#7614 = LINE ( 'NONE', #26245, #7250 ) ; -#7615 = ORIENTED_EDGE ( 'NONE', *, *, #24892, .F. ) ; -#7616 = AXIS2_PLACEMENT_3D ( 'NONE', #35014, #10714, #7022 ) ; -#7617 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 82.27946979429611929, 297.5967072516833127 ) ) ; -#7618 = AXIS2_PLACEMENT_3D ( 'NONE', #20127, #1327, #7869 ) ; -#7619 = AXIS2_PLACEMENT_3D ( 'NONE', #7149, #9435, #22515 ) ; -#7620 = ORIENTED_EDGE ( 'NONE', *, *, #12234, .T. ) ; -#7621 = CARTESIAN_POINT ( 'NONE', ( 38.70841052475000055, 119.0653296949000151, 90.11979583391000403 ) ) ; -#7622 = CARTESIAN_POINT ( 'NONE', ( -35.95198627950571790, 115.8887714456496383, 87.28949839086233453 ) ) ; -#7623 = CARTESIAN_POINT ( 'NONE', ( -45.57969790969411861, 124.0544719173705772, 91.68157259218224908 ) ) ; -#7624 = CARTESIAN_POINT ( 'NONE', ( 37.65057158750833821, 122.6594394773597969, 91.02725657039249541 ) ) ; -#7625 = CONICAL_SURFACE ( 'NONE', #29191, 2.499997363466079037, 0.7853981633710050980 ) ; -#7626 = ORIENTED_EDGE ( 'NONE', *, *, #5244, .T. ) ; -#7627 = ORIENTED_EDGE ( 'NONE', *, *, #38022, .F. ) ; -#7628 = DIRECTION ( 'NONE', ( 0.0005884949961245230978, -0.2249510543439041388, 0.9743698870671267942 ) ) ; -#7629 = VERTEX_POINT ( 'NONE', #17402 ) ; -#7630 = CARTESIAN_POINT ( 'NONE', ( -35.42916843553630457, 192.6084977412129717, 106.9123174018029943 ) ) ; -#7632 = EDGE_CURVE ( 'NONE', #27492, #11405, #20189, .T. ) ; -#7631 = CARTESIAN_POINT ( 'NONE', ( -38.03218355952305529, 118.0144299118464630, 89.71435174365882403 ) ) ; -#7633 = ADVANCED_FACE ( 'NONE', ( #20066 ), #35797, .T. ) ; -#7634 = EDGE_CURVE ( 'NONE', #27521, #9326, #24819, .T. ) ; -#7635 = ADVANCED_FACE ( 'NONE', ( #7805 ), #18873, .F. ) ; -#7636 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#7637 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4367, #30135, #26879, #5171 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7638 = ORIENTED_EDGE ( 'NONE', *, *, #24110, .F. ) ; -#7639 = CARTESIAN_POINT ( 'NONE', ( -43.13843726988963567, 112.6550928102931834, 129.5909698073101595 ) ) ; -#7640 = FACE_OUTER_BOUND ( 'NONE', #2939, .T. ) ; -#7641 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#7642 = CARTESIAN_POINT ( 'NONE', ( -3.668404234652287155, 128.0226348370951541, 91.77725148381138354 ) ) ; -#7643 = ADVANCED_FACE ( 'NONE', ( #32554 ), #29699, .F. ) ; -#7644 = AXIS2_PLACEMENT_3D ( 'NONE', #27684, #3304, #18431 ) ; -#7645 = ORIENTED_EDGE ( 'NONE', *, *, #2452, .F. ) ; -#7646 = LINE ( 'NONE', #38921, #8192 ) ; -#7647 = CARTESIAN_POINT ( 'NONE', ( -22.49970497326182439, 151.8550686446309896, 95.23816841905139086 ) ) ; -#7648 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5219, #34387, #25419, #6575 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7649 = AXIS2_PLACEMENT_3D ( 'NONE', #15220, #21767, #31565 ) ; -#7650 = CARTESIAN_POINT ( 'NONE', ( 30.31510154549722458, 127.1681252649556626, 89.16473717014450528 ) ) ; -#7651 = EDGE_CURVE ( 'NONE', #32876, #9290, #9630, .T. ) ; -#7652 = VERTEX_POINT ( 'NONE', #2096 ) ; -#7653 = DIRECTION ( 'NONE', ( 0.0001408404346094399215, -0.2255194953558362636, 0.9742386449830560124 ) ) ; -#7655 = CARTESIAN_POINT ( 'NONE', ( -36.08362193231000248, 112.3719106449999998, 89.65513700520000384 ) ) ; -#7654 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7826081015363517412, 0.6225147061794341630 ) ) ; -#7656 = ORIENTED_EDGE ( 'NONE', *, *, #38076, .T. ) ; -#7657 = ORIENTED_EDGE ( 'NONE', *, *, #35527, .F. ) ; -#7658 = CARTESIAN_POINT ( 'NONE', ( -13.49852954174844299, 137.6306192790454475, 94.00136703131360605 ) ) ; -#7659 = DIRECTION ( 'NONE', ( -0.6087614115774629964, -0.7729348350621531027, -0.1788331191967996447 ) ) ; -#7660 = CARTESIAN_POINT ( 'NONE', ( 15.05621097247296980, 125.1021127306558043, 171.3704188677303648 ) ) ; -#7661 = DIRECTION ( 'NONE', ( 0.7855032201832807814, -0.6188575693014479739, 0.000000000000000000 ) ) ; -#7662 = LINE ( 'NONE', #25904, #14264 ) ; -#7663 = ORIENTED_EDGE ( 'NONE', *, *, #15145, .F. ) ; -#7664 = VERTEX_POINT ( 'NONE', #2498 ) ; -#7665 = PLANE ( 'NONE', #38929 ) ; -#7666 = VERTEX_POINT ( 'NONE', #17603 ) ; -#7667 = ORIENTED_EDGE ( 'NONE', *, *, #37429, .T. ) ; -#7668 = ORIENTED_EDGE ( 'NONE', *, *, #2345, .F. ) ; -#7669 = DIRECTION ( 'NONE', ( 0.7933532970003738249, 0.5930762008556724751, 0.1372995488602876402 ) ) ; -#7670 = CYLINDRICAL_SURFACE ( 'NONE', #21109, 2.000000000000014655 ) ; -#7671 = CARTESIAN_POINT ( 'NONE', ( 30.44722896069117724, 127.1067747388918434, 88.97944275832713856 ) ) ; -#7672 = VECTOR ( 'NONE', #11265, 1000.000000000000114 ) ; -#7673 = VERTEX_POINT ( 'NONE', #37236 ) ; -#7674 = DIRECTION ( 'NONE', ( -0.0005884949961227338390, 0.2249510543439056653, -0.9743698870671265722 ) ) ; -#7675 = CARTESIAN_POINT ( 'NONE', ( 38.08087559214000350, 118.5847423712999955, 87.56841820341999494 ) ) ; -#7676 = CARTESIAN_POINT ( 'NONE', ( 25.66664312785736968, 120.1441062793254417, 90.08149356691757248 ) ) ; -#7677 = CARTESIAN_POINT ( 'NONE', ( -43.56994142101562062, 121.4012961811330626, 90.41976514615660676 ) ) ; -#7678 = CONICAL_SURFACE ( 'NONE', #27946, 9.999999999987785770, 0.7853981633973015075 ) ; -#7679 = ORIENTED_EDGE ( 'NONE', *, *, #38160, .T. ) ; -#7680 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#7681 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921572969, -0.2249510932971622301 ) ) ; -#7682 = DIRECTION ( 'NONE', ( 0.0006039748319371906473, -0.000000000000000000, 0.9999998176071844824 ) ) ; -#7683 = VERTEX_POINT ( 'NONE', #5954 ) ; -#7684 = CARTESIAN_POINT ( 'NONE', ( 0.5796509708708875719, 188.6024196665420050, 103.1948729230731061 ) ) ; -#7685 = LINE ( 'NONE', #38558, #27995 ) ; -#7686 = EDGE_CURVE ( 'NONE', #31634, #22903, #12102, .T. ) ; -#7687 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7010, #1483, #19483, #13760 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7688 = EDGE_CURVE ( 'NONE', #6603, #39904, #3873, .T. ) ; -#7689 = CARTESIAN_POINT ( 'NONE', ( -6.168135754641124180, 163.2166086438842001, 100.0749825304044265 ) ) ; -#7690 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971582333 ) ) ; -#7691 = ORIENTED_EDGE ( 'NONE', *, *, #40085, .F. ) ; -#7692 = LINE ( 'NONE', #16687, #4996 ) ; -#7693 = CARTESIAN_POINT ( 'NONE', ( 2.230626752277192537, 189.8962178526613798, 103.9420327300870213 ) ) ; -#7694 = CYLINDRICAL_SURFACE ( 'NONE', #20182, 5.000000000000007994 ) ; -#7695 = LINE ( 'NONE', #7486, #19043 ) ; -#7696 = ORIENTED_EDGE ( 'NONE', *, *, #29821, .T. ) ; -#7697 = CARTESIAN_POINT ( 'NONE', ( -25.67549068909692522, 191.4258646064230902, 104.2046749456761603 ) ) ; -#7698 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971553745 ) ) ; -#7699 = CARTESIAN_POINT ( 'NONE', ( 38.02735593688370130, 118.5964293117260695, 87.52753786365937572 ) ) ; -#7700 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364692610378, 136.5649596138845538, 181.4686487119390961 ) ) ; -#7701 = EDGE_LOOP ( 'NONE', ( #32677, #26430, #24395, #34821 ) ) ; -#7702 = VECTOR ( 'NONE', #34187, 1000.000000000000227 ) ; -#7703 = CIRCLE ( 'NONE', #39696, 6.000000000000007994 ) ; -#7704 = PLANE ( 'NONE', #29185 ) ; -#7705 = EDGE_CURVE ( 'NONE', #14883, #25194, #30909, .T. ) ; -#7706 = DIRECTION ( 'NONE', ( -0.6087611434179115433, 0.7728348325624405657, 0.1792657018023848803 ) ) ; -#7707 = FACE_OUTER_BOUND ( 'NONE', #16882, .T. ) ; -#7708 = FACE_OUTER_BOUND ( 'NONE', #8852, .T. ) ; -#7709 = CARTESIAN_POINT ( 'NONE', ( 36.48199150421999803, 190.6222350763999884, 106.8659481697000047 ) ) ; -#7710 = CARTESIAN_POINT ( 'NONE', ( 18.27501454559784122, 126.3924864382006632, 174.4075621399051101 ) ) ; -#7711 = CARTESIAN_POINT ( 'NONE', ( -25.50804057823069471, 190.9260211217805363, 106.3128357153982648 ) ) ; -#7712 = CARTESIAN_POINT ( 'NONE', ( 25.99332206926874278, 209.7096538831000032, 78.04280567916214295 ) ) ; -#7713 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178587041921E-05, 0.0002331579774917524482 ) ) ; -#7714 = VERTEX_POINT ( 'NONE', #21310 ) ; -#7715 = CARTESIAN_POINT ( 'NONE', ( 42.10159726138748226, 77.14301703112127484, 276.8136732519894849 ) ) ; -#7716 = CARTESIAN_POINT ( 'NONE', ( 37.17804754624985719, 145.4524169400428946, 280.9300640675564864 ) ) ; -#7717 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#7718 = VERTEX_POINT ( 'NONE', #8437 ) ; -#7719 = FACE_OUTER_BOUND ( 'NONE', #2208, .T. ) ; -#7720 = ORIENTED_EDGE ( 'NONE', *, *, #32167, .T. ) ; -#7721 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25917, #22244, #10173, #22837 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.570060973614779032, 2.960051731740213743 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8453711073098807427, 0.8453711073098807427, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#7722 = AXIS2_PLACEMENT_3D ( 'NONE', #25606, #3697, #32330 ) ; -#7723 = DIRECTION ( 'NONE', ( -1.447458112927613770E-19, -1.000000000000000000, 1.271205603797056623E-14 ) ) ; -#7724 = DIRECTION ( 'NONE', ( -0.0005734119072328723934, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#7725 = ORIENTED_EDGE ( 'NONE', *, *, #28897, .T. ) ; -#7726 = CARTESIAN_POINT ( 'NONE', ( 36.56395785382211727, 191.5078140368809727, 106.3610736895479789 ) ) ; -#7727 = AXIS2_PLACEMENT_3D ( 'NONE', #24113, #1610, #4674 ) ; -#7728 = CARTESIAN_POINT ( 'NONE', ( 3.544766722543614357, 167.8297556397829453, 101.4672138571396687 ) ) ; -#7729 = CIRCLE ( 'NONE', #10441, 2.000000000000011546 ) ; -#7730 = CARTESIAN_POINT ( 'NONE', ( 25.99876818124551292, 118.1164810761916470, 87.25208046938912787 ) ) ; -#7731 = CARTESIAN_POINT ( 'NONE', ( -13.50000254103607134, 126.8013067660671567, 88.93239042800610150 ) ) ; -#7732 = EDGE_CURVE ( 'NONE', #38732, #24067, #15365, .T. ) ; -#7733 = EDGE_CURVE ( 'NONE', #1631, #10082, #12356, .T. ) ; -#7734 = DIRECTION ( 'NONE', ( 0.6087614109020721420, 0.7729348355671186166, 0.1788331193133692876 ) ) ; -#7735 = LINE ( 'NONE', #4461, #33436 ) ; -#7736 = ORIENTED_EDGE ( 'NONE', *, *, #20732, .F. ) ; -#7737 = CARTESIAN_POINT ( 'NONE', ( 15.50029468041106817, 151.8594625358016401, 95.21623178145287625 ) ) ; -#7738 = PLANE ( 'NONE', #16226 ) ; -#7739 = ADVANCED_FACE ( 'NONE', ( #24787 ), #39890, .T. ) ; -#7740 = FACE_OUTER_BOUND ( 'NONE', #16224, .T. ) ; -#7741 = VERTEX_POINT ( 'NONE', #40291 ) ; -#7742 = CARTESIAN_POINT ( 'NONE', ( 23.35827205255252892, 181.8168341326200448, 101.7856298503688492 ) ) ; -#7743 = FACE_OUTER_BOUND ( 'NONE', #16795, .T. ) ; -#7744 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.387778780778639066E-14 ) ) ; -#7745 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250105753, 132.8554482850478848, 90.84904174526991483 ) ) ; -#7746 = CARTESIAN_POINT ( 'NONE', ( 5.704625823861016798, 115.9590670288128393, 152.9217693071938982 ) ) ; -#7747 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971555410 ) ) ; -#7748 = VECTOR ( 'NONE', #13627, 1000.000000000000114 ) ; -#7749 = DIRECTION ( 'NONE', ( 0.0005884949961239352434, -0.2249510543439079413, 0.9743698870671259060 ) ) ; -#7750 = CARTESIAN_POINT ( 'NONE', ( 38.78370429339999959, 119.1138702176999971, 90.11952439853000385 ) ) ; -#7751 = EDGE_LOOP ( 'NONE', ( #21564, #32349, #3691, #30380 ) ) ; -#7752 = CARTESIAN_POINT ( 'NONE', ( 15.03079896862295861, 124.8517197123057088, 88.46813332591423773 ) ) ; -#7753 = DIRECTION ( 'NONE', ( -0.0005884949961181157882, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#7754 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552357 ) ) ; -#7755 = CONICAL_SURFACE ( 'NONE', #34530, 4.999999999914826354, 0.7853981634347277918 ) ; -#7756 = CARTESIAN_POINT ( 'NONE', ( -27.08876248542915377, 119.4912842839333535, 171.3567424277059956 ) ) ; -#7757 = CARTESIAN_POINT ( 'NONE', ( -28.46728868142984226, 182.0597503807817645, 102.2150741964074143 ) ) ; -#7758 = AXIS2_PLACEMENT_3D ( 'NONE', #26282, #23602, #7653 ) ; -#7759 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #6282, #19148 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7760 = VECTOR ( 'NONE', #34199, 1000.000000000000000 ) ; -#7761 = CARTESIAN_POINT ( 'NONE', ( -14.78422084203157461, 175.4439834284964945, 102.7320481277236013 ) ) ; -#7762 = VERTEX_POINT ( 'NONE', #5545 ) ; -#7763 = ORIENTED_EDGE ( 'NONE', *, *, #1455, .T. ) ; -#7764 = ORIENTED_EDGE ( 'NONE', *, *, #35081, .T. ) ; -#7765 = CARTESIAN_POINT ( 'NONE', ( -13.50102315917679974, 124.6787954048031679, 88.87557530041469533 ) ) ; -#7766 = EDGE_CURVE ( 'NONE', #39651, #34711, #30100, .T. ) ; -#7767 = CARTESIAN_POINT ( 'NONE', ( 15.83475876442500940, 160.0983460365729059, 99.51258769526648962 ) ) ; -#7768 = ORIENTED_EDGE ( 'NONE', *, *, #36654, .T. ) ; -#7769 = CARTESIAN_POINT ( 'NONE', ( 16.16445611541705674, 122.9245094293323888, 174.2137880000448718 ) ) ; -#7770 = EDGE_CURVE ( 'NONE', #32422, #31750, #2704, .T. ) ; -#7771 = CARTESIAN_POINT ( 'NONE', ( -29.78153364950144422, 126.4887807563219440, 91.43890500524419451 ) ) ; -#7772 = CARTESIAN_POINT ( 'NONE', ( -38.00362794936000199, 118.6130157638999947, 87.61697703909000268 ) ) ; -#7773 = ORIENTED_EDGE ( 'NONE', *, *, #39907, .F. ) ; -#7774 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18, #18794, #412, #6738 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7775 = CARTESIAN_POINT ( 'NONE', ( 17.00047812746359810, 137.4649845012766889, 177.5753949225429551 ) ) ; -#7776 = VERTEX_POINT ( 'NONE', #21100 ) ; -#7777 = CARTESIAN_POINT ( 'NONE', ( 5.664848030825724301, 124.6188265068983441, 88.76455461985773354 ) ) ; -#7778 = CARTESIAN_POINT ( 'NONE', ( -32.82620923289504589, 141.9145509277669532, 282.5750060058261965 ) ) ; -#7779 = ADVANCED_FACE ( 'NONE', ( #27654 ), #27049, .T. ) ; -#7780 = EDGE_CURVE ( 'NONE', #23353, #39699, #16939, .T. ) ; -#7781 = CYLINDRICAL_SURFACE ( 'NONE', #32628, 2.000000000000014655 ) ; -#7782 = LINE ( 'NONE', #7583, #28817 ) ; -#7783 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#7784 = ADVANCED_FACE ( 'NONE', ( #37041 ), #647, .F. ) ; -#7785 = ORIENTED_EDGE ( 'NONE', *, *, #4941, .T. ) ; -#7786 = AXIS2_PLACEMENT_3D ( 'NONE', #33740, #32925, #39264 ) ; -#7787 = CARTESIAN_POINT ( 'NONE', ( -19.99999816303952471, 191.5261162992163690, 103.8822987450886046 ) ) ; -#7788 = EDGE_CURVE ( 'NONE', #26229, #37821, #31066, .T. ) ; -#7789 = CARTESIAN_POINT ( 'NONE', ( 37.43095215650283336, 132.6072067203139966, 336.9709689194860402 ) ) ; -#7790 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#7791 = CARTESIAN_POINT ( 'NONE', ( -35.63072100744419402, 191.7838021594926659, 106.9393198751362064 ) ) ; -#7792 = CIRCLE ( 'NONE', #39103, 5.999999999973051779 ) ; -#7793 = AXIS2_PLACEMENT_3D ( 'NONE', #12258, #37200, #15321 ) ; -#7794 = ORIENTED_EDGE ( 'NONE', *, *, #27298, .F. ) ; -#7795 = CARTESIAN_POINT ( 'NONE', ( 17.30417074659255761, 152.9391053872499526, 180.9092052391793004 ) ) ; -#7796 = CARTESIAN_POINT ( 'NONE', ( -25.50006458888940131, 118.8155663869242886, 89.78318340809063614 ) ) ; -#7797 = ORIENTED_EDGE ( 'NONE', *, *, #1013, .T. ) ; -#7798 = ORIENTED_EDGE ( 'NONE', *, *, #3716, .T. ) ; -#7799 = VECTOR ( 'NONE', #34983, 1000.000000000000114 ) ; -#7800 = ORIENTED_EDGE ( 'NONE', *, *, #4537, .F. ) ; -#7801 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1439, #10664, #38256, #16769 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7802 = CARTESIAN_POINT ( 'NONE', ( -21.87345861519190038, 193.2440397361608859, 28.36825712722428605 ) ) ; -#7803 = ORIENTED_EDGE ( 'NONE', *, *, #5449, .F. ) ; -#7804 = CARTESIAN_POINT ( 'NONE', ( -27.86528758660999827, 186.6966694207999922, 105.3378367195000038 ) ) ; -#7805 = FACE_OUTER_BOUND ( 'NONE', #30030, .T. ) ; -#7806 = EDGE_CURVE ( 'NONE', #12963, #32994, #27259, .T. ) ; -#7807 = CARTESIAN_POINT ( 'NONE', ( 5.666470275070000895, 124.7419549469727542, 88.96160009636332688 ) ) ; -#7808 = ORIENTED_EDGE ( 'NONE', *, *, #1352, .T. ) ; -#7809 = CARTESIAN_POINT ( 'NONE', ( 26.00355954743800879, 120.0650824375095453, 90.41110813385893152 ) ) ; -#7810 = CARTESIAN_POINT ( 'NONE', ( -5.669876885668252875, 128.5855644063385057, 89.33958911438577388 ) ) ; -#7811 = DIRECTION ( 'NONE', ( 0.0005884949961199882054, -0.2249510543439090515, 0.9743698870671257950 ) ) ; -#7812 = ORIENTED_EDGE ( 'NONE', *, *, #25040, .F. ) ; -#7813 = AXIS2_PLACEMENT_3D ( 'NONE', #31231, #12423, #37563 ) ; -#7814 = CONICAL_SURFACE ( 'NONE', #18929, 2.499987184277071339, 0.7853981634084753471 ) ; -#7815 = ORIENTED_EDGE ( 'NONE', *, *, #24566, .F. ) ; -#7816 = EDGE_CURVE ( 'NONE', #23591, #19822, #6709, .T. ) ; -#7817 = AXIS2_PLACEMENT_3D ( 'NONE', #27294, #8883, #24224 ) ; -#7818 = AXIS2_PLACEMENT_3D ( 'NONE', #18444, #36876, #27903 ) ; -#7819 = CONICAL_SURFACE ( 'NONE', #30708, 30.49999999998559730, 0.7853981633973063925 ) ; -#7820 = ORIENTED_EDGE ( 'NONE', *, *, #15900, .T. ) ; -#7821 = CARTESIAN_POINT ( 'NONE', ( -3.168113297478124313, 183.4473166593645033, 105.0858980959790188 ) ) ; -#7822 = EDGE_CURVE ( 'NONE', #2849, #18222, #31914, .T. ) ; -#7823 = CARTESIAN_POINT ( 'NONE', ( 5.669143597388600853, 187.3556546440009356, 105.5526921997536078 ) ) ; -#7824 = CARTESIAN_POINT ( 'NONE', ( 30.07038983360635243, 134.2444639735435317, 93.70962392686422504 ) ) ; -#7825 = EDGE_CURVE ( 'NONE', #15218, #30145, #4755, .T. ) ; -#7826 = VERTEX_POINT ( 'NONE', #22312 ) ; -#7827 = VERTEX_POINT ( 'NONE', #21909 ) ; -#7828 = DIRECTION ( 'NONE', ( 0.0005734119072318730843, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#7829 = EDGE_CURVE ( 'NONE', #18693, #8704, #13102, .T. ) ; -#7830 = EDGE_CURVE ( 'NONE', #36424, #22426, #22514, .T. ) ; -#7831 = ORIENTED_EDGE ( 'NONE', *, *, #29687, .T. ) ; -#7832 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #34102, #9383, #11851, #18551 ), - ( #3026, #15512, #36777, #15119 ), - ( #12636, #30657, #9581, #28002 ), - ( #2655, #12438, #21854, #34298 ), - ( #17875, #14642, #20545, #1964 ), - ( #18081, #21174, #20757, #39759 ), - ( #14432, #4802, #14232, #24464 ), - ( #24261, #36703, #11978, #33631 ), - ( #11351, #20971, #36913, #39154 ), - ( #11775, #5629, #26708, #15041 ), - ( #27545, #5009, #8085, #8716 ), - ( #11163, #30372, #8920, #30172 ), - ( #17263, #29966, #2168, #2573 ), - ( #5206, #39970, #27125, #32821 ), - ( #36296, #17677, #39561, #26916 ), - ( #11570, #23837, #24042, #8295 ), - ( #33214, #36500, #33426, #33018 ), - ( #29774, #23634, #36083, #8506 ), - ( #2372, #5419, #17471, #1753 ), - ( #39348, #14846, #27330, #30584 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -7.662039796166000266E-06, 0.001947477951146999895, 0.003902617942089999913, 0.007809034349275999903, 0.01562186716364999915, 0.02343469997802000160, 0.03124753279240000126, 0.04687319842115000162, 0.06249886404991000094, 0.09375019530740000273, 0.1250015265648999896, 0.1875041890797999877, 0.2500068515948999925, 0.3750091000290999843, 0.5000113484632999761, 0.7500158453317999907, 1.000000000000000000, 1.192566656214000043 ), - ( 6.650148147435999969E-07, 1.000000500385000102 ), - .UNSPECIFIED. ) ; -#7833 = CARTESIAN_POINT ( 'NONE', ( 30.06878009202964463, 135.2977368468020813, 91.38385643107594092 ) ) ; -#7834 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1803, #17922, #20599, #36549, #5053, #7929, #39605, #32864, #17311, #11617, #14278 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000902611, 0.3750000000001291744, 0.4375000000001486034, 0.4687500000001207923, 0.5000000000000929257, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7835 = CARTESIAN_POINT ( 'NONE', ( -38.26543874032973491, 118.2653806693816136, 89.71123565515037512 ) ) ; -#7836 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36457, #33586, #18036, #30542 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7837 = ORIENTED_EDGE ( 'NONE', *, *, #15273, .T. ) ; -#7838 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#7839 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27571, #20582, #21419, #36731 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0003943868672497987098, 0.0003970494017626595581 ), - .UNSPECIFIED. ) ; -#7840 = CARTESIAN_POINT ( 'NONE', ( 2.563981084831000068, 190.9709217690999878, 106.3045548138999976 ) ) ; -#7841 = VERTEX_POINT ( 'NONE', #25784 ) ; -#7842 = CARTESIAN_POINT ( 'NONE', ( 37.28562273015844397, 178.8217641854361091, 136.8524436601264540 ) ) ; -#7843 = AXIS2_PLACEMENT_3D ( 'NONE', #19503, #13584, #35228 ) ; -#7844 = LINE ( 'NONE', #20101, #8193 ) ; -#7845 = CARTESIAN_POINT ( 'NONE', ( 20.30299311939850071, 153.1411371379373918, 94.99607687304013837 ) ) ; -#7846 = CARTESIAN_POINT ( 'NONE', ( 32.43759465430078137, 141.7182063835813324, 280.9329271823174281 ) ) ; -#7847 = CONICAL_SURFACE ( 'NONE', #11102, 5.999999999898423475, 0.7853981633778843729 ) ; -#7848 = ORIENTED_EDGE ( 'NONE', *, *, #15721, .F. ) ; -#7849 = CIRCLE ( 'NONE', #10472, 4.499999999986576960 ) ; -#7850 = CARTESIAN_POINT ( 'NONE', ( 4.034499241909815126, 137.2431130921461886, 91.84870606007839910 ) ) ; -#7851 = LINE ( 'NONE', #1725, #4489 ) ; -#7852 = VERTEX_POINT ( 'NONE', #34536 ) ; -#7853 = CARTESIAN_POINT ( 'NONE', ( -30.04055490880000079, 165.2216646563843199, 152.9217693939943388 ) ) ; -#7855 = CARTESIAN_POINT ( 'NONE', ( -36.18897578704999773, 114.9859802024000004, 89.88506924981000168 ) ) ; -#7854 = DIRECTION ( 'NONE', ( 0.6087614109020721420, 0.7729348355671186166, 0.1788331193133692876 ) ) ; -#7856 = VERTEX_POINT ( 'NONE', #15748 ) ; -#7857 = FACE_OUTER_BOUND ( 'NONE', #4539, .T. ) ; -#7858 = EDGE_LOOP ( 'NONE', ( #36397, #16271, #4409, #24044 ) ) ; -#7859 = ADVANCED_FACE ( 'NONE', ( #34348 ), #20215, .F. ) ; -#7860 = CARTESIAN_POINT ( 'NONE', ( 16.16550992384005170, 152.4595644213394223, 178.9888250856261607 ) ) ; -#7861 = EDGE_CURVE ( 'NONE', #19286, #7358, #1281, .T. ) ; -#7862 = DIRECTION ( 'NONE', ( -0.0005884949961216158097, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#7863 = CARTESIAN_POINT ( 'NONE', ( 0.04578642046451000119, 211.2500000000000000, 75.80847693012999855 ) ) ; -#7864 = ADVANCED_FACE ( 'NONE', ( #16158 ), #28052, .F. ) ; -#7865 = CARTESIAN_POINT ( 'NONE', ( 36.40558664052492333, 191.8188463803718093, 104.3612499972096117 ) ) ; -#7866 = ORIENTED_EDGE ( 'NONE', *, *, #28623, .F. ) ; -#7867 = EDGE_CURVE ( 'NONE', #23412, #36516, #34155, .T. ) ; -#7868 = ORIENTED_EDGE ( 'NONE', *, *, #21132, .F. ) ; -#7869 = DIRECTION ( 'NONE', ( -1.063726576468305383E-07, 0.9743700557780770044, 0.2249510933581244931 ) ) ; -#7870 = ORIENTED_EDGE ( 'NONE', *, *, #18914, .F. ) ; -#7871 = ORIENTED_EDGE ( 'NONE', *, *, #29264, .F. ) ; -#7873 = CONICAL_SURFACE ( 'NONE', #13087, 17.00000000000406430, 0.7853981633972577647 ) ; -#7872 = CARTESIAN_POINT ( 'NONE', ( 3.064236136099508290, 190.8512031035150471, 106.7914583158460573 ) ) ; -#7874 = CARTESIAN_POINT ( 'NONE', ( 2.544444642231999953, 209.0637104426000121, 73.60054458572000158 ) ) ; -#7875 = EDGE_CURVE ( 'NONE', #10320, #479, #28440, .T. ) ; -#7876 = VECTOR ( 'NONE', #18269, 1000.000000000000000 ) ; -#7877 = VERTEX_POINT ( 'NONE', #31109 ) ; -#7878 = PLANE ( 'NONE', #29179 ) ; -#7879 = VECTOR ( 'NONE', #4085, 1000.000000000000114 ) ; -#7880 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; -#7881 = CARTESIAN_POINT ( 'NONE', ( 38.02815534111000062, 191.5231178303000092, 104.5088530676000147 ) ) ; -#7882 = CARTESIAN_POINT ( 'NONE', ( -25.83548129009000149, 120.8342218634000034, 87.73633095686001582 ) ) ; -#7883 = ADVANCED_FACE ( 'NONE', ( #3874 ), #9712, .F. ) ; -#7884 = ORIENTED_EDGE ( 'NONE', *, *, #32790, .F. ) ; -#7885 = LINE ( 'NONE', #29973, #1029 ) ; -#7886 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391912172 ) ) ; -#7887 = VERTEX_POINT ( 'NONE', #19614 ) ; -#7888 = CARTESIAN_POINT ( 'NONE', ( 0.5820739880337706396, 188.6030464522529826, 103.1950161645411725 ) ) ; -#7889 = CARTESIAN_POINT ( 'NONE', ( -37.23494651666909050, 103.9956957637453598, 184.2025836917128174 ) ) ; -#7890 = CARTESIAN_POINT ( 'NONE', ( 3.168113141152071321, 127.9133523189982498, 92.26104312719712652 ) ) ; -#7891 = CARTESIAN_POINT ( 'NONE', ( 45.91741224157529189, 185.4616417385437046, 105.5241924283433548 ) ) ; -#7892 = VERTEX_POINT ( 'NONE', #32898 ) ; -#7893 = EDGE_CURVE ( 'NONE', #22776, #25168, #37864, .T. ) ; -#7894 = CARTESIAN_POINT ( 'NONE', ( -25.99978576141418429, 118.1122949349609286, 90.28348809642494643 ) ) ; -#7895 = CARTESIAN_POINT ( 'NONE', ( 1.723508806196166532, 189.3712161428316563, 103.7908781100297659 ) ) ; -#7896 = DIRECTION ( 'NONE', ( -0.0004161288024459554248, 0.8480480898107214394, -0.5299191110020532447 ) ) ; -#7897 = VERTEX_POINT ( 'NONE', #16940 ) ; -#7898 = DIRECTION ( 'NONE', ( -0.0005884949961210389057, 0.2249510543439053878, -0.9743698870671265722 ) ) ; -#7899 = ORIENTED_EDGE ( 'NONE', *, *, #10155, .T. ) ; -#7900 = ORIENTED_EDGE ( 'NONE', *, *, #39029, .T. ) ; -#7901 = CARTESIAN_POINT ( 'NONE', ( -25.50922756583905837, 191.3757872987501969, 104.3640622938216183 ) ) ; -#7902 = DIRECTION ( 'NONE', ( -0.0006039748319373067654, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#7903 = CARTESIAN_POINT ( 'NONE', ( 25.64356753708000269, 191.4983924930999990, 104.2449497898000033 ) ) ; -#7904 = VECTOR ( 'NONE', #7838, 1000.000000000000114 ) ; -#7905 = AXIS2_PLACEMENT_3D ( 'NONE', #22223, #3184, #34651 ) ; -#7906 = CARTESIAN_POINT ( 'NONE', ( -5.668571547460837579, 124.2905521247553366, 90.91684019452070231 ) ) ; -#7907 = ORIENTED_EDGE ( 'NONE', *, *, #35124, .T. ) ; -#7908 = VECTOR ( 'NONE', #8757, 1000.000000000000227 ) ; -#7909 = CARTESIAN_POINT ( 'NONE', ( -14.78424365577531141, 182.9075039701052958, 104.4551379424934083 ) ) ; -#7910 = AXIS2_PLACEMENT_3D ( 'NONE', #24153, #24361, #9214 ) ; -#7911 = DIRECTION ( 'NONE', ( -0.9999998176072601996, 5.311345650496605610E-11, 0.0006039747068119591823 ) ) ; -#7912 = CARTESIAN_POINT ( 'NONE', ( -25.40406319347369646, 116.2731550828873139, 87.28312770962722311 ) ) ; -#7913 = CARTESIAN_POINT ( 'NONE', ( 39.71797952931839149, 110.6587743677033586, 169.3312915083336918 ) ) ; -#7914 = EDGE_CURVE ( 'NONE', #14055, #23221, #32639, .T. ) ; -#7915 = CARTESIAN_POINT ( 'NONE', ( 36.62411393520999781, 190.8924316886999861, 106.6482428512000098 ) ) ; -#7916 = CARTESIAN_POINT ( 'NONE', ( 32.56862158914320560, 175.5141961308963801, 100.1538973425462444 ) ) ; -#7917 = EDGE_CURVE ( 'NONE', #40452, #39678, #15016, .T. ) ; -#7918 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #25048, #35207 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#7919 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 3.427539337001264681E-16, -0.0006039748319384838837 ) ) ; -#7920 = EDGE_CURVE ( 'NONE', #23190, #1172, #13696, .T. ) ; -#7921 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989940797, 0.1373964268091562024 ) ) ; -#7922 = CARTESIAN_POINT ( 'NONE', ( 3.044162730076025447, 208.9211496123335507, 73.11923083669719858 ) ) ; -#7923 = ORIENTED_EDGE ( 'NONE', *, *, #8732, .T. ) ; -#7924 = CARTESIAN_POINT ( 'NONE', ( -37.65053461645775457, 212.3970732061722231, 28.08152331534148161 ) ) ; -#7925 = DIRECTION ( 'NONE', ( -8.673617379883984985E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#7926 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173914670, 126.6881577898831495, 89.42249239926104565 ) ) ; -#7927 = ADVANCED_FACE ( 'NONE', ( #38425 ), #29242, .T. ) ; -#7928 = ORIENTED_EDGE ( 'NONE', *, *, #19856, .F. ) ; -#7929 = CARTESIAN_POINT ( 'NONE', ( 5.665198925310773070, 181.8644090848704025, 101.8756595240227654 ) ) ; -#7930 = ORIENTED_EDGE ( 'NONE', *, *, #38231, .F. ) ; -#7931 = EDGE_CURVE ( 'NONE', #34936, #27937, #13032, .T. ) ; -#7932 = DIRECTION ( 'NONE', ( 0.0004161288024527328268, -0.8480480898032328740, 0.5299191110140372141 ) ) ; -#7933 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; -#7934 = CARTESIAN_POINT ( 'NONE', ( 25.40105660042022251, 116.2731026557913765, 87.25244269034133993 ) ) ; -#7935 = VERTEX_POINT ( 'NONE', #1418 ) ; -#7936 = CARTESIAN_POINT ( 'NONE', ( 36.37336898559946974, 191.7343303945321225, 106.3837163451585752 ) ) ; -#7937 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10340, #28542, #6437, #506 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 1.042368180638002949E-06, 0.0007115812285030307088 ), - .UNSPECIFIED. ) ; -#7938 = LINE ( 'NONE', #20821, #13975 ) ; -#7939 = CARTESIAN_POINT ( 'NONE', ( -25.83464932577865270, 120.7303327882271873, 87.71236904360661413 ) ) ; -#7940 = FACE_OUTER_BOUND ( 'NONE', #11797, .T. ) ; -#7941 = CARTESIAN_POINT ( 'NONE', ( -22.49970497326940588, 160.6243991471941968, 97.26272825661190780 ) ) ; -#7942 = ORIENTED_EDGE ( 'NONE', *, *, #40460, .T. ) ; -#7943 = ORIENTED_EDGE ( 'NONE', *, *, #34270, .F. ) ; -#7944 = ADVANCED_FACE ( 'NONE', ( #26378 ), #14110, .F. ) ; -#7945 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498902562, 132.2978364234161290, 93.26432363106762580 ) ) ; -#7946 = DIRECTION ( 'NONE', ( 0.5987319960703996191, 0.8009494346596138792, 0.000000000000000000 ) ) ; -#7947 = CARTESIAN_POINT ( 'NONE', ( 15.83500835682426633, 127.1069917442591617, 91.89618787420208434 ) ) ; -#7948 = CARTESIAN_POINT ( 'NONE', ( -45.59680607712631684, 124.5521801936699262, 92.16782543916392001 ) ) ; -#7949 = ORIENTED_EDGE ( 'NONE', *, *, #29872, .T. ) ; -#7950 = FACE_OUTER_BOUND ( 'NONE', #3900, .T. ) ; -#7951 = LINE ( 'NONE', #14504, #5906 ) ; -#7952 = CARTESIAN_POINT ( 'NONE', ( -28.41397273838000359, 125.0533781296000200, 91.23143372289999320 ) ) ; -#7953 = CARTESIAN_POINT ( 'NONE', ( -82.81915783535940534, 72.22391443751210716, 166.5742336941279973 ) ) ; -#7954 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825873969720803, 0.0005734119034471432848 ) ) ; -#7955 = PLANE ( 'NONE', #5985 ) ; -#7956 = VECTOR ( 'NONE', #29016, 1000.000000000000000 ) ; -#7957 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749385498, 179.6299767372515817, 101.6260513915996739 ) ) ; -#7958 = VECTOR ( 'NONE', #5280, 1000.000000000000114 ) ; -#7959 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971581501 ) ) ; -#7960 = CIRCLE ( 'NONE', #31498, 6.000000000000007994 ) ; -#7961 = CARTESIAN_POINT ( 'NONE', ( 37.43201049002699676, 166.9755643439367816, 188.5080295440252200 ) ) ; -#7962 = CARTESIAN_POINT ( 'NONE', ( 38.87085646289000351, 118.8888690499999967, 89.81811197227000321 ) ) ; -#7963 = ORIENTED_EDGE ( 'NONE', *, *, #19593, .F. ) ; -#7964 = CARTESIAN_POINT ( 'NONE', ( -21.44693681792356443, 182.5559435529752363, 101.8122371725110611 ) ) ; -#7965 = CARTESIAN_POINT ( 'NONE', ( -21.44517132691637329, 129.4739009503746558, 92.63619159901811884 ) ) ; -#7966 = CARTESIAN_POINT ( 'NONE', ( -36.14192390877251171, 191.8989000296091092, 106.4365041918967592 ) ) ; -#7967 = CARTESIAN_POINT ( 'NONE', ( 44.94235576104665597, 66.48397716096599197, 321.1673902962083957 ) ) ; -#7968 = EDGE_CURVE ( 'NONE', #1951, #22363, #25720, .T. ) ; -#7969 = ADVANCED_FACE ( 'NONE', ( #13499 ), #11104, .T. ) ; -#7971 = VERTEX_POINT ( 'NONE', #10842 ) ; -#7970 = DIRECTION ( 'NONE', ( 0.1843855715116846650, 0.08049128682204491347, -0.9795525068948782721 ) ) ; -#7972 = ORIENTED_EDGE ( 'NONE', *, *, #26674, .T. ) ; -#7973 = ORIENTED_EDGE ( 'NONE', *, *, #19543, .T. ) ; -#7974 = ORIENTED_EDGE ( 'NONE', *, *, #31011, .T. ) ; -#7975 = FACE_OUTER_BOUND ( 'NONE', #7991, .T. ) ; -#7976 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319484430396 ) ) ; -#7977 = ORIENTED_EDGE ( 'NONE', *, *, #17697, .T. ) ; -#7978 = FACE_OUTER_BOUND ( 'NONE', #20459, .T. ) ; -#7979 = CARTESIAN_POINT ( 'NONE', ( -34.62136824934677293, 159.8657254837204391, 187.5296924617526599 ) ) ; -#7980 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; -#7981 = CARTESIAN_POINT ( 'NONE', ( 14.16683332331358613, 129.7278030047937705, 90.10754002185558420 ) ) ; -#7982 = CARTESIAN_POINT ( 'NONE', ( -19.46367937371129742, 126.2449231135791052, 175.9963188856066267 ) ) ; -#7983 = ORIENTED_EDGE ( 'NONE', *, *, #17795, .T. ) ; -#7984 = DIRECTION ( 'NONE', ( 0.0006039748319391906751, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#7985 = ORIENTED_EDGE ( 'NONE', *, *, #32973, .T. ) ; -#7986 = DIRECTION ( 'NONE', ( 0.7933533416835718555, -0.5930537051408170113, -0.1373964266575322390 ) ) ; -#7987 = CONICAL_SURFACE ( 'NONE', #7337, 2.502997276898424772, 0.7853981634249621591 ) ; -#7988 = CARTESIAN_POINT ( 'NONE', ( -2.685652211178042759, 190.9457805259862369, 106.5600337294049638 ) ) ; -#7989 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#7990 = CONICAL_SURFACE ( 'NONE', #22373, 3.499999999950321516, 0.7853981633778843729 ) ; -#7991 = EDGE_LOOP ( 'NONE', ( #17317, #31001, #33412, #2271 ) ) ; -#7992 = ADVANCED_FACE ( 'NONE', ( #22712 ), #14936, .F. ) ; -#7993 = CARTESIAN_POINT ( 'NONE', ( -26.13683318140000011, 191.6581722882000065, 103.7775482495000006 ) ) ; -#7994 = AXIS2_PLACEMENT_3D ( 'NONE', #40237, #28004, #18964 ) ; -#7995 = CARTESIAN_POINT ( 'NONE', ( 1.510991691235000101, 188.7915705609999861, 103.2373913670000007 ) ) ; -#7996 = CARTESIAN_POINT ( 'NONE', ( 16.56895240876187003, 123.0679515848563454, 172.2907917757468681 ) ) ; -#7997 = ORIENTED_EDGE ( 'NONE', *, *, #8494, .F. ) ; -#7998 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#7999 = EDGE_LOOP ( 'NONE', ( #24304, #34522, #22303, #24378 ) ) ; -#8000 = EDGE_LOOP ( 'NONE', ( #7018, #6061, #18030, #34031 ) ) ; -#8001 = EDGE_CURVE ( 'NONE', #6720, #26044, #27681, .T. ) ; -#8002 = EDGE_LOOP ( 'NONE', ( #39685, #6253, #28469, #8922, #26057, #39648 ) ) ; -#8003 = CARTESIAN_POINT ( 'NONE', ( -38.50399426135000169, 118.5032430122000022, 89.70860371832000624 ) ) ; -#8004 = ORIENTED_EDGE ( 'NONE', *, *, #31061, .F. ) ; -#8005 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#8006 = DIRECTION ( 'NONE', ( 0.0006039748319388569577, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#8007 = EDGE_CURVE ( 'NONE', #30603, #16409, #7546, .T. ) ; -#8008 = ORIENTED_EDGE ( 'NONE', *, *, #34246, .T. ) ; -#8009 = CARTESIAN_POINT ( 'NONE', ( 25.01935866475762182, 130.6173723549316605, 89.79320596012071576 ) ) ; -#8010 = DIRECTION ( 'NONE', ( 0.7933535320750288999, 0.5930759023596230417, 0.1372994799130531074 ) ) ; -#8011 = AXIS2_PLACEMENT_3D ( 'NONE', #10551, #32999, #2151 ) ; -#8012 = ORIENTED_EDGE ( 'NONE', *, *, #35641, .F. ) ; -#8013 = CARTESIAN_POINT ( 'NONE', ( 26.13011340010889683, 121.2564972074009830, 90.71553933329148833 ) ) ; -#8014 = CARTESIAN_POINT ( 'NONE', ( -15.49852918602411300, 173.9514291674110780, 102.3878961845165776 ) ) ; -#8015 = EDGE_CURVE ( 'NONE', #35793, #16546, #7729, .T. ) ; -#8016 = AXIS2_PLACEMENT_3D ( 'NONE', #1330, #17467, #33418 ) ; -#8017 = EDGE_CURVE ( 'NONE', #6960, #9305, #23752, .T. ) ; -#8019 = CARTESIAN_POINT ( 'NONE', ( -30.45075997731206030, 185.6036007986156449, 102.5212824999076986 ) ) ; -#8018 = CARTESIAN_POINT ( 'NONE', ( -25.50991579498579398, 209.7152486954105086, 73.57374465072240355 ) ) ; -#8020 = EDGE_CURVE ( 'NONE', #604, #36902, #33950, .T. ) ; -#8021 = EDGE_LOOP ( 'NONE', ( #13141, #34261, #20864, #24192 ) ) ; -#8022 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552635 ) ) ; -#8023 = CONICAL_SURFACE ( 'NONE', #33467, 2.503061174963238766, 0.7853981634355203800 ) ; -#8024 = ORIENTED_EDGE ( 'NONE', *, *, #16923, .T. ) ; -#8025 = ORIENTED_EDGE ( 'NONE', *, *, #29196, .T. ) ; -#8026 = CARTESIAN_POINT ( 'NONE', ( -36.13188863639395976, 116.3632294363277424, 87.28960704737795595 ) ) ; -#8027 = CARTESIAN_POINT ( 'NONE', ( -26.69629712813124556, 110.6131156702000027, 90.28390873370305769 ) ) ; -#8028 = CARTESIAN_POINT ( 'NONE', ( -45.17721186414367907, 180.6407286098181544, 103.9501681112560192 ) ) ; -#8029 = CARTESIAN_POINT ( 'NONE', ( -22.78187663633837801, 153.7285825244628086, 98.23663543168041201 ) ) ; -#8030 = ORIENTED_EDGE ( 'NONE', *, *, #33864, .T. ) ; -#8031 = ORIENTED_EDGE ( 'NONE', *, *, #4413, .F. ) ; -#8032 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #4452, #16910 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8033 = CARTESIAN_POINT ( 'NONE', ( 38.54411846755796489, 218.5902260770999987, 73.03522440067472132 ) ) ; -#8034 = CARTESIAN_POINT ( 'NONE', ( 25.83181227377999889, 121.1031950916000000, 87.76725331590999701 ) ) ; -#8035 = ORIENTED_EDGE ( 'NONE', *, *, #35626, .T. ) ; -#8036 = VERTEX_POINT ( 'NONE', #20421 ) ; -#8037 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 77.27946979429643193, 322.5967026918629585 ) ) ; -#8038 = ORIENTED_EDGE ( 'NONE', *, *, #23611, .F. ) ; -#8039 = CIRCLE ( 'NONE', #9372, 2.000000000000011546 ) ; -#8040 = CARTESIAN_POINT ( 'NONE', ( -38.21353522366803901, 118.2110904979577128, 89.71187766670830399 ) ) ; -#8041 = VERTEX_POINT ( 'NONE', #29850 ) ; -#8042 = AXIS2_PLACEMENT_3D ( 'NONE', #20912, #24806, #33370 ) ; -#8043 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, 2.333520449303964061E-14, 0.9999998176071844824 ) ) ; -#8044 = VERTEX_POINT ( 'NONE', #17340 ) ; -#8045 = CARTESIAN_POINT ( 'NONE', ( 22.50835269910143666, 151.3303562393625441, 183.1450669823467194 ) ) ; -#8046 = CONICAL_SURFACE ( 'NONE', #14578, 40.50000000002031442, 0.7853981633973055043 ) ; -#8047 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971563737 ) ) ; -#8048 = LINE ( 'NONE', #20314, #1278 ) ; -#8049 = CARTESIAN_POINT ( 'NONE', ( 21.21457926054944920, 175.8986325760867828, 100.7626612099922454 ) ) ; -#8050 = EDGE_CURVE ( 'NONE', #22666, #33783, #29036, .T. ) ; -#8051 = VERTEX_POINT ( 'NONE', #36992 ) ; -#8052 = CARTESIAN_POINT ( 'NONE', ( 25.99214295446221357, 205.1071317750680123, 76.08915132579089402 ) ) ; -#8053 = DIRECTION ( 'NONE', ( 0.6087614115774527823, 0.7729348350621607633, 0.1788331191968013378 ) ) ; -#8054 = CARTESIAN_POINT ( 'NONE', ( -2.851221542150457200, 209.7096659646922774, 76.06022685436926167 ) ) ; -#8055 = EDGE_CURVE ( 'NONE', #16596, #14862, #11649, .T. ) ; -#8056 = ORIENTED_EDGE ( 'NONE', *, *, #37016, .T. ) ; -#8057 = CARTESIAN_POINT ( 'NONE', ( 6.042308921164076807, 177.7921139377573638, 100.6958234779730645 ) ) ; -#8058 = EDGE_CURVE ( 'NONE', #36343, #24826, #11504, .T. ) ; -#8059 = EDGE_CURVE ( 'NONE', #40259, #5402, #8095, .T. ) ; -#8061 = CYLINDRICAL_SURFACE ( 'NONE', #16781, 2.250000000000011102 ) ; -#8060 = LINE ( 'NONE', #32801, #35669 ) ; -#8062 = EDGE_CURVE ( 'NONE', #25237, #13011, #13695, .T. ) ; -#8063 = VERTEX_POINT ( 'NONE', #8584 ) ; -#8064 = CYLINDRICAL_SURFACE ( 'NONE', #34080, 2.000000000000011546 ) ; -#8065 = EDGE_CURVE ( 'NONE', #18716, #38112, #31492, .T. ) ; -#8066 = VECTOR ( 'NONE', #18842, 999.9999999999998863 ) ; -#8067 = AXIS2_PLACEMENT_3D ( 'NONE', #36996, #31256, #3233 ) ; -#8068 = ORIENTED_EDGE ( 'NONE', *, *, #26651, .F. ) ; -#8069 = CARTESIAN_POINT ( 'NONE', ( 62.95950931629634795, 92.27946979429611929, 297.5205190635954295 ) ) ; -#8070 = CARTESIAN_POINT ( 'NONE', ( 0.04563542675669964022, 271.9029643395999187, 75.55847697571874733 ) ) ; -#8071 = CARTESIAN_POINT ( 'NONE', ( 15.50147166925602527, 127.1825504195482353, 91.57172455528431954 ) ) ; -#8072 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#8073 = CARTESIAN_POINT ( 'NONE', ( 12.63937458780924494, 177.5948492622155186, 100.8158580061204219 ) ) ; -#8075 = ORIENTED_EDGE ( 'NONE', *, *, #39539, .F. ) ; -#8074 = AXIS2_PLACEMENT_3D ( 'NONE', #4484, #29448, #34743 ) ; -#8076 = ORIENTED_EDGE ( 'NONE', *, *, #26316, .F. ) ; -#8077 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772234801672, 136.6775772631780796, 180.9814965275865575 ) ) ; -#8078 = ORIENTED_EDGE ( 'NONE', *, *, #19775, .T. ) ; -#8079 = VERTEX_POINT ( 'NONE', #18156 ) ; -#8080 = DIRECTION ( 'NONE', ( 0.6087611434179115433, -0.7728348325624404547, -0.1792657018023851023 ) ) ; -#8081 = CARTESIAN_POINT ( 'NONE', ( 2.870476498559999978, 209.1880350332000091, 73.24767605647001290 ) ) ; -#8082 = ORIENTED_EDGE ( 'NONE', *, *, #26651, .T. ) ; -#8083 = CARTESIAN_POINT ( 'NONE', ( 13.01264957174517356, 177.7922272993784816, 100.6916336907332408 ) ) ; -#8084 = FACE_OUTER_BOUND ( 'NONE', #30094, .T. ) ; -#8085 = CARTESIAN_POINT ( 'NONE', ( -36.14064454963000372, 191.7996476902000040, 104.2912827661999984 ) ) ; -#8086 = CARTESIAN_POINT ( 'NONE', ( 37.45139837402000182, 191.5507549815000061, 104.5084902340000070 ) ) ; -#8087 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38373, #10382, #26125, #34881 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999997749458457985 ), - .UNSPECIFIED. ) ; -#8088 = ORIENTED_EDGE ( 'NONE', *, *, #8400, .F. ) ; -#8089 = CARTESIAN_POINT ( 'NONE', ( 41.51603850386035788, 135.1693297037100194, 25.18785158773614796 ) ) ; -#8090 = ORIENTED_EDGE ( 'NONE', *, *, #14635, .T. ) ; -#8091 = DIRECTION ( 'NONE', ( 0.7933535320750287889, -0.5931614265262138419, -0.1369295264925107780 ) ) ; -#8092 = DIRECTION ( 'NONE', ( -0.6088160902985568779, 0.7729595817128234181, 0.1785397805306046526 ) ) ; -#8093 = DIRECTION ( 'NONE', ( 0.0005884949961155384228, -0.2249510543439099397, 0.9743698870671255730 ) ) ; -#8094 = EDGE_LOOP ( 'NONE', ( #35642, #32031, #26069, #5798 ) ) ; -#8095 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #36583, #12055 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 5.382452939443789803E-08, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8096 = CARTESIAN_POINT ( 'NONE', ( 0.6328254411848658334, 188.6147578804658451, 103.1976893086753506 ) ) ; -#8097 = CARTESIAN_POINT ( 'NONE', ( 22.99918985293999540, 115.6131156702015801, 87.75369723384940812 ) ) ; -#8098 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; -#8099 = CARTESIAN_POINT ( 'NONE', ( -35.43925701251282590, 191.9759150222000130, 101.9428517634907507 ) ) ; -#8100 = VERTEX_POINT ( 'NONE', #39837 ) ; -#8101 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9380918495502710286, -0.3463866074307025977 ) ) ; -#8102 = CARTESIAN_POINT ( 'NONE', ( 15.12415969602515986, 146.0659008074709106, 180.8278994957862551 ) ) ; -#8103 = AXIS2_PLACEMENT_3D ( 'NONE', #31495, #31712, #21903 ) ; -#8104 = CIRCLE ( 'NONE', #32278, 2.499999999990780264 ) ; -#8105 = CARTESIAN_POINT ( 'NONE', ( -20.01829689993581596, 209.7096928646539880, 76.07061354826153377 ) ) ; -#8106 = EDGE_CURVE ( 'NONE', #17839, #18192, #36383, .T. ) ; -#8107 = ORIENTED_EDGE ( 'NONE', *, *, #22711, .F. ) ; -#8108 = FACE_OUTER_BOUND ( 'NONE', #31697, .T. ) ; -#8109 = ORIENTED_EDGE ( 'NONE', *, *, #12790, .F. ) ; -#8110 = VERTEX_POINT ( 'NONE', #24334 ) ; -#8111 = EDGE_CURVE ( 'NONE', #24320, #24828, #26146, .T. ) ; -#8112 = AXIS2_PLACEMENT_3D ( 'NONE', #16961, #4908, #29461 ) ; -#8113 = CARTESIAN_POINT ( 'NONE', ( -25.64570212326999865, 191.2554111844000033, 104.2075963127000051 ) ) ; -#8114 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540931966, 151.8558896893983103, 95.23413014777732144 ) ) ; -#8115 = CARTESIAN_POINT ( 'NONE', ( -25.20476889543461851, 212.3494275232980044, 73.57346788151119199 ) ) ; -#8116 = CARTESIAN_POINT ( 'NONE', ( 3.045964837637491485, 205.1071438019466484, 76.10297588903854660 ) ) ; -#8117 = ADVANCED_FACE ( 'NONE', ( #20840 ), #34567, .F. ) ; -#8118 = CARTESIAN_POINT ( 'NONE', ( 16.88368854683466935, 152.4476604039728898, 182.0571496254905242 ) ) ; -#8119 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 82.27946979429611929, 297.5967072516833127 ) ) ; -#8120 = VERTEX_POINT ( 'NONE', #17548 ) ; -#8121 = EDGE_CURVE ( 'NONE', #12044, #39862, #8172, .T. ) ; -#8122 = LINE ( 'NONE', #11194, #22038 ) ; -#8123 = ADVANCED_FACE ( 'NONE', ( #40042 ), #12386, .F. ) ; -#8124 = CARTESIAN_POINT ( 'NONE', ( 42.42192200091505327, 180.1607944338011862, 148.5017479457221441 ) ) ; -#8125 = LINE ( 'NONE', #20585, #36208 ) ; -#8126 = CARTESIAN_POINT ( 'NONE', ( 21.61913182270516742, 154.2531527860821541, 95.25201104625905657 ) ) ; -#8127 = DIRECTION ( 'NONE', ( 0.7066905234170505201, 0.1590644458417531104, -0.6894106223301111891 ) ) ; -#8128 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066962549, 129.9712533186751102, 92.22833354197516087 ) ) ; -#8129 = CARTESIAN_POINT ( 'NONE', ( -38.98625979382970996, 119.3757451136368672, 87.77085995517417416 ) ) ; -#8130 = ORIENTED_EDGE ( 'NONE', *, *, #7875, .F. ) ; -#8131 = AXIS2_PLACEMENT_3D ( 'NONE', #29390, #29194, #1358 ) ; -#8132 = CARTESIAN_POINT ( 'NONE', ( -5.671312717824411820, 181.1260227605253021, 104.4549565478647253 ) ) ; -#8133 = CARTESIAN_POINT ( 'NONE', ( -19.70055405364098533, 149.1723619494412389, 182.9474843209757751 ) ) ; -#8134 = AXIS2_PLACEMENT_3D ( 'NONE', #19611, #19006, #22706 ) ; -#8135 = CARTESIAN_POINT ( 'NONE', ( -31.07623358299026251, 135.1199993735448572, 90.86660040197580201 ) ) ; -#8136 = VECTOR ( 'NONE', #11637, 1000.000000000000114 ) ; -#8137 = ORIENTED_EDGE ( 'NONE', *, *, #3030, .F. ) ; -#8138 = CARTESIAN_POINT ( 'NONE', ( 39.71672226492471935, 182.4826294143295797, 106.8893320580963007 ) ) ; -#8139 = AXIS2_PLACEMENT_3D ( 'NONE', #22319, #6747, #28642 ) ; -#8140 = ORIENTED_EDGE ( 'NONE', *, *, #32533, .F. ) ; -#8141 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250900025, 132.4055461762744983, 92.79778151959283150 ) ) ; -#8142 = EDGE_LOOP ( 'NONE', ( #18826, #6914, #15665, #7848 ) ) ; -#8143 = CARTESIAN_POINT ( 'NONE', ( 36.13089926330142276, 192.2307435129849296, 106.3898830433148248 ) ) ; -#8144 = LINE ( 'NONE', #35927, #23786 ) ; -#8145 = CARTESIAN_POINT ( 'NONE', ( -12.63532165819085940, 130.1640888693136731, 92.54240592023801071 ) ) ; -#8146 = CARTESIAN_POINT ( 'NONE', ( -14.55132762993606477, 129.4747796237930118, 92.63223137880015656 ) ) ; -#8147 = CARTESIAN_POINT ( 'NONE', ( -22.68873265250381976, 154.4034425878945171, 95.31346902715758063 ) ) ; -#8148 = ORIENTED_EDGE ( 'NONE', *, *, #19320, .T. ) ; -#8149 = DIRECTION ( 'NONE', ( -0.7691761624280200049, -0.6302414090841089722, 0.1056588729268925636 ) ) ; -#8150 = CARTESIAN_POINT ( 'NONE', ( -20.00006126831510400, 120.3902141372887087, 87.45929000627990035 ) ) ; -#8151 = CARTESIAN_POINT ( 'NONE', ( 13.67163921588000086, 134.7331883168999980, 93.82918430779000118 ) ) ; -#8152 = ADVANCED_FACE ( 'NONE', ( #17955 ), #7819, .F. ) ; -#8153 = ADVANCED_FACE ( 'NONE', ( #717 ), #35886, .F. ) ; -#8154 = DIRECTION ( 'NONE', ( 0.6087611434179120984, -0.7728348325624403437, -0.1792657018023839366 ) ) ; -#8155 = EDGE_CURVE ( 'NONE', #17879, #1388, #39293, .T. ) ; -#8156 = ORIENTED_EDGE ( 'NONE', *, *, #34149, .T. ) ; -#8157 = LINE ( 'NONE', #35333, #23143 ) ; -#8158 = EDGE_CURVE ( 'NONE', #2940, #629, #5180, .T. ) ; -#8159 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26467, #29933, #4769, #10932 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8160 = CARTESIAN_POINT ( 'NONE', ( -43.53198541835717350, 120.4444449957113648, 91.66393424540790136 ) ) ; -#8161 = AXIS2_PLACEMENT_3D ( 'NONE', #17840, #17649, #33181 ) ; -#8162 = CARTESIAN_POINT ( 'NONE', ( -13.55543936442099096, 147.3963946565219203, 96.76916085569253312 ) ) ; -#8163 = PLANE ( 'NONE', #12380 ) ; -#8164 = CARTESIAN_POINT ( 'NONE', ( 21.26009108512010570, 128.3999477444776574, 91.84930485354649932 ) ) ; -#8165 = VECTOR ( 'NONE', #25526, 1000.000000000000000 ) ; -#8166 = AXIS2_PLACEMENT_3D ( 'NONE', #37522, #15453, #27947 ) ; -#8167 = CARTESIAN_POINT ( 'NONE', ( 22.49964039506790670, 136.6763645039129074, 180.9867425820801259 ) ) ; -#8168 = ADVANCED_FACE ( 'NONE', ( #38145 ), #16315, .F. ) ; -#8169 = CARTESIAN_POINT ( 'NONE', ( 28.70581487919770680, 163.6075652324868486, 97.92051968927451355 ) ) ; -#8170 = AXIS2_PLACEMENT_3D ( 'NONE', #4386, #32606, #32807 ) ; -#8171 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #543, #15880, #28770, #22248 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8172 = LINE ( 'NONE', #30052, #35792 ) ; -#8173 = CARTESIAN_POINT ( 'NONE', ( 28.46606743108605642, 130.6255393001868299, 90.13513050975397789 ) ) ; -#8174 = LINE ( 'NONE', #14517, #3672 ) ; -#8175 = EDGE_LOOP ( 'NONE', ( #20363, #4295, #39090, #13610 ) ) ; -#8176 = CARTESIAN_POINT ( 'NONE', ( -22.82366484708005672, 169.1007803578971220, 29.42961924709861066 ) ) ; -#8177 = CARTESIAN_POINT ( 'NONE', ( 33.41957710359000089, 226.1502260771000010, 73.28831954084999722 ) ) ; -#8178 = CARTESIAN_POINT ( 'NONE', ( -36.28616296343275138, 191.6774367654532796, 106.4232239427282707 ) ) ; -#8179 = CARTESIAN_POINT ( 'NONE', ( -21.48366051631042239, 115.4955022973411900, 87.28075988464726720 ) ) ; -#8180 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#8181 = ORIENTED_EDGE ( 'NONE', *, *, #11299, .T. ) ; -#8182 = ORIENTED_EDGE ( 'NONE', *, *, #16146, .F. ) ; -#8183 = CARTESIAN_POINT ( 'NONE', ( -39.79500347691000428, 182.5468005769366187, 106.5836252739005658 ) ) ; -#8184 = EDGE_LOOP ( 'NONE', ( #2785, #5227, #36798, #28911 ) ) ; -#8185 = LINE ( 'NONE', #20653, #38 ) ; -#8186 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17497, #28098, #14460, #36325 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8187 = CARTESIAN_POINT ( 'NONE', ( 39.79702541312468611, 141.5973318770025173, 284.1405295046018864 ) ) ; -#8188 = VERTEX_POINT ( 'NONE', #1117 ) ; -#8189 = CONICAL_SURFACE ( 'NONE', #23192, 59.40509898896483065, 0.7853981633972950682 ) ; -#8190 = CARTESIAN_POINT ( 'NONE', ( -15.99988210103421871, 186.2297624492397858, 102.6571153657711051 ) ) ; -#8191 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.523234146902447552E-15, 0.0006039748319393680506 ) ) ; -#8192 = VECTOR ( 'NONE', #237, 999.9999999999998863 ) ; -#8193 = VECTOR ( 'NONE', #29331, 999.9999999999998863 ) ; -#8194 = CARTESIAN_POINT ( 'NONE', ( -36.81041944407999722, 117.5332847971999968, 87.39354551883999989 ) ) ; -#8195 = ORIENTED_EDGE ( 'NONE', *, *, #39588, .T. ) ; -#8196 = VECTOR ( 'NONE', #8091, 999.9999999999998863 ) ; -#8197 = CARTESIAN_POINT ( 'NONE', ( -21.82963563099358950, 129.7230376101904881, 90.12818080884812844 ) ) ; -#8198 = EDGE_LOOP ( 'NONE', ( #39345, #15625, #25269, #5832 ) ) ; -#8199 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418800025, 218.5902260770999987, 73.08022052563953253 ) ) ; -#8200 = AXIS2_PLACEMENT_3D ( 'NONE', #22277, #37408, #9005 ) ; -#8201 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971538202 ) ) ; -#8202 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#8203 = ORIENTED_EDGE ( 'NONE', *, *, #37380, .F. ) ; -#8204 = ORIENTED_EDGE ( 'NONE', *, *, #16487, .T. ) ; -#8205 = CARTESIAN_POINT ( 'NONE', ( -0.9403621044584999922, 189.0418273829999976, 103.6974160350000034 ) ) ; -#8206 = CARTESIAN_POINT ( 'NONE', ( 0.7117835834011440044, 189.0161218224870083, 103.6960389501960123 ) ) ; -#8207 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; -#8208 = CARTESIAN_POINT ( 'NONE', ( -35.65705446583450566, 191.7229687839729593, 106.9366313765358854 ) ) ; -#8209 = VERTEX_POINT ( 'NONE', #34647 ) ; -#8210 = ADVANCED_FACE ( 'NONE', ( #19114 ), #10543, .F. ) ; -#8211 = ORIENTED_EDGE ( 'NONE', *, *, #22432, .T. ) ; -#8212 = CARTESIAN_POINT ( 'NONE', ( -26.74382575616715130, 120.3580507813137075, 171.5572023280520000 ) ) ; -#8213 = EDGE_CURVE ( 'NONE', #20812, #18841, #8433, .T. ) ; -#8214 = ORIENTED_EDGE ( 'NONE', *, *, #6248, .F. ) ; -#8215 = EDGE_LOOP ( 'NONE', ( #3667, #12752, #18094, #37851 ) ) ; -#8216 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18137, #27598, #34088, #36974 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8217 = ORIENTED_EDGE ( 'NONE', *, *, #33316, .T. ) ; -#8218 = CARTESIAN_POINT ( 'NONE', ( -27.41957310755384114, 125.0505560954758835, 89.05282576069730283 ) ) ; -#8219 = AXIS2_PLACEMENT_3D ( 'NONE', #9605, #18378, #22080 ) ; -#8220 = VERTEX_POINT ( 'NONE', #32410 ) ; -#8221 = CARTESIAN_POINT ( 'NONE', ( 3.058447091124538719, 190.6904732739033648, 106.7543539244942394 ) ) ; -#8222 = CONICAL_SURFACE ( 'NONE', #40193, 5.000000000424002167, 0.7853981633778847060 ) ; -#8223 = FACE_OUTER_BOUND ( 'NONE', #1643, .T. ) ; -#8224 = CARTESIAN_POINT ( 'NONE', ( -12.67632453871999942, 151.9652147204000130, 28.07991271570000080 ) ) ; -#8225 = DIRECTION ( 'NONE', ( -0.0004963947332026163962, -0.5299192641669762116, -0.8480479509184604137 ) ) ; -#8226 = ORIENTED_EDGE ( 'NONE', *, *, #13010, .T. ) ; -#8227 = DIRECTION ( 'NONE', ( 0.9999998268368047727, 0.0001323825927353974201, -0.0005734119020230789678 ) ) ; -#8228 = ORIENTED_EDGE ( 'NONE', *, *, #38023, .F. ) ; -#8229 = CIRCLE ( 'NONE', #31089, 3.500000000007123635 ) ; -#8230 = CARTESIAN_POINT ( 'NONE', ( 28.02681684991999944, 124.7590000943000064, 91.17562171158999718 ) ) ; -#8231 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568455 ) ) ; -#8232 = VECTOR ( 'NONE', #14239, 1000.000000000000227 ) ; -#8234 = CARTESIAN_POINT ( 'NONE', ( -42.47220679908992480, 189.9442792002049316, 106.2657712603332385 ) ) ; -#8233 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265228896, 0.1368326740407718456 ) ) ; -#8235 = EDGE_LOOP ( 'NONE', ( #2947, #29041, #4521, #24380, #33218, #2727, #38496, #34829, #27788, #29556, #34220, #21983, #11346, #24237, #18238, #36042 ) ) ; -#8236 = EDGE_CURVE ( 'NONE', #39798, #796, #39745, .T. ) ; -#8237 = ORIENTED_EDGE ( 'NONE', *, *, #40010, .F. ) ; -#8238 = CARTESIAN_POINT ( 'NONE', ( -35.98930003077260409, 192.1481011322285610, 104.4284500425794562 ) ) ; -#8239 = EDGE_LOOP ( 'NONE', ( #18196, #36213, #18213, #5409 ) ) ; -#8240 = CARTESIAN_POINT ( 'NONE', ( -36.72119652792175515, 117.5199652785488524, 87.28996297457759113 ) ) ; -#8241 = DIRECTION ( 'NONE', ( -0.5988681445390194868, 0.8008476418498040594, 0.000000000000000000 ) ) ; -#8242 = FACE_OUTER_BOUND ( 'NONE', #1847, .T. ) ; -#8243 = CARTESIAN_POINT ( 'NONE', ( -37.26309767763914493, 111.8941053232203160, 150.0343454695379819 ) ) ; -#8244 = ORIENTED_EDGE ( 'NONE', *, *, #34696, .T. ) ; -#8245 = ORIENTED_EDGE ( 'NONE', *, *, #30559, .F. ) ; -#8246 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927744103482, -0.0005734119022083112227 ) ) ; -#8247 = CARTESIAN_POINT ( 'NONE', ( 20.33494057836571045, 190.9269296371502378, 106.4564606968243510 ) ) ; -#8248 = AXIS2_PLACEMENT_3D ( 'NONE', #325, #31628, #16263 ) ; -#8249 = CARTESIAN_POINT ( 'NONE', ( 27.47889980971000057, 124.6377240942999975, 88.58226852807001706 ) ) ; -#8250 = ORIENTED_EDGE ( 'NONE', *, *, #12641, .T. ) ; -#8251 = ORIENTED_EDGE ( 'NONE', *, *, #3760, .F. ) ; -#8252 = CARTESIAN_POINT ( 'NONE', ( 30.06842554564726910, 135.2666963995015408, 91.33418159856985596 ) ) ; -#8253 = AXIS2_PLACEMENT_3D ( 'NONE', #12876, #785, #15916 ) ; -#8254 = AXIS2_PLACEMENT_3D ( 'NONE', #26065, #34820, #6826 ) ; -#8255 = EDGE_CURVE ( 'NONE', #28384, #17683, #38526, .T. ) ; -#8256 = CARTESIAN_POINT ( 'NONE', ( 3.069762710617847556, 190.8498451990714955, 106.7968295637148799 ) ) ; -#8257 = EDGE_CURVE ( 'NONE', #23280, #6308, #33944, .T. ) ; -#8258 = EDGE_LOOP ( 'NONE', ( #27305, #17635, #19442, #35866 ) ) ; -#8259 = CARTESIAN_POINT ( 'NONE', ( 5.667964583423158231, 129.9727540529065948, 92.22183313054385678 ) ) ; -#8260 = CARTESIAN_POINT ( 'NONE', ( 76.10601358362096391, 156.3575724116909669, 95.70494597592171715 ) ) ; -#8261 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098504, 179.0628333271180850, 104.0826189413490539 ) ) ; -#8262 = CARTESIAN_POINT ( 'NONE', ( -35.95366953697975987, 209.7096538831000032, 78.08022010983776795 ) ) ; -#8263 = EDGE_CURVE ( 'NONE', #367, #14957, #25488, .T. ) ; -#8264 = VERTEX_POINT ( 'NONE', #25288 ) ; -#8265 = DIRECTION ( 'NONE', ( -0.7933533411653073131, 0.5930537057989907490, 0.1373964268091705798 ) ) ; -#8266 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.110223024625155594E-14, -1.000000000000000000 ) ) ; -#8267 = ORIENTED_EDGE ( 'NONE', *, *, #27232, .F. ) ; -#8268 = AXIS2_PLACEMENT_3D ( 'NONE', #21172, #40362, #12366 ) ; -#8269 = CARTESIAN_POINT ( 'NONE', ( 10.44426510892352589, 177.7926467814048124, 100.6933375042854095 ) ) ; -#8270 = CIRCLE ( 'NONE', #14157, 2.000000000000000444 ) ; -#8271 = AXIS2_PLACEMENT_3D ( 'NONE', #35742, #16749, #23503 ) ; -#8273 = CARTESIAN_POINT ( 'NONE', ( 14.12167057796713010, 158.3605014131640303, 96.20479564579193266 ) ) ; -#8272 = CARTESIAN_POINT ( 'NONE', ( 14.15993356491004640, 135.7023639446290417, 90.97372837016631308 ) ) ; -#8274 = ORIENTED_EDGE ( 'NONE', *, *, #30050, .T. ) ; -#8275 = VERTEX_POINT ( 'NONE', #22218 ) ; -#8276 = EDGE_CURVE ( 'NONE', #26011, #23779, #33434, .T. ) ; -#8277 = EDGE_LOOP ( 'NONE', ( #2378, #37293, #3927, #39568 ) ) ; -#8279 = AXIS2_PLACEMENT_3D ( 'NONE', #36656, #8661, #30533 ) ; -#8278 = LINE ( 'NONE', #8069, #34242 ) ; -#8280 = CARTESIAN_POINT ( 'NONE', ( 20.50029381458971400, 151.8610500385970852, 95.21357840886264512 ) ) ; -#8281 = CARTESIAN_POINT ( 'NONE', ( 19.35706105504437602, 157.8277727518531037, 166.6153729214301507 ) ) ; -#8282 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38371, #14044, #26518, #7283 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8283 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#8284 = ORIENTED_EDGE ( 'NONE', *, *, #24612, .T. ) ; -#8285 = ORIENTED_EDGE ( 'NONE', *, *, #13872, .F. ) ; -#8286 = CARTESIAN_POINT ( 'NONE', ( -42.63673691994630843, 120.8556943064256473, 91.02934306460012692 ) ) ; -#8287 = ORIENTED_EDGE ( 'NONE', *, *, #17137, .F. ) ; -#8288 = ORIENTED_EDGE ( 'NONE', *, *, #35404, .F. ) ; -#8289 = FACE_OUTER_BOUND ( 'NONE', #33072, .T. ) ; -#8290 = CARTESIAN_POINT ( 'NONE', ( 2.674747366820000138, 209.4039250993000110, 73.39437287834999779 ) ) ; -#8291 = ORIENTED_EDGE ( 'NONE', *, *, #3942, .T. ) ; -#8292 = EDGE_CURVE ( 'NONE', #21765, #7552, #15417, .T. ) ; -#8293 = VERTEX_POINT ( 'NONE', #7246 ) ; -#8294 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 5.991633438574710639E-15, -0.0006039748319372744562 ) ) ; -#8295 = CARTESIAN_POINT ( 'NONE', ( -36.12682697814000221, 192.1857872781000083, 104.5704194111000191 ) ) ; -#8296 = CARTESIAN_POINT ( 'NONE', ( 38.03732978805999920, 191.1273048889999870, 103.8765410749000040 ) ) ; -#8297 = ORIENTED_EDGE ( 'NONE', *, *, #31610, .F. ) ; -#8298 = CARTESIAN_POINT ( 'NONE', ( -25.66813934661154661, 120.6730681322564465, 87.86559688811576052 ) ) ; -#8299 = EDGE_CURVE ( 'NONE', #29253, #38732, #22236, .T. ) ; -#8300 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#8301 = ORIENTED_EDGE ( 'NONE', *, *, #21663, .T. ) ; -#8302 = DIRECTION ( 'NONE', ( -0.0004161288024450390572, 0.8480480898092163100, -0.5299191110044617625 ) ) ; -#8303 = CARTESIAN_POINT ( 'NONE', ( -3.334889541086432985, 126.1639861300818097, 91.69003341170677857 ) ) ; -#8304 = CARTESIAN_POINT ( 'NONE', ( 16.00176583132817498, 118.9451395335793649, 90.18281804087268938 ) ) ; -#8305 = ORIENTED_EDGE ( 'NONE', *, *, #9133, .F. ) ; -#8306 = CONICAL_SURFACE ( 'NONE', #10909, 6.499999999766678194, 0.7853981634251984145 ) ; -#8307 = CARTESIAN_POINT ( 'NONE', ( -12.60649365401999944, 163.2729245447999915, 152.4718672074000381 ) ) ; -#8308 = EDGE_CURVE ( 'NONE', #18764, #19078, #30146, .T. ) ; -#8309 = CARTESIAN_POINT ( 'NONE', ( -16.55494438683570735, 127.1017686116984180, 154.7943589889946168 ) ) ; -#8310 = EDGE_CURVE ( 'NONE', #32791, #21410, #20942, .T. ) ; -#8311 = DIRECTION ( 'NONE', ( -0.0004161288024540093665, -0.5299192578742120130, -0.8480479980348188951 ) ) ; -#8312 = ADVANCED_FACE ( 'NONE', ( #4984 ), #2143, .F. ) ; -#8313 = ORIENTED_EDGE ( 'NONE', *, *, #29773, .T. ) ; -#8314 = PLANE ( 'NONE', #12655 ) ; -#8315 = ADVANCED_FACE ( 'NONE', ( #39530 ), #18839, .F. ) ; -#8316 = FACE_OUTER_BOUND ( 'NONE', #18262, .T. ) ; -#8317 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#8318 = ORIENTED_EDGE ( 'NONE', *, *, #11868, .T. ) ; -#8319 = CARTESIAN_POINT ( 'NONE', ( -22.49860963037942341, 158.0258723631266378, 98.88646763493585468 ) ) ; -#8320 = ORIENTED_EDGE ( 'NONE', *, *, #34309, .F. ) ; -#8321 = ORIENTED_EDGE ( 'NONE', *, *, #36289, .T. ) ; -#8322 = CARTESIAN_POINT ( 'NONE', ( -6.045835231059395021, 134.9182589738620095, 90.80491324842614631 ) ) ; -#8323 = CARTESIAN_POINT ( 'NONE', ( -45.14168110797990607, 115.6906603679936154, 128.0405359920818853 ) ) ; -#8324 = DIRECTION ( 'NONE', ( 0.0005559617641677616195, -0.3907311284691155073, 0.9205046855675251827 ) ) ; -#8325 = CARTESIAN_POINT ( 'NONE', ( -20.58392306733278332, 211.7448544280097451, 75.57086740851539730 ) ) ; -#8326 = LINE ( 'NONE', #20787, #40032 ) ; -#8327 = CARTESIAN_POINT ( 'NONE', ( 39.06385346265498981, 191.4135374074515994, 104.3337792663689072 ) ) ; -#8328 = ORIENTED_EDGE ( 'NONE', *, *, #37793, .F. ) ; -#8329 = CARTESIAN_POINT ( 'NONE', ( -14.89128842545527576, 182.7456056360065020, 104.5888761284686694 ) ) ; -#8330 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20082, #22781, #26255, #7216, #3747, #32376, #35813, #17010, #1085, #7823, #35215 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999997887246, 0.3749999999997143396, 0.4374999999997122857, 0.4687499999996813105, 0.4999999999996502797, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8331 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#8332 = ADVANCED_FACE ( 'NONE', ( #1728 ), #9739, .T. ) ; -#8333 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#8334 = CARTESIAN_POINT ( 'NONE', ( 2.519724450483999956, 209.0000002173999860, 32.65697486330000032 ) ) ; -#8335 = CARTESIAN_POINT ( 'NONE', ( 15.59057381605467896, 127.7851801377404826, 174.7303348607053692 ) ) ; -#8336 = CIRCLE ( 'NONE', #29878, 59.40509898823096790 ) ; -#8337 = CARTESIAN_POINT ( 'NONE', ( 19.01986883121886862, 124.9296800124309925, 178.2906471469820247 ) ) ; -#8338 = CARTESIAN_POINT ( 'NONE', ( 19.31194489278902537, 124.3312024124945339, 178.3888998772247305 ) ) ; -#8339 = FACE_OUTER_BOUND ( 'NONE', #25179, .T. ) ; -#8340 = CARTESIAN_POINT ( 'NONE', ( -35.77119973190495017, 192.3543298451174053, 104.2454963614574126 ) ) ; -#8341 = AXIS2_PLACEMENT_3D ( 'NONE', #11200, #14066, #1791 ) ; -#8342 = ORIENTED_EDGE ( 'NONE', *, *, #39532, .T. ) ; -#8343 = EDGE_LOOP ( 'NONE', ( #37131, #7063, #32785, #24255 ) ) ; -#8344 = CARTESIAN_POINT ( 'NONE', ( 25.99199080364422443, 211.0901596425212574, 76.04279652306830428 ) ) ; -#8345 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11221, #30229, #33278, #17325 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8346 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#8347 = ADVANCED_FACE ( 'NONE', ( #36056 ), #20321, .F. ) ; -#8348 = ORIENTED_EDGE ( 'NONE', *, *, #32715, .F. ) ; -#8349 = CARTESIAN_POINT ( 'NONE', ( 33.37602094669033193, 84.06324503389978986, 284.1448219155665242 ) ) ; -#8350 = ORIENTED_EDGE ( 'NONE', *, *, #31018, .F. ) ; -#8351 = CARTESIAN_POINT ( 'NONE', ( -38.24019460149000338, 119.1859645161000003, 87.44767029253000601 ) ) ; -#8352 = EDGE_CURVE ( 'NONE', #8293, #18457, #26682, .T. ) ; -#8353 = CARTESIAN_POINT ( 'NONE', ( -5.675054657474391639, 124.3656264979204167, 88.36836997283377571 ) ) ; -#8354 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2255194953558363191, 0.9742386449830560124 ) ) ; -#8355 = EDGE_LOOP ( 'NONE', ( #25291, #5321, #39152, #23356 ) ) ; -#8356 = CARTESIAN_POINT ( 'NONE', ( 36.26293756970083138, 191.9133757257809805, 106.3931895791960329 ) ) ; -#8357 = EDGE_CURVE ( 'NONE', #1132, #12650, #16834, .T. ) ; -#8358 = CYLINDRICAL_SURFACE ( 'NONE', #31608, 2.000000000000014655 ) ; -#8359 = CARTESIAN_POINT ( 'NONE', ( -36.37433508471929855, 115.1473213475028103, 89.75326492886478036 ) ) ; -#8360 = DIRECTION ( 'NONE', ( -0.0005884949961189803310, 0.2249510543439054433, -0.9743698870671265722 ) ) ; -#8361 = DIRECTION ( 'NONE', ( -0.5668486650917774483, -0.8238218701100766816, 0.0003423623896884662554 ) ) ; -#8362 = CARTESIAN_POINT ( 'NONE', ( 15.50029466864684835, 174.4049028184354881, 100.4212577462347866 ) ) ; -#8363 = EDGE_LOOP ( 'NONE', ( #3717, #21156, #12072, #34836 ) ) ; -#8364 = ADVANCED_FACE ( 'NONE', ( #10735 ), #25421, .T. ) ; -#8365 = ORIENTED_EDGE ( 'NONE', *, *, #31892, .F. ) ; -#8366 = CARTESIAN_POINT ( 'NONE', ( -39.79500347691000428, 182.5468005769366187, 106.5836252739005658 ) ) ; -#8367 = CARTESIAN_POINT ( 'NONE', ( -25.60482130047309823, 148.7605380546862079, 204.9143772511571910 ) ) ; -#8368 = CARTESIAN_POINT ( 'NONE', ( 40.49581267819608854, 84.18892247206676416, 282.5307213418886931 ) ) ; -#8369 = ORIENTED_EDGE ( 'NONE', *, *, #21373, .T. ) ; -#8370 = VECTOR ( 'NONE', #33077, 1000.000000000000227 ) ; -#8371 = CARTESIAN_POINT ( 'NONE', ( -13.46869826275617754, 154.0042694268834111, 95.55785016883520200 ) ) ; -#8372 = VERTEX_POINT ( 'NONE', #26887 ) ; -#8373 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#8374 = CARTESIAN_POINT ( 'NONE', ( -42.14140742790571181, 120.7945795707638297, 90.64491201421904520 ) ) ; -#8375 = CIRCLE ( 'NONE', #36439, 7.499999999987333688 ) ; -#8376 = LINE ( 'NONE', #23298, #24842 ) ; -#8377 = DIRECTION ( 'NONE', ( -0.0005884949961131590327, 0.2249510543438973387, -0.9743698870671282375 ) ) ; -#8378 = CARTESIAN_POINT ( 'NONE', ( -23.41217839213117813, 214.0714960154889468, 73.07264445148327070 ) ) ; -#8379 = CARTESIAN_POINT ( 'NONE', ( 13.88517613221250713, 135.5848694388539002, 93.51252930518586481 ) ) ; -#8380 = CARTESIAN_POINT ( 'NONE', ( 3.666638755409086681, 184.0129645450027738, 102.6466012127862371 ) ) ; -#8381 = CARTESIAN_POINT ( 'NONE', ( -25.80849207073569218, 209.7108689636089025, 73.27563589262052801 ) ) ; -#8382 = CARTESIAN_POINT ( 'NONE', ( 37.59407280179000566, 112.0479120775361821, 151.0714151308390854 ) ) ; -#8383 = CARTESIAN_POINT ( 'NONE', ( 38.65917831171999808, 118.7960982540000003, 87.80084228631000087 ) ) ; -#8384 = CARTESIAN_POINT ( 'NONE', ( 20.48051720016978550, 208.3330510408972884, 73.76180694069462618 ) ) ; -#8385 = CARTESIAN_POINT ( 'NONE', ( 38.30233299830000959, 119.0433665966999968, 90.39987451477999514 ) ) ; -#8386 = EDGE_LOOP ( 'NONE', ( #616, #18197, #32293, #38608 ) ) ; -#8387 = CARTESIAN_POINT ( 'NONE', ( 15.50176591790000025, 174.8481220399000335, 103.0893428321000016 ) ) ; -#8388 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12273, #27235, #39660, #18383 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999975533700791175 ), - .UNSPECIFIED. ) ; -#8389 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971546529 ) ) ; -#8390 = CARTESIAN_POINT ( 'NONE', ( -23.36170564740040234, 182.0604262685139361, 102.2121465934016129 ) ) ; -#8391 = CARTESIAN_POINT ( 'NONE', ( 26.01897932439291239, 191.0393230234643340, 106.8210248016044375 ) ) ; -#8393 = ORIENTED_EDGE ( 'NONE', *, *, #36551, .F. ) ; -#8392 = FACE_OUTER_BOUND ( 'NONE', #25050, .T. ) ; -#8394 = ORIENTED_EDGE ( 'NONE', *, *, #24220, .T. ) ; -#8395 = VERTEX_POINT ( 'NONE', #14404 ) ; -#8396 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#8397 = EDGE_LOOP ( 'NONE', ( #18494, #2082, #35153, #35028 ) ) ; -#8398 = DIRECTION ( 'NONE', ( 0.0006039748319392653766, 3.841674172953530792E-18, 0.9999998176071845934 ) ) ; -#8399 = EDGE_CURVE ( 'NONE', #34665, #33491, #29542, .T. ) ; -#8400 = EDGE_CURVE ( 'NONE', #39173, #7664, #25210, .T. ) ; -#8401 = VECTOR ( 'NONE', #23850, 1000.000000000000114 ) ; -#8402 = CARTESIAN_POINT ( 'NONE', ( -94.40216589637994105, 221.9412051121879301, 195.0241205818432491 ) ) ; -#8403 = ORIENTED_EDGE ( 'NONE', *, *, #24984, .F. ) ; -#8404 = CARTESIAN_POINT ( 'NONE', ( -20.16489867514991730, 151.3249859477512018, 97.50919180760990912 ) ) ; -#8405 = EDGE_CURVE ( 'NONE', #32868, #189, #27395, .T. ) ; -#8406 = EDGE_CURVE ( 'NONE', #26291, #14524, #13006, .T. ) ; -#8407 = ORIENTED_EDGE ( 'NONE', *, *, #27949, .T. ) ; -#8408 = CARTESIAN_POINT ( 'NONE', ( -39.71020355217999764, 119.5364205527000081, 89.96485858007000047 ) ) ; -#8409 = DIRECTION ( 'NONE', ( -0.0005884949961259457879, 0.2249510543439049437, -0.9743698870671266832 ) ) ; -#8410 = CARTESIAN_POINT ( 'NONE', ( -31.19810823188564797, 110.6131156702000027, 87.28662716757878570 ) ) ; -#8411 = CARTESIAN_POINT ( 'NONE', ( -35.85197975471000120, 116.1896316198000108, 87.15460714735000636 ) ) ; -#8412 = EDGE_LOOP ( 'NONE', ( #11520, #19501, #22417, #37945 ) ) ; -#8413 = ADVANCED_FACE ( 'NONE', ( #20523 ), #11326, .T. ) ; -#8414 = PLANE ( 'NONE', #22563 ) ; -#8415 = CARTESIAN_POINT ( 'NONE', ( 4.404252103613135461, 188.0359524915844815, 103.0617836839577421 ) ) ; -#8416 = CARTESIAN_POINT ( 'NONE', ( 20.50146814542411278, 184.4050074329408915, 104.7795556516932436 ) ) ; -#8417 = LINE ( 'NONE', #29676, #19542 ) ; -#8418 = CARTESIAN_POINT ( 'NONE', ( -12.63730865053593000, 181.2845053770731738, 104.3593437533184556 ) ) ; -#8419 = EDGE_LOOP ( 'NONE', ( #866, #26047, #6716, #22645 ) ) ; -#8420 = EDGE_CURVE ( 'NONE', #22426, #29452, #12508, .T. ) ; -#8421 = EDGE_LOOP ( 'NONE', ( #39712, #12937, #12869, #13540 ) ) ; -#8422 = CARTESIAN_POINT ( 'NONE', ( 20.50029254611199292, 184.8549113859068029, 102.8308091169877798 ) ) ; -#8423 = CARTESIAN_POINT ( 'NONE', ( 0.5945401647096061337, 189.0170313296219717, 103.6953509331899852 ) ) ; -#8424 = CARTESIAN_POINT ( 'NONE', ( 26.78494046123167394, 122.8681522354715838, 91.08200428504154900 ) ) ; -#8425 = ORIENTED_EDGE ( 'NONE', *, *, #9028, .T. ) ; -#8426 = CARTESIAN_POINT ( 'NONE', ( -0.4015627557743999820, 191.0000000000000000, 162.9824824849000322 ) ) ; -#8427 = ORIENTED_EDGE ( 'NONE', *, *, #13113, .T. ) ; -#8428 = EDGE_CURVE ( 'NONE', #29659, #12341, #13967, .T. ) ; -#8429 = CIRCLE ( 'NONE', #24754, 2.000000000183163262 ) ; -#8430 = CIRCLE ( 'NONE', #31270, 2.500000000049116711 ) ; -#8431 = ORIENTED_EDGE ( 'NONE', *, *, #31405, .F. ) ; -#8432 = DIRECTION ( 'NONE', ( -0.7066905234111825473, -0.1590644036919597049, 0.6894106320611468330 ) ) ; -#8433 = CIRCLE ( 'NONE', #37803, 8.000000000000007105 ) ; -#8434 = ORIENTED_EDGE ( 'NONE', *, *, #17107, .T. ) ; -#8435 = CARTESIAN_POINT ( 'NONE', ( 22.66333107552271287, 213.5901743958560814, 73.54467151608274378 ) ) ; -#8436 = AXIS2_PLACEMENT_3D ( 'NONE', #7745, #26183, #14109 ) ; -#8437 = CARTESIAN_POINT ( 'NONE', ( 17.25783335673383689, 152.2632692426403196, 183.6728012514050477 ) ) ; -#8438 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173983415, 185.7936928887390025, 103.0680828614480760 ) ) ; -#8439 = ORIENTED_EDGE ( 'NONE', *, *, #7545, .T. ) ; -#8440 = CARTESIAN_POINT ( 'NONE', ( 28.66350241469961446, 179.7814215269904139, 27.86386413335047507 ) ) ; -#8441 = VERTEX_POINT ( 'NONE', #2927 ) ; -#8442 = CARTESIAN_POINT ( 'NONE', ( 26.06074785331999877, 120.9057430171999954, 90.62944187114999295 ) ) ; -#8443 = FACE_OUTER_BOUND ( 'NONE', #35805, .T. ) ; -#8445 = CARTESIAN_POINT ( 'NONE', ( -42.82182963578055990, 189.4469289804731602, 106.3937290658157622 ) ) ; -#8444 = CARTESIAN_POINT ( 'NONE', ( 15.59065710782552650, 147.2783093505951229, 179.8436489131068186 ) ) ; -#8446 = EDGE_LOOP ( 'NONE', ( #34323, #15046, #18007, #25023 ) ) ; -#8447 = ORIENTED_EDGE ( 'NONE', *, *, #37980, .T. ) ; -#8448 = CARTESIAN_POINT ( 'NONE', ( 36.04645032798080706, 209.7096537570166390, 75.53673338561257822 ) ) ; -#8449 = ADVANCED_FACE ( 'NONE', ( #21359 ), #27912, .T. ) ; -#8450 = EDGE_CURVE ( 'NONE', #34762, #22424, #8625, .T. ) ; -#8451 = ORIENTED_EDGE ( 'NONE', *, *, #18573, .F. ) ; -#8452 = LINE ( 'NONE', #23990, #21133 ) ; -#8453 = AXIS2_PLACEMENT_3D ( 'NONE', #22884, #7522, #13080 ) ; -#8454 = DIRECTION ( 'NONE', ( -0.6087614109020677011, -0.7729348355671219473, -0.1788331193133700647 ) ) ; -#8455 = CARTESIAN_POINT ( 'NONE', ( -35.93925701852640486, 191.9759150222000130, 101.9431537509654220 ) ) ; -#8456 = ORIENTED_EDGE ( 'NONE', *, *, #20814, .T. ) ; -#8457 = AXIS2_PLACEMENT_3D ( 'NONE', #25882, #12792, #501 ) ; -#8458 = AXIS2_PLACEMENT_3D ( 'NONE', #36014, #5139, #4533 ) ; -#8459 = DIRECTION ( 'NONE', ( -0.0008702530711002103318, 0.2253087760482092305, -0.9742870203873447155 ) ) ; -#8460 = AXIS2_PLACEMENT_3D ( 'NONE', #25036, #34788, #71 ) ; -#8461 = CARTESIAN_POINT ( 'NONE', ( -30.07180902684082469, 134.5538535379703262, 93.54580703498288585 ) ) ; -#8462 = CARTESIAN_POINT ( 'NONE', ( 13.50718655633492382, 188.3455032986072979, 103.1278069412195748 ) ) ; -#8463 = EDGE_CURVE ( 'NONE', #37032, #25663, #21566, .T. ) ; -#8464 = ORIENTED_EDGE ( 'NONE', *, *, #3901, .T. ) ; -#8465 = LINE ( 'NONE', #37071, #11499 ) ; -#8466 = CARTESIAN_POINT ( 'NONE', ( 2.297205121341999945, 189.9561994427999991, 106.0117969655000110 ) ) ; -#8467 = EDGE_LOOP ( 'NONE', ( #4144, #19241, #3798, #32744, #18962, #3996, #25994, #30086, #3782, #17288, #23610, #9626 ) ) ; -#8468 = CARTESIAN_POINT ( 'NONE', ( 39.04675176836854433, 209.7096538831000316, 76.03492163576670748 ) ) ; -#8469 = ADVANCED_FACE ( 'NONE', ( #37087 ), #40337, .F. ) ; -#8470 = FACE_OUTER_BOUND ( 'NONE', #27960, .T. ) ; -#8471 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; -#8472 = CARTESIAN_POINT ( 'NONE', ( 5.217102900732569104, 135.0871424630537945, 181.2784941562133270 ) ) ; -#8473 = ORIENTED_EDGE ( 'NONE', *, *, #23307, .F. ) ; -#8474 = CARTESIAN_POINT ( 'NONE', ( 25.99186909154838787, 205.2975165461204483, 75.64064060287584823 ) ) ; -#8475 = DIRECTION ( 'NONE', ( -2.355754480376490302E-12, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#8476 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; -#8477 = ORIENTED_EDGE ( 'NONE', *, *, #38625, .F. ) ; -#8478 = CONICAL_SURFACE ( 'NONE', #18293, 2.503080759942041489, 0.7853981634198553552 ) ; -#8479 = VECTOR ( 'NONE', #2203, 1000.000000000000000 ) ; -#8480 = CARTESIAN_POINT ( 'NONE', ( 39.79988895049328335, 119.8651423291884726, 87.81508310122019623 ) ) ; -#8481 = VERTEX_POINT ( 'NONE', #24436 ) ; -#8482 = AXIS2_PLACEMENT_3D ( 'NONE', #33300, #17751, #27203 ) ; -#8484 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921578520, -0.2249510932971593991 ) ) ; -#8483 = CARTESIAN_POINT ( 'NONE', ( -15.99823277108970743, 185.2321969574450975, 105.5057198903149782 ) ) ; -#8485 = ORIENTED_EDGE ( 'NONE', *, *, #33500, .F. ) ; -#8486 = VERTEX_POINT ( 'NONE', #24843 ) ; -#8487 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971560961 ) ) ; -#8488 = ORIENTED_EDGE ( 'NONE', *, *, #3523, .T. ) ; -#8489 = CARTESIAN_POINT ( 'NONE', ( 2.926120382530000175, 209.1401824993000389, 76.01042625537000674 ) ) ; -#8490 = CARTESIAN_POINT ( 'NONE', ( 37.17435508146867562, 191.1177037234376428, 106.3028558592205002 ) ) ; -#8491 = CARTESIAN_POINT ( 'NONE', ( 12.63930000360815775, 177.2888256666688562, 101.0070828283669471 ) ) ; -#8492 = ADVANCED_FACE ( 'NONE', ( #30556 ), #10386, .F. ) ; -#8493 = ORIENTED_EDGE ( 'NONE', *, *, #21424, .F. ) ; -#8494 = EDGE_CURVE ( 'NONE', #16249, #1239, #30555, .T. ) ; -#8495 = EDGE_LOOP ( 'NONE', ( #21630, #26153 ) ) ; -#8496 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#8497 = ORIENTED_EDGE ( 'NONE', *, *, #14007, .F. ) ; -#8498 = ORIENTED_EDGE ( 'NONE', *, *, #21233, .F. ) ; -#8499 = CYLINDRICAL_SURFACE ( 'NONE', #28294, 2.000000000000014655 ) ; -#8500 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971557076 ) ) ; -#8501 = CARTESIAN_POINT ( 'NONE', ( -20.49970532888763941, 191.4139234226054498, 104.3698659823340478 ) ) ; -#8502 = CARTESIAN_POINT ( 'NONE', ( 12.63943526405010154, 181.6152899300451509, 104.1402435546899170 ) ) ; -#8503 = VERTEX_POINT ( 'NONE', #18053 ) ; -#8504 = EDGE_LOOP ( 'NONE', ( #16462, #39338, #32922, #6245, #34889, #39965, #24208, #23027, #13012 ) ) ; -#8505 = DIRECTION ( 'NONE', ( 0.7933535325932939974, -0.5931614258681802143, -0.1369295263402624252 ) ) ; -#8506 = CARTESIAN_POINT ( 'NONE', ( -36.08104566930000345, 192.3950126661999889, 104.5573297432000004 ) ) ; -#8507 = CARTESIAN_POINT ( 'NONE', ( 36.22716640846000047, 191.3195042085999944, 103.6679230210999947 ) ) ; -#8508 = CARTESIAN_POINT ( 'NONE', ( -25.50305200493978219, 120.5913031158892750, 88.01798731102564943 ) ) ; -#8509 = VECTOR ( 'NONE', #28374, 1000.000000000000227 ) ; -#8510 = ORIENTED_EDGE ( 'NONE', *, *, #10341, .T. ) ; -#8511 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; -#8512 = FACE_OUTER_BOUND ( 'NONE', #31279, .T. ) ; -#8513 = ORIENTED_EDGE ( 'NONE', *, *, #21704, .T. ) ; -#8514 = AXIS2_PLACEMENT_3D ( 'NONE', #30818, #27764, #12214 ) ; -#8515 = CARTESIAN_POINT ( 'NONE', ( 0.7483071947399341228, 188.6199125398798628, 103.1988096077017616 ) ) ; -#8516 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562904 ) ) ; -#8517 = CARTESIAN_POINT ( 'NONE', ( -14.56364043194524882, 124.5953383809047779, 88.42681732072288980 ) ) ; -#8518 = ORIENTED_EDGE ( 'NONE', *, *, #13441, .F. ) ; -#8519 = CARTESIAN_POINT ( 'NONE', ( -21.44693681792356443, 182.5559435529752363, 101.8122371725110611 ) ) ; -#8520 = EDGE_CURVE ( 'NONE', #40259, #14084, #36483, .T. ) ; -#8521 = CARTESIAN_POINT ( 'NONE', ( 1.677769475863515547, 189.3391757884121773, 103.7816631172656088 ) ) ; -#8522 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#8523 = EDGE_LOOP ( 'NONE', ( #4040, #5882, #34548 ) ) ; -#8524 = CARTESIAN_POINT ( 'NONE', ( -25.50901378188272872, 210.6290357530666597, 75.57427749355011315 ) ) ; -#8525 = ORIENTED_EDGE ( 'NONE', *, *, #20187, .F. ) ; -#8526 = ORIENTED_EDGE ( 'NONE', *, *, #21800, .T. ) ; -#8527 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568178 ) ) ; -#8528 = PLANE ( 'NONE', #15967 ) ; -#8529 = CARTESIAN_POINT ( 'NONE', ( 35.67769589643999950, 112.3628679466000051, 90.12501460967999378 ) ) ; -#8530 = CARTESIAN_POINT ( 'NONE', ( 39.06373257172650426, 191.2886342178498751, 104.1338925413297432 ) ) ; -#8531 = VERTEX_POINT ( 'NONE', #34202 ) ; -#8532 = ADVANCED_FACE ( 'NONE', ( #3133 ), #28646, .F. ) ; -#8533 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15838, #19307, #37719, #22606 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8534 = CARTESIAN_POINT ( 'NONE', ( -45.98534017754115411, 187.3083424662111725, 103.4373877126195680 ) ) ; -#8535 = AXIS2_PLACEMENT_3D ( 'NONE', #31190, #18088, #5843 ) ; -#8536 = EDGE_CURVE ( 'NONE', #39629, #37162, #21488, .T. ) ; -#8537 = VECTOR ( 'NONE', #33877, 1000.000000000000000 ) ; -#8538 = CARTESIAN_POINT ( 'NONE', ( -14.13194399373848142, 115.2628856887303073, 152.7619685138874104 ) ) ; -#8539 = CARTESIAN_POINT ( 'NONE', ( -3.776848093818052199, 137.2994165897591188, 91.59881672241711215 ) ) ; -#8540 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25989, #4486, #20643, #1425 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8541 = AXIS2_PLACEMENT_3D ( 'NONE', #22724, #38839, #4703 ) ; -#8542 = CARTESIAN_POINT ( 'NONE', ( 19.01953534574752069, 125.4129100880593057, 176.1943672198347883 ) ) ; -#8543 = CARTESIAN_POINT ( 'NONE', ( 32.40151345882750888, 176.2355478910340310, 100.3205354780729692 ) ) ; -#8544 = AXIS2_PLACEMENT_3D ( 'NONE', #26203, #35969, #7567 ) ; -#8545 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#8546 = EDGE_CURVE ( 'NONE', #39814, #21071, #19308, .T. ) ; -#8547 = ADVANCED_FACE ( 'NONE', ( #28690 ), #24105, .T. ) ; -#8548 = CARTESIAN_POINT ( 'NONE', ( 15.10714335843527145, 176.3834766976846993, 100.3651329064352922 ) ) ; -#8549 = ORIENTED_EDGE ( 'NONE', *, *, #32169, .T. ) ; -#8550 = VERTEX_POINT ( 'NONE', #10090 ) ; -#8551 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099476, 182.4219699177349128, 101.7574819547242697 ) ) ; -#8552 = DIRECTION ( 'NONE', ( 0.7075227875440994740, -0.1589708073325998561, 0.6885780910846993619 ) ) ; -#8553 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#8554 = EDGE_LOOP ( 'NONE', ( #18096, #20893 ) ) ; -#8555 = CARTESIAN_POINT ( 'NONE', ( 77.74752315181704887, 192.2565373609087089, 194.3622733290381461 ) ) ; -#8556 = EDGE_LOOP ( 'NONE', ( #38056, #18468, #35809, #14660 ) ) ; -#8557 = CARTESIAN_POINT ( 'NONE', ( -17.26180060959741525, 121.6800750551767578, 175.7628748181817855 ) ) ; -#8558 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251390299, 179.1753088543660510, 103.5954339978240029 ) ) ; -#8559 = CARTESIAN_POINT ( 'NONE', ( 30.03524845263000032, 185.6785554479999973, 102.7586311877000185 ) ) ; -#8560 = EDGE_LOOP ( 'NONE', ( #25147, #2906, #24691, #4620 ) ) ; -#8561 = DIRECTION ( 'NONE', ( 0.7855817641270325113, 0.6187578620680785901, 0.000000000000000000 ) ) ; -#8562 = CARTESIAN_POINT ( 'NONE', ( -37.31440426593247395, 172.2715631620466468, 165.0215178663606252 ) ) ; -#8563 = DIRECTION ( 'NONE', ( -6.938893903762204978E-15, 0.9743700557921589622, 0.2249510932971546529 ) ) ; -#8564 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971549582 ) ) ; -#8565 = DIRECTION ( 'NONE', ( 0.9914448404770122014, 0.1271187482266248059, 0.02963025718429710201 ) ) ; -#8566 = EDGE_LOOP ( 'NONE', ( #20303, #15071, #22485, #12550 ) ) ; -#8567 = AXIS2_PLACEMENT_3D ( 'NONE', #11791, #9119, #36714 ) ; -#8568 = CARTESIAN_POINT ( 'NONE', ( -41.13832148997259708, 182.7434276679351797, 104.9463272867566133 ) ) ; -#8569 = ADVANCED_FACE ( 'NONE', ( #10298 ), #14287, .F. ) ; -#8570 = CARTESIAN_POINT ( 'NONE', ( -44.12429222051905242, 188.3338783572263253, 106.2387882118758995 ) ) ; -#8571 = DIRECTION ( 'NONE', ( 0.7857167650892390443, -0.6185862428610306996, -0.0004745532376930882020 ) ) ; -#8572 = CONICAL_SURFACE ( 'NONE', #33359, 5.000000000095701225, 0.7853981634197699790 ) ; -#8573 = CARTESIAN_POINT ( 'NONE', ( 16.79405117887437271, 152.3217338832941721, 181.8411719429184075 ) ) ; -#8574 = ORIENTED_EDGE ( 'NONE', *, *, #37287, .T. ) ; -#8575 = EDGE_LOOP ( 'NONE', ( #8228, #12816, #22601, #22747 ) ) ; -#8576 = DIRECTION ( 'NONE', ( 0.7856637144487861324, -0.6186538028643616682, 0.000000000000000000 ) ) ; -#8577 = CARTESIAN_POINT ( 'NONE', ( -40.97271368781576228, 120.4617346393614525, 90.56736283153441036 ) ) ; -#8578 = DIRECTION ( 'NONE', ( 0.0005734119072325851883, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#8579 = CARTESIAN_POINT ( 'NONE', ( 35.04645051037203984, 217.7719116314000019, 75.53733736051518122 ) ) ; -#8580 = CARTESIAN_POINT ( 'NONE', ( 12.63462730242783572, 181.0589446024862639, 104.4878890928621615 ) ) ; -#8581 = CARTESIAN_POINT ( 'NONE', ( 36.04737028554169598, 207.4083918097923629, 77.05990514452676621 ) ) ; -#8582 = ADVANCED_FACE ( 'NONE', ( #3331 ), #29955, .F. ) ; -#8583 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971550969 ) ) ; -#8584 = CARTESIAN_POINT ( 'NONE', ( -43.65360665174738841, 185.3905100451317765, 107.6115822775834374 ) ) ; -#8585 = CARTESIAN_POINT ( 'NONE', ( 20.48136443024816344, 209.7093559074854454, 75.54613107284740181 ) ) ; -#8586 = ADVANCED_FACE ( 'NONE', ( #13164 ), #33194, .T. ) ; -#8587 = DATE_AND_TIME ( #5494, #5527 ) ; -#8588 = CARTESIAN_POINT ( 'NONE', ( 26.89533298033946096, 123.7171680322964562, 88.19903550279475724 ) ) ; -#8589 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#8590 = EDGE_CURVE ( 'NONE', #12877, #30394, #13553, .T. ) ; -#8591 = CARTESIAN_POINT ( 'NONE', ( 17.27144951970729991, 122.5453306081213043, 172.0736587966182469 ) ) ; -#8592 = DIRECTION ( 'NONE', ( -0.0004270746993301994870, 0.7071067811864992780, -0.7071066522153991452 ) ) ; -#8593 = FACE_OUTER_BOUND ( 'NONE', #12767, .T. ) ; -#8594 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971550969 ) ) ; -#8595 = VECTOR ( 'NONE', #35320, 1000.000000000000227 ) ; -#8596 = EDGE_CURVE ( 'NONE', #35367, #36684, #19064, .T. ) ; -#8597 = EDGE_LOOP ( 'NONE', ( #22798, #820, #24849, #8434 ) ) ; -#8598 = CARTESIAN_POINT ( 'NONE', ( -20.50006521734148990, 193.1656132470480429, 104.1466103976766107 ) ) ; -#8599 = ORIENTED_EDGE ( 'NONE', *, *, #30832, .T. ) ; -#8600 = ORIENTED_EDGE ( 'NONE', *, *, #37377, .F. ) ; -#8601 = EDGE_CURVE ( 'NONE', #4106, #4933, #22741, .T. ) ; -#8602 = ORIENTED_EDGE ( 'NONE', *, *, #29815, .T. ) ; -#8603 = CONICAL_SURFACE ( 'NONE', #16393, 5.999999999898478542, 0.7853981633778843729 ) ; -#8604 = CARTESIAN_POINT ( 'NONE', ( -25.50112048447915569, 120.6553735626000048, 88.03695903724376137 ) ) ; -#8605 = ADVANCED_FACE ( 'NONE', ( #34401 ), #6444, .F. ) ; -#8606 = EDGE_LOOP ( 'NONE', ( #19912, #2683, #22465, #18068 ) ) ; -#8607 = DIRECTION ( 'NONE', ( 0.1779895592101686796, 0.3532431349384635433, -0.9184437949221587738 ) ) ; -#8608 = DIRECTION ( 'NONE', ( -0.7069397808361403968, 0.6508952239913371463, 0.2767156548817158446 ) ) ; -#8609 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#8610 = ORIENTED_EDGE ( 'NONE', *, *, #14635, .F. ) ; -#8611 = LINE ( 'NONE', #27442, #10074 ) ; -#8612 = CARTESIAN_POINT ( 'NONE', ( -77.80691370946981067, 191.9356020547612900, 194.2498739115223145 ) ) ; -#8613 = DIRECTION ( 'NONE', ( 0.0005884949961204579902, -0.2249510543439042221, 0.9743698870671267942 ) ) ; -#8614 = PLANE ( 'NONE', #7339 ) ; -#8615 = ORIENTED_EDGE ( 'NONE', *, *, #40085, .T. ) ; -#8616 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319377338326 ) ) ; -#8617 = FACE_OUTER_BOUND ( 'NONE', #4059, .T. ) ; -#8618 = FACE_OUTER_BOUND ( 'NONE', #1219, .T. ) ; -#8619 = CARTESIAN_POINT ( 'NONE', ( 36.19813064229271049, 115.7978980914772364, 90.24592207534902855 ) ) ; -#8620 = CARTESIAN_POINT ( 'NONE', ( 36.05382442431439216, 109.6131156806000035, 87.74600877644128616 ) ) ; -#8621 = EDGE_LOOP ( 'NONE', ( #1130, #33920, #15739, #19058 ) ) ; -#8622 = CARTESIAN_POINT ( 'NONE', ( -40.95638651213572956, 220.4002260740000168, 73.58324080466404382 ) ) ; -#8623 = CARTESIAN_POINT ( 'NONE', ( 0.9444534192402208594, 189.0472900984059663, 103.7089565807309981 ) ) ; -#8624 = CARTESIAN_POINT ( 'NONE', ( 28.14966852377056483, 124.3573228059849498, 91.42498220208800319 ) ) ; -#8625 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30958, #27704, #37285, #5395, #27516, #40141, #12153, #6200, #33604, #33806, #15418 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000685563, 0.3750000000001185163, 0.4375000000001610378, 0.4687500000001221800, 0.5000000000000832667, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8626 = ORIENTED_EDGE ( 'NONE', *, *, #12535, .F. ) ; -#8627 = EDGE_LOOP ( 'NONE', ( #15570, #38780, #2212, #20657 ) ) ; -#8628 = CONICAL_SURFACE ( 'NONE', #13827, 5.000000000037475800, 0.7853981634506773668 ) ; -#8629 = CARTESIAN_POINT ( 'NONE', ( 20.25161797161999999, 187.6280213585999945, 105.7803707432999971 ) ) ; -#8630 = ORIENTED_EDGE ( 'NONE', *, *, #16146, .T. ) ; -#8631 = AXIS2_PLACEMENT_3D ( 'NONE', #9375, #12625, #12042 ) ; -#8632 = VECTOR ( 'NONE', #3425, 1000.000000000000114 ) ; -#8633 = EDGE_CURVE ( 'NONE', #7007, #26180, #4126, .T. ) ; -#8634 = ADVANCED_FACE ( 'NONE', ( #18857 ), #7203, .T. ) ; -#8635 = ORIENTED_EDGE ( 'NONE', *, *, #28305, .T. ) ; -#8636 = EDGE_CURVE ( 'NONE', #28271, #13439, #16598, .T. ) ; -#8637 = ORIENTED_EDGE ( 'NONE', *, *, #4065, .T. ) ; -#8638 = CARTESIAN_POINT ( 'NONE', ( -37.05605030574000125, 191.0258856046000062, 106.5406989459000044 ) ) ; -#8639 = DIRECTION ( 'NONE', ( 0.9999998268367130683, 0.0001323824760006246388, -0.0005734120890906795271 ) ) ; -#8640 = CARTESIAN_POINT ( 'NONE', ( 38.59086485963890567, 79.69179921679354095, 285.2955982571226059 ) ) ; -#8641 = EDGE_CURVE ( 'NONE', #8771, #29915, #1069, .T. ) ; -#8642 = ORIENTED_EDGE ( 'NONE', *, *, #24712, .T. ) ; -#8643 = LINE ( 'NONE', #5549, #19836 ) ; -#8644 = ORIENTED_EDGE ( 'NONE', *, *, #23925, .T. ) ; -#8645 = EDGE_CURVE ( 'NONE', #662, #16108, #20161, .T. ) ; -#8646 = CARTESIAN_POINT ( 'NONE', ( 26.02775071507020499, 120.6384143230500143, 90.56953989852389952 ) ) ; -#8647 = CARTESIAN_POINT ( 'NONE', ( -26.01003256183229695, 210.6300345901000242, 76.07590184482684492 ) ) ; -#8649 = CARTESIAN_POINT ( 'NONE', ( 40.49581267819608854, 84.18892247206676416, 282.5307213418886931 ) ) ; -#8648 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825959531803938, 0.0005734119014747785219 ) ) ; -#8650 = EDGE_LOOP ( 'NONE', ( #17019, #26307, #5725, #38933, #21921, #39958, #9306, #4101, #26925, #25906 ) ) ; -#8651 = EDGE_CURVE ( 'NONE', #1667, #5335, #37685, .T. ) ; -#8652 = VERTEX_POINT ( 'NONE', #34596 ) ; -#8653 = CARTESIAN_POINT ( 'NONE', ( 20.02704401006072743, 117.6316107474358432, 87.25568845928445683 ) ) ; -#8654 = VECTOR ( 'NONE', #29626, 1000.000000000000114 ) ; -#8655 = ORIENTED_EDGE ( 'NONE', *, *, #10107, .F. ) ; -#8657 = AXIS2_PLACEMENT_3D ( 'NONE', #22004, #36858, #33782 ) ; -#8656 = FACE_OUTER_BOUND ( 'NONE', #32622, .T. ) ; -#8658 = EDGE_CURVE ( 'NONE', #10328, #38615, #6594, .T. ) ; -#8659 = CONICAL_SURFACE ( 'NONE', #6012, 2.249999999984611421, 0.7853981634347277918 ) ; -#8660 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5220, #14244, #35673, #29576 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8661 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#8662 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#8663 = CARTESIAN_POINT ( 'NONE', ( 12.63659917731993865, 130.8565322054421927, 89.99855747202538225 ) ) ; -#8664 = CARTESIAN_POINT ( 'NONE', ( -12.64352839772552173, 134.9564157408762242, 90.87116896037730385 ) ) ; -#8665 = VERTEX_POINT ( 'NONE', #25436 ) ; -#8666 = ORIENTED_EDGE ( 'NONE', *, *, #3401, .F. ) ; -#8667 = CARTESIAN_POINT ( 'NONE', ( -1.429316825074233188, 189.2366094587022474, 103.7538750078491034 ) ) ; -#8668 = CARTESIAN_POINT ( 'NONE', ( 20.50147137495634198, 190.9646546281344683, 106.2940065278771016 ) ) ; -#8669 = CYLINDRICAL_SURFACE ( 'NONE', #34658, 40.00000000000000000 ) ; -#8670 = CARTESIAN_POINT ( 'NONE', ( 25.66514228811999843, 121.0763891642999965, 87.93230023964001418 ) ) ; -#8671 = VERTEX_POINT ( 'NONE', #9897 ) ; -#8672 = ORIENTED_EDGE ( 'NONE', *, *, #32541, .F. ) ; -#8673 = CARTESIAN_POINT ( 'NONE', ( 35.54675198585685791, 209.7096512551739238, 76.03703539298859937 ) ) ; -#8674 = CARTESIAN_POINT ( 'NONE', ( 2.321157821276000455, 189.0697464220000086, 106.3805944500000038 ) ) ; -#8675 = ORIENTED_EDGE ( 'NONE', *, *, #38836, .F. ) ; -#8676 = CARTESIAN_POINT ( 'NONE', ( 5.669776689925148716, 130.9358280359080595, 89.95242648389140072 ) ) ; -#8677 = LINE ( 'NONE', #40329, #2622 ) ; -#8678 = LINE ( 'NONE', #21140, #13062 ) ; -#8679 = CIRCLE ( 'NONE', #25672, 16.50000000000000000 ) ; -#8680 = ADVANCED_FACE ( 'NONE', ( #22368 ), #34791, .F. ) ; -#8681 = VERTEX_POINT ( 'NONE', #1689 ) ; -#8682 = ADVANCED_FACE ( 'NONE', ( #10501 ), #29990, .F. ) ; -#8683 = AXIS2_PLACEMENT_3D ( 'NONE', #18735, #36564, #5692 ) ; -#8684 = ADVANCED_FACE ( 'NONE', ( #30110 ), #19518, .T. ) ; -#8685 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14038, #35882, #29785, #7684, #7888, #1344, #26312, #4615, #20351, #14242, #26716, #39164, #8096, #20558, #33027, #29977, #14441, #39361, #11361, #11788, #28472, #2379, #22143, #8515, #36711, #31146, #25020, #6380, #37465, #25218, #24053, #12939, #31752, #3500, #20982, #21945, #34774, #33435, #21745, #18834, #6775, #31342, #3713, #15587, #243, #39767, #3313, #12725, #25418, #34572, #9467, #15985, #19245, #17884, #37668, #9668, #34184, #36513, #16189, #453, #5426, #27340, #15782, #6184, #37869, #28277, #9874, #30382, #18637, #6574, #19048, #22351, #24268, #12516, #31541, #28672 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 1, 1, 1, 2, 2, 1, 1, 2, 2, 1, 1, 2, 2, 1, 1, 1, 1, 2, 2, 1, 1, 1, 1, 1, 1, 1, 2, 2, 1, 1, 1, 1, 1, 1, 2, 2, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.03124999999947112445, 0.04687499999920669014, 0.06249999999894224889, 0.09374999999841299170, 0.1093749999981470239, 0.1249999999978810561, 0.1562499999973329667, 0.1874999999967849051, 0.2187499999962368158, 0.2343749999959629238, 0.2421874999958204266, 0.2460937499957437380, 0.2499999999956670493, 0.2812499999958106844, 0.2968749999958828489, 0.3046874999959189312, 0.3124999999959550134, 0.3437499999960999530, 0.3593749999961756147, 0.3671874999962137509, 0.3749999999962518871, 0.4374999999965747954, 0.4687499999967366660, 0.4843749999968176567, 0.4921874999968535169, 0.4960937499968759434, 0.4999999999968983699, 0.6249999999975812681, 0.6874999999979228837, 0.7187499999980997423, 0.7343749999981823429, 0.7421874999982177590, 0.7460937499982416288, 0.7480468749982472909, 0.7490234374982557286, 0.7499999999982641663, 0.8124999999985818011, 0.8437499999987405630, 0.8593749999988243848, 0.8671874999988656851, 0.8710937499988817834, 0.8730468749988948840, 0.8740234374989059862, 0.8749999999989169774, 0.9062499999992081889, 0.9218749999993504085, 0.9296874999994176880, 0.9335937499994479971, 0.9355468749994635402, 0.9374999999994790834, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8686 = CARTESIAN_POINT ( 'NONE', ( 15.58035690247840144, 137.1114215606455389, 91.29817711239832079 ) ) ; -#8687 = LINE ( 'NONE', #21144, #20851 ) ; -#8688 = VECTOR ( 'NONE', #15361, 1000.000000000000000 ) ; -#8689 = ORIENTED_EDGE ( 'NONE', *, *, #14697, .F. ) ; -#8690 = ADVANCED_FACE ( 'NONE', ( #32365 ), #18870, .F. ) ; -#8691 = CARTESIAN_POINT ( 'NONE', ( -13.82977187757395221, 154.4043701110990128, 95.30833257247996926 ) ) ; -#8692 = VERTEX_POINT ( 'NONE', #38677 ) ; -#8694 = CARTESIAN_POINT ( 'NONE', ( -41.95974523811950263, 77.14301703112136011, 284.1899085454229521 ) ) ; -#8693 = DIRECTION ( 'NONE', ( 0.0005884949961229014566, -0.2249510543439049715, 0.9743698870671266832 ) ) ; -#8695 = VERTEX_POINT ( 'NONE', #36224 ) ; -#8696 = ADVANCED_FACE ( 'NONE', ( #2102 ), #25449, .T. ) ; -#8697 = ORIENTED_EDGE ( 'NONE', *, *, #19800, .F. ) ; -#8698 = DIRECTION ( 'NONE', ( -4.163336342485308837E-15, 0.9743700557921587402, 0.2249510932971551525 ) ) ; -#8699 = VERTEX_POINT ( 'NONE', #13961 ) ; -#8700 = CARTESIAN_POINT ( 'NONE', ( 2.842207948177999821, 209.6286538536000137, 75.93572464195000293 ) ) ; -#8701 = CARTESIAN_POINT ( 'NONE', ( -2.952854090120908381, 209.7096538831000032, 78.06028844424199065 ) ) ; -#8702 = LINE ( 'NONE', #36280, #7034 ) ; -#8703 = ORIENTED_EDGE ( 'NONE', *, *, #15195, .T. ) ; -#8704 = VERTEX_POINT ( 'NONE', #4334 ) ; -#8705 = DIRECTION ( 'NONE', ( -0.0002393071182782277790, -0.2252352986010052460, 0.9743043687658488050 ) ) ; -#8706 = VERTEX_POINT ( 'NONE', #38886 ) ; -#8707 = VERTEX_POINT ( 'NONE', #14573 ) ; -#8708 = FACE_OUTER_BOUND ( 'NONE', #15779, .T. ) ; -#8709 = CYLINDRICAL_SURFACE ( 'NONE', #27664, 6.000000000000008882 ) ; -#8710 = DIRECTION ( 'NONE', ( 0.0004161288024354952049, -0.8480480898215656538, 0.5299191109846985714 ) ) ; -#8711 = CARTESIAN_POINT ( 'NONE', ( 23.31161622905471731, 134.9426957410666716, 90.79281772715843601 ) ) ; -#8712 = CIRCLE ( 'NONE', #31552, 40.50000000002204104 ) ; -#8713 = ORIENTED_EDGE ( 'NONE', *, *, #15088, .F. ) ; -#8714 = ORIENTED_EDGE ( 'NONE', *, *, #5315, .F. ) ; -#8715 = CYLINDRICAL_SURFACE ( 'NONE', #7591, 1.000000000000001554 ) ; -#8716 = CARTESIAN_POINT ( 'NONE', ( -36.30859555223000257, 191.9504843571999970, 104.5588447405000068 ) ) ; -#8717 = AXIS2_PLACEMENT_3D ( 'NONE', #5827, #18470, #12358 ) ; -#8718 = ORIENTED_EDGE ( 'NONE', *, *, #16763, .F. ) ; -#8719 = CARTESIAN_POINT ( 'NONE', ( -25.83465801582000054, 120.7303359361000048, 87.71237979401999496 ) ) ; -#8720 = ORIENTED_EDGE ( 'NONE', *, *, #18518, .F. ) ; -#8721 = CARTESIAN_POINT ( 'NONE', ( -21.21281380558005125, 182.9066539643694966, 104.4588199671594850 ) ) ; -#8722 = CARTESIAN_POINT ( 'NONE', ( 39.91788020334763587, 190.3182931183406481, 106.6461671755548508 ) ) ; -#8723 = VERTEX_POINT ( 'NONE', #10902 ) ; -#8724 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901141, 132.2978364233219963, 93.26432363102219369 ) ) ; -#8725 = CARTESIAN_POINT ( 'NONE', ( -15.14908912525229567, 124.9619667792663051, 88.51181376764675690 ) ) ; -#8726 = CARTESIAN_POINT ( 'NONE', ( 19.99933118494021755, 196.5785306413737601, 103.8628508136982731 ) ) ; -#8727 = CARTESIAN_POINT ( 'NONE', ( 23.36209697621471193, 182.0666116869439861, 102.1853546028109321 ) ) ; -#8728 = CARTESIAN_POINT ( 'NONE', ( -15.83177648456734943, 137.5598563050514258, 94.32865390342180945 ) ) ; -#8729 = ORIENTED_EDGE ( 'NONE', *, *, #8276, .T. ) ; -#8730 = CARTESIAN_POINT ( 'NONE', ( -0.4558744191268589985, 208.9999999999999716, 73.05877941917057683 ) ) ; -#8731 = ORIENTED_EDGE ( 'NONE', *, *, #16458, .T. ) ; -#8732 = EDGE_CURVE ( 'NONE', #21532, #39497, #11290, .T. ) ; -#8733 = LINE ( 'NONE', #15066, #21860 ) ; -#8734 = EDGE_CURVE ( 'NONE', #17312, #39158, #7480, .T. ) ; -#8735 = CARTESIAN_POINT ( 'NONE', ( 16.00200912906086614, 173.8361395730204322, 102.8554915256801650 ) ) ; -#8736 = CARTESIAN_POINT ( 'NONE', ( -25.50053198731683324, 120.4304220968047474, 89.01133250720081946 ) ) ; -#8737 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31093, #5, #3257, #28423 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8738 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; -#8739 = VECTOR ( 'NONE', #2048, 1000.000000000000114 ) ; -#8740 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971546251 ) ) ; -#8741 = ORIENTED_EDGE ( 'NONE', *, *, #39531, .T. ) ; -#8742 = EDGE_CURVE ( 'NONE', #10555, #33981, #11095, .T. ) ; -#8743 = VECTOR ( 'NONE', #32130, 1000.000000000000000 ) ; -#8744 = CARTESIAN_POINT ( 'NONE', ( -6.038835622038210005, 135.1607352200812215, 91.19296211258786400 ) ) ; -#8745 = VECTOR ( 'NONE', #5520, 1000.000000000000000 ) ; -#8746 = ORIENTED_EDGE ( 'NONE', *, *, #36386, .F. ) ; -#8747 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567345 ) ) ; -#8748 = CARTESIAN_POINT ( 'NONE', ( -20.49854722029782295, 184.1159485384492314, 104.7375718384251542 ) ) ; -#8749 = CARTESIAN_POINT ( 'NONE', ( 21.33595229338290622, 124.0143879427035642, 174.3475635039766587 ) ) ; -#8750 = DIRECTION ( 'NONE', ( 0.0005884949961244146776, -0.2249510543439057209, 0.9743698870671265722 ) ) ; -#8751 = CARTESIAN_POINT ( 'NONE', ( -17.26213291099019997, 152.2612616225560771, 183.6636115490260863 ) ) ; -#8752 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21075, #15147, #36401, #12078 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8753 = CARTESIAN_POINT ( 'NONE', ( -36.84324029226966957, 117.2651960508476634, 90.29003723313010710 ) ) ; -#8754 = VERTEX_POINT ( 'NONE', #8014 ) ; -#8755 = DIRECTION ( 'NONE', ( 0.0006039748319378514686, 1.190362635753271326E-14, 0.9999998176071847045 ) ) ; -#8756 = EDGE_CURVE ( 'NONE', #35118, #3175, #20696, .T. ) ; -#8757 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363196006660E-14, -0.9999998176071844824 ) ) ; -#8758 = ORIENTED_EDGE ( 'NONE', *, *, #33565, .T. ) ; -#8759 = CARTESIAN_POINT ( 'NONE', ( -20.33313815255117163, 174.4356457342066165, 100.2789485125420583 ) ) ; -#8760 = ORIENTED_EDGE ( 'NONE', *, *, #33318, .T. ) ; -#8761 = CARTESIAN_POINT ( 'NONE', ( -38.28386786901999983, 119.2293362182000038, 87.45079503396999598 ) ) ; -#8762 = CARTESIAN_POINT ( 'NONE', ( -5.668458121731908328, 130.7278572272551571, 90.08794464196098772 ) ) ; -#8763 = CARTESIAN_POINT ( 'NONE', ( 36.08489528552837555, 191.2182783123578247, 106.8419584201553079 ) ) ; -#8764 = AXIS2_PLACEMENT_3D ( 'NONE', #8629, #15164, #14958 ) ; -#8765 = CONICAL_SURFACE ( 'NONE', #40084, 2.502986836105446145, 0.7853981633574639298 ) ; -#8766 = EDGE_CURVE ( 'NONE', #16835, #24779, #27058, .T. ) ; -#8767 = DIRECTION ( 'NONE', ( -3.549981615672110651E-11, -0.9743700557841834531, -0.2249510933316997141 ) ) ; -#8768 = CARTESIAN_POINT ( 'NONE', ( 23.72254622402000024, 114.0103269029000188, 152.4718672074000381 ) ) ; -#8769 = CARTESIAN_POINT ( 'NONE', ( 41.37407482599210340, 109.2646873992651422, 170.0357904634387580 ) ) ; -#8770 = CARTESIAN_POINT ( 'NONE', ( -32.65040898612480191, 153.0051697192221241, 291.5764532040477093 ) ) ; -#8771 = VERTEX_POINT ( 'NONE', #29297 ) ; -#8772 = VERTEX_POINT ( 'NONE', #35391 ) ; -#8773 = CARTESIAN_POINT ( 'NONE', ( 38.50022159043000158, 118.6460062394999966, 87.79248012469000173 ) ) ; -#8774 = AXIS2_PLACEMENT_3D ( 'NONE', #27690, #5986, #15396 ) ; -#8775 = CARTESIAN_POINT ( 'NONE', ( 20.24064596600999977, 199.6921864814999878, 89.48934496540999817 ) ) ; -#8776 = CARTESIAN_POINT ( 'NONE', ( 37.31163124181149016, 191.4712155356178300, 104.3367040115298607 ) ) ; -#8777 = FACE_OUTER_BOUND ( 'NONE', #39339, .T. ) ; -#8778 = VERTEX_POINT ( 'NONE', #7398 ) ; -#8779 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; -#8780 = EDGE_CURVE ( 'NONE', #34131, #2174, #13383, .T. ) ; -#8781 = CARTESIAN_POINT ( 'NONE', ( -43.84816494817811616, 120.4493680208014723, 90.56624447257551935 ) ) ; -#8782 = CARTESIAN_POINT ( 'NONE', ( 15.66686322801795406, 127.6698194824295882, 89.46046031359570350 ) ) ; -#8783 = CARTESIAN_POINT ( 'NONE', ( -5.669412827410644340, 187.7434695915656562, 103.5134950631828588 ) ) ; -#8784 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265227786, -0.1368326740407709297 ) ) ; -#8785 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#8786 = ADVANCED_FACE ( 'NONE', ( #4743 ), #17203, .T. ) ; -#8787 = CARTESIAN_POINT ( 'NONE', ( -25.76318952320184152, 209.7106752283213780, 73.32088370617481132 ) ) ; -#8788 = VECTOR ( 'NONE', #27639, 1000.000000000000114 ) ; -#8789 = LINE ( 'NONE', #36785, #16091 ) ; -#8790 = PERSON_AND_ORGANIZATION_ROLE ( 'classification_officer' ) ; -#8791 = PLANE ( 'NONE', #15455 ) ; -#8792 = CIRCLE ( 'NONE', #26420, 8.000000000000007105 ) ; -#8793 = CIRCLE ( 'NONE', #10072, 2.000000000000011546 ) ; -#8794 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#8795 = DIRECTION ( 'NONE', ( 0.0005884949671858177161, -0.2249510543353067382, 0.9743698870691291924 ) ) ; -#8796 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319389714494 ) ) ; -#8797 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#8798 = ORIENTED_EDGE ( 'NONE', *, *, #13168, .T. ) ; -#8799 = CARTESIAN_POINT ( 'NONE', ( 28.70581487418796129, 148.8854600315911796, 94.52165327196804867 ) ) ; -#8800 = ORIENTED_EDGE ( 'NONE', *, *, #25214, .T. ) ; -#8801 = ORIENTED_EDGE ( 'NONE', *, *, #25950, .F. ) ; -#8802 = VERTEX_POINT ( 'NONE', #14366 ) ; -#8803 = DIRECTION ( 'NONE', ( 0.9999998268366048215, 0.0001323826692270894153, -0.0005734122332635458808 ) ) ; -#8804 = ORIENTED_EDGE ( 'NONE', *, *, #32973, .F. ) ; -#8805 = CARTESIAN_POINT ( 'NONE', ( 20.32589321757966516, 126.8344400321431920, 91.66874526613595719 ) ) ; -#8806 = CARTESIAN_POINT ( 'NONE', ( 18.87587832947231092, 125.0050401149588879, 178.4556788297441585 ) ) ; -#8807 = CARTESIAN_POINT ( 'NONE', ( -42.86870032173014522, 121.2410338499262537, 90.70283413665809746 ) ) ; -#8808 = VERTEX_POINT ( 'NONE', #37047 ) ; -#8809 = CARTESIAN_POINT ( 'NONE', ( 15.50107933875540667, 127.3325056150999899, 90.92214182049345084 ) ) ; -#8810 = DIRECTION ( 'NONE', ( -0.6087613186456907188, -0.7730177010543248795, -0.1784749023741044327 ) ) ; -#8811 = DIRECTION ( 'NONE', ( 0.5986917825334797660, 0.8009794122048706777, -0.0003615948347012658639 ) ) ; -#8812 = CARTESIAN_POINT ( 'NONE', ( -12.63809828823728232, 131.0198806733800438, 89.90888323108799796 ) ) ; -#8813 = ORIENTED_EDGE ( 'NONE', *, *, #3386, .T. ) ; -#8814 = CARTESIAN_POINT ( 'NONE', ( -35.95473150036615806, 205.5673820438667292, 76.32193034923589892 ) ) ; -#8815 = EDGE_CURVE ( 'NONE', #206, #2569, #15343, .T. ) ; -#8816 = CARTESIAN_POINT ( 'NONE', ( -15.38775925502634756, 176.1499588361438384, 100.3296392074066006 ) ) ; -#8817 = FACE_OUTER_BOUND ( 'NONE', #23576, .T. ) ; -#8818 = CARTESIAN_POINT ( 'NONE', ( 23.08502856561264593, 148.5869484094654354, 197.0326829874275347 ) ) ; -#8819 = CARTESIAN_POINT ( 'NONE', ( -6.679083190205946056E-14, 155.6803346354327289, 98.67347229705578115 ) ) ; -#8820 = CIRCLE ( 'NONE', #14029, 1.749999999939591433 ) ; -#8821 = ORIENTED_EDGE ( 'NONE', *, *, #17512, .F. ) ; -#8822 = EDGE_CURVE ( 'NONE', #12107, #11953, #4602, .T. ) ; -#8823 = CARTESIAN_POINT ( 'NONE', ( -31.19810823188564797, 110.6131156702000027, 87.28662716757878570 ) ) ; -#8824 = CARTESIAN_POINT ( 'NONE', ( 0.5740959785458999987, 188.8577272846999904, 103.5276859817000030 ) ) ; -#8825 = CONICAL_SURFACE ( 'NONE', #20555, 6.499999999947934981, 0.7853981633829972830 ) ; -#8826 = AXIS2_PLACEMENT_3D ( 'NONE', #30032, #35936, #17329 ) ; -#8827 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971555410 ) ) ; -#8828 = PLANE ( 'NONE', #20820 ) ; -#8829 = AXIS2_PLACEMENT_3D ( 'NONE', #16846, #26483, #4585 ) ; -#8830 = EDGE_CURVE ( 'NONE', #32100, #11480, #33560, .T. ) ; -#8831 = ORIENTED_EDGE ( 'NONE', *, *, #8111, .T. ) ; -#8832 = CARTESIAN_POINT ( 'NONE', ( -39.17187909013465230, 120.2212968650121496, 87.43185284211611474 ) ) ; -#8833 = EDGE_LOOP ( 'NONE', ( #21079, #12411, #14440, #2708, #31783 ) ) ; -#8834 = ADVANCED_FACE ( 'NONE', ( #30302 ), #24597, .F. ) ; -#8835 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25424, #28282, #12732, #3509 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.579035019922823579, 6.150665660457575790 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8045411634788331989, 0.8045411634788331989, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#8836 = EDGE_CURVE ( 'NONE', #5617, #18856, #10497, .T. ) ; -#8837 = EDGE_CURVE ( 'NONE', #2295, #10713, #28527, .T. ) ; -#8838 = VERTEX_POINT ( 'NONE', #12109 ) ; -#8839 = DIRECTION ( 'NONE', ( 0.0005884949961243997156, -0.2249510543439061094, 0.9743698870671263501 ) ) ; -#8840 = CARTESIAN_POINT ( 'NONE', ( -36.23778119402999920, 191.7113188957999910, 106.6305335173999964 ) ) ; -#8841 = CARTESIAN_POINT ( 'NONE', ( -20.01989362473241130, 208.7351702940684675, 73.14224971100274786 ) ) ; -#8842 = CARTESIAN_POINT ( 'NONE', ( -36.75858231525709385, 191.2532611179763649, 106.3676456459981665 ) ) ; -#8843 = ORIENTED_EDGE ( 'NONE', *, *, #23916, .T. ) ; -#8844 = CARTESIAN_POINT ( 'NONE', ( -12.64022723116406510, 134.3423969131311821, 93.66938630730395232 ) ) ; -#8845 = VERTEX_POINT ( 'NONE', #37243 ) ; -#8846 = CARTESIAN_POINT ( 'NONE', ( 26.94166893793940076, 123.1531157623659851, 91.15290741612201941 ) ) ; -#8847 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8501, #10809, #24252, #33420 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8848 = CARTESIAN_POINT ( 'NONE', ( 13.53487526333000091, 138.6412561347999883, 152.4718672074000381 ) ) ; -#8850 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673502968, 185.7972672194256063, 103.0526007371361175 ) ) ; -#8849 = CARTESIAN_POINT ( 'NONE', ( 44.30515803278058229, 188.2843354219114929, 106.1739411498338939 ) ) ; -#8851 = AXIS2_PLACEMENT_3D ( 'NONE', #30099, #29896, #2095 ) ; -#8852 = EDGE_LOOP ( 'NONE', ( #7800, #16513, #26325 ) ) ; -#8853 = ADVANCED_FACE ( 'NONE', ( #8443 ), #21319, .F. ) ; -#8854 = AXIS2_PLACEMENT_3D ( 'NONE', #26009, #1655, #7984 ) ; -#8855 = AXIS2_PLACEMENT_3D ( 'NONE', #40177, #37125, #25072 ) ; -#8856 = ORIENTED_EDGE ( 'NONE', *, *, #29168, .T. ) ; -#8857 = AXIS2_PLACEMENT_3D ( 'NONE', #39218, #16736, #32492 ) ; -#8858 = CARTESIAN_POINT ( 'NONE', ( 15.94054669826102177, 152.1475402096681080, 184.5616883112009816 ) ) ; -#8859 = VECTOR ( 'NONE', #10407, 1000.000000000000114 ) ; -#8860 = EDGE_LOOP ( 'NONE', ( #6201, #2870, #31185, #37497 ) ) ; -#8861 = CARTESIAN_POINT ( 'NONE', ( 38.87094024417000071, 119.1787111753999966, 90.12667056598999693 ) ) ; -#8862 = CARTESIAN_POINT ( 'NONE', ( -30.05378917699556141, 127.2828694753868319, 89.56979070794703546 ) ) ; -#8863 = CARTESIAN_POINT ( 'NONE', ( -40.45487666627001033, 206.4002260771000010, 76.08293836136373045 ) ) ; -#8864 = CARTESIAN_POINT ( 'NONE', ( 30.79668133981403599, 129.4657338577335395, 89.52384042189491709 ) ) ; -#8865 = CARTESIAN_POINT ( 'NONE', ( 37.33113517456880714, 106.2740459041111478, 174.4753009534431669 ) ) ; -#8866 = ORIENTED_EDGE ( 'NONE', *, *, #24900, .T. ) ; -#8867 = ADVANCED_FACE ( 'NONE', ( #5962 ), #24783, .T. ) ; -#8868 = VERTEX_POINT ( 'NONE', #15373 ) ; -#8869 = DIRECTION ( 'NONE', ( -0.0006039748319384964604, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#8870 = CARTESIAN_POINT ( 'NONE', ( -14.55129768904543930, 135.1122403316443581, 93.93374132341575944 ) ) ; -#8871 = ORIENTED_EDGE ( 'NONE', *, *, #22806, .F. ) ; -#8872 = EDGE_CURVE ( 'NONE', #25826, #8188, #29529, .T. ) ; -#8873 = CARTESIAN_POINT ( 'NONE', ( -36.31535205723999837, 190.8511612753999884, 106.8152324706999963 ) ) ; -#8874 = DIRECTION ( 'NONE', ( 9.251858538525972270E-15, -1.000000000000000000, 1.387778780778895919E-14 ) ) ; -#8875 = EDGE_CURVE ( 'NONE', #31409, #9446, #6558, .T. ) ; -#8876 = CARTESIAN_POINT ( 'NONE', ( 0.7701782471999670809, 188.3723031557926788, 106.2344282965262465 ) ) ; -#8877 = CARTESIAN_POINT ( 'NONE', ( -20.51953037942761782, 208.4917401325288324, 73.73871995449873396 ) ) ; -#8878 = ADVANCED_FACE ( 'NONE', ( #18215 ), #2298, .T. ) ; -#8879 = CARTESIAN_POINT ( 'NONE', ( -36.31535185967262436, 190.8511613781771530, 106.8152324789805903 ) ) ; -#8880 = AXIS2_PLACEMENT_3D ( 'NONE', #17342, #20842, #30057 ) ; -#8881 = VECTOR ( 'NONE', #38275, 1000.000000000000114 ) ; -#8882 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971567623 ) ) ; -#8883 = DIRECTION ( 'NONE', ( 0.0006039748319386881474, 1.110222822128452674E-14, 0.9999998176071845934 ) ) ; -#8884 = AXIS2_PLACEMENT_3D ( 'NONE', #1446, #29274, #13727 ) ; -#8885 = ORIENTED_EDGE ( 'NONE', *, *, #18337, .F. ) ; -#8886 = AXIS2_PLACEMENT_3D ( 'NONE', #6033, #30590, #3156 ) ; -#8887 = DIRECTION ( 'NONE', ( 0.0006039748319391408018, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#8888 = CARTESIAN_POINT ( 'NONE', ( -1.762796035792233207, 151.6652447683722471, 130.5904578368917441 ) ) ; -#8889 = ORIENTED_EDGE ( 'NONE', *, *, #21396, .F. ) ; -#8890 = CARTESIAN_POINT ( 'NONE', ( 15.95546908501697558, 121.2205045768968432, 177.4121190822531560 ) ) ; -#8891 = VERTEX_POINT ( 'NONE', #25792 ) ; -#8893 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569566 ) ) ; -#8892 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559019 ) ) ; -#8894 = ORIENTED_EDGE ( 'NONE', *, *, #23439, .F. ) ; -#8895 = VERTEX_POINT ( 'NONE', #37838 ) ; -#8896 = ORIENTED_EDGE ( 'NONE', *, *, #22582, .T. ) ; -#8897 = CARTESIAN_POINT ( 'NONE', ( 2.639085314459999942, 209.3675475706999976, 75.69331483121000304 ) ) ; -#8898 = VECTOR ( 'NONE', #32040, 1000.000000000000000 ) ; -#8899 = CARTESIAN_POINT ( 'NONE', ( -4.037441715711839407, 168.3837378232002209, 99.04296232379908815 ) ) ; -#8900 = DIRECTION ( 'NONE', ( 0.0005884949961203239828, -0.2249510543439058874, 0.9743698870671263501 ) ) ; -#8901 = ORIENTED_EDGE ( 'NONE', *, *, #17974, .F. ) ; -#8902 = AXIS2_PLACEMENT_3D ( 'NONE', #1131, #16855, #31831 ) ; -#8903 = ORIENTED_EDGE ( 'NONE', *, *, #20606, .T. ) ; -#8904 = CARTESIAN_POINT ( 'NONE', ( -22.50000097825470746, 184.9622399467538685, 102.3653456266050483 ) ) ; -#8905 = ORIENTED_EDGE ( 'NONE', *, *, #13071, .F. ) ; -#8906 = AXIS2_PLACEMENT_3D ( 'NONE', #19112, #25888, #16646 ) ; -#8907 = ORIENTED_EDGE ( 'NONE', *, *, #12101, .F. ) ; -#8908 = CARTESIAN_POINT ( 'NONE', ( 20.46346868659919238, 151.7331366245661286, 196.7148367672695883 ) ) ; -#8909 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927766006264, 0.0005734119022010027242 ) ) ; -#8910 = CARTESIAN_POINT ( 'NONE', ( -45.26777240408874547, 110.5472149921316571, 150.9714395293199232 ) ) ; -#8911 = CARTESIAN_POINT ( 'NONE', ( 2.779653847929548949, 209.6693628105339826, 73.22349325451288848 ) ) ; -#8912 = EDGE_LOOP ( 'NONE', ( #28451, #39786, #2319, #28304 ) ) ; -#8913 = EDGE_CURVE ( 'NONE', #8188, #35446, #12958, .T. ) ; -#8914 = AXIS2_PLACEMENT_3D ( 'NONE', #11454, #27013, #20860 ) ; -#8915 = VERTEX_POINT ( 'NONE', #22116 ) ; -#8916 = EDGE_CURVE ( 'NONE', #20686, #32437, #29, .T. ) ; -#8917 = ORIENTED_EDGE ( 'NONE', *, *, #13812, .F. ) ; -#8918 = CARTESIAN_POINT ( 'NONE', ( -5.669681737655269060, 123.9839218370772187, 91.10844462476967465 ) ) ; -#8919 = ADVANCED_FACE ( 'NONE', ( #25386 ), #34744, .T. ) ; -#8920 = CARTESIAN_POINT ( 'NONE', ( -36.11135576184000229, 191.8228972718000307, 104.2943896964000032 ) ) ; -#8921 = CARTESIAN_POINT ( 'NONE', ( -25.94032117352999833, 122.9550272655999947, 88.56828463643999783 ) ) ; -#8922 = ORIENTED_EDGE ( 'NONE', *, *, #28081, .T. ) ; -#8923 = DIRECTION ( 'NONE', ( -0.0006039748319368648446, -1.157494911401840404E-14, -0.9999998176071845934 ) ) ; -#8924 = DIRECTION ( 'NONE', ( 0.0005884949961239144267, -0.2249510543439066923, 0.9743698870671261281 ) ) ; -#8925 = CARTESIAN_POINT ( 'NONE', ( 40.07504156640001014, 190.2887409542544788, 106.6480229763039063 ) ) ; -#8926 = ORIENTED_EDGE ( 'NONE', *, *, #30510, .T. ) ; -#8927 = EDGE_CURVE ( 'NONE', #26246, #8652, #29022, .T. ) ; -#8928 = CARTESIAN_POINT ( 'NONE', ( -0.1043368103128384378, 188.6124742552540283, 103.1976073196855026 ) ) ; -#8929 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178587041921E-05, -0.0002331579774917524482 ) ) ; -#8930 = EDGE_CURVE ( 'NONE', #22954, #17036, #34531, .T. ) ; -#8931 = CARTESIAN_POINT ( 'NONE', ( 36.04562886062198857, 218.5902260770999987, 75.53673388173362468 ) ) ; -#8932 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364818587623, 136.5649596138779884, 181.4686487119677167 ) ) ; -#8933 = ORIENTED_EDGE ( 'NONE', *, *, #33990, .T. ) ; -#8934 = LINE ( 'NONE', #20990, #13232 ) ; -#8935 = ORIENTED_EDGE ( 'NONE', *, *, #4551, .T. ) ; -#8936 = EDGE_LOOP ( 'NONE', ( #25796, #16078, #32976, #3398 ) ) ; -#8937 = CARTESIAN_POINT ( 'NONE', ( 2.941278393888057341, 209.7096877029368613, 73.05672770647804271 ) ) ; -#8938 = AXIS2_PLACEMENT_3D ( 'NONE', #27319, #36901, #3483 ) ; -#8939 = DIRECTION ( 'NONE', ( -0.7700768272164115746, -0.6290960810766029754, 0.1059235618659280648 ) ) ; -#8940 = AXIS2_PLACEMENT_3D ( 'NONE', #2044, #21055, #33908 ) ; -#8941 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023851578 ) ) ; -#8942 = ORIENTED_EDGE ( 'NONE', *, *, #38023, .T. ) ; -#8943 = FACE_OUTER_BOUND ( 'NONE', #2492, .T. ) ; -#8944 = ORIENTED_EDGE ( 'NONE', *, *, #35864, .F. ) ; -#8945 = AXIS2_PLACEMENT_3D ( 'NONE', #4729, #26023, #4318 ) ; -#8946 = CARTESIAN_POINT ( 'NONE', ( 14.17036435349962353, 176.4975660804189488, 100.9051904591885886 ) ) ; -#8947 = CONICAL_SURFACE ( 'NONE', #28518, 2.249999999906822978, 0.7853981633778703841 ) ; -#8948 = CARTESIAN_POINT ( 'NONE', ( -6.038589899303025810, 135.0345199613422551, 90.99097522609406496 ) ) ; -#8949 = ORIENTED_EDGE ( 'NONE', *, *, #25034, .F. ) ; -#8950 = CARTESIAN_POINT ( 'NONE', ( -20.99834812677269369, 175.6169579277373032, 103.1178387243066510 ) ) ; -#8951 = CARTESIAN_POINT ( 'NONE', ( -15.66640061118684812, 151.8962593205783946, 95.07257227604921468 ) ) ; -#8952 = CARTESIAN_POINT ( 'NONE', ( -37.24442942593478278, 164.8639741617558059, 196.9343803322838369 ) ) ; -#8953 = CARTESIAN_POINT ( 'NONE', ( 20.50176505208000322, 157.9337197842999956, 99.18132479289999992 ) ) ; -#8954 = CARTESIAN_POINT ( 'NONE', ( 5.704476631508000217, 114.0103269029000188, 152.4718672074000381 ) ) ; -#8955 = EDGE_LOOP ( 'NONE', ( #22217, #3988, #8518, #25010 ) ) ; -#8956 = DIRECTION ( 'NONE', ( -0.0005884949961208347504, 0.2249510543439081633, -0.9743698870671259060 ) ) ; -#8957 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#8958 = CARTESIAN_POINT ( 'NONE', ( -40.55546040088514559, 184.3694242608361265, 104.8082136547167096 ) ) ; -#8959 = VERTEX_POINT ( 'NONE', #6955 ) ; -#8960 = CARTESIAN_POINT ( 'NONE', ( 30.06604060545006973, 134.3090764877889569, 93.66925167689640830 ) ) ; -#8961 = EDGE_CURVE ( 'NONE', #26268, #1952, #11945, .T. ) ; -#8962 = CARTESIAN_POINT ( 'NONE', ( -28.46737701145232791, 128.5818728664343951, 89.35557892710436079 ) ) ; -#8963 = ADVANCED_FACE ( 'NONE', ( #38240 ), #33888, .T. ) ; -#8964 = VERTEX_POINT ( 'NONE', #31723 ) ; -#8965 = CARTESIAN_POINT ( 'NONE', ( 22.53365398946230158, 145.9296226677156767, 152.0219650208057089 ) ) ; -#8966 = AXIS2_PLACEMENT_3D ( 'NONE', #25289, #19326, #31824 ) ; -#8967 = FACE_OUTER_BOUND ( 'NONE', #4342, .T. ) ; -#8968 = CARTESIAN_POINT ( 'NONE', ( 35.72955092202045080, 193.9703422006220705, 102.7464518626500904 ) ) ; -#8969 = DIRECTION ( 'NONE', ( -0.5614015438086682463, -0.2604365532041851283, -0.7854941809869552261 ) ) ; -#8970 = ORIENTED_EDGE ( 'NONE', *, *, #22325, .T. ) ; -#8971 = CARTESIAN_POINT ( 'NONE', ( -20.89133279417689337, 135.6510826495900517, 94.06197212497137627 ) ) ; -#8972 = DIRECTION ( 'NONE', ( 0.5987319967475925875, 0.8009494341533932582, 0.000000000000000000 ) ) ; -#8973 = CARTESIAN_POINT ( 'NONE', ( -6.035970131896196911, 174.6797516720102976, 103.0634797155744167 ) ) ; -#8974 = CARTESIAN_POINT ( 'NONE', ( -23.79008126526258593, 115.2160427521631334, 90.28215345216254661 ) ) ; -#8975 = CARTESIAN_POINT ( 'NONE', ( 3.188020543578640176, 126.4217074165510439, 88.83774635480644122 ) ) ; -#8976 = ORIENTED_EDGE ( 'NONE', *, *, #37096, .T. ) ; -#8977 = VERTEX_POINT ( 'NONE', #3684 ) ; -#8978 = CARTESIAN_POINT ( 'NONE', ( 39.39884470921000315, 119.4108113951999997, 87.86449634650999485 ) ) ; -#8979 = PLANE ( 'NONE', #16003 ) ; -#8980 = CARTESIAN_POINT ( 'NONE', ( 36.75369171218457609, 191.6321295115402563, 104.3442627534098506 ) ) ; -#8981 = CARTESIAN_POINT ( 'NONE', ( -17.26244873158546511, 152.5112902433045861, 182.5794626460271957 ) ) ; -#8982 = EDGE_LOOP ( 'NONE', ( #21849, #15992, #9779, #33763 ) ) ; -#8983 = DIRECTION ( 'NONE', ( -0.0005884949961221956410, 0.2249510543439041110, -0.9743698870671267942 ) ) ; -#8984 = DIRECTION ( 'NONE', ( -0.7933533411653341805, 0.5930537057989598848, 0.1373964268091485141 ) ) ; -#8985 = CARTESIAN_POINT ( 'NONE', ( 24.14312846718948435, 213.8597117594435701, 73.04392223777644233 ) ) ; -#8986 = CARTESIAN_POINT ( 'NONE', ( 12.63828875764826343, 181.2191498300309149, 104.3877799491323657 ) ) ; -#8987 = ADVANCED_FACE ( 'NONE', ( #10251 ), #4075, .F. ) ; -#8988 = CARTESIAN_POINT ( 'NONE', ( 15.05323202847136876, 135.9260618574729165, 94.10374647281754790 ) ) ; -#8989 = AXIS2_PLACEMENT_3D ( 'NONE', #16569, #22544, #28467 ) ; -#8990 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048993906, 177.1117171981997558, 103.6430084149375688 ) ) ; -#8991 = CONICAL_SURFACE ( 'NONE', #31192, 3.002819725383311322, 0.7853589219486486472 ) ; -#8992 = DIRECTION ( 'NONE', ( -0.0005884949961216158097, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#8993 = COORDINATED_UNIVERSAL_TIME_OFFSET ( 8, 0, .AHEAD. ) ; -#8994 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; -#8995 = CARTESIAN_POINT ( 'NONE', ( 36.74499328828947142, 191.3591568088928909, 106.3388620510278457 ) ) ; -#8996 = DIRECTION ( 'NONE', ( -8.006416042957766484E-15, 0.9743700557921585181, 0.2249510932971565125 ) ) ; -#8997 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #27500, #36665 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#8998 = DIRECTION ( 'NONE', ( 0.7942820423213362568, 0.5918950211223029667, 0.1370267171630251968 ) ) ; -#8999 = CARTESIAN_POINT ( 'NONE', ( 37.96499713718259983, 190.9621088645640157, 106.2897951478049947 ) ) ; -#9000 = ORIENTED_EDGE ( 'NONE', *, *, #23613, .F. ) ; -#9002 = EDGE_LOOP ( 'NONE', ( #27435, #916 ) ) ; -#9001 = CARTESIAN_POINT ( 'NONE', ( 36.62814241374000090, 191.2703535884000132, 106.4498546874999931 ) ) ; -#9003 = EDGE_LOOP ( 'NONE', ( #23769, #37028, #4048, #4094 ) ) ; -#9004 = ORIENTED_EDGE ( 'NONE', *, *, #2020, .F. ) ; -#9005 = DIRECTION ( 'NONE', ( 1.110223024561561099E-14, 0.9743700557921592953, 0.2249510932971529042 ) ) ; -#9006 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#9007 = CARTESIAN_POINT ( 'NONE', ( -31.60569785394651277, 177.3017686088606126, 100.6053507231819566 ) ) ; -#9008 = EDGE_CURVE ( 'NONE', #39273, #14135, #822, .T. ) ; -#9009 = VERTEX_POINT ( 'NONE', #6547 ) ; -#9010 = CARTESIAN_POINT ( 'NONE', ( -39.19212960309999971, 119.4692301673999992, 90.21497160778000080 ) ) ; -#9011 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825968184599486, 0.0005734119012737704749 ) ) ; -#9012 = LINE ( 'NONE', #5517, #17039 ) ; -#9013 = VERTEX_POINT ( 'NONE', #3882 ) ; -#9014 = CARTESIAN_POINT ( 'NONE', ( 15.50029468041064362, 174.4049028184014105, 100.4212577462938327 ) ) ; -#9015 = VECTOR ( 'NONE', #29425, 1000.000000000000114 ) ; -#9016 = DIRECTION ( 'NONE', ( 0.7066903926851649809, 0.000000000000000000, -0.7075229246367126246 ) ) ; -#9017 = CARTESIAN_POINT ( 'NONE', ( 36.94455153219831089, 117.2454428897012519, 90.24547125583531226 ) ) ; -#9018 = AXIS2_PLACEMENT_3D ( 'NONE', #7712, #7919, #29207 ) ; -#9019 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563182 ) ) ; -#9020 = ORIENTED_EDGE ( 'NONE', *, *, #17828, .F. ) ; -#9021 = CARTESIAN_POINT ( 'NONE', ( -26.85016591629000260, 189.2575623740999902, 103.2237545534000134 ) ) ; -#9022 = DIRECTION ( 'NONE', ( -0.0005884949961270922233, 0.2249510543439054433, -0.9743698870671265722 ) ) ; -#9023 = CARTESIAN_POINT ( 'NONE', ( -37.31403596624686969, 185.5641699427571893, 107.6478458894942065 ) ) ; -#9024 = ORIENTED_EDGE ( 'NONE', *, *, #13376, .F. ) ; -#9025 = ORIENTED_EDGE ( 'NONE', *, *, #23583, .T. ) ; -#9026 = CARTESIAN_POINT ( 'NONE', ( 38.29411851311186865, 218.5902260770999987, 73.03537539441880710 ) ) ; -#9027 = ORIENTED_EDGE ( 'NONE', *, *, #18205, .T. ) ; -#9028 = EDGE_CURVE ( 'NONE', #9881, #18343, #1766, .T. ) ; -#9029 = CARTESIAN_POINT ( 'NONE', ( -36.55029116362000252, 191.5651398178999898, 104.9986570192999977 ) ) ; -#9030 = CARTESIAN_POINT ( 'NONE', ( 14.89441505909820762, 175.5348048312332025, 102.9061423033102756 ) ) ; -#9031 = CARTESIAN_POINT ( 'NONE', ( -25.50945386513487989, 211.0902258593999932, 74.23939878291034233 ) ) ; -#9032 = CARTESIAN_POINT ( 'NONE', ( 44.87027855527305320, 186.7831729946450992, 105.8418005208418435 ) ) ; -#9033 = CARTESIAN_POINT ( 'NONE', ( -5.670672681055139108, 181.8783021462742227, 101.9067947796755931 ) ) ; -#9034 = CARTESIAN_POINT ( 'NONE', ( -0.6722830789079499159, 188.9999999857274418, 105.7361035176449349 ) ) ; -#9035 = ORIENTED_EDGE ( 'NONE', *, *, #33176, .F. ) ; -#9036 = EDGE_CURVE ( 'NONE', #9304, #29634, #39105, .T. ) ; -#9037 = CARTESIAN_POINT ( 'NONE', ( -22.49823188806079344, 127.0672912568829247, 92.08444022695447018 ) ) ; -#9038 = AXIS2_PLACEMENT_3D ( 'NONE', #31147, #245, #18836 ) ; -#9039 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#9040 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#9041 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6237, #18691, #33648, #24064, #31194, #15645 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9042 = VECTOR ( 'NONE', #9145, 1000.000000000000000 ) ; -#9044 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 67.27946979429627561, 310.0857197240632104 ) ) ; -#9043 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971574007 ) ) ; -#9045 = EDGE_CURVE ( 'NONE', #2967, #19190, #34367, .T. ) ; -#9046 = ORIENTED_EDGE ( 'NONE', *, *, #7350, .F. ) ; -#9047 = EDGE_CURVE ( 'NONE', #5617, #4266, #21514, .T. ) ; -#9048 = EDGE_CURVE ( 'NONE', #7852, #36789, #9988, .T. ) ; -#9049 = ORIENTED_EDGE ( 'NONE', *, *, #28884, .F. ) ; -#9051 = ADVANCED_FACE ( 'NONE', ( #32509 ), #11049, .F. ) ; -#9050 = CARTESIAN_POINT ( 'NONE', ( 30.17614581013264186, 126.7625099995479445, 88.90012669361888697 ) ) ; -#9052 = CARTESIAN_POINT ( 'NONE', ( 13.50176809758824703, 126.1286536816045327, 91.84597050332364176 ) ) ; -#9053 = EDGE_CURVE ( 'NONE', #20341, #30736, #29449, .T. ) ; -#9054 = CARTESIAN_POINT ( 'NONE', ( 39.63353669152581915, 119.7633698288389184, 87.79166280016082169 ) ) ; -#9055 = CARTESIAN_POINT ( 'NONE', ( -25.49128147572124092, 192.8634534852218110, 104.3291085408993411 ) ) ; -#9056 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250095806, 177.4328783376051888, 101.1405542638008939 ) ) ; -#9057 = VERTEX_POINT ( 'NONE', #1222 ) ; -#9058 = VERTEX_POINT ( 'NONE', #26193 ) ; -#9059 = CARTESIAN_POINT ( 'NONE', ( -20.01813817220386937, 208.9308472833029953, 76.18768590624890180 ) ) ; -#9060 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.271205363196006660E-14, -0.9999998176071844824 ) ) ; -#9061 = DIRECTION ( 'NONE', ( 0.0005884949961243157984, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#9062 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25350, #29215, #34710, #6919 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 2.725652208953761146, 4.544051345060554858 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7429183312171805387, 0.7429183312171805387, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#9063 = FACE_OUTER_BOUND ( 'NONE', #12761, .T. ) ; -#9064 = ORIENTED_EDGE ( 'NONE', *, *, #8590, .F. ) ; -#9065 = ORIENTED_EDGE ( 'NONE', *, *, #14466, .F. ) ; -#9066 = AXIS2_PLACEMENT_3D ( 'NONE', #21933, #18424, #5779 ) ; -#9067 = CARTESIAN_POINT ( 'NONE', ( 35.79920382921711308, 209.7096538412770030, 75.78427872630588524 ) ) ; -#9068 = CARTESIAN_POINT ( 'NONE', ( -14.20829634260898544, 150.7122502792225873, 27.79156830144150092 ) ) ; -#9069 = VECTOR ( 'NONE', #34478, 1000.000000000000114 ) ; -#9070 = CARTESIAN_POINT ( 'NONE', ( 2.441738457499000425, 189.8317159618999881, 106.1741859263999999 ) ) ; -#9071 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825928200210802, -0.0005734119021977812343 ) ) ; -#9072 = ADVANCED_FACE ( 'NONE', ( #7556 ), #38631, .T. ) ; -#9073 = DIRECTION ( 'NONE', ( -0.7933532970003751572, -0.5930762008556708098, -0.1372995488602872238 ) ) ; -#9074 = CARTESIAN_POINT ( 'NONE', ( 20.16822828554578706, 137.8789466221655857, 94.38057372190250760 ) ) ; -#9075 = FACE_OUTER_BOUND ( 'NONE', #20728, .T. ) ; -#9076 = ORIENTED_EDGE ( 'NONE', *, *, #19316, .F. ) ; -#9077 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620729128, 0.0004744508866335443741 ) ) ; -#9078 = CARTESIAN_POINT ( 'NONE', ( -20.24273581848683889, 127.1220280533010225, 91.84170706686390417 ) ) ; -#9079 = EDGE_LOOP ( 'NONE', ( #3192, #105, #8008, #28507 ) ) ; -#9080 = CARTESIAN_POINT ( 'NONE', ( 29.17518171049927034, 209.7097231784644009, 73.04088300409637213 ) ) ; -#9081 = ORIENTED_EDGE ( 'NONE', *, *, #26780, .T. ) ; -#9083 = CARTESIAN_POINT ( 'NONE', ( 35.56396753058658078, 192.2313336904389871, 103.8839717972468719 ) ) ; -#9082 = CARTESIAN_POINT ( 'NONE', ( 16.28891463742873569, 151.6603294600179765, 160.4527445207948801 ) ) ; -#9084 = EDGE_LOOP ( 'NONE', ( #17796, #31488, #40241, #5543 ) ) ; -#9086 = EDGE_LOOP ( 'NONE', ( #11510, #15328, #18428, #5179 ) ) ; -#9085 = EDGE_CURVE ( 'NONE', #11474, #11331, #23114, .T. ) ; -#9087 = ORIENTED_EDGE ( 'NONE', *, *, #26316, .T. ) ; -#9088 = CARTESIAN_POINT ( 'NONE', ( 3.180503606262000016, 209.1196423350000089, 76.28617253618000404 ) ) ; -#9089 = EDGE_CURVE ( 'NONE', #27242, #4266, #8540, .T. ) ; -#9090 = CIRCLE ( 'NONE', #37827, 2.000000000000011546 ) ; -#9091 = CARTESIAN_POINT ( 'NONE', ( -25.83320125070846274, 118.1125350644666696, 90.11672424654607028 ) ) ; -#9092 = LINE ( 'NONE', #21580, #9339 ) ; -#9093 = CONICAL_SURFACE ( 'NONE', #12352, 3.005897397098168167, 0.7853589132598342015 ) ; -#9094 = CARTESIAN_POINT ( 'NONE', ( 44.30339254327586218, 188.9591885891941558, 103.2508314896253552 ) ) ; -#9095 = ORIENTED_EDGE ( 'NONE', *, *, #38380, .F. ) ; -#9096 = VERTEX_POINT ( 'NONE', #38830 ) ; -#9097 = ADVANCED_FACE ( 'NONE', ( #13907 ), #9093, .F. ) ; -#9098 = CIRCLE ( 'NONE', #19520, 51.90509898892980090 ) ; -#9099 = ORIENTED_EDGE ( 'NONE', *, *, #29264, .T. ) ; -#9100 = ORIENTED_EDGE ( 'NONE', *, *, #10938, .F. ) ; -#9102 = EDGE_CURVE ( 'NONE', #8778, #11332, #13887, .T. ) ; -#9101 = PLANE ( 'NONE', #4768 ) ; -#9103 = CARTESIAN_POINT ( 'NONE', ( -19.37816306946693956, 125.5365691439678244, 178.4012088705679560 ) ) ; -#9104 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640315690, 0.2252353050503788645 ) ) ; -#9105 = LINE ( 'NONE', #27537, #32002 ) ; -#9106 = VERTEX_POINT ( 'NONE', #35956 ) ; -#9107 = VERTEX_POINT ( 'NONE', #33105 ) ; -#9108 = CARTESIAN_POINT ( 'NONE', ( 25.99018610745488900, 211.0908525021142168, 73.04280463953621449 ) ) ; -#9109 = DIRECTION ( 'NONE', ( -0.0006039748319343064527, 0.000000000000000000, -0.9999998176071845934 ) ) ; -#9110 = CARTESIAN_POINT ( 'NONE', ( -28.46687738437000093, 130.4181374611307263, 90.29266601293539907 ) ) ; -#9111 = EDGE_LOOP ( 'NONE', ( #10314, #152, #3315, #7523 ) ) ; -#9112 = CARTESIAN_POINT ( 'NONE', ( 15.99998378901094576, 184.9656665294078266, 102.3459542884652365 ) ) ; -#9113 = ORIENTED_EDGE ( 'NONE', *, *, #16273, .F. ) ; -#9114 = CARTESIAN_POINT ( 'NONE', ( -22.49970497326689767, 174.4001378592136575, 100.4431087167393031 ) ) ; -#9115 = CARTESIAN_POINT ( 'NONE', ( -23.36013443277664692, 183.4461002756636674, 105.1009555742510031 ) ) ; -#9116 = CARTESIAN_POINT ( 'NONE', ( -40.39772054252907907, 190.1557916721299932, 106.7158979401700947 ) ) ; -#9117 = ORIENTED_EDGE ( 'NONE', *, *, #1032, .T. ) ; -#9118 = LINE ( 'NONE', #30794, #36605 ) ; -#9119 = DIRECTION ( 'NONE', ( 0.0005884949961248443469, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#9120 = VECTOR ( 'NONE', #14649, 1000.000000000000000 ) ; -#9121 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049007406, 177.1117171981941851, 103.6430084149362898 ) ) ; -#9122 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480527206264441, 0.5299193337450082142 ) ) ; -#9123 = CIRCLE ( 'NONE', #32634, 2.500000000047894133 ) ; -#9124 = ORIENTED_EDGE ( 'NONE', *, *, #26536, .F. ) ; -#9125 = CARTESIAN_POINT ( 'NONE', ( 25.40348470219815624, 116.2738580246023474, 90.25244177100570653 ) ) ; -#9126 = ORIENTED_EDGE ( 'NONE', *, *, #23820, .T. ) ; -#9127 = CIRCLE ( 'NONE', #36550, 2.749999999927935423 ) ; -#9128 = CARTESIAN_POINT ( 'NONE', ( 36.61849814939751724, 77.14301703113001452, 291.5364272799121750 ) ) ; -#9129 = FACE_OUTER_BOUND ( 'NONE', #13265, .T. ) ; -#9130 = CONICAL_SURFACE ( 'NONE', #13038, 5.003486694794308853, 0.7853981633880587898 ) ; -#9131 = CARTESIAN_POINT ( 'NONE', ( 25.49182901039327831, 209.7089661076149127, 75.54314178666862745 ) ) ; -#9132 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; -#9133 = EDGE_CURVE ( 'NONE', #372, #20220, #35405, .T. ) ; -#9134 = ORIENTED_EDGE ( 'NONE', *, *, #7825, .T. ) ; -#9135 = EDGE_CURVE ( 'NONE', #29784, #36964, #14308, .T. ) ; -#9136 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16796, #24385, #11693, #27044, #8218, #36425 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9137 = CARTESIAN_POINT ( 'NONE', ( -38.20245686653000661, 118.7297676069999994, 90.14874192493999772 ) ) ; -#9138 = CARTESIAN_POINT ( 'NONE', ( 15.66823977521199218, 185.3098073501215026, 105.1624151300140397 ) ) ; -#9139 = ORIENTED_EDGE ( 'NONE', *, *, #5136, .F. ) ; -#9140 = DIRECTION ( 'NONE', ( -0.1305262373691798983, 0.9659583596717404852, 0.2233547598295697878 ) ) ; -#9141 = EDGE_CURVE ( 'NONE', #7741, #1667, #35748, .T. ) ; -#9142 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524656274, 149.3470289647502511, 130.0514119197545142 ) ) ; -#9143 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22673, #35298, #19575, #10399, #22869, #36338, #2202, #1577, #4643, #20793 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000001860734, 0.3750000000002791101, 0.4375000000002600697, 0.5000000000002410294, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9144 = CARTESIAN_POINT ( 'NONE', ( -15.49970617573983311, 151.8558896894846839, 95.23413014739874427 ) ) ; -#9145 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#9146 = CARTESIAN_POINT ( 'NONE', ( -37.15756392146106890, 117.7187502869175688, 90.29022707672584147 ) ) ; -#9147 = VERTEX_POINT ( 'NONE', #1840 ) ; -#9148 = EDGE_CURVE ( 'NONE', #4337, #18000, #3659, .T. ) ; -#9150 = AXIS2_PLACEMENT_3D ( 'NONE', #29833, #17733, #11632 ) ; -#9149 = DIRECTION ( 'NONE', ( -0.0005884949961228161299, 0.2249510543439076360, -0.9743698870671260170 ) ) ; -#9151 = AXIS2_PLACEMENT_3D ( 'NONE', #28313, #5622, #18077 ) ; -#9152 = CARTESIAN_POINT ( 'NONE', ( 15.83329133259355892, 160.6986494121390763, 96.91476092110876550 ) ) ; -#9153 = VECTOR ( 'NONE', #27967, 1000.000000000000000 ) ; -#9154 = ORIENTED_EDGE ( 'NONE', *, *, #6038, .T. ) ; -#9155 = DIRECTION ( 'NONE', ( 0.9999998176071458467, 6.423608955952692560E-11, -0.0006039748961739839408 ) ) ; -#9156 = CIRCLE ( 'NONE', #30728, 2.000000000040583092 ) ; -#9157 = CARTESIAN_POINT ( 'NONE', ( 15.99974815555098218, 138.5019114137554936, 91.61902897505088106 ) ) ; -#9158 = EDGE_LOOP ( 'NONE', ( #36011, #18686, #35781, #17721 ) ) ; -#9159 = DIRECTION ( 'NONE', ( -0.1843855713908465477, -0.08049128666858569592, 0.9795525069302342125 ) ) ; -#9160 = EDGE_CURVE ( 'NONE', #4109, #1948, #30467, .T. ) ; -#9161 = LINE ( 'NONE', #27981, #20586 ) ; -#9162 = CARTESIAN_POINT ( 'NONE', ( -43.34074992346683786, 121.9127549832748514, 88.07565497363744100 ) ) ; -#9163 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39819, #5476, #29625, #14492 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0009046650482442253728, 0.0009710577665168405566 ), - .UNSPECIFIED. ) ; -#9164 = ORIENTED_EDGE ( 'NONE', *, *, #15911, .F. ) ; -#9165 = CARTESIAN_POINT ( 'NONE', ( 36.10151592346490190, 191.1961136956948906, 106.8385014937324655 ) ) ; -#9166 = CARTESIAN_POINT ( 'NONE', ( -2.464592264399565469, 152.1442425547639630, 99.91119810786710786 ) ) ; -#9167 = CARTESIAN_POINT ( 'NONE', ( -37.24083814574551354, 106.2470826507470889, 174.4507514582041381 ) ) ; -#9168 = CARTESIAN_POINT ( 'NONE', ( 13.47462245814947934, 158.2310456470601423, 98.74105996008697161 ) ) ; -#9169 = CARTESIAN_POINT ( 'NONE', ( -22.49823197028072030, 137.5162774524455358, 94.49663580420342157 ) ) ; -#9170 = ORIENTED_EDGE ( 'NONE', *, *, #32238, .F. ) ; -#9171 = VERTEX_POINT ( 'NONE', #8390 ) ; -#9172 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#9173 = DIRECTION ( 'NONE', ( 0.0005884949961181604574, -0.2249510543439091625, 0.9743698870671256840 ) ) ; -#9174 = LINE ( 'NONE', #2829, #9069 ) ; -#9175 = CYLINDRICAL_SURFACE ( 'NONE', #39278, 48.00000000000002132 ) ; -#9176 = ORIENTED_EDGE ( 'NONE', *, *, #35, .F. ) ; -#9177 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971596766 ) ) ; -#9178 = CARTESIAN_POINT ( 'NONE', ( -28.47263367539243717, 181.2100821311606467, 104.4136188016237412 ) ) ; -#9179 = CARTESIAN_POINT ( 'NONE', ( 15.83343177718414552, 127.7072229588672485, 89.29794427536299395 ) ) ; -#9180 = CONICAL_SURFACE ( 'NONE', #35905, 2.503000015132546885, 0.7853981633220994407 ) ; -#9181 = CONICAL_SURFACE ( 'NONE', #15699, 2.502999999838765088, 0.7853981634080003937 ) ; -#9182 = CARTESIAN_POINT ( 'NONE', ( -20.49957889925088139, 194.9089184157244574, 105.3865625666390713 ) ) ; -#9183 = CARTESIAN_POINT ( 'NONE', ( -25.83759314228409210, 190.9097546720246896, 106.6513809942738931 ) ) ; -#9184 = AXIS2_PLACEMENT_3D ( 'NONE', #23615, #4588, #5404 ) ; -#9185 = CARTESIAN_POINT ( 'NONE', ( -30.11575774535129923, 182.2816626742635435, 101.7541501812646487 ) ) ; -#9186 = ADVANCED_FACE ( 'NONE', ( #30062 ), #33711, .F. ) ; -#9187 = AXIS2_PLACEMENT_3D ( 'NONE', #29166, #12819, #6658 ) ; -#9188 = EDGE_CURVE ( 'NONE', #35508, #26180, #14991, .T. ) ; -#9189 = EDGE_CURVE ( 'NONE', #9773, #13129, #24487, .T. ) ; -#9190 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7587, #10878, #29281, #29075 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9191 = PERSON_AND_ORGANIZATION_ROLE ( 'creator' ) ; -#9192 = CARTESIAN_POINT ( 'NONE', ( 4.701270843627139762, 181.8782530787316318, 101.6399871078483415 ) ) ; -#9193 = CARTESIAN_POINT ( 'NONE', ( -37.13575228356130253, 117.3340227016620787, 87.73004207770956953 ) ) ; -#9194 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; -#9195 = EDGE_CURVE ( 'NONE', #12564, #2594, #11000, .T. ) ; -#9196 = CARTESIAN_POINT ( 'NONE', ( 77.66020299980834807, 192.0465887426067866, 194.3137169050042701 ) ) ; -#9197 = CARTESIAN_POINT ( 'NONE', ( 36.36655296585029618, 191.7208402573679962, 106.4157350352320037 ) ) ; -#9198 = VERTEX_POINT ( 'NONE', #27819 ) ; -#9199 = CARTESIAN_POINT ( 'NONE', ( 36.66573766188999883, 191.2416103959000111, 106.4445292027000107 ) ) ; -#9200 = ORIENTED_EDGE ( 'NONE', *, *, #1697, .F. ) ; -#9201 = ORIENTED_EDGE ( 'NONE', *, *, #7198, .F. ) ; -#9202 = ORIENTED_EDGE ( 'NONE', *, *, #3031, .T. ) ; -#9203 = EDGE_CURVE ( 'NONE', #12706, #16466, #2252, .T. ) ; -#9204 = CARTESIAN_POINT ( 'NONE', ( -0.03375341898833555260, -31.76863880746333280, 137.4221703796379188 ) ) ; -#9205 = CARTESIAN_POINT ( 'NONE', ( -20.21994974020127955, 184.9112019368533026, 102.5811191251855661 ) ) ; -#9206 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35840, #20108, #36051, #10942 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9207 = CARTESIAN_POINT ( 'NONE', ( 31.79177573931936962, 115.2378407561303391, 176.5461501322318725 ) ) ; -#9208 = CARTESIAN_POINT ( 'NONE', ( -38.90532417260193654, 169.1823092633644023, 183.8675584944714387 ) ) ; -#9209 = VERTEX_POINT ( 'NONE', #17760 ) ; -#9210 = CARTESIAN_POINT ( 'NONE', ( -39.21221060463999919, 118.9500855288000025, 89.58294657444000109 ) ) ; -#9211 = EDGE_CURVE ( 'NONE', #10701, #21872, #34860, .T. ) ; -#9212 = AXIS2_PLACEMENT_3D ( 'NONE', #12912, #37839, #35345 ) ; -#9213 = CARTESIAN_POINT ( 'NONE', ( -15.38986229257041849, 129.3784849134285935, 89.53159292728777530 ) ) ; -#9214 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971577337 ) ) ; -#9215 = CARTESIAN_POINT ( 'NONE', ( 0.05270753573795999847, 0.000000000000000000, 87.26775245800000391 ) ) ; -#9216 = ORIENTED_EDGE ( 'NONE', *, *, #16815, .F. ) ; -#9217 = CARTESIAN_POINT ( 'NONE', ( 20.50176505208000322, 136.5173134723999908, 94.23695690543999604 ) ) ; -#9218 = VECTOR ( 'NONE', #33786, 1000.000000000000114 ) ; -#9219 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567345 ) ) ; -#9220 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971560406 ) ) ; -#9221 = DIRECTION ( 'NONE', ( 0.0005884949961235717104, -0.2249510543439064147, 0.9743698870671262391 ) ) ; -#9222 = CARTESIAN_POINT ( 'NONE', ( -5.345045829023177042, 188.3421103602547078, 103.1383541418427825 ) ) ; -#9223 = DIRECTION ( 'NONE', ( -0.9914447795421099663, -0.1272537940605282525, -0.02904687618140097335 ) ) ; -#9224 = ORIENTED_EDGE ( 'NONE', *, *, #13298, .F. ) ; -#9225 = CARTESIAN_POINT ( 'NONE', ( -25.62364350484000042, 191.5126371725000070, 104.2709893052000183 ) ) ; -#9226 = CARTESIAN_POINT ( 'NONE', ( 2.551106744431880013, 190.8269631700860032, 104.2238537024139902 ) ) ; -#9227 = LINE ( 'NONE', #28041, #11019 ) ; -#9228 = ORIENTED_EDGE ( 'NONE', *, *, #15816, .F. ) ; -#9229 = ORIENTED_EDGE ( 'NONE', *, *, #39073, .F. ) ; -#9230 = CARTESIAN_POINT ( 'NONE', ( 42.85442617173308832, 113.6598254356972149, 123.5406245648973993 ) ) ; -#9231 = ORIENTED_EDGE ( 'NONE', *, *, #10483, .F. ) ; -#9232 = CARTESIAN_POINT ( 'NONE', ( 20.00174584374092035, 192.4630694782412093, 106.9093782835173272 ) ) ; -#9233 = CARTESIAN_POINT ( 'NONE', ( -38.45586748819795986, 218.5902260770999987, 73.08173046273984141 ) ) ; -#9234 = ADVANCED_FACE ( 'NONE', ( #8593 ), #15131, .F. ) ; -#9235 = EDGE_CURVE ( 'NONE', #10196, #22508, #18291, .T. ) ; -#9236 = CARTESIAN_POINT ( 'NONE', ( -35.93177844966999857, 192.5575653067000133, 105.7869005091999952 ) ) ; -#9237 = CARTESIAN_POINT ( 'NONE', ( -12.63302500439942477, 177.0349334693919729, 103.5018215138099293 ) ) ; -#9238 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#9239 = AXIS2_PLACEMENT_3D ( 'NONE', #3080, #37038, #36428 ) ; -#9240 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9514, #35369, #35168, #23342 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9241 = CARTESIAN_POINT ( 'NONE', ( 25.80813857899862640, 134.9224874684686597, 90.78667747519583031 ) ) ; -#9242 = FACE_OUTER_BOUND ( 'NONE', #27910, .T. ) ; -#9243 = ORIENTED_EDGE ( 'NONE', *, *, #30308, .T. ) ; -#9244 = CARTESIAN_POINT ( 'NONE', ( 22.73844078587000084, 180.7017300104000128, 28.07991271570000080 ) ) ; -#9245 = CARTESIAN_POINT ( 'NONE', ( -35.97272584480918312, 191.5347990022295050, 103.8939579469935524 ) ) ; -#9246 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971549582 ) ) ; -#9247 = ADVANCED_FACE ( 'NONE', ( #17559 ), #2050, .F. ) ; -#9249 = CARTESIAN_POINT ( 'NONE', ( 22.50034184233011914, 153.8097659799650501, 95.66226703669086362 ) ) ; -#9248 = CARTESIAN_POINT ( 'NONE', ( -28.46561152636741809, 183.4461128628643962, 105.1009010528843390 ) ) ; -#9250 = VERTEX_POINT ( 'NONE', #36391 ) ; -#9251 = CARTESIAN_POINT ( 'NONE', ( -36.27941088227176181, 191.8189068658341796, 104.4052308140100820 ) ) ; -#9252 = ORIENTED_EDGE ( 'NONE', *, *, #39725, .F. ) ; -#9253 = VERTEX_POINT ( 'NONE', #27003 ) ; -#9254 = CARTESIAN_POINT ( 'NONE', ( -5.669730063980141566, 182.0627683792234848, 102.2020018026141486 ) ) ; -#9255 = EDGE_CURVE ( 'NONE', #32868, #275, #28050, .T. ) ; -#9256 = CARTESIAN_POINT ( 'NONE', ( -6.037582702418865743, 135.2929569925057365, 91.40456025213514124 ) ) ; -#9257 = CARTESIAN_POINT ( 'NONE', ( -25.49160734743147927, 193.7303623055392165, 103.7895634579492139 ) ) ; -#9258 = CARTESIAN_POINT ( 'NONE', ( -12.63910804469136018, 135.1699220826425005, 91.21284715633554185 ) ) ; -#9259 = ORIENTED_EDGE ( 'NONE', *, *, #4039, .T. ) ; -#9260 = EDGE_LOOP ( 'NONE', ( #29024, #30174, #29760, #3819 ) ) ; -#9261 = CARTESIAN_POINT ( 'NONE', ( -8.050307609250221930, 161.2716461841048101, 96.89027781497259184 ) ) ; -#9262 = CIRCLE ( 'NONE', #26888, 7.999999999999992895 ) ; -#9263 = DIRECTION ( 'NONE', ( -0.6087613505917195411, 0.7729391288371411095, 0.1788147676737769087 ) ) ; -#9264 = VECTOR ( 'NONE', #22255, 1000.000000000000114 ) ; -#9265 = ORIENTED_EDGE ( 'NONE', *, *, #17828, .T. ) ; -#9266 = CARTESIAN_POINT ( 'NONE', ( -35.93343814688130067, 191.2052343210330321, 106.8950642838330083 ) ) ; -#9267 = AXIS2_PLACEMENT_3D ( 'NONE', #8009, #28545, #1683 ) ; -#9268 = DIRECTION ( 'NONE', ( -0.0005884949961203652909, 0.2249510543439047217, -0.9743698870671267942 ) ) ; -#9269 = CARTESIAN_POINT ( 'NONE', ( 2.685831580372000094, 190.9740651400000218, 106.4314954190000009 ) ) ; -#9270 = EDGE_CURVE ( 'NONE', #37805, #26191, #28407, .T. ) ; -#9271 = ORIENTED_EDGE ( 'NONE', *, *, #12203, .F. ) ; -#9272 = CARTESIAN_POINT ( 'NONE', ( 0.7697222838020335578, 188.3790661465463359, 106.2290520075631264 ) ) ; -#9273 = ORIENTED_EDGE ( 'NONE', *, *, #39440, .T. ) ; -#9274 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#9275 = CARTESIAN_POINT ( 'NONE', ( 37.42082352723856076, 132.6200669550715929, 336.9739440566017379 ) ) ; -#9276 = CARTESIAN_POINT ( 'NONE', ( 22.73844078587000084, 174.8555096756470562, 26.73020615591706317 ) ) ; -#9277 = VERTEX_POINT ( 'NONE', #11860 ) ; -#9278 = CARTESIAN_POINT ( 'NONE', ( -20.02002437005085511, 209.7095682957761085, 73.07054393135327075 ) ) ; -#9279 = EDGE_CURVE ( 'NONE', #18386, #7608, #21473, .T. ) ; -#9280 = FACE_OUTER_BOUND ( 'NONE', #8575, .T. ) ; -#9281 = EDGE_CURVE ( 'NONE', #20336, #29879, #31334, .T. ) ; -#9282 = CARTESIAN_POINT ( 'NONE', ( 20.00171108015191024, 119.7153632178993377, 90.35824133875276232 ) ) ; -#9283 = DIRECTION ( 'NONE', ( -0.7933533411653075351, 0.5930537057989938576, 0.1373964268091553698 ) ) ; -#9284 = ADVANCED_FACE ( 'NONE', ( #775 ), #18973, .F. ) ; -#9285 = VERTEX_POINT ( 'NONE', #6701 ) ; -#9286 = DIRECTION ( 'NONE', ( -0.0005884949961206773243, 0.2249510543439054433, -0.9743698870671265722 ) ) ; -#9287 = ORIENTED_EDGE ( 'NONE', *, *, #22386, .F. ) ; -#9289 = CARTESIAN_POINT ( 'NONE', ( 35.56220589193565473, 192.2733171777023244, 103.8779218060368663 ) ) ; -#9288 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971558741 ) ) ; -#9290 = VERTEX_POINT ( 'NONE', #37991 ) ; -#9291 = ORIENTED_EDGE ( 'NONE', *, *, #18405, .F. ) ; -#9292 = CARTESIAN_POINT ( 'NONE', ( 25.49066424179351387, 208.8330507578011179, 73.60756374810169689 ) ) ; -#9293 = AXIS2_PLACEMENT_3D ( 'NONE', #33564, #5557, #14979 ) ; -#9294 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923337649, 151.9719590600774097, 94.73025963079751932 ) ) ; -#9295 = ORIENTED_EDGE ( 'NONE', *, *, #13010, .F. ) ; -#9296 = CARTESIAN_POINT ( 'NONE', ( 2.409583324830999906, 208.9008541284999865, 75.55482340362000571 ) ) ; -#9297 = FACE_OUTER_BOUND ( 'NONE', #34906, .T. ) ; -#9298 = ORIENTED_EDGE ( 'NONE', *, *, #8658, .T. ) ; -#9299 = ORIENTED_EDGE ( 'NONE', *, *, #18020, .T. ) ; -#9300 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -7.450515246535590627E-18, -0.0006039748319384396482 ) ) ; -#9301 = FACE_OUTER_BOUND ( 'NONE', #38349, .T. ) ; -#9302 = CARTESIAN_POINT ( 'NONE', ( 13.50310082153462687, 187.4283568871894659, 105.6628883825429313 ) ) ; -#9303 = CARTESIAN_POINT ( 'NONE', ( 22.94777843336958512, 135.0298113340575981, 90.81314969911097990 ) ) ; -#9304 = VERTEX_POINT ( 'NONE', #25341 ) ; -#9305 = VERTEX_POINT ( 'NONE', #12647 ) ; -#9306 = ORIENTED_EDGE ( 'NONE', *, *, #7732, .T. ) ; -#9307 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; -#9308 = CARTESIAN_POINT ( 'NONE', ( -23.35464359634993770, 177.7881151143831744, 100.7126876897662697 ) ) ; -#9309 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28498, #21965, #37898, #40340 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9310 = CARTESIAN_POINT ( 'NONE', ( -26.24957250174999857, 122.9022317860000015, 88.21403771043999598 ) ) ; -#9311 = VERTEX_POINT ( 'NONE', #31258 ) ; -#9312 = CARTESIAN_POINT ( 'NONE', ( 37.19332676480694744, 118.8604558151628794, 122.9910815359380507 ) ) ; -#9313 = CARTESIAN_POINT ( 'NONE', ( 41.01618596887276880, 189.1080813873311399, 107.1984901808192916 ) ) ; -#9314 = ORIENTED_EDGE ( 'NONE', *, *, #36322, .T. ) ; -#9315 = EDGE_CURVE ( 'NONE', #25669, #39751, #19731, .T. ) ; -#9316 = AXIS2_PLACEMENT_3D ( 'NONE', #6069, #36743, #139 ) ; -#9317 = CARTESIAN_POINT ( 'NONE', ( 25.99899579567569319, 120.3902236067009710, 87.43149108635580546 ) ) ; -#9318 = CARTESIAN_POINT ( 'NONE', ( 38.79583243979153195, 119.2582491005199188, 90.26888869832909279 ) ) ; -#9319 = AXIS2_PLACEMENT_3D ( 'NONE', #12883, #4050, #25356 ) ; -#9320 = ADVANCED_FACE ( 'NONE', ( #37589 ), #30702, .F. ) ; -#9321 = CIRCLE ( 'NONE', #20417, 2.500000000030116354 ) ; -#9322 = CARTESIAN_POINT ( 'NONE', ( -39.69261857620511336, 119.4152473592345842, 89.81183687744525912 ) ) ; -#9323 = CARTESIAN_POINT ( 'NONE', ( 20.49980344970378354, 118.1127835573565221, 87.75514417896067698 ) ) ; -#9324 = VERTEX_POINT ( 'NONE', #28795 ) ; -#9325 = CARTESIAN_POINT ( 'NONE', ( -38.14644832516935224, 118.6015573411539350, 87.71343857591170945 ) ) ; -#9326 = VERTEX_POINT ( 'NONE', #31678 ) ; -#9328 = EDGE_CURVE ( 'NONE', #37550, #3470, #27089, .T. ) ; -#9327 = CARTESIAN_POINT ( 'NONE', ( 32.97800373234639437, 77.14301703112774078, 291.5386260473334801 ) ) ; -#9329 = ADVANCED_FACE ( 'NONE', ( #28402 ), #31875, .F. ) ; -#9330 = CARTESIAN_POINT ( 'NONE', ( -37.87234534139999909, 118.4650738466999940, 87.61639254823001011 ) ) ; -#9331 = CARTESIAN_POINT ( 'NONE', ( 38.15918854550000106, 118.9362607739000026, 90.40236251288000346 ) ) ; -#9332 = ADVANCED_FACE ( 'NONE', ( #375 ), #33917, .F. ) ; -#9333 = ADVANCED_FACE ( 'NONE', ( #16311 ), #28010, .F. ) ; -#9334 = ORIENTED_EDGE ( 'NONE', *, *, #5392, .F. ) ; -#9335 = PLANE ( 'NONE', #34349 ) ; -#9336 = ORIENTED_EDGE ( 'NONE', *, *, #2531, .T. ) ; -#9337 = DIRECTION ( 'NONE', ( 0.0006039748319385305044, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#9338 = CARTESIAN_POINT ( 'NONE', ( -38.55330989715999834, 118.3701213246999941, 89.55576858278001851 ) ) ; -#9339 = VECTOR ( 'NONE', #34017, 1000.000000000000114 ) ; -#9340 = CARTESIAN_POINT ( 'NONE', ( -30.69780633562609751, 110.6131156702000027, 87.78632508902590814 ) ) ; -#9341 = EDGE_LOOP ( 'NONE', ( #21820, #6556 ) ) ; -#9342 = CARTESIAN_POINT ( 'NONE', ( -20.89111388057672158, 175.7038788979348283, 103.3088927995675590 ) ) ; -#9343 = CARTESIAN_POINT ( 'NONE', ( 22.50071842841086678, 154.4094130781474803, 95.28756121982962668 ) ) ; -#9344 = CARTESIAN_POINT ( 'NONE', ( -3.756824743301873770, 174.7284091586126920, 102.8468063176449903 ) ) ; -#9345 = VECTOR ( 'NONE', #15234, 1000.000000000000114 ) ; -#9346 = CARTESIAN_POINT ( 'NONE', ( -5.668109638569103659, 126.1268167267171378, 91.85392722789381992 ) ) ; -#9347 = DIRECTION ( 'NONE', ( -0.0006039748319292908250, -1.314021223879979801E-14, -0.9999998176071847045 ) ) ; -#9348 = ORIENTED_EDGE ( 'NONE', *, *, #17357, .T. ) ; -#9349 = CARTESIAN_POINT ( 'NONE', ( -19.70066204944312815, 149.3538291754968554, 182.1602101174578365 ) ) ; -#9350 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971575672 ) ) ; -#9351 = EDGE_CURVE ( 'NONE', #31797, #26863, #22273, .T. ) ; -#9352 = LINE ( 'NONE', #28362, #14426 ) ; -#9353 = ORIENTED_EDGE ( 'NONE', *, *, #21989, .T. ) ; -#9354 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501099925, 176.3833156737908041, 103.4640034347438160 ) ) ; -#9355 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058470054, 185.7947294611689983, 103.0635929737944565 ) ) ; -#9356 = EDGE_LOOP ( 'NONE', ( #31074, #37756, #10506, #37472 ) ) ; -#9357 = DIRECTION ( 'NONE', ( -0.0004161288024547937867, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#9358 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37664, #37865, #13328, #28865 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9359 = CARTESIAN_POINT ( 'NONE', ( 14.20467396702673746, 115.2632914020303048, 152.7602116350681456 ) ) ; -#9360 = DIRECTION ( 'NONE', ( -2.258754526012903512E-19, -1.000000000000000000, -4.625929269274426393E-16 ) ) ; -#9361 = ORIENTED_EDGE ( 'NONE', *, *, #24602, .T. ) ; -#9362 = CARTESIAN_POINT ( 'NONE', ( 28.43929873840000155, 125.3863105753000013, 88.75451872105999485 ) ) ; -#9363 = EDGE_CURVE ( 'NONE', #8695, #31711, #7497, .T. ) ; -#9364 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923093933, 174.5173791610974376, 99.93528093888356523 ) ) ; -#9365 = CARTESIAN_POINT ( 'NONE', ( -25.61448796683999873, 191.5574138185000095, 106.5411355717999982 ) ) ; -#9366 = CARTESIAN_POINT ( 'NONE', ( -5.674480817841737412, 181.6879534348617824, 101.6022789869470131 ) ) ; -#9367 = CARTESIAN_POINT ( 'NONE', ( -17.26183737405610330, 121.4975388230068916, 176.5517749385022057 ) ) ; -#9368 = ORIENTED_EDGE ( 'NONE', *, *, #35218, .T. ) ; -#9369 = DIRECTION ( 'NONE', ( -0.0005884949961241829836, 0.2249510543439074139, -0.9743698870671260170 ) ) ; -#9370 = ADVANCED_FACE ( 'NONE', ( #6303 ), #12448, .F. ) ; -#9371 = FACE_OUTER_BOUND ( 'NONE', #4604, .T. ) ; -#9372 = AXIS2_PLACEMENT_3D ( 'NONE', #28893, #16806, #13353 ) ; -#9373 = CARTESIAN_POINT ( 'NONE', ( 36.78043872729679720, 191.6213203184406382, 104.3437258726304151 ) ) ; -#9374 = ADVANCED_FACE ( 'NONE', ( #19381 ), #13261, .T. ) ; -#9375 = CARTESIAN_POINT ( 'NONE', ( 76.10630783111386677, 156.2450968845475359, 96.19213091945711369 ) ) ; -#9376 = ORIENTED_EDGE ( 'NONE', *, *, #29488, .T. ) ; -#9377 = ORIENTED_EDGE ( 'NONE', *, *, #34878, .F. ) ; -#9378 = AXIS2_PLACEMENT_3D ( 'NONE', #7013, #28906, #13367 ) ; -#9379 = FACE_OUTER_BOUND ( 'NONE', #38639, .T. ) ; -#9380 = CARTESIAN_POINT ( 'NONE', ( 30.06862252804696212, 175.3593846892260046, 100.1196662353369362 ) ) ; -#9381 = CARTESIAN_POINT ( 'NONE', ( 16.00000031304551129, 127.7446264382961232, 89.13542822417404921 ) ) ; -#9382 = ADVANCED_FACE ( 'NONE', ( #31067 ), #289, .F. ) ; -#9383 = CARTESIAN_POINT ( 'NONE', ( -36.05702791021000309, 191.5952182986000309, 104.0132102184000047 ) ) ; -#9384 = CARTESIAN_POINT ( 'NONE', ( -26.00248196372567477, 190.9001546227889037, 106.8203149384555815 ) ) ; -#9385 = CARTESIAN_POINT ( 'NONE', ( -30.48035046349547628, 182.6378642661185552, 101.8366060183172550 ) ) ; -#9386 = CARTESIAN_POINT ( 'NONE', ( -19.70056751610980683, 149.1949662753088433, 182.8494181478328358 ) ) ; -#9387 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#9388 = COORDINATED_UNIVERSAL_TIME_OFFSET ( 8, 0, .AHEAD. ) ; -#9389 = CARTESIAN_POINT ( 'NONE', ( -12.62895464393706924, 177.1149013944556145, 103.6296996846185152 ) ) ; -#9390 = CARTESIAN_POINT ( 'NONE', ( 31.79421365039000591, 226.4002260770902808, 73.53930126517946064 ) ) ; -#9391 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557941447071, -0.2249510932885531445 ) ) ; -#9392 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#9393 = CARTESIAN_POINT ( 'NONE', ( 36.67762507159000052, 191.4660682097999995, 105.6908988317999984 ) ) ; -#9394 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #7660, #29953 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9395 = ORIENTED_EDGE ( 'NONE', *, *, #24382, .F. ) ; -#9396 = CARTESIAN_POINT ( 'NONE', ( 36.51773902275000694, 190.9747009333999870, 106.6659721184000063 ) ) ; -#9397 = ORIENTED_EDGE ( 'NONE', *, *, #8520, .F. ) ; -#9398 = ORIENTED_EDGE ( 'NONE', *, *, #12278, .F. ) ; -#9399 = EDGE_LOOP ( 'NONE', ( #11712, #38319 ) ) ; -#9400 = CARTESIAN_POINT ( 'NONE', ( -5.162153182269309859, 135.0725709097216622, 90.83999922111836156 ) ) ; -#9401 = AXIS2_PLACEMENT_3D ( 'NONE', #13143, #38271, #16390 ) ; -#9402 = CARTESIAN_POINT ( 'NONE', ( 20.48555995111231809, 211.0898943587194481, 73.54694346759191603 ) ) ; -#9403 = CONICAL_SURFACE ( 'NONE', #32250, 2.499999999874955137, 0.7853981634107377596 ) ; -#9404 = FACE_OUTER_BOUND ( 'NONE', #26959, .T. ) ; -#9405 = AXIS2_PLACEMENT_3D ( 'NONE', #9244, #21318, #12910 ) ; -#9406 = ORIENTED_EDGE ( 'NONE', *, *, #4113, .F. ) ; -#9407 = CARTESIAN_POINT ( 'NONE', ( -38.85031400081999919, 118.9564915689000060, 89.86658617362999735 ) ) ; -#9408 = LINE ( 'NONE', #31276, #33851 ) ; -#9409 = CARTESIAN_POINT ( 'NONE', ( 36.05539628075284497, 119.7153703235578774, 90.34852797225485688 ) ) ; -#9410 = EDGE_CURVE ( 'NONE', #28125, #38430, #13849, .T. ) ; -#9411 = VERTEX_POINT ( 'NONE', #26341 ) ; -#9412 = CARTESIAN_POINT ( 'NONE', ( 25.49032535677042688, 209.7096538831000032, 78.04310947658244402 ) ) ; -#9413 = EDGE_CURVE ( 'NONE', #25693, #3248, #33358, .T. ) ; -#9414 = EDGE_CURVE ( 'NONE', #17381, #19871, #38774, .T. ) ; -#9415 = CARTESIAN_POINT ( 'NONE', ( 25.99193850452332910, 211.4827920245210748, 76.04285411136869755 ) ) ; -#9416 = EDGE_CURVE ( 'NONE', #36005, #31399, #3238, .T. ) ; -#9417 = CARTESIAN_POINT ( 'NONE', ( -32.78648776892129035, 141.8832786522445133, 282.0370463350590740 ) ) ; -#9418 = CARTESIAN_POINT ( 'NONE', ( -3.537744142989006857, 173.0598683674986376, 99.60908667913541592 ) ) ; -#9419 = CARTESIAN_POINT ( 'NONE', ( 36.05503237434692210, 111.0397749124999933, 89.74600841160673781 ) ) ; -#9420 = ORIENTED_EDGE ( 'NONE', *, *, #18611, .T. ) ; -#9421 = CARTESIAN_POINT ( 'NONE', ( 12.63969765807997625, 176.7434396814577440, 103.0154879366982641 ) ) ; -#9422 = CARTESIAN_POINT ( 'NONE', ( 2.551442792066930032, 190.9974047891880105, 104.2715986393109944 ) ) ; -#9423 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#9424 = ADVANCED_FACE ( 'NONE', ( #14269 ), #3872, .T. ) ; -#9425 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12758, #4132, #37694, #37902 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9426 = ORIENTED_EDGE ( 'NONE', *, *, #34273, .F. ) ; -#9427 = ORIENTED_EDGE ( 'NONE', *, *, #36357, .F. ) ; -#9428 = DIRECTION ( 'NONE', ( -0.6087904839324249640, 0.7729173423006456822, 0.1788097554503956799 ) ) ; -#9429 = EDGE_LOOP ( 'NONE', ( #21268, #24611, #38970 ) ) ; -#9430 = ADVANCED_FACE ( 'NONE', ( #23261 ), #16503, .F. ) ; -#9431 = CARTESIAN_POINT ( 'NONE', ( -15.94435305949166626, 121.6629303779242406, 175.4476447897932019 ) ) ; -#9432 = VECTOR ( 'NONE', #27653, 1000.000000000000114 ) ; -#9433 = DIRECTION ( 'NONE', ( -0.7947985590179719173, 0.5913221741348984040, 0.1365039814779489546 ) ) ; -#9434 = CARTESIAN_POINT ( 'NONE', ( -12.63563752004072782, 176.9377883658784754, 103.3463588580742964 ) ) ; -#9435 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -0.000000000000000000, 0.0006039748319387908213 ) ) ; -#9436 = CARTESIAN_POINT ( 'NONE', ( 30.05382551891246834, 103.6131156702177094, 87.74963262556697430 ) ) ; -#9437 = CARTESIAN_POINT ( 'NONE', ( -2.242517155490072689, 190.1395195109974452, 106.0676264810896612 ) ) ; -#9438 = VERTEX_POINT ( 'NONE', #1788 ) ; -#9439 = FACE_OUTER_BOUND ( 'NONE', #21154, .T. ) ; -#9440 = CARTESIAN_POINT ( 'NONE', ( 37.66308823783763415, 78.96001237643454829, 291.8950395725842100 ) ) ; -#9441 = DIRECTION ( 'NONE', ( 0.0002331579778304189888, 0.000000000000000000, -0.9999999728186783621 ) ) ; -#9443 = CARTESIAN_POINT ( 'NONE', ( -15.94501330445751996, 152.5955922385961969, 182.6046949465412865 ) ) ; -#9442 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#9444 = VERTEX_POINT ( 'NONE', #35096 ) ; -#9445 = EDGE_LOOP ( 'NONE', ( #33187, #37183, #15177, #39625 ) ) ; -#9446 = VERTEX_POINT ( 'NONE', #4033 ) ; -#9448 = ORIENTED_EDGE ( 'NONE', *, *, #8742, .T. ) ; -#9447 = LOCAL_TIME ( 14, 25, 27.00000000000000000, #8993 ) ; -#9449 = CIRCLE ( 'NONE', #14686, 6.499999999869228162 ) ; -#9450 = DIRECTION ( 'NONE', ( 0.6087602524243990176, 0.7731011285869124894, 0.1781168157300828114 ) ) ; -#9451 = CARTESIAN_POINT ( 'NONE', ( 43.53526136507346678, 121.9496774062499043, 88.05073105187337035 ) ) ; -#9452 = FACE_OUTER_BOUND ( 'NONE', #24402, .T. ) ; -#9453 = FACE_OUTER_BOUND ( 'NONE', #37867, .T. ) ; -#9454 = FACE_OUTER_BOUND ( 'NONE', #33831, .T. ) ; -#9455 = CIRCLE ( 'NONE', #32957, 4.500000000016830093 ) ; -#9456 = AXIS2_PLACEMENT_3D ( 'NONE', #3912, #32542, #1051 ) ; -#9457 = FACE_OUTER_BOUND ( 'NONE', #35816, .T. ) ; -#9458 = ORIENTED_EDGE ( 'NONE', *, *, #15955, .F. ) ; -#9459 = FACE_OUTER_BOUND ( 'NONE', #29134, .T. ) ; -#9460 = ORIENTED_EDGE ( 'NONE', *, *, #16537, .T. ) ; -#9461 = EDGE_CURVE ( 'NONE', #4210, #36212, #28992, .T. ) ; -#9462 = AXIS2_PLACEMENT_3D ( 'NONE', #21623, #30816, #21423 ) ; -#9463 = ADVANCED_FACE ( 'NONE', ( #10597 ), #7147, .T. ) ; -#9464 = DIRECTION ( 'NONE', ( 0.1632030863883311977, -0.3417424275059330885, 0.9255143790539803739 ) ) ; -#9465 = ORIENTED_EDGE ( 'NONE', *, *, #14784, .T. ) ; -#9466 = CARTESIAN_POINT ( 'NONE', ( 19.98210856654580780, 205.1070970766282358, 76.09272704596726555 ) ) ; -#9467 = CARTESIAN_POINT ( 'NONE', ( 1.981463868355714641, 189.0541665519779713, 103.2983202685192055 ) ) ; -#9468 = LINE ( 'NONE', #9068, #516 ) ; -#9469 = ORIENTED_EDGE ( 'NONE', *, *, #9188, .F. ) ; -#9470 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921592953, -0.2249510932971527932 ) ) ; -#9471 = PLANE ( 'NONE', #29829 ) ; -#9472 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501099925, 181.7423509806621951, 104.7012344478815322 ) ) ; -#9473 = CARTESIAN_POINT ( 'NONE', ( -39.61054748937312553, 129.5177821288435780, 336.3042500576304974 ) ) ; -#9474 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927756174176, 0.0005734119022080326911 ) ) ; -#9475 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3920, #28096, #10080, #28877 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9476 = ORIENTED_EDGE ( 'NONE', *, *, #27899, .T. ) ; -#9477 = CARTESIAN_POINT ( 'NONE', ( -15.56570128701472377, 147.2799833431736545, 179.8363833230590103 ) ) ; -#9478 = DIRECTION ( 'NONE', ( 0.6188015000093128881, -0.7855473910504855439, 0.000000000000000000 ) ) ; -#9479 = CARTESIAN_POINT ( 'NONE', ( 17.99823451500899907, 132.2978359559240289, 93.26432565570340216 ) ) ; -#9480 = EDGE_CURVE ( 'NONE', #17741, #38457, #26148, .T. ) ; -#9481 = CIRCLE ( 'NONE', #24530, 2.000000000309440917 ) ; -#9482 = CONICAL_SURFACE ( 'NONE', #38851, 2.502997798619384540, 0.7853981633682427521 ) ; -#9483 = VERTEX_POINT ( 'NONE', #11198 ) ; -#9484 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597599 ) ) ; -#9485 = CARTESIAN_POINT ( 'NONE', ( 25.99285328132379291, 207.8686442202288447, 77.26134345908226919 ) ) ; -#9487 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825911284117981, 0.0005734119025914883282 ) ) ; -#9486 = CARTESIAN_POINT ( 'NONE', ( 37.19332676483216460, 178.1386719297145476, 136.6947527228966521 ) ) ; -#9488 = VERTEX_POINT ( 'NONE', #23877 ) ; -#9489 = CARTESIAN_POINT ( 'NONE', ( 25.49062502244311190, 209.7098837966309475, 73.54308088453358039 ) ) ; -#9490 = EDGE_LOOP ( 'NONE', ( #14977, #13346, #34161, #30959 ) ) ; -#9491 = CARTESIAN_POINT ( 'NONE', ( -37.30573013310910113, 122.1249136379386613, 105.8120874930726671 ) ) ; -#9492 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971580390 ) ) ; -#9493 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #27683, #20920 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9494 = CARTESIAN_POINT ( 'NONE', ( 5.667815391071755471, 185.3463280707672141, 105.0058324240259822 ) ) ; -#9495 = CARTESIAN_POINT ( 'NONE', ( -44.76913686494872735, 108.4408363393548882, 169.8241779223887136 ) ) ; -#9496 = ORIENTED_EDGE ( 'NONE', *, *, #40182, .T. ) ; -#9497 = ORIENTED_EDGE ( 'NONE', *, *, #27391, .F. ) ; -#9498 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 1.540743955509789367E-33, -0.0006039748319385908944 ) ) ; -#9499 = CARTESIAN_POINT ( 'NONE', ( -16.53785153513707584, 123.0772470471530085, 172.1883206570706477 ) ) ; -#9500 = CARTESIAN_POINT ( 'NONE', ( -25.02288790531975593, 130.6107453957711471, 89.82190044176225285 ) ) ; -#9501 = CARTESIAN_POINT ( 'NONE', ( 2.780295052165365988, 209.6670236940893233, 73.22349242878858888 ) ) ; -#9502 = LINE ( 'NONE', #28122, #2003 ) ; -#9503 = VERTEX_POINT ( 'NONE', #39387 ) ; -#9504 = ORIENTED_EDGE ( 'NONE', *, *, #9480, .T. ) ; -#9505 = CARTESIAN_POINT ( 'NONE', ( 24.53348384879784305, 109.6131156702000027, 87.75296677373469834 ) ) ; -#9506 = EDGE_CURVE ( 'NONE', #37463, #13780, #19663, .T. ) ; -#9507 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; -#9508 = EDGE_CURVE ( 'NONE', #8441, #8041, #24293, .T. ) ; -#9509 = CARTESIAN_POINT ( 'NONE', ( -25.67151722820999993, 122.1102479606999935, 88.37309007614000222 ) ) ; -#9510 = CIRCLE ( 'NONE', #33635, 2.000000000000011546 ) ; -#9511 = ORIENTED_EDGE ( 'NONE', *, *, #30842, .F. ) ; -#9512 = DIRECTION ( 'NONE', ( -2.081668171172156523E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#9513 = LINE ( 'NONE', #5423, #16670 ) ; -#9514 = CARTESIAN_POINT ( 'NONE', ( -26.00624846271685442, 190.8511609718977127, 106.8090059743847178 ) ) ; -#9515 = ORIENTED_EDGE ( 'NONE', *, *, #13298, .T. ) ; -#9516 = AXIS2_PLACEMENT_3D ( 'NONE', #5737, #36192, #27446 ) ; -#9517 = CONICAL_SURFACE ( 'NONE', #25197, 2.249999999963673503, 0.7853981633778843729 ) ; -#9518 = CARTESIAN_POINT ( 'NONE', ( -36.94477238337578484, 116.4506421962486797, 89.73586812368668575 ) ) ; -#9519 = AXIS2_PLACEMENT_3D ( 'NONE', #40400, #40001, #5454 ) ; -#9520 = EDGE_CURVE ( 'NONE', #28131, #36832, #9127, .T. ) ; -#9521 = CIRCLE ( 'NONE', #40201, 5.500000000022822633 ) ; -#9522 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058320840, 128.4724153155870567, 89.82969158201160553 ) ) ; -#9523 = DIRECTION ( 'NONE', ( 0.0005884949961156549746, -0.2249510543439098842, 0.9743698870671255730 ) ) ; -#9524 = CARTESIAN_POINT ( 'NONE', ( -19.33075647067465397, 149.2722955532668436, 181.2498491173590764 ) ) ; -#9525 = ORIENTED_EDGE ( 'NONE', *, *, #3356, .T. ) ; -#9526 = CARTESIAN_POINT ( 'NONE', ( 40.54675149456901551, 220.4002261244750116, 76.03401540774370915 ) ) ; -#9527 = ORIENTED_EDGE ( 'NONE', *, *, #27758, .F. ) ; -#9528 = CARTESIAN_POINT ( 'NONE', ( 30.80442935676257221, 110.6131156702000027, 88.74917946218410236 ) ) ; -#9529 = CARTESIAN_POINT ( 'NONE', ( 25.99030219703914568, 209.7096538831000032, 73.04280978677728342 ) ) ; -#9530 = ADVANCED_FACE ( 'NONE', ( #2609 ), #5182, .F. ) ; -#9531 = CARTESIAN_POINT ( 'NONE', ( -29.09726181183376781, 181.7433723500874976, 101.6292608991324897 ) ) ; -#9532 = EDGE_LOOP ( 'NONE', ( #27145, #3543, #7449, #32430, #329 ) ) ; -#9533 = FACE_OUTER_BOUND ( 'NONE', #37357, .T. ) ; -#9534 = ORIENTED_EDGE ( 'NONE', *, *, #22527, .F. ) ; -#9535 = VECTOR ( 'NONE', #34267, 1000.000000000000227 ) ; -#9536 = AXIS2_PLACEMENT_3D ( 'NONE', #32716, #35540, #35346 ) ; -#9537 = CARTESIAN_POINT ( 'NONE', ( -25.86880953606799949, 189.5976987908379954, 103.9537772934139923 ) ) ; -#9538 = LINE ( 'NONE', #19911, #17109 ) ; -#9539 = VERTEX_POINT ( 'NONE', #24081 ) ; -#9540 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#9541 = ADVANCED_FACE ( 'NONE', ( #5453 ), #39610, .F. ) ; -#9542 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048787848, 153.7268358529419743, 98.24418217436381440 ) ) ; -#9543 = DIRECTION ( 'NONE', ( 0.9999998268370344778, 0.0001323825049342479854, -0.0005734115218532780545 ) ) ; -#9544 = AXIS2_PLACEMENT_3D ( 'NONE', #13774, #7427, #17432 ) ; -#9545 = CARTESIAN_POINT ( 'NONE', ( -21.26225680614087921, 158.5941992317567895, 96.28012005377419769 ) ) ; -#9546 = CYLINDRICAL_SURFACE ( 'NONE', #30470, 2.000000000000001332 ) ; -#9547 = ORIENTED_EDGE ( 'NONE', *, *, #13716, .F. ) ; -#9548 = ORIENTED_EDGE ( 'NONE', *, *, #10181, .T. ) ; -#9549 = DIRECTION ( 'NONE', ( 0.5986917825334768795, 0.8009794122048727871, -0.0003615948347011540827 ) ) ; -#9550 = EDGE_CURVE ( 'NONE', #38290, #14324, #34784, .T. ) ; -#9551 = CARTESIAN_POINT ( 'NONE', ( -38.98458235476000056, 142.5847786539000026, 26.89884147244999824 ) ) ; -#9552 = VERTEX_POINT ( 'NONE', #14676 ) ; -#9553 = CARTESIAN_POINT ( 'NONE', ( -23.36243050683136957, 135.2128115065362124, 91.28990528929200821 ) ) ; -#9555 = ADVANCED_FACE ( 'NONE', ( #36737 ), #33662, .T. ) ; -#9554 = DIRECTION ( 'NONE', ( -0.7066795775423952986, -4.274442269987938000E-15, 0.7075337268883383768 ) ) ; -#9556 = EDGE_CURVE ( 'NONE', #19444, #6128, #18214, .T. ) ; -#9557 = ORIENTED_EDGE ( 'NONE', *, *, #35352, .T. ) ; -#9558 = DIRECTION ( 'NONE', ( 0.0005734119072325851883, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#9559 = ADVANCED_FACE ( 'NONE', ( #26672 ), #29378, .F. ) ; -#9560 = EDGE_CURVE ( 'NONE', #34014, #7336, #22207, .T. ) ; -#9561 = DIRECTION ( 'NONE', ( -0.7856637698373362122, -0.6186537325232790430, 0.000000000000000000 ) ) ; -#9562 = DIRECTION ( 'NONE', ( -0.0006039748319381367221, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#9563 = EDGE_LOOP ( 'NONE', ( #19849, #38381, #25995, #5600 ) ) ; -#9564 = CARTESIAN_POINT ( 'NONE', ( 28.52923972082999882, 125.2870818839000009, 88.56041932755000801 ) ) ; -#9565 = CARTESIAN_POINT ( 'NONE', ( 25.65932787654801572, 211.0906275801376637, 73.37418414931370592 ) ) ; -#9566 = DIRECTION ( 'NONE', ( -0.0005884949961224280940, 0.2249510543439061094, -0.9743698870671263501 ) ) ; -#9567 = DIRECTION ( 'NONE', ( 0.7933533175743878729, 0.5930761747309519771, 0.1372995428259456974 ) ) ; -#9568 = DIRECTION ( 'NONE', ( -3.469446951882167451E-15, 0.9743700557921584071, 0.2249510932971570953 ) ) ; -#9569 = AXIS2_PLACEMENT_3D ( 'NONE', #4168, #16447, #28937 ) ; -#9570 = ORIENTED_EDGE ( 'NONE', *, *, #11155, .T. ) ; -#9571 = CARTESIAN_POINT ( 'NONE', ( 2.561557522426483491, 191.9759150222000130, 101.9199002238076162 ) ) ; -#9572 = CARTESIAN_POINT ( 'NONE', ( 5.667647268250993520, 124.2920528419670632, 90.91033987003989125 ) ) ; -#9573 = CARTESIAN_POINT ( 'NONE', ( 36.04502488578000197, 218.5902260770999987, 74.53673406417000535 ) ) ; -#9574 = CIRCLE ( 'NONE', #21984, 2.499999999952864371 ) ; -#9575 = CARTESIAN_POINT ( 'NONE', ( -45.98849231353116096, 125.1674804258049392, 91.77005729733592432 ) ) ; -#9576 = VERTEX_POINT ( 'NONE', #10933 ) ; -#9577 = ORIENTED_EDGE ( 'NONE', *, *, #27459, .T. ) ; -#9578 = CARTESIAN_POINT ( 'NONE', ( 38.49288589009113792, 119.0337946565482667, 90.25041038663783866 ) ) ; -#9579 = CARTESIAN_POINT ( 'NONE', ( 19.30946322470169108, 148.8544289525886768, 180.8759745330408748 ) ) ; -#9580 = CARTESIAN_POINT ( 'NONE', ( 24.19055539170138047, 213.8395337131380813, 73.04389359310243890 ) ) ; -#9581 = CARTESIAN_POINT ( 'NONE', ( -36.20902675056999698, 191.7497827512000015, 104.2839535104999982 ) ) ; -#9582 = EDGE_LOOP ( 'NONE', ( #30036, #16361, #20302, #2948, #15951, #20967 ) ) ; -#9583 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391913256 ) ) ; -#9584 = CARTESIAN_POINT ( 'NONE', ( -23.35287815472955941, 177.1132788188974132, 103.6357243926429135 ) ) ; -#9585 = CARTESIAN_POINT ( 'NONE', ( 20.50146814542411278, 184.4050074329408915, 104.7795556516932436 ) ) ; -#9586 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#9587 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265227786, 0.1368326740407719844 ) ) ; -#9588 = EDGE_CURVE ( 'NONE', #33439, #520, #8048, .T. ) ; -#9589 = CONICAL_SURFACE ( 'NONE', #6337, 2.502999999975751066, 0.7853981634562235969 ) ; -#9590 = CARTESIAN_POINT ( 'NONE', ( 20.16458336689871089, 127.3986389566010899, 89.22184904988743881 ) ) ; -#9591 = CARTESIAN_POINT ( 'NONE', ( 37.18343761575999906, 191.4768738335000080, 104.3136478636999982 ) ) ; -#9592 = AXIS2_PLACEMENT_3D ( 'NONE', #32725, #16959, #13916 ) ; -#9593 = CARTESIAN_POINT ( 'NONE', ( 36.55216596207999658, 191.7401717577000397, 106.2476387699000071 ) ) ; -#9594 = AXIS2_PLACEMENT_3D ( 'NONE', #24741, #37192, #15314 ) ; -#9595 = VERTEX_POINT ( 'NONE', #11129 ) ; -#9596 = ORIENTED_EDGE ( 'NONE', *, *, #24623, .F. ) ; -#9597 = ORIENTED_EDGE ( 'NONE', *, *, #12026, .F. ) ; -#9598 = FACE_OUTER_BOUND ( 'NONE', #3664, .T. ) ; -#9599 = EDGE_CURVE ( 'NONE', #2544, #11548, #30014, .T. ) ; -#9600 = CARTESIAN_POINT ( 'NONE', ( 20.14652253711376773, 126.7948032831537404, 91.84390006618201596 ) ) ; -#9601 = CONICAL_SURFACE ( 'NONE', #23970, 3.003184325552035627, 0.7853589132226472813 ) ; -#9602 = ADVANCED_FACE ( 'NONE', ( #29934 ), #29332, .T. ) ; -#9603 = DIRECTION ( 'NONE', ( 0.0006039748319378610095, 9.939046677758948188E-15, 0.9999998176071845934 ) ) ; -#9604 = PLANE ( 'NONE', #22657 ) ; -#9605 = CARTESIAN_POINT ( 'NONE', ( 12.31588672122218320, 137.2441267807453471, 91.84393833925072670 ) ) ; -#9606 = ORIENTED_EDGE ( 'NONE', *, *, #13694, .T. ) ; -#9607 = CARTESIAN_POINT ( 'NONE', ( 37.88562005261000110, 118.7629374576000174, 87.34018596161999426 ) ) ; -#9608 = EDGE_CURVE ( 'NONE', #26876, #14927, #32788, .T. ) ; -#9609 = CARTESIAN_POINT ( 'NONE', ( 37.48938149088855454, 212.8449748121827838, 73.03586143537702924 ) ) ; -#9610 = CARTESIAN_POINT ( 'NONE', ( -29.41585490894198784, 161.0327472628627561, 187.1177767716451399 ) ) ; -#9611 = FACE_OUTER_BOUND ( 'NONE', #6267, .T. ) ; -#9612 = ORIENTED_EDGE ( 'NONE', *, *, #12689, .F. ) ; -#9613 = FACE_OUTER_BOUND ( 'NONE', #8560, .T. ) ; -#9614 = CARTESIAN_POINT ( 'NONE', ( 5.666787591738080110, 130.4226561615404023, 90.27309335817682268 ) ) ; -#9615 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29837, #32692, #4673, #39621, #17126, #23699, #36568, #14293, #11029, #26573 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999807931, 0.3749999999999774070, 0.4374999999999818479, 0.4999999999999863443, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9616 = FACE_OUTER_BOUND ( 'NONE', #25556, .T. ) ; -#9617 = PLANE ( 'NONE', #12536 ) ; -#9618 = ORIENTED_EDGE ( 'NONE', *, *, #24793, .F. ) ; -#9619 = ORIENTED_EDGE ( 'NONE', *, *, #15969, .F. ) ; -#9620 = CARTESIAN_POINT ( 'NONE', ( 12.64366213596533406, 177.0557396825045373, 103.5152694373627895 ) ) ; -#9621 = CARTESIAN_POINT ( 'NONE', ( 1.317609656703000010, 189.1505943148000028, 103.7349513905000009 ) ) ; -#9622 = DIRECTION ( 'NONE', ( 0.7066795775021792458, -8.644699693605865341E-15, -0.7075337269285059127 ) ) ; -#9623 = VECTOR ( 'NONE', #6770, 1000.000000000000000 ) ; -#9624 = EDGE_LOOP ( 'NONE', ( #26096, #20483, #31135, #633 ) ) ; -#9625 = CARTESIAN_POINT ( 'NONE', ( -12.59997215317999952, 114.0103269030000064, 152.4718672074000381 ) ) ; -#9626 = ORIENTED_EDGE ( 'NONE', *, *, #6554, .F. ) ; -#9627 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37870, #15987, #12134, #15589 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9628 = VECTOR ( 'NONE', #16255, 1000.000000000000227 ) ; -#9629 = DIRECTION ( 'NONE', ( -0.0005884949961222158072, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#9630 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39081, #21517, #8841, #12295, #33144, #20689, #30514, #15171, #33955, #36836 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9631 = CARTESIAN_POINT ( 'NONE', ( -39.39972888957502306, 182.9666818760945830, 104.9968195249913236 ) ) ; -#9632 = CARTESIAN_POINT ( 'NONE', ( 13.46162264378999929, 153.1807780540000294, 28.07991271570000080 ) ) ; -#9633 = CARTESIAN_POINT ( 'NONE', ( 35.98188939040999657, 134.7361418062000098, 93.81639134258000468 ) ) ; -#9634 = CARTESIAN_POINT ( 'NONE', ( -2.214908976321755318, 190.0835411280691574, 106.0514516821102120 ) ) ; -#9635 = ORIENTED_EDGE ( 'NONE', *, *, #32122, .T. ) ; -#9636 = EDGE_CURVE ( 'NONE', #30285, #37352, #35209, .T. ) ; -#9637 = ADVANCED_FACE ( 'NONE', ( #13589 ), #26880, .F. ) ; -#9638 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8380, #5290, #21666, #2243 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9639 = CARTESIAN_POINT ( 'NONE', ( 24.94568828298271157, 117.2261764025736568, 170.8458856035829569 ) ) ; -#9640 = CARTESIAN_POINT ( 'NONE', ( 39.71644058364383056, 182.4824187750803333, 106.8892835983133693 ) ) ; -#9641 = EDGE_CURVE ( 'NONE', #37303, #12627, #1106, .T. ) ; -#9642 = EDGE_CURVE ( 'NONE', #906, #21267, #31416, .T. ) ; -#9643 = FACE_OUTER_BOUND ( 'NONE', #30130, .T. ) ; -#9644 = ORIENTED_EDGE ( 'NONE', *, *, #24296, .F. ) ; -#9645 = ORIENTED_EDGE ( 'NONE', *, *, #21529, .T. ) ; -#9646 = DIRECTION ( 'NONE', ( -0.7730662169443226484, -0.5272861007345266415, -0.3526159273084134571 ) ) ; -#9647 = CIRCLE ( 'NONE', #21401, 4.749999999995090150 ) ; -#9648 = CARTESIAN_POINT ( 'NONE', ( -29.94780647572998333, 103.6131156703220597, 87.78587210778204053 ) ) ; -#9649 = CIRCLE ( 'NONE', #11611, 6.000000000333073125 ) ; -#9650 = EDGE_LOOP ( 'NONE', ( #9695, #14802, #10810, #23964 ) ) ; -#9651 = DIRECTION ( 'NONE', ( -0.6087613502019255662, 0.7729389820454566351, 0.1788154035167601463 ) ) ; -#9652 = LINE ( 'NONE', #12925, #8743 ) ; -#9653 = EDGE_CURVE ( 'NONE', #36851, #3943, #16637, .T. ) ; -#9654 = CARTESIAN_POINT ( 'NONE', ( -38.65167172564999731, 119.0452778641000009, 90.11067139839001072 ) ) ; -#9655 = CARTESIAN_POINT ( 'NONE', ( -38.25200071130999646, 118.9539271141999990, 87.58069048670999734 ) ) ; -#9656 = LINE ( 'NONE', #19034, #15189 ) ; -#9657 = VERTEX_POINT ( 'NONE', #29138 ) ; -#9658 = CARTESIAN_POINT ( 'NONE', ( 17.27193878522344406, 122.1565749163837182, 173.7593392666709917 ) ) ; -#9659 = ORIENTED_EDGE ( 'NONE', *, *, #38423, .F. ) ; -#9660 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251391720, 179.1753088543719343, 103.5954339977985796 ) ) ; -#9661 = LINE ( 'NONE', #34380, #1140 ) ; -#9662 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28164, #31017, #24905, #10156, #37350, #9952, #31830, #38153, #18514, #19125, #34659, #730, #35051, #21818 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000997535, 0.3750000000000997535, 0.5000000000000998090, 0.6250000000000998090, 0.6875000000000498490, 0.7499999999999997780, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9663 = FACE_OUTER_BOUND ( 'NONE', #281, .T. ) ; -#9664 = EDGE_LOOP ( 'NONE', ( #34549, #17245, #10847, #37241 ) ) ; -#9665 = VERTEX_POINT ( 'NONE', #38513 ) ; -#9666 = CARTESIAN_POINT ( 'NONE', ( 20.94993391244204872, 135.9271259092254240, 94.10042936185872975 ) ) ; -#9667 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28619, #25968, #19187, #23091 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.0001384919294626354644 ), - .UNSPECIFIED. ) ; -#9668 = CARTESIAN_POINT ( 'NONE', ( 2.119762003991769284, 189.1507938075172888, 103.3205449036793766 ) ) ; -#9669 = CARTESIAN_POINT ( 'NONE', ( -30.07200330635000185, 135.2897752494975521, 91.41834187731066663 ) ) ; -#9670 = ORIENTED_EDGE ( 'NONE', *, *, #7788, .T. ) ; -#9671 = CARTESIAN_POINT ( 'NONE', ( -13.49823529423287560, 173.8389516671386161, 102.8738727251156462 ) ) ; -#9672 = CYLINDRICAL_SURFACE ( 'NONE', #33721, 2.000000000000011546 ) ; -#9673 = ORIENTED_EDGE ( 'NONE', *, *, #27501, .T. ) ; -#9674 = CARTESIAN_POINT ( 'NONE', ( 21.00135297806761514, 116.5765964922940725, 89.75535705397723518 ) ) ; -#9675 = CYLINDRICAL_SURFACE ( 'NONE', #18294, 1.750000000000001998 ) ; -#9676 = CARTESIAN_POINT ( 'NONE', ( -25.44744374708999857, 121.4359792056000060, 90.13081907286000671 ) ) ; -#9677 = AXIS2_PLACEMENT_3D ( 'NONE', #29470, #17374, #1862 ) ; -#9678 = ORIENTED_EDGE ( 'NONE', *, *, #23817, .T. ) ; -#9679 = CARTESIAN_POINT ( 'NONE', ( 2.729058208330169322, 189.6265354008074269, 106.5089234100929332 ) ) ; -#9680 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; -#9681 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11655, #4896, #17558, #20846 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9682 = AXIS2_PLACEMENT_3D ( 'NONE', #27374, #39795, #18118 ) ; -#9683 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#9684 = ORIENTED_EDGE ( 'NONE', *, *, #16099, .T. ) ; -#9685 = EDGE_CURVE ( 'NONE', #26196, #25299, #16090, .T. ) ; -#9686 = CARTESIAN_POINT ( 'NONE', ( -15.56569021289253740, 127.6492525721004654, 175.3175532804469015 ) ) ; -#9687 = CARTESIAN_POINT ( 'NONE', ( 3.166377416628577190, 128.5876387387983186, 89.33781556475464924 ) ) ; -#9688 = EDGE_CURVE ( 'NONE', #2849, #3073, #24234, .T. ) ; -#9689 = EDGE_CURVE ( 'NONE', #23147, #5203, #4368, .T. ) ; -#9691 = CARTESIAN_POINT ( 'NONE', ( -16.78015712463011866, 121.5863303463596452, 177.0789580759722810 ) ) ; -#9690 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265228896, 0.1368326740407718733 ) ) ; -#9692 = EDGE_LOOP ( 'NONE', ( #39069, #485, #7930, #13504 ) ) ; -#9693 = CARTESIAN_POINT ( 'NONE', ( -14.08011580147661235, 129.1601492223334446, 176.8499123979196099 ) ) ; -#9694 = DIRECTION ( 'NONE', ( 0.6087616187692346248, -0.7730003051580285334, -0.1785492081725818803 ) ) ; -#9695 = ORIENTED_EDGE ( 'NONE', *, *, #12729, .F. ) ; -#9696 = LINE ( 'NONE', #22175, #23880 ) ; -#9697 = EDGE_CURVE ( 'NONE', #17622, #20919, #32636, .T. ) ; -#9698 = DIRECTION ( 'NONE', ( -0.0004161288024526093362, -0.5299192578742120130, -0.8480479980348188951 ) ) ; -#9699 = ORIENTED_EDGE ( 'NONE', *, *, #18453, .F. ) ; -#9700 = ORIENTED_EDGE ( 'NONE', *, *, #8734, .T. ) ; -#9701 = PLANE ( 'NONE', #19126 ) ; -#9702 = EDGE_CURVE ( 'NONE', #11066, #22581, #33389, .T. ) ; -#9703 = CIRCLE ( 'NONE', #14929, 2.000000003389833303 ) ; -#9704 = DIRECTION ( 'NONE', ( -0.0006039748319386757875, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#9705 = CARTESIAN_POINT ( 'NONE', ( -2.813786152616000180, 190.8797540774000083, 106.6764626145999983 ) ) ; -#9706 = CARTESIAN_POINT ( 'NONE', ( 36.11091198150000281, 191.5180279879000125, 103.8372736401999958 ) ) ; -#9707 = EDGE_LOOP ( 'NONE', ( #38399, #11105, #2669, #40190 ) ) ; -#9708 = ORIENTED_EDGE ( 'NONE', *, *, #19650, .T. ) ; -#9709 = CIRCLE ( 'NONE', #22757, 2.500000000052250204 ) ; -#9710 = ORIENTED_EDGE ( 'NONE', *, *, #3626, .F. ) ; -#9711 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#9712 = CONICAL_SURFACE ( 'NONE', #30613, 6.500001099657994885, 0.7853982150629152947 ) ; -#9713 = LINE ( 'NONE', #22591, #10042 ) ; -#9714 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, -1.271205595054999941E-14 ) ) ; -#9715 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#9716 = AXIS2_PLACEMENT_3D ( 'NONE', #6942, #24981, #19008 ) ; -#9717 = ORIENTED_EDGE ( 'NONE', *, *, #36251, .T. ) ; -#9718 = EDGE_CURVE ( 'NONE', #35915, #6019, #8677, .T. ) ; -#9719 = EDGE_LOOP ( 'NONE', ( #29211, #10236, #27680, #17843 ) ) ; -#9720 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, -1.298960938811000068E-14 ) ) ; -#9721 = DIRECTION ( 'NONE', ( -0.0005884949961261904923, 0.2255194585872569157, -0.9742384859325513569 ) ) ; -#9722 = EDGE_LOOP ( 'NONE', ( #22191, #24248, #29802, #383, #35603, #28973, #24646, #30975, #26660, #29309, #3548 ) ) ; -#9723 = CARTESIAN_POINT ( 'NONE', ( -13.50000076883903510, 154.4042507776735818, 95.30811371979322644 ) ) ; -#9724 = ORIENTED_EDGE ( 'NONE', *, *, #28033, .F. ) ; -#9725 = CARTESIAN_POINT ( 'NONE', ( -5.667652426752654904, 187.3243678606383753, 105.5115252951561189 ) ) ; -#9726 = CARTESIAN_POINT ( 'NONE', ( -1.108382502455999896, 188.2795632126000100, 106.3695074111000025 ) ) ; -#9727 = FACE_OUTER_BOUND ( 'NONE', #2235, .T. ) ; -#9728 = VERTEX_POINT ( 'NONE', #33592 ) ; -#9729 = FACE_OUTER_BOUND ( 'NONE', #10558, .T. ) ; -#9730 = ORIENTED_EDGE ( 'NONE', *, *, #3756, .T. ) ; -#9731 = CARTESIAN_POINT ( 'NONE', ( 34.37515011644319429, 83.27714336192299527, 284.1420403139794644 ) ) ; -#9732 = CARTESIAN_POINT ( 'NONE', ( -25.83474554800833189, 118.1159992059333206, 87.45011729634273934 ) ) ; -#9733 = LINE ( 'NONE', #29143, #19608 ) ; -#9734 = CIRCLE ( 'NONE', #38427, 1.750000000000001998 ) ; -#9735 = ORIENTED_EDGE ( 'NONE', *, *, #22358, .T. ) ; -#9736 = CARTESIAN_POINT ( 'NONE', ( -22.49823197369664385, 157.6225053518252821, 99.13851915872771770 ) ) ; -#9737 = ORIENTED_EDGE ( 'NONE', *, *, #9195, .T. ) ; -#9738 = AXIS2_PLACEMENT_3D ( 'NONE', #19843, #20458, #33537 ) ; -#9739 = CONICAL_SURFACE ( 'NONE', #23415, 4.999999999912411397, 0.7853981633778838178 ) ; -#9740 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319364896022 ) ) ; -#9741 = EDGE_CURVE ( 'NONE', #22525, #28860, #25479, .T. ) ; -#9742 = EDGE_CURVE ( 'NONE', #7259, #8, #11942, .T. ) ; -#9743 = AXIS2_PLACEMENT_3D ( 'NONE', #23806, #36267, #2744 ) ; -#9744 = CARTESIAN_POINT ( 'NONE', ( -38.55367922949000103, 118.3586223536000119, 89.54641048761999400 ) ) ; -#9745 = ORIENTED_EDGE ( 'NONE', *, *, #20612, .T. ) ; -#9746 = ORIENTED_EDGE ( 'NONE', *, *, #23032, .T. ) ; -#9747 = CARTESIAN_POINT ( 'NONE', ( 37.40799538047578920, 111.9543163460056121, 150.4009621148262283 ) ) ; -#9748 = CARTESIAN_POINT ( 'NONE', ( -26.00142186005520983, 120.7678123865047297, 87.55007858260474052 ) ) ; -#9749 = CARTESIAN_POINT ( 'NONE', ( -20.06090143618003907, 160.1206884207606151, 96.63181232735072967 ) ) ; -#9750 = FACE_BOUND ( 'NONE', #35223, .T. ) ; -#9751 = ORIENTED_EDGE ( 'NONE', *, *, #3660, .T. ) ; -#9752 = EDGE_LOOP ( 'NONE', ( #14650, #34927, #20435, #32090 ) ) ; -#9753 = CYLINDRICAL_SURFACE ( 'NONE', #15245, 2.000000000000014655 ) ; -#9754 = PLANE ( 'NONE', #32068 ) ; -#9755 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #36088, #29567 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9756 = ORIENTED_EDGE ( 'NONE', *, *, #18051, .T. ) ; -#9757 = CARTESIAN_POINT ( 'NONE', ( -15.10513900131456388, 175.7048190624925610, 103.3056127689209376 ) ) ; -#9758 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30312, #27486, #18023, #17817 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9759 = ORIENTED_EDGE ( 'NONE', *, *, #25675, .T. ) ; -#9760 = DIRECTION ( 'NONE', ( -0.0005884949961233675551, 0.2249510543439052490, -0.9743698870671265722 ) ) ; -#9761 = AXIS2_PLACEMENT_3D ( 'NONE', #23279, #20603, #14485 ) ; -#9762 = ADVANCED_FACE ( 'NONE', ( #5587 ), #12334, .F. ) ; -#9763 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#9764 = CARTESIAN_POINT ( 'NONE', ( -22.49859347127474152, 158.2257569248202458, 98.76156587771905038 ) ) ; -#9765 = ORIENTED_EDGE ( 'NONE', *, *, #33879, .F. ) ; -#9766 = CARTESIAN_POINT ( 'NONE', ( 28.39476059464999835, 125.2008286205000047, 88.54061883459999649 ) ) ; -#9767 = VECTOR ( 'NONE', #36047, 1000.000000000000114 ) ; -#9768 = DIRECTION ( 'NONE', ( -2.081668171257503147E-15, 0.9743700557921587402, 0.2249510932971554300 ) ) ; -#9769 = VECTOR ( 'NONE', #8998, 999.9999999999998863 ) ; -#9770 = CARTESIAN_POINT ( 'NONE', ( 41.20534109643615039, 166.2329448439782027, 182.1790434216227084 ) ) ; -#9771 = CARTESIAN_POINT ( 'NONE', ( 3.868560647465115299, 175.2822330077133017, 100.4606273346248457 ) ) ; -#9772 = FACE_OUTER_BOUND ( 'NONE', #11016, .T. ) ; -#9773 = VERTEX_POINT ( 'NONE', #24223 ) ; -#9774 = CARTESIAN_POINT ( 'NONE', ( 6.035817316620117445, 176.7425654412684537, 103.0192746809948403 ) ) ; -#9775 = CARTESIAN_POINT ( 'NONE', ( 0.6241150675635340761, 189.0009256389474217, 103.6843667366763810 ) ) ; -#9776 = CARTESIAN_POINT ( 'NONE', ( 36.44740353825743995, 191.7901934835035149, 104.3576882541939312 ) ) ; -#9777 = EDGE_CURVE ( 'NONE', #40162, #30287, #7849, .T. ) ; -#9778 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799607651, 137.3509909075849009, 91.38105903666725283 ) ) ; -#9779 = ORIENTED_EDGE ( 'NONE', *, *, #34410, .F. ) ; -#9780 = ORIENTED_EDGE ( 'NONE', *, *, #33014, .F. ) ; -#9781 = CARTESIAN_POINT ( 'NONE', ( 38.50707698816808744, 119.0448651478242681, 90.25104051021725127 ) ) ; -#9782 = CARTESIAN_POINT ( 'NONE', ( 19.45332703025135146, 148.3679948532157482, 180.6096929009134158 ) ) ; -#9783 = CARTESIAN_POINT ( 'NONE', ( -3.779454719330632262, 168.4408027603464291, 98.79105186909471570 ) ) ; -#9784 = EDGE_CURVE ( 'NONE', #654, #29169, #37894, .T. ) ; -#9785 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #23073, #19171, #7111, #19584 ), - ( #35103, #7310, #22685, #19774 ), - ( #22479, #32081, #1380, #34902 ), - ( #16508, #25955, #4237, #35306 ), - ( #10002, #32275, #29415, #6916 ), - ( #13859, #19389, #31882, #28999 ), - ( #16714, #29212, #32472, #3836 ), - ( #26348, #4042, #28803, #38781 ), - ( #1184, #979, #13266, #13072 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 3, 4 ), - ( 4, 4 ), - ( 1.184794198244000012E-11, 0.3333321166536000191, 0.6666659962015000218, 0.9999984199999000234, 1.009998404199780486 ), - ( 0.1756414547379999969, 0.8243585473361000338 ), - .UNSPECIFIED. ) ; -#9786 = CARTESIAN_POINT ( 'NONE', ( -23.36043048140919609, 183.5592642829485328, 104.6107884962622876 ) ) ; -#9787 = ORIENTED_EDGE ( 'NONE', *, *, #13790, .T. ) ; -#9788 = ADVANCED_FACE ( 'NONE', ( #20725 ), #21139, .F. ) ; -#9789 = EDGE_CURVE ( 'NONE', #35367, #18185, #27698, .T. ) ; -#9790 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.261220487827980678E-14, 0.9999998176071847045 ) ) ; -#9791 = CIRCLE ( 'NONE', #4536, 7.500000216081117443 ) ; -#9792 = PLANE ( 'NONE', #21025 ) ; -#9793 = VECTOR ( 'NONE', #35607, 1000.000000000000000 ) ; -#9794 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971550692 ) ) ; -#9795 = ORIENTED_EDGE ( 'NONE', *, *, #31523, .T. ) ; -#9796 = CARTESIAN_POINT ( 'NONE', ( 28.35076616234001179, 124.9606007872231004, 91.22203692840190570 ) ) ; -#9797 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319379635751 ) ) ; -#9798 = CIRCLE ( 'NONE', #35844, 2.250000000000011102 ) ; -#9799 = CARTESIAN_POINT ( 'NONE', ( 20.11399216128939571, 127.4110302031022712, 89.17284890815865595 ) ) ; -#9800 = CARTESIAN_POINT ( 'NONE', ( 37.96459381866999649, 191.1162765711000020, 105.6220215677000027 ) ) ; -#9801 = VECTOR ( 'NONE', #36260, 1000.000000000000000 ) ; -#9802 = AXIS2_PLACEMENT_3D ( 'NONE', #22106, #21712, #3464 ) ; -#9803 = CARTESIAN_POINT ( 'NONE', ( 36.35497006709000090, 190.7198586766999995, 106.8900521645000055 ) ) ; -#9804 = ORIENTED_EDGE ( 'NONE', *, *, #18242, .T. ) ; -#9805 = ORIENTED_EDGE ( 'NONE', *, *, #24102, .F. ) ; -#9806 = FACE_OUTER_BOUND ( 'NONE', #2489, .T. ) ; -#9807 = CARTESIAN_POINT ( 'NONE', ( 15.99999439207489615, 185.9093013714976053, 102.5638074086867846 ) ) ; -#9808 = LINE ( 'NONE', #31689, #19331 ) ; -#9809 = DIRECTION ( 'NONE', ( 0.6087613186456907188, -0.7729176985478710682, -0.1789074850089337476 ) ) ; -#9810 = ORIENTED_EDGE ( 'NONE', *, *, #631, .T. ) ; -#9811 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971543198 ) ) ; -#9812 = VERTEX_POINT ( 'NONE', #5795 ) ; -#9813 = CARTESIAN_POINT ( 'NONE', ( -4.606609670189222960, 130.7903696091986490, 89.85103943815249750 ) ) ; -#9814 = CARTESIAN_POINT ( 'NONE', ( -36.27950425524976907, 191.8188495074159334, 104.4051415298545180 ) ) ; -#9815 = ORIENTED_EDGE ( 'NONE', *, *, #4920, .T. ) ; -#9816 = CARTESIAN_POINT ( 'NONE', ( 36.06588537441000142, 194.9391275604999976, 107.7152975676000040 ) ) ; -#9817 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#9818 = CARTESIAN_POINT ( 'NONE', ( -44.88970483650875565, 186.0423651227323205, 106.4552165319083628 ) ) ; -#9819 = DIRECTION ( 'NONE', ( 0.7933533411653070910, -0.5930537057989907490, -0.1373964268091706076 ) ) ; -#9820 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; -#9821 = CARTESIAN_POINT ( 'NONE', ( 22.11658946403013815, 136.0358612623089982, 91.55906883338052182 ) ) ; -#9822 = ORIENTED_EDGE ( 'NONE', *, *, #3611, .T. ) ; -#9823 = VERTEX_POINT ( 'NONE', #5172 ) ; -#9824 = CIRCLE ( 'NONE', #29400, 4.500000000062149397 ) ; -#9825 = CARTESIAN_POINT ( 'NONE', ( 12.64052830712477515, 176.9480430948374021, 103.3429212818187324 ) ) ; -#9826 = VECTOR ( 'NONE', #4407, 999.9999999999998863 ) ; -#9827 = FACE_OUTER_BOUND ( 'NONE', #21165, .T. ) ; -#9828 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921569638, -0.2249510932971626187 ) ) ; -#9829 = EDGE_CURVE ( 'NONE', #31713, #31820, #22873, .T. ) ; -#9830 = CONICAL_SURFACE ( 'NONE', #13092, 4.999999999982041032, 0.7853981634219900920 ) ; -#9831 = VECTOR ( 'NONE', #18249, 1000.000000000000114 ) ; -#9832 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; -#9833 = ORIENTED_EDGE ( 'NONE', *, *, #21232, .F. ) ; -#9834 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319364147923 ) ) ; -#9835 = EDGE_LOOP ( 'NONE', ( #1328, #11087, #19299, #1110, #39245, #21671, #23662, #13944, #39732, #14381, #9570 ) ) ; -#9836 = EDGE_CURVE ( 'NONE', #14883, #10112, #9156, .T. ) ; -#9838 = ADVANCED_FACE ( 'NONE', ( #12145 ), #38516, .F. ) ; -#9837 = CARTESIAN_POINT ( 'NONE', ( -20.49970530398912771, 127.6304983571866813, 89.64427666219336288 ) ) ; -#9839 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21734, #24609, #39916, #30535, #33978, #18426, #18626, #30316, #8663, #27277, #27489, #24204, #11927, #24408, #16564, #15770, #22737 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000008273937, 0.1875000000012067292, 0.2187500000014120094, 0.2343750000014990786, 0.2500000000015861201, 0.3750000000012484458, 0.4375000000010796364, 0.4687500000009522383, 0.5000000000008247847, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9840 = EDGE_CURVE ( 'NONE', #16668, #36222, #14604, .T. ) ; -#9841 = CARTESIAN_POINT ( 'NONE', ( -12.63532509571790108, 176.8621834306625260, 103.2253653902710511 ) ) ; -#9842 = EDGE_CURVE ( 'NONE', #30285, #2544, #12364, .T. ) ; -#9843 = CARTESIAN_POINT ( 'NONE', ( 15.50107933576640029, 185.4974642970334173, 104.3505830678656849 ) ) ; -#9844 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552156487, 3.781093664149108639E-12, 291.5584375788758393 ) ) ; -#9845 = FACE_OUTER_BOUND ( 'NONE', #35264, .T. ) ; -#9846 = EDGE_LOOP ( 'NONE', ( #19005, #1036, #11760, #1668 ) ) ; -#9847 = FACE_OUTER_BOUND ( 'NONE', #36842, .T. ) ; -#9848 = CARTESIAN_POINT ( 'NONE', ( 24.33241291692780806, 117.2920445016514748, 170.8609620625155117 ) ) ; -#9849 = CARTESIAN_POINT ( 'NONE', ( 43.14456005852381537, 112.6780295318855565, 129.4537069268840526 ) ) ; -#9850 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; -#9851 = ORIENTED_EDGE ( 'NONE', *, *, #35576, .T. ) ; -#9852 = ORIENTED_EDGE ( 'NONE', *, *, #30889, .T. ) ; -#9853 = VECTOR ( 'NONE', #18688, 1000.000000000000114 ) ; -#9854 = AXIS2_PLACEMENT_3D ( 'NONE', #37916, #4150, #9920 ) ; -#9855 = ORIENTED_EDGE ( 'NONE', *, *, #29115, .T. ) ; -#9856 = CARTESIAN_POINT ( 'NONE', ( 23.68305125547955470, 135.1720086282025477, 91.18766367950343010 ) ) ; -#9857 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927783543234, -0.0005734119022076374994 ) ) ; -#9858 = AXIS2_PLACEMENT_3D ( 'NONE', #38054, #19033, #18824 ) ; -#9859 = PLANE ( 'NONE', #18697 ) ; -#9860 = VERTEX_POINT ( 'NONE', #11532 ) ; -#9861 = LINE ( 'NONE', #433, #11314 ) ; -#9862 = CARTESIAN_POINT ( 'NONE', ( -38.59197811685999824, 118.5863865315999988, 89.70884965135999778 ) ) ; -#9863 = CARTESIAN_POINT ( 'NONE', ( -38.14759201839999747, 119.0917469409999967, 87.44184615819000328 ) ) ; -#9864 = LINE ( 'NONE', #7171, #34627 ) ; -#9865 = CARTESIAN_POINT ( 'NONE', ( 6.026693642215255053, 134.9199437178238838, 90.79804054718465522 ) ) ; -#9866 = ORIENTED_EDGE ( 'NONE', *, *, #40007, .F. ) ; -#9867 = EDGE_LOOP ( 'NONE', ( #27272, #10620, #12127, #17463 ) ) ; -#9868 = LINE ( 'NONE', #22342, #20474 ) ; -#9869 = CARTESIAN_POINT ( 'NONE', ( 31.86660797104250875, 191.2310028312767258, 27.90332390889487257 ) ) ; -#9870 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971571509 ) ) ; -#9871 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282902982, 164.6343173020860320, 97.67551052990278038 ) ) ; -#9872 = ORIENTED_EDGE ( 'NONE', *, *, #3964, .F. ) ; -#9873 = CARTESIAN_POINT ( 'NONE', ( -2.938990254353359699, 191.1128505916019833, 103.7748658681480123 ) ) ; -#9874 = CARTESIAN_POINT ( 'NONE', ( 2.774572678350095689, 189.9381179826846449, 103.5019175557437734 ) ) ; -#9876 = EDGE_CURVE ( 'NONE', #33925, #3470, #33971, .T. ) ; -#9875 = CARTESIAN_POINT ( 'NONE', ( -26.01077944034773282, 209.7097224531575534, 73.07398733611859143 ) ) ; -#9877 = CARTESIAN_POINT ( 'NONE', ( 0.04503145192460000085, 226.4002260771000010, 74.55847715811999876 ) ) ; -#9878 = EDGE_CURVE ( 'NONE', #15288, #34118, #29457, .T. ) ; -#9879 = EDGE_CURVE ( 'NONE', #10049, #22996, #9475, .T. ) ; -#9880 = ORIENTED_EDGE ( 'NONE', *, *, #11733, .T. ) ; -#9881 = VERTEX_POINT ( 'NONE', #3723 ) ; -#9882 = CARTESIAN_POINT ( 'NONE', ( 20.49980344970378354, 118.1127835573565221, 87.75514417896067698 ) ) ; -#9883 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825996983, 153.3598638654817989, 97.61100683840648173 ) ) ; -#9884 = VERTEX_POINT ( 'NONE', #37274 ) ; -#9885 = ADVANCED_FACE ( 'NONE', ( #38080 ), #9675, .F. ) ; -#9886 = CARTESIAN_POINT ( 'NONE', ( 2.729597314120624674, 191.4510214948855946, 104.1933275101542762 ) ) ; -#9887 = CARTESIAN_POINT ( 'NONE', ( 0.5638618802117814077, 189.0000000030334490, 105.7369977366696219 ) ) ; -#9888 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#9889 = CIRCLE ( 'NONE', #1972, 5.999999999999998224 ) ; -#9890 = ORIENTED_EDGE ( 'NONE', *, *, #21442, .T. ) ; -#9891 = AXIS2_PLACEMENT_3D ( 'NONE', #26210, #8613, #33929 ) ; -#9892 = CARTESIAN_POINT ( 'NONE', ( -19.99827189493212387, 119.1180982749954609, 90.27979767742741046 ) ) ; -#9893 = CARTESIAN_POINT ( 'NONE', ( -5.343454222961205424, 124.3650038869850079, 88.36807164162695472 ) ) ; -#9894 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#9895 = ADVANCED_FACE ( 'NONE', ( #6586 ), #13093, .F. ) ; -#9896 = ORIENTED_EDGE ( 'NONE', *, *, #4917, .F. ) ; -#9897 = CARTESIAN_POINT ( 'NONE', ( 3.166377416628577190, 128.5876387387983186, 89.33781556475464924 ) ) ; -#9898 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#9900 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709481474, 77.27946979429643193, 322.5205145037752459 ) ) ; -#9899 = CARTESIAN_POINT ( 'NONE', ( -21.82963555936113309, 135.9868450106493185, 91.57429495730107760 ) ) ; -#9901 = ADVANCED_FACE ( 'NONE', ( #34584 ), #856, .F. ) ; -#9902 = LINE ( 'NONE', #34795, #16394 ) ; -#9903 = ORIENTED_EDGE ( 'NONE', *, *, #8059, .F. ) ; -#9904 = LINE ( 'NONE', #9491, #36263 ) ; -#9905 = CARTESIAN_POINT ( 'NONE', ( 3.166361157742045407, 185.3154562800214649, 102.4344721822745328 ) ) ; -#9906 = ORIENTED_EDGE ( 'NONE', *, *, #6486, .F. ) ; -#9907 = CIRCLE ( 'NONE', #5980, 6.500000000016243895 ) ; -#9908 = EDGE_LOOP ( 'NONE', ( #36895, #19490, #6706, #6341 ) ) ; -#9910 = VECTOR ( 'NONE', #39120, 1000.000000000000000 ) ; -#9909 = CARTESIAN_POINT ( 'NONE', ( -25.99225322733968113, 193.8169247290872761, 102.7186084094945926 ) ) ; -#9911 = AXIS2_PLACEMENT_3D ( 'NONE', #32319, #26194, #10852 ) ; -#9912 = CARTESIAN_POINT ( 'NONE', ( 13.50308961628300430, 187.4748527437822645, 105.7372973370598004 ) ) ; -#9913 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597321 ) ) ; -#9914 = CARTESIAN_POINT ( 'NONE', ( 36.31286245014000258, 191.7213987641999893, 104.1933407292000027 ) ) ; -#9915 = VERTEX_POINT ( 'NONE', #9887 ) ; -#9916 = ORIENTED_EDGE ( 'NONE', *, *, #34850, .F. ) ; -#9917 = CARTESIAN_POINT ( 'NONE', ( -29.94780647242213689, 109.6131156702000027, 87.78587210770182025 ) ) ; -#9918 = CYLINDRICAL_SURFACE ( 'NONE', #25064, 2.000000000000014655 ) ; -#9919 = CARTESIAN_POINT ( 'NONE', ( -30.77616838766000029, 184.0515098276000003, 103.7026069805999953 ) ) ; -#9920 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; -#9921 = ORIENTED_EDGE ( 'NONE', *, *, #22451, .F. ) ; -#9922 = CARTESIAN_POINT ( 'NONE', ( 31.79391125766024118, 112.9712782986316171, 186.3766760902708199 ) ) ; -#9923 = ORIENTED_EDGE ( 'NONE', *, *, #20804, .F. ) ; -#9925 = EDGE_CURVE ( 'NONE', #19846, #13511, #660, .T. ) ; -#9924 = CARTESIAN_POINT ( 'NONE', ( -37.00271443861222309, 116.5564442434732371, 89.73446267232999674 ) ) ; -#9926 = ADVANCED_FACE ( 'NONE', ( #34782 ), #3512, .F. ) ; -#9927 = EDGE_CURVE ( 'NONE', #10716, #40452, #36250, .T. ) ; -#9928 = PLANE ( 'NONE', #11804 ) ; -#9929 = ORIENTED_EDGE ( 'NONE', *, *, #26552, .T. ) ; -#9930 = CARTESIAN_POINT ( 'NONE', ( 40.54493956969010071, 206.4002260771000010, 73.03401595486556630 ) ) ; -#9931 = CARTESIAN_POINT ( 'NONE', ( -46.53618338323362735, 143.6732897604458685, 289.8004740256295690 ) ) ; -#9932 = CARTESIAN_POINT ( 'NONE', ( 22.11776639833565028, 135.5859592220768945, 93.50780862338704935 ) ) ; -#9933 = EDGE_CURVE ( 'NONE', #5155, #24392, #23587, .T. ) ; -#9934 = ORIENTED_EDGE ( 'NONE', *, *, #35500, .F. ) ; -#9935 = FACE_OUTER_BOUND ( 'NONE', #24719, .T. ) ; -#9936 = ORIENTED_EDGE ( 'NONE', *, *, #37629, .T. ) ; -#9937 = ORIENTED_EDGE ( 'NONE', *, *, #7733, .F. ) ; -#9938 = FACE_OUTER_BOUND ( 'NONE', #14898, .T. ) ; -#9939 = AXIS2_PLACEMENT_3D ( 'NONE', #19188, #31901, #32291 ) ; -#9940 = CARTESIAN_POINT ( 'NONE', ( -37.29435884442529670, 164.6092402323636463, 198.2106787237848948 ) ) ; -#9941 = LINE ( 'NONE', #7045, #18965 ) ; -#9942 = CONICAL_SURFACE ( 'NONE', #32772, 2.502997546632800940, 0.7853981634134501455 ) ; -#9943 = EDGE_CURVE ( 'NONE', #36211, #27638, #671, .T. ) ; -#9944 = AXIS2_PLACEMENT_3D ( 'NONE', #12003, #40191, #37537 ) ; -#9945 = DIRECTION ( 'NONE', ( 0.0005884949961175196939, -0.2249510543439042221, 0.9743698870671267942 ) ) ; -#9946 = ORIENTED_EDGE ( 'NONE', *, *, #3219, .T. ) ; -#9947 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#9948 = CARTESIAN_POINT ( 'NONE', ( 16.00000031304551129, 127.7446264382961232, 89.13542822417404921 ) ) ; -#9949 = ORIENTED_EDGE ( 'NONE', *, *, #32184, .T. ) ; -#9950 = CARTESIAN_POINT ( 'NONE', ( 8.188663998450230963, 161.0533193647609949, 96.83006515600399666 ) ) ; -#9951 = CARTESIAN_POINT ( 'NONE', ( 25.49919833444198858, 118.8155663768459505, 87.75236248755290092 ) ) ; -#9952 = CARTESIAN_POINT ( 'NONE', ( 23.36304559730844232, 177.4675757536537617, 100.8901253294131237 ) ) ; -#9953 = DIRECTION ( 'NONE', ( 0.0005884949950583391728, -0.2249510543447034716, 0.9743698870669428302 ) ) ; -#9954 = EDGE_LOOP ( 'NONE', ( #29504, #35960, #27331, #37545 ) ) ; -#9955 = ORIENTED_EDGE ( 'NONE', *, *, #33115, .T. ) ; -#9956 = EDGE_LOOP ( 'NONE', ( #11216, #30512, #34415, #37312 ) ) ; -#9957 = CARTESIAN_POINT ( 'NONE', ( 37.40434350968867250, 145.4460227941551409, 282.5393146728916918 ) ) ; -#9958 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971548471 ) ) ; -#9959 = EDGE_LOOP ( 'NONE', ( #19073, #34780, #23859, #13830 ) ) ; -#9960 = VERTEX_POINT ( 'NONE', #10289 ) ; -#9961 = DIRECTION ( 'NONE', ( -0.6087611434178765712, -0.7731004625452565504, -0.1781166614241066204 ) ) ; -#9962 = CARTESIAN_POINT ( 'NONE', ( 19.98271301993268523, 207.8686081833218111, 77.26500776042075813 ) ) ; -#9963 = VECTOR ( 'NONE', #15666, 1000.000000000000227 ) ; -#9964 = ORIENTED_EDGE ( 'NONE', *, *, #23682, .T. ) ; -#9965 = FACE_OUTER_BOUND ( 'NONE', #40009, .T. ) ; -#9966 = CONICAL_SURFACE ( 'NONE', #32795, 2.503158050477443552, 0.7853981633930871009 ) ; -#9967 = AXIS2_PLACEMENT_3D ( 'NONE', #36336, #17096, #8333 ) ; -#9968 = LINE ( 'NONE', #28766, #7748 ) ; -#9969 = ORIENTED_EDGE ( 'NONE', *, *, #12535, .T. ) ; -#9970 = CARTESIAN_POINT ( 'NONE', ( 28.40947388104000382, 125.3678125673000068, 88.75007089381999492 ) ) ; -#9971 = FACE_OUTER_BOUND ( 'NONE', #16704, .T. ) ; -#9972 = CARTESIAN_POINT ( 'NONE', ( -31.70415073521903082, 226.4002260770974715, 75.57765305100397768 ) ) ; -#9973 = EDGE_CURVE ( 'NONE', #26075, #6177, #8376, .T. ) ; -#9974 = EDGE_CURVE ( 'NONE', #8110, #33342, #30455, .T. ) ; -#9975 = CARTESIAN_POINT ( 'NONE', ( 20.50029382911849041, 160.6303866027595575, 97.23813965018092631 ) ) ; -#9976 = CARTESIAN_POINT ( 'NONE', ( 36.04411892353206781, 218.5902260770999987, 73.03673433784747715 ) ) ; -#9977 = ORIENTED_EDGE ( 'NONE', *, *, #24430, .T. ) ; -#9978 = CARTESIAN_POINT ( 'NONE', ( 0.5444273898015423718, 211.0000000000153761, 73.55817535318051625 ) ) ; -#9979 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 132.9679238121742912, 90.36185680194377312 ) ) ; -#9980 = CARTESIAN_POINT ( 'NONE', ( -1.546702755154200526, 188.6421838410412306, 106.2842503570885810 ) ) ; -#9981 = CARTESIAN_POINT ( 'NONE', ( -26.00138850119475364, 118.1173731751006102, 87.28355378449504087 ) ) ; -#9982 = DIRECTION ( 'NONE', ( 0.0005884949961254435855, -0.2249510543439056098, 0.9743698870671265722 ) ) ; -#9983 = DIRECTION ( 'NONE', ( -0.7856246811335055868, -0.6187033702784217049, 0.000000000000000000 ) ) ; -#9984 = CARTESIAN_POINT ( 'NONE', ( -3.742149463410260335, 168.4491106192983523, 98.75463826265171008 ) ) ; -#9985 = AXIS2_PLACEMENT_3D ( 'NONE', #20765, #6823, #28719 ) ; -#9986 = CARTESIAN_POINT ( 'NONE', ( -25.71583257454510374, 189.5945154360309743, 106.0004275678039960 ) ) ; -#9987 = ORIENTED_EDGE ( 'NONE', *, *, #30388, .T. ) ; -#9988 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28844, #31509, #22522, #34940, #16357, #13307, #7156, #23511, #4282, #20224, #13508, #8178, #39240, #29250, #32318, #7966, #14318, #13705, #16756, #32908, #35538, #20026 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 1, 1, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999997939149, 0.1874999999997047362, 0.2187499999996750932, 0.2343749999996755651, 0.2421874999996899980, 0.2499999999997044031, 0.3749999999997604139, 0.4374999999997855604, 0.4999999999998107070, 0.7499999999999052980, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#9989 = CIRCLE ( 'NONE', #14544, 5.249999999999986677 ) ; -#9990 = CARTESIAN_POINT ( 'NONE', ( -19.00212931565669550, 148.4455407551447195, 183.7151382749372033 ) ) ; -#9991 = ADVANCED_FACE ( 'NONE', ( #23495 ), #20836, .T. ) ; -#9992 = CIRCLE ( 'NONE', #23039, 2.499999999999997335 ) ; -#9993 = CARTESIAN_POINT ( 'NONE', ( 19.98210856654580780, 205.1070970766282358, 76.09272704596726555 ) ) ; -#9994 = EDGE_LOOP ( 'NONE', ( #4626, #13949, #20764, #22397 ) ) ; -#9995 = CARTESIAN_POINT ( 'NONE', ( 20.49918579871235735, 117.7855550408559253, 87.75515918128132853 ) ) ; -#9996 = CARTESIAN_POINT ( 'NONE', ( 23.36030151151609857, 181.4168257864797340, 104.2589971034701222 ) ) ; -#9997 = DIRECTION ( 'NONE', ( 0.9914447795421099663, 0.1272537940605282525, 0.02904687618140097335 ) ) ; -#9998 = CARTESIAN_POINT ( 'NONE', ( -41.39564160242315438, 120.8598907892144609, 87.92272842288021195 ) ) ; -#9999 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#10000 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10001 = ORIENTED_EDGE ( 'NONE', *, *, #36269, .T. ) ; -#10002 = CARTESIAN_POINT ( 'NONE', ( -2.874686192646000116, 209.6463030548999882, 76.06021946686999513 ) ) ; -#10003 = CARTESIAN_POINT ( 'NONE', ( 20.50068614270568190, 184.7049436401913738, 103.4803894424373141 ) ) ; -#10004 = FACE_OUTER_BOUND ( 'NONE', #2698, .T. ) ; -#10005 = ORIENTED_EDGE ( 'NONE', *, *, #20292, .T. ) ; -#10006 = CARTESIAN_POINT ( 'NONE', ( 6.042308921164076807, 177.7921139377573638, 100.6958234779730645 ) ) ; -#10007 = VERTEX_POINT ( 'NONE', #21045 ) ; -#10008 = EDGE_CURVE ( 'NONE', #25177, #2058, #6992, .T. ) ; -#10009 = DIRECTION ( 'NONE', ( 0.6087614883550945821, -0.7730004026499608383, -0.1785492307423601210 ) ) ; -#10010 = LINE ( 'NONE', #4049, #7112 ) ; -#10011 = CARTESIAN_POINT ( 'NONE', ( -37.58602203893437377, 191.4135895612745912, 104.3798639524113270 ) ) ; -#10012 = CARTESIAN_POINT ( 'NONE', ( -42.49459211381155654, 185.0676328030043294, 127.1859204975182251 ) ) ; -#10013 = LINE ( 'NONE', #37812, #21425 ) ; -#10014 = ADVANCED_FACE ( 'NONE', ( #7743 ), #6531, .F. ) ; -#10015 = CIRCLE ( 'NONE', #29595, 4.500000000010447643 ) ; -#10016 = EDGE_CURVE ( 'NONE', #16362, #32161, #28031, .T. ) ; -#10017 = CARTESIAN_POINT ( 'NONE', ( 22.99888613823950578, 118.1131156702000169, 87.25083745503069110 ) ) ; -#10018 = CARTESIAN_POINT ( 'NONE', ( 20.50039165879256942, 118.8156470718432729, 87.75541749211321019 ) ) ; -#10019 = EDGE_LOOP ( 'NONE', ( #33170, #40204, #36069, #22683 ) ) ; -#10020 = CARTESIAN_POINT ( 'NONE', ( 12.64122564679159311, 176.9953992898509227, 103.4187065096068210 ) ) ; -#10021 = CONICAL_SURFACE ( 'NONE', #18454, 6.499999999875097245, 0.7853981634274167511 ) ; -#10022 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10023 = FACE_OUTER_BOUND ( 'NONE', #703, .T. ) ; -#10024 = PLANE ( 'NONE', #39247 ) ; -#10025 = ORIENTED_EDGE ( 'NONE', *, *, #40135, .T. ) ; -#10026 = PLANE ( 'NONE', #8134 ) ; -#10027 = VERTEX_POINT ( 'NONE', #17948 ) ; -#10028 = CARTESIAN_POINT ( 'NONE', ( 20.00178331300101320, 191.9758063960465790, 106.9093738487591736 ) ) ; -#10029 = CARTESIAN_POINT ( 'NONE', ( -12.63378477145710299, 177.0226112301060368, 103.4821023998732272 ) ) ; -#10030 = CARTESIAN_POINT ( 'NONE', ( -15.49852918059724693, 160.1761146120170736, 99.20761365264185372 ) ) ; -#10031 = EDGE_CURVE ( 'NONE', #19312, #25364, #7951, .T. ) ; -#10032 = CARTESIAN_POINT ( 'NONE', ( -3.083129345975000213, 209.1876396531000069, 72.95049128518999737 ) ) ; -#10033 = LINE ( 'NONE', #1421, #37631 ) ; -#10034 = CIRCLE ( 'NONE', #29617, 2.000000000000011546 ) ; -#10035 = EDGE_LOOP ( 'NONE', ( #37263, #18372, #33048, #11371 ) ) ; -#10036 = CARTESIAN_POINT ( 'NONE', ( 15.05621097247296980, 125.1021127306558043, 171.3704188677303648 ) ) ; -#10037 = DIRECTION ( 'NONE', ( 0.0005884949961248781740, -0.2249510543439064425, 0.9743698870671262391 ) ) ; -#10038 = DIRECTION ( 'NONE', ( 4.622231023467483304E-33, -1.000000000000000000, -2.791711714772432647E-36 ) ) ; -#10039 = AXIS2_PLACEMENT_3D ( 'NONE', #15968, #25003, #22535 ) ; -#10040 = CARTESIAN_POINT ( 'NONE', ( -43.94868134759096279, 113.2635659203109242, 86.34157100920022287 ) ) ; -#10041 = ORIENTED_EDGE ( 'NONE', *, *, #14697, .T. ) ; -#10042 = VECTOR ( 'NONE', #34222, 1000.000000000000000 ) ; -#10043 = EDGE_LOOP ( 'NONE', ( #36128, #6187, #5198, #17012, #3155 ) ) ; -#10044 = CARTESIAN_POINT ( 'NONE', ( 23.67998985452990368, 134.9222885997251637, 90.78792508986444432 ) ) ; -#10045 = ADVANCED_FACE ( 'NONE', ( #4680 ), #4880, .F. ) ; -#10046 = CARTESIAN_POINT ( 'NONE', ( 28.46126684983220301, 181.2175652934160723, 104.3810058980785698 ) ) ; -#10047 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10048 = LINE ( 'NONE', #17859, #23276 ) ; -#10049 = VERTEX_POINT ( 'NONE', #1616 ) ; -#10050 = VERTEX_POINT ( 'NONE', #1824 ) ; -#10051 = DIRECTION ( 'NONE', ( 0.0006039748302207421579, 7.542342735779980945E-05, 0.9999998147628383904 ) ) ; -#10052 = EDGE_CURVE ( 'NONE', #31713, #37217, #11421, .T. ) ; -#10053 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#10054 = CARTESIAN_POINT ( 'NONE', ( -38.71072168210999820, 118.8966380287999982, 89.91271735956999578 ) ) ; -#10055 = CARTESIAN_POINT ( 'NONE', ( -38.35938540240999828, 118.8192337114000026, 87.71744047141000067 ) ) ; -#10056 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; -#10057 = CARTESIAN_POINT ( 'NONE', ( 13.76493622865632105, 124.4309290350651622, 178.6669391780345109 ) ) ; -#10058 = ORIENTED_EDGE ( 'NONE', *, *, #10804, .T. ) ; -#10059 = CARTESIAN_POINT ( 'NONE', ( -12.63662705431230293, 128.0215907353206717, 91.78242701837325512 ) ) ; -#10060 = ORIENTED_EDGE ( 'NONE', *, *, #5575, .T. ) ; -#10061 = CARTESIAN_POINT ( 'NONE', ( 10.21688458673440891, 134.9203821546222741, 90.79555158895830402 ) ) ; -#10062 = CARTESIAN_POINT ( 'NONE', ( -23.00006628334871550, 115.6131129681876359, 89.78164257609942922 ) ) ; -#10063 = ADVANCED_FACE ( 'NONE', ( #36159 ), #16313, .F. ) ; -#10064 = ADVANCED_FACE ( 'NONE', ( #17544 ), #39424, .T. ) ; -#10065 = CARTESIAN_POINT ( 'NONE', ( -20.00104315107090258, 184.5969240560925186, 102.2825614518015982 ) ) ; -#10066 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988409597765, 156.3551877982712028, 95.75036263596727792 ) ) ; -#10067 = ORIENTED_EDGE ( 'NONE', *, *, #5442, .F. ) ; -#10068 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; -#10069 = ADVANCED_FACE ( 'NONE', ( #39632, #34294, #33901 ), #31053, .T. ) ; -#10070 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927798816119, -0.0005734119022070481271 ) ) ; -#10071 = AXIS2_PLACEMENT_3D ( 'NONE', #1981, #36929, #9470 ) ; -#10072 = AXIS2_PLACEMENT_3D ( 'NONE', #40421, #21447, #2821 ) ; -#10073 = PLANE ( 'NONE', #19464 ) ; -#10074 = VECTOR ( 'NONE', #33521, 1000.000000000000227 ) ; -#10075 = ORIENTED_EDGE ( 'NONE', *, *, #898, .F. ) ; -#10076 = FACE_OUTER_BOUND ( 'NONE', #33660, .T. ) ; -#10077 = FACE_OUTER_BOUND ( 'NONE', #24461, .T. ) ; -#10078 = EDGE_LOOP ( 'NONE', ( #39926, #33403, #4136, #10463, #36228, #11660, #33716, #22337, #33365, #1072 ) ) ; -#10079 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#10080 = CARTESIAN_POINT ( 'NONE', ( 21.09369789642633108, 176.5485049525730403, 100.3996169591982408 ) ) ; -#10081 = FACE_OUTER_BOUND ( 'NONE', #34043, .T. ) ; -#10082 = VERTEX_POINT ( 'NONE', #18357 ) ; -#10083 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28202, #21254, #37388, #18152, #15121, #24535, #21466, #24739, #21664, #9385, #9185, #21415, #5856, #17903, #6053, #18500, #118, #9531, #2973, #12579 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999517331, 0.1874999999999391875, 0.2187499999999441280, 0.2343749999999461264, 0.2499999999999481526, 0.4999999999999749090, 0.6249999999999944489, 0.6875000000000048850, 0.7187500000000140998, 0.7343750000000180966, 0.7500000000000219824, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10084 = FACE_OUTER_BOUND ( 'NONE', #4081, .T. ) ; -#10085 = CARTESIAN_POINT ( 'NONE', ( -5.675054657474391639, 124.3656264979204167, 88.36836997283377571 ) ) ; -#10086 = EDGE_CURVE ( 'NONE', #15609, #6503, #27608, .T. ) ; -#10087 = VERTEX_POINT ( 'NONE', #34100 ) ; -#10088 = ORIENTED_EDGE ( 'NONE', *, *, #6190, .F. ) ; -#10089 = CARTESIAN_POINT ( 'NONE', ( 26.00433782744423894, 120.0770285022223618, 90.42368137231409264 ) ) ; -#10090 = CARTESIAN_POINT ( 'NONE', ( 32.37049208148693680, 138.3096525682149718, 91.56466976714693828 ) ) ; -#10091 = ORIENTED_EDGE ( 'NONE', *, *, #38187, .F. ) ; -#10093 = LINE ( 'NONE', #29101, #5741 ) ; -#10092 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971566513 ) ) ; -#10094 = AXIS2_PLACEMENT_3D ( 'NONE', #38627, #29853, #23107 ) ; -#10095 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319412346130 ) ) ; -#10096 = AXIS2_PLACEMENT_3D ( 'NONE', #19410, #3866, #11034 ) ; -#10097 = VECTOR ( 'NONE', #747, 1000.000000000000114 ) ; -#10098 = VERTEX_POINT ( 'NONE', #21852 ) ; -#10099 = CARTESIAN_POINT ( 'NONE', ( 13.45852275855000180, 176.5968831303999877, 28.07991271570000080 ) ) ; -#10100 = EDGE_CURVE ( 'NONE', #32767, #13796, #28871, .T. ) ; -#10101 = CARTESIAN_POINT ( 'NONE', ( 39.72066837979766518, 175.7297623423441166, 136.1382466769391897 ) ) ; -#10103 = ORIENTED_EDGE ( 'NONE', *, *, #3811, .T. ) ; -#10102 = CIRCLE ( 'NONE', #32935, 6.500000000009833023 ) ; -#10104 = ORIENTED_EDGE ( 'NONE', *, *, #33281, .T. ) ; -#10105 = CARTESIAN_POINT ( 'NONE', ( 39.02126669689999972, 118.7292573019000059, 89.54553178854999373 ) ) ; -#10106 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; -#10107 = EDGE_CURVE ( 'NONE', #29513, #20244, #20248, .T. ) ; -#10108 = CARTESIAN_POINT ( 'NONE', ( -46.11428651860251904, 125.3901704247413420, 91.70828747460114982 ) ) ; -#10109 = CARTESIAN_POINT ( 'NONE', ( -2.557040332230999802, 190.9413657988000068, 106.4259741240000068 ) ) ; -#10110 = EDGE_CURVE ( 'NONE', #19817, #24492, #29714, .T. ) ; -#10111 = ORIENTED_EDGE ( 'NONE', *, *, #13520, .T. ) ; -#10112 = VERTEX_POINT ( 'NONE', #27799 ) ; -#10113 = CARTESIAN_POINT ( 'NONE', ( -6.035627011758199600, 176.7717547812872283, 103.0754667242794369 ) ) ; -#10114 = CARTESIAN_POINT ( 'NONE', ( -12.63689782195842426, 177.3133338180326461, 101.0041712154207971 ) ) ; -#10115 = CARTESIAN_POINT ( 'NONE', ( -23.36135659116623131, 134.7454096763920575, 93.42281670956344897 ) ) ; -#10116 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394468890994, 77.14301703112153064, 297.5584364845176424 ) ) ; -#10117 = EDGE_CURVE ( 'NONE', #18466, #27631, #33274, .T. ) ; -#10118 = CARTESIAN_POINT ( 'NONE', ( -3.419728389424999904, 184.9596546093000029, 102.6128657888999953 ) ) ; -#10119 = ORIENTED_EDGE ( 'NONE', *, *, #37569, .F. ) ; -#10120 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #25515, #25112, #9362, #9564 ), - ( #22041, #34672, #13237, #16478 ), - ( #34279, #153, #25920, #31228 ), - ( #942, #13031, #12612, #3805 ), - ( #7076, #37559, #9970, #3203 ), - ( #15682, #6672, #19141, #34470 ), - ( #16283, #13433, #18940, #35072 ), - ( #15878, #22443, #25719, #9766 ), - ( #28370, #28968, #21834, #343 ), - ( #28183, #10175, #31643, #12829 ), - ( #25315, #3601, #16083, #6879 ), - ( #19351, #27284, #4202, #30124 ), - ( #14593, #23582, #8249, #23792 ), - ( #5576, #39711, #36246, #17826 ), - ( #11117, #14195, #30328, #36661 ), - ( #39109, #14801, #17429, #20923 ), - ( #38365, #27080, #18034, #11726 ), - ( #30540, #29925, #39511, #26663 ), - ( #36036, #8670, #8034, #11310 ), - ( #21124, #32241, #22840, #29726 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( 4.144611087445999877E-13, 0.001560744696352999979, 0.003123273415232000021, 0.006248330852988999602, 0.009373388290745000850, 0.01249844572850000030, 0.02499867547953000049, 0.04999913498157999847, 0.07499959448364000580, 0.1000000539855999959, 0.1500009729898000022, 0.2000018919939000051, 0.3000016515100000225, 0.4000014110264000222, 0.5000011705425999597, 0.6000009300586000016, 0.8000004490911000188, 0.9999999999993000044 ), - ( 0.1755538993766999900, 0.8244309313148000529 ), - .UNSPECIFIED. ) ; -#10121 = CARTESIAN_POINT ( 'NONE', ( -21.48379418977146216, 213.0894754797338635, 73.57151699824268576 ) ) ; -#10122 = ORIENTED_EDGE ( 'NONE', *, *, #38794, .T. ) ; -#10123 = CARTESIAN_POINT ( 'NONE', ( -36.88617345849917228, 116.3403704899029805, 89.73734838559249738 ) ) ; -#10124 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; -#10125 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37977, #31858, #38181, #7087, #19561, #25929, #25322, #13635, #32449, #4212, #9775, #32059, #35471, #22253, #34880, #4019, #19949, #3608, #16485, #4421, #28975, #549, #954, #13442, #26124, #22851, #35282, #29189, #16878, #19149, #32248, #1158, #19361, #37766, #29385, #38564, #34683, #755, #10584, #3815, #28583, #23050, #1350, #31653, #16292, #13042, #25522, #13244, #14045, #1770, #39370, #8521, #7895, #11586, #10779, #1561, #5433, #10979, #26520, #5224, #38757, #35678, #5028, #13834, #30190, #7693, #39175, #39574, #17691, #35891, #33037, #24063, #1982, #20987, #17891, #36519, #20156, #30390, #36313, #17284, #11177, #11367, #26723 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 2, 1, 2, 2, 2, 2, 1, 1, 1, 2, 2, 2, 2, 1, 1, 1, 2, 2, 2, 2, 1, 1, 1, 1, 1, 2, 2, 2, 2, 2, 1, 1, 1, 1, 1, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.03124999999964665071, 0.04687499999947851437, 0.06249999999931038497, 0.09374999999901274805, 0.1249999999987151111, 0.1562499999984174603, 0.1718749999982719656, 0.1874999999981264431, 0.2187499999978410326, 0.2343749999976944276, 0.2421874999976163789, 0.2499999999975383025, 0.3124999999969176878, 0.3437499999966042719, 0.3593749999964475639, 0.3671874999963690711, 0.3710937499963357644, 0.3730468749963191111, 0.3749999999963024577, 0.4374999999957845387, 0.4687499999955245800, 0.4843749999953838037, 0.4921874999953129159, 0.4960937499952750573, 0.4980468749952560725, 0.4999999999952371432, 0.6249999999941835416, 0.6874999999936627360, 0.7187499999934022776, 0.7343749999932634998, 0.7421874999931941108, 0.7460937499931673544, 0.7480468749931539207, 0.7490234374931551420, 0.7499999999931562522, 0.8124999999930890837, 0.8437499999930507810, 0.8593749999930213601, 0.8671874999930213601, 0.8710937499930025973, 0.8730468749929957140, 0.8740234374929921612, 0.8745117187430150318, 0.8747558593680300199, 0.8749999999930448968, 0.9062499999947836171, 0.9374999999965223374, 0.9687499999982611687, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10126 = CARTESIAN_POINT ( 'NONE', ( -14.44401576354613326, 124.5449641176314799, 88.41511525325832110 ) ) ; -#10127 = AXIS2_PLACEMENT_3D ( 'NONE', #11997, #30807, #28147 ) ; -#10128 = CARTESIAN_POINT ( 'NONE', ( -2.561038461354999907, 190.7963388503999909, 106.3865919585000057 ) ) ; -#10129 = AXIS2_PLACEMENT_3D ( 'NONE', #19705, #32009, #19899 ) ; -#10130 = CONICAL_SURFACE ( 'NONE', #22539, 2.500000720456969194, 0.7853981633184845546 ) ; -#10131 = DIRECTION ( 'NONE', ( 0.0005884949961234677354, -0.2249510543439058596, 0.9743698870671263501 ) ) ; -#10132 = ORIENTED_EDGE ( 'NONE', *, *, #25902, .T. ) ; -#10133 = CARTESIAN_POINT ( 'NONE', ( -35.95405601968200671, 218.5902260770999987, 76.08021997850752882 ) ) ; -#10134 = ORIENTED_EDGE ( 'NONE', *, *, #15852, .F. ) ; -#10135 = CIRCLE ( 'NONE', #29713, 51.40509898898542929 ) ; -#10136 = DIRECTION ( 'NONE', ( -0.0006039748319386088922, 0.000000000000000000, -0.9999998176071845934 ) ) ; -#10137 = CARTESIAN_POINT ( 'NONE', ( 30.05352353131179655, 109.6131156702000027, 87.24963271652086405 ) ) ; -#10138 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #20746, #27114, #26490, #29553 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.570796326794891895, 3.141592653589798889 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8047378541243626060, 0.8047378541243626060, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#10139 = CARTESIAN_POINT ( 'NONE', ( 19.31897996664549311, 125.9032283610015952, 175.4006784427203911 ) ) ; -#10140 = FACE_OUTER_BOUND ( 'NONE', #35350, .T. ) ; -#10141 = FACE_OUTER_BOUND ( 'NONE', #18403, .T. ) ; -#10142 = ORIENTED_EDGE ( 'NONE', *, *, #9973, .F. ) ; -#10143 = CARTESIAN_POINT ( 'NONE', ( 28.46393509008022349, 182.0672870871918576, 102.1824291507762865 ) ) ; -#10144 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7196, #34399, #3517, #28687, #25235 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 4 ), - ( 0.000000000000000000, 0.001674833360455941925, 0.003349666720911883850 ), - .UNSPECIFIED. ) ; -#10145 = CARTESIAN_POINT ( 'NONE', ( -45.12594099392538993, 124.0049325119809254, 93.44049169948378619 ) ) ; -#10146 = CARTESIAN_POINT ( 'NONE', ( -35.90900567064999649, 113.8802525378000041, 89.89618011484999727 ) ) ; -#10147 = ORIENTED_EDGE ( 'NONE', *, *, #9702, .F. ) ; -#10148 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -4.625929269271484533E-15, 0.0006039748319299392864 ) ) ; -#10149 = ORIENTED_EDGE ( 'NONE', *, *, #22113, .F. ) ; -#10150 = ADVANCED_FACE ( 'NONE', ( #18956 ), #36773, .F. ) ; -#10151 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#10152 = ADVANCED_FACE ( 'NONE', ( #21661 ), #28761, .F. ) ; -#10153 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16109, #10198, #29396, #7101 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10154 = CARTESIAN_POINT ( 'NONE', ( 25.49919833792598212, 119.3071684866960567, 87.75237467855311024 ) ) ; -#10155 = EDGE_CURVE ( 'NONE', #38686, #16668, #12433, .T. ) ; -#10156 = CARTESIAN_POINT ( 'NONE', ( 23.36315499107861982, 177.3935024194639425, 100.9364114368636223 ) ) ; -#10157 = ADVANCED_FACE ( 'NONE', ( #40435 ), #32008, .F. ) ; -#10158 = DIRECTION ( 'NONE', ( 0.0005884949961258157921, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10159 = VERTEX_POINT ( 'NONE', #30656 ) ; -#10160 = AXIS2_PLACEMENT_3D ( 'NONE', #4939, #14564, #1886 ) ; -#10161 = ORIENTED_EDGE ( 'NONE', *, *, #29687, .F. ) ; -#10162 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10163 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825944865401622, 0.0005734119018115155621 ) ) ; -#10164 = AXIS2_PLACEMENT_3D ( 'NONE', #11426, #14503, #5283 ) ; -#10165 = CIRCLE ( 'NONE', #40199, 51.90509898902980979 ) ; -#10166 = EDGE_CURVE ( 'NONE', #16493, #34215, #30838, .T. ) ; -#10167 = EDGE_LOOP ( 'NONE', ( #13999, #37058, #29712, #27594 ) ) ; -#10168 = CARTESIAN_POINT ( 'NONE', ( -30.77616838766000029, 127.9758643804000116, 90.75652178872999798 ) ) ; -#10169 = VECTOR ( 'NONE', #34998, 1000.000000000000000 ) ; -#10170 = FACE_OUTER_BOUND ( 'NONE', #5590, .T. ) ; -#10171 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10172 = EDGE_CURVE ( 'NONE', #14325, #5169, #35238, .T. ) ; -#10173 = CARTESIAN_POINT ( 'NONE', ( 37.32093527568547131, 124.9538660553759115, 92.22097858659103053 ) ) ; -#10174 = EDGE_LOOP ( 'NONE', ( #3446, #3544, #17555, #18364, #24725, #31535, #37627, #7602 ) ) ; -#10175 = CARTESIAN_POINT ( 'NONE', ( 27.98864118927000533, 125.2419143087000180, 88.89258992074999810 ) ) ; -#10176 = CARTESIAN_POINT ( 'NONE', ( -14.91027383994646272, 151.7163915728016548, 177.9904694539845025 ) ) ; -#10177 = PLANE ( 'NONE', #29929 ) ; -#10178 = DIRECTION ( 'NONE', ( -0.0005884949961238529524, 0.2249510543439058596, -0.9743698870671263501 ) ) ; -#10179 = CARTESIAN_POINT ( 'NONE', ( 5.659153654835778369, 124.3673852322629187, 88.36203164978959990 ) ) ; -#10180 = EDGE_LOOP ( 'NONE', ( #17599, #5888, #5416, #31224 ) ) ; -#10181 = EDGE_CURVE ( 'NONE', #7714, #33558, #25508, .T. ) ; -#10182 = CARTESIAN_POINT ( 'NONE', ( 18.98511042798971360, 148.3283295584973871, 184.1927148392349807 ) ) ; -#10183 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10184 = CARTESIAN_POINT ( 'NONE', ( 3.166376970775131028, 185.9099593149100542, 102.5717182116986521 ) ) ; -#10185 = VECTOR ( 'NONE', #15484, 1000.000000000000000 ) ; -#10186 = CARTESIAN_POINT ( 'NONE', ( 25.99886678296517672, 118.8155665066540934, 87.25209012101137773 ) ) ; -#10187 = EDGE_LOOP ( 'NONE', ( #30177, #26805, #9815, #27311, #23951, #39119, #20115, #36899, #30169, #4916, #22198, #23486, #18724, #12218, #28629 ) ) ; -#10188 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825909994896701, 0.0005734119026157004058 ) ) ; -#10189 = LINE ( 'NONE', #35686, #37520 ) ; -#10190 = VECTOR ( 'NONE', #39992, 1000.000000000000227 ) ; -#10191 = DIRECTION ( 'NONE', ( 0.7856637149787887298, -0.6186538021912810770, 0.000000000000000000 ) ) ; -#10192 = CARTESIAN_POINT ( 'NONE', ( 25.50046720880995110, 119.8278461341044903, 89.86771791569053391 ) ) ; -#10193 = CARTESIAN_POINT ( 'NONE', ( 35.65259997913155132, 138.3326317399398988, 284.1430326337134602 ) ) ; -#10194 = CONICAL_SURFACE ( 'NONE', #33012, 2.502986300332882497, 0.7853981634574371817 ) ; -#10195 = CARTESIAN_POINT ( 'NONE', ( -15.66504166165583811, 173.9170443170240787, 102.5510515039815971 ) ) ; -#10196 = VERTEX_POINT ( 'NONE', #28782 ) ; -#10197 = AXIS2_PLACEMENT_3D ( 'NONE', #23177, #4347, #29509 ) ; -#10198 = CARTESIAN_POINT ( 'NONE', ( -15.83311930531312939, 174.4825619823285763, 100.1161292540394214 ) ) ; -#10199 = AXIS2_PLACEMENT_3D ( 'NONE', #15047, #8924, #15250 ) ; -#10200 = CARTESIAN_POINT ( 'NONE', ( 39.05471716683091188, 128.1851843108063917, 89.22321456362486458 ) ) ; -#10201 = CARTESIAN_POINT ( 'NONE', ( -15.99998378297181745, 127.7446958148473186, 89.15477705487283799 ) ) ; -#10202 = CARTESIAN_POINT ( 'NONE', ( 20.56429213702289971, 117.4584657514178758, 87.75512422162726978 ) ) ; -#10203 = CARTESIAN_POINT ( 'NONE', ( -31.70535867972207456, 220.4002260770999726, 73.57765341566839368 ) ) ; -#10204 = DIRECTION ( 'NONE', ( 0.0005884949672441799938, -0.2249510543775923299, 0.9743698870593667793 ) ) ; -#10205 = CARTESIAN_POINT ( 'NONE', ( 20.04841488032064234, 118.1066675202736036, 90.20916913282452754 ) ) ; -#10206 = ADVANCED_FACE ( 'NONE', ( #25528 ), #35479, .T. ) ; -#10207 = CARTESIAN_POINT ( 'NONE', ( -8.245636600931119276, 134.9179796086513363, 90.80620474745657589 ) ) ; -#10208 = ADVANCED_FACE ( 'NONE', ( #22857 ), #22461, .F. ) ; -#10209 = CARTESIAN_POINT ( 'NONE', ( -25.75142470483000068, 118.4643410412000009, 87.53333755287000884 ) ) ; -#10210 = CARTESIAN_POINT ( 'NONE', ( 13.50046316317049566, 187.7460073498711495, 103.5025028263219014 ) ) ; -#10211 = ORIENTED_EDGE ( 'NONE', *, *, #35841, .F. ) ; -#10212 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10213 = DIRECTION ( 'NONE', ( 0.0002393071182786170076, 0.2252352986010032476, -0.9743043687658492491 ) ) ; -#10214 = DIRECTION ( 'NONE', ( 0.7856637149787886187, -0.6186538021912811880, 0.000000000000000000 ) ) ; -#10215 = CIRCLE ( 'NONE', #39542, 5.499999999931961092 ) ; -#10216 = ORIENTED_EDGE ( 'NONE', *, *, #28480, .T. ) ; -#10217 = CARTESIAN_POINT ( 'NONE', ( -43.57149722038838036, 121.9974985178074434, 87.84418581487720701 ) ) ; -#10218 = VECTOR ( 'NONE', #21430, 1000.000000000000114 ) ; -#10219 = ORIENTED_EDGE ( 'NONE', *, *, #32353, .F. ) ; -#10220 = CIRCLE ( 'NONE', #8906, 5.999999999996103561 ) ; -#10221 = CARTESIAN_POINT ( 'NONE', ( 1.222756100067673435, 140.3958132876599620, 157.8527939211185753 ) ) ; -#10222 = CARTESIAN_POINT ( 'NONE', ( -36.54959120146399698, 191.6649449992200971, 104.3912839148767233 ) ) ; -#10223 = CIRCLE ( 'NONE', #10197, 2.500000000042679638 ) ; -#10224 = CARTESIAN_POINT ( 'NONE', ( -45.81619705300119705, 185.6006999936632837, 105.6694458431696688 ) ) ; -#10225 = VECTOR ( 'NONE', #33535, 1000.000000000000114 ) ; -#10226 = CARTESIAN_POINT ( 'NONE', ( -12.63766980425072184, 130.4202329703295788, 90.28358935384768813 ) ) ; -#10227 = FACE_OUTER_BOUND ( 'NONE', #11583, .T. ) ; -#10228 = EDGE_LOOP ( 'NONE', ( #9353, #38947 ) ) ; -#10229 = EDGE_CURVE ( 'NONE', #14171, #36248, #556, .T. ) ; -#10230 = CARTESIAN_POINT ( 'NONE', ( 2.545697083959657991, 209.0000005535759158, 75.65980364788404700 ) ) ; -#10231 = CARTESIAN_POINT ( 'NONE', ( -5.093541643503057159, 177.6102236329692232, 100.6605505116180410 ) ) ; -#10232 = CARTESIAN_POINT ( 'NONE', ( 4.034652562532943243, 176.8532558938365753, 100.4802775065020199 ) ) ; -#10233 = CARTESIAN_POINT ( 'NONE', ( -37.91598371520999677, 191.5233122829000081, 104.5546425013999965 ) ) ; -#10234 = VERTEX_POINT ( 'NONE', #361 ) ; -#10235 = DIRECTION ( 'NONE', ( -0.6185863125140933505, -0.7857168535612663041, 0.000000000000000000 ) ) ; -#10236 = ORIENTED_EDGE ( 'NONE', *, *, #24688, .F. ) ; -#10237 = CARTESIAN_POINT ( 'NONE', ( 36.96746166380989251, 116.2895703986138045, 89.69339363532195364 ) ) ; -#10238 = CARTESIAN_POINT ( 'NONE', ( -35.69644648028999967, 112.4664344015000097, 90.03934455280000293 ) ) ; -#10239 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098504, 132.2930706491197554, 93.28496646308185802 ) ) ; -#10240 = CIRCLE ( 'NONE', #18692, 2.000000000000000000 ) ; -#10241 = CARTESIAN_POINT ( 'NONE', ( 39.06502905710053142, 190.9636352783319069, 106.2825191316666888 ) ) ; -#10242 = CIRCLE ( 'NONE', #27889, 4.999999999999990230 ) ; -#10243 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 5.029100215316657124E-18, 0.0006039748319386160479 ) ) ; -#10244 = CIRCLE ( 'NONE', #22652, 2.250000000025644820 ) ; -#10245 = DIRECTION ( 'NONE', ( 0.7933533411653341805, -0.5930537057989598848, -0.1373964268091485141 ) ) ; -#10246 = CARTESIAN_POINT ( 'NONE', ( -2.701082792949999867, 209.7945284301000299, 73.18331558202000053 ) ) ; -#10247 = CARTESIAN_POINT ( 'NONE', ( 38.53322760872000430, 118.5959699799000049, 89.80756470608000086 ) ) ; -#10248 = ORIENTED_EDGE ( 'NONE', *, *, #13662, .T. ) ; -#10249 = CIRCLE ( 'NONE', #17395, 2.499999999981690646 ) ; -#10250 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971564015 ) ) ; -#10251 = FACE_OUTER_BOUND ( 'NONE', #16721, .T. ) ; -#10252 = LINE ( 'NONE', #1223, #37272 ) ; -#10253 = VECTOR ( 'NONE', #33894, 1000.000000000000114 ) ; -#10254 = EDGE_CURVE ( 'NONE', #1631, #2366, #4024, .T. ) ; -#10255 = ADVANCED_FACE ( 'NONE', ( #12850 ), #23560, .T. ) ; -#10257 = ORIENTED_EDGE ( 'NONE', *, *, #23162, .T. ) ; -#10256 = CARTESIAN_POINT ( 'NONE', ( -13.47107783232944378, 153.8044057555319739, 95.68275536702104489 ) ) ; -#10258 = ORIENTED_EDGE ( 'NONE', *, *, #18995, .F. ) ; -#10259 = VERTEX_POINT ( 'NONE', #32064 ) ; -#10260 = CARTESIAN_POINT ( 'NONE', ( -13.50128341151254041, 124.5457894246117405, 88.66272138216928056 ) ) ; -#10261 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775456658 ) ) ; -#10262 = CARTESIAN_POINT ( 'NONE', ( -5.960622339528989677, 163.5635530557085247, 97.41814418763185301 ) ) ; -#10263 = VERTEX_POINT ( 'NONE', #31454 ) ; -#10264 = VERTEX_POINT ( 'NONE', #13450 ) ; -#10265 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#10266 = DIRECTION ( 'NONE', ( 0.0002393071182785534462, 0.2252352986010039970, -0.9743043687658490271 ) ) ; -#10267 = CARTESIAN_POINT ( 'NONE', ( 76.10601358361095947, 156.3729538787885645, 95.70849706805188362 ) ) ; -#10268 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971540422 ) ) ; -#10269 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#10270 = ORIENTED_EDGE ( 'NONE', *, *, #34722, .F. ) ; -#10271 = CARTESIAN_POINT ( 'NONE', ( -35.44629553183553838, 112.4664344014998818, 90.28919351346762312 ) ) ; -#10272 = VECTOR ( 'NONE', #5705, 1000.000000000000000 ) ; -#10273 = ORIENTED_EDGE ( 'NONE', *, *, #36044, .F. ) ; -#10274 = CARTESIAN_POINT ( 'NONE', ( -25.50005268430136951, 117.7857744470418879, 89.78316151549972801 ) ) ; -#10275 = AXIS2_PLACEMENT_3D ( 'NONE', #16324, #7317, #38210 ) ; -#10276 = CARTESIAN_POINT ( 'NONE', ( 22.74075048786999886, 163.2545600168000135, 28.07991271570000080 ) ) ; -#10277 = VECTOR ( 'NONE', #34011, 1000.000000000000114 ) ; -#10278 = CARTESIAN_POINT ( 'NONE', ( -27.39351927441814638, 155.9581902257390880, 179.7869227509170003 ) ) ; -#10279 = EDGE_LOOP ( 'NONE', ( #34581, #15735, #7233, #4765 ) ) ; -#10280 = EDGE_CURVE ( 'NONE', #17189, #22581, #33791, .T. ) ; -#10281 = CARTESIAN_POINT ( 'NONE', ( -2.604892257046000026, 190.8452476264000097, 104.0499095697999934 ) ) ; -#10282 = DIRECTION ( 'NONE', ( -1.387778780823376196E-15, 0.9743700557921586292, 0.2249510932971564570 ) ) ; -#10283 = CARTESIAN_POINT ( 'NONE', ( -35.45366962857106330, 209.7096538831000032, 78.07991812242501339 ) ) ; -#10284 = ORIENTED_EDGE ( 'NONE', *, *, #26126, .T. ) ; -#10285 = CARTESIAN_POINT ( 'NONE', ( 6.034640325019517526, 177.1924675499267892, 101.0705349078851327 ) ) ; -#10286 = CARTESIAN_POINT ( 'NONE', ( 16.22247671335948382, 122.0701589875174164, 174.5870958018068109 ) ) ; -#10287 = EDGE_LOOP ( 'NONE', ( #37822, #3056, #5253, #6807 ) ) ; -#10288 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; -#10289 = CARTESIAN_POINT ( 'NONE', ( -16.53432056516032489, 121.7275407210895679, 178.0345399794734078 ) ) ; -#10290 = ADVANCED_FACE ( 'NONE', ( #22261 ), #25737, .T. ) ; -#10291 = EDGE_LOOP ( 'NONE', ( #8926, #38614, #32514, #30704 ) ) ; -#10292 = LINE ( 'NONE', #4119, #14744 ) ; -#10293 = CARTESIAN_POINT ( 'NONE', ( -3.170187864156448043, 126.4764607245763273, 88.85422735284892326 ) ) ; -#10294 = CARTESIAN_POINT ( 'NONE', ( 23.68970156757699641, 130.2249728062055283, 92.61131571664684259 ) ) ; -#10295 = ADVANCED_FACE ( 'NONE', ( #34691 ), #5248, .F. ) ; -#10296 = EDGE_LOOP ( 'NONE', ( #16238, #34785, #9684, #23803, #13116, #9949 ) ) ; -#10297 = CARTESIAN_POINT ( 'NONE', ( 25.83775114702000053, 120.3471401855999972, 90.32964940587000058 ) ) ; -#10298 = FACE_OUTER_BOUND ( 'NONE', #17993, .T. ) ; -#10299 = EDGE_CURVE ( 'NONE', #18545, #22996, #3505, .T. ) ; -#10300 = ADVANCED_FACE ( 'NONE', ( #6687 ), #34886, .F. ) ; -#10301 = AXIS2_PLACEMENT_3D ( 'NONE', #32468, #38776, #19768 ) ; -#10303 = PLANE ( 'NONE', #10968 ) ; -#10302 = PLANE ( 'NONE', #6719 ) ; -#10304 = EDGE_CURVE ( 'NONE', #11064, #20943, #16104, .T. ) ; -#10305 = ORIENTED_EDGE ( 'NONE', *, *, #22796, .T. ) ; -#10306 = CARTESIAN_POINT ( 'NONE', ( 12.63809651561607517, 175.3577520439124555, 100.1267379975303129 ) ) ; -#10307 = EDGE_CURVE ( 'NONE', #9884, #1120, #14767, .T. ) ; -#10308 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5066, #5269, #32687, #39216 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.002038048205810061037 ), - .UNSPECIFIED. ) ; -#10309 = CARTESIAN_POINT ( 'NONE', ( 12.31023268411626148, 134.2457138696073855, 93.71750156584897695 ) ) ; -#10310 = ORIENTED_EDGE ( 'NONE', *, *, #24383, .T. ) ; -#10311 = CARTESIAN_POINT ( 'NONE', ( -20.51863885680050359, 209.7097602209678939, 75.57089512796630970 ) ) ; -#10312 = CARTESIAN_POINT ( 'NONE', ( -8.050307605157906110, 151.4365984322141117, 94.61967771673485572 ) ) ; -#10313 = ORIENTED_EDGE ( 'NONE', *, *, #40232, .T. ) ; -#10314 = ORIENTED_EDGE ( 'NONE', *, *, #2541, .T. ) ; -#10315 = CARTESIAN_POINT ( 'NONE', ( 39.03663829597000046, 118.7256501412000063, 89.52709215164999534 ) ) ; -#10316 = CARTESIAN_POINT ( 'NONE', ( -35.46521474675949293, 113.6040542059936627, 87.28920439305406376 ) ) ; -#10317 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927783657346, -0.0005734119022073981076 ) ) ; -#10318 = CARTESIAN_POINT ( 'NONE', ( 17.27897118364565898, 126.5703640932063223, 154.6621420009977612 ) ) ; -#10319 = CARTESIAN_POINT ( 'NONE', ( 37.35642412351155173, 166.8680590464960005, 188.4831583878417121 ) ) ; -#10320 = VERTEX_POINT ( 'NONE', #32650 ) ; -#10321 = VERTEX_POINT ( 'NONE', #1569 ) ; -#10322 = FACE_OUTER_BOUND ( 'NONE', #3442, .T. ) ; -#10323 = CARTESIAN_POINT ( 'NONE', ( 19.98059076253610300, 209.7097557544199162, 73.04669817794425057 ) ) ; -#10324 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#10325 = CARTESIAN_POINT ( 'NONE', ( -35.94780537797892350, 109.6131156792400105, 87.78949595639598158 ) ) ; -#10326 = ORIENTED_EDGE ( 'NONE', *, *, #30745, .T. ) ; -#10327 = CARTESIAN_POINT ( 'NONE', ( 45.24519689809859813, 116.5437060779667036, 124.8975000631534158 ) ) ; -#10328 = VERTEX_POINT ( 'NONE', #14051 ) ; -#10329 = CARTESIAN_POINT ( 'NONE', ( -37.84443728459891787, 117.7927406794386371, 89.71739196407644101 ) ) ; -#10330 = VERTEX_POINT ( 'NONE', #13840 ) ; -#10331 = FACE_OUTER_BOUND ( 'NONE', #35149, .T. ) ; -#10332 = EDGE_LOOP ( 'NONE', ( #25058, #26592, #8250, #12521 ) ) ; -#10333 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#10334 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921579630, -0.2249510932971593713 ) ) ; -#10335 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#10336 = EDGE_CURVE ( 'NONE', #35367, #13602, #15705, .T. ) ; -#10337 = ORIENTED_EDGE ( 'NONE', *, *, #816, .F. ) ; -#10338 = CARTESIAN_POINT ( 'NONE', ( 12.63088349563799184, 181.6904995670203391, 101.5918601121804556 ) ) ; -#10339 = CARTESIAN_POINT ( 'NONE', ( -25.50129508846853099, 118.1132512059233335, 87.78307593003776788 ) ) ; -#10340 = CARTESIAN_POINT ( 'NONE', ( 42.43787138009228244, 189.9416574239004376, 106.2771675705110823 ) ) ; -#10341 = EDGE_CURVE ( 'NONE', #36184, #18716, #16690, .T. ) ; -#10342 = CARTESIAN_POINT ( 'NONE', ( -20.01839671862364867, 211.0902260915352429, 76.07059681904712534 ) ) ; -#10343 = ORIENTED_EDGE ( 'NONE', *, *, #10100, .T. ) ; -#10344 = EDGE_CURVE ( 'NONE', #39849, #28841, #36324, .T. ) ; -#10345 = CARTESIAN_POINT ( 'NONE', ( 28.46032611397967571, 181.9423863315211065, 101.9825489435484371 ) ) ; -#10346 = CARTESIAN_POINT ( 'NONE', ( 23.00039803961572460, 115.6131156701970895, 89.75408929892711285 ) ) ; -#10347 = EDGE_CURVE ( 'NONE', #17666, #37266, #6918, .T. ) ; -#10348 = CARTESIAN_POINT ( 'NONE', ( -37.75582100020000098, 118.2672493073999931, 90.15050444096000604 ) ) ; -#10349 = EDGE_CURVE ( 'NONE', #21433, #133, #24551, .T. ) ; -#10350 = ORIENTED_EDGE ( 'NONE', *, *, #29144, .F. ) ; -#10351 = VERTEX_POINT ( 'NONE', #10784 ) ; -#10352 = CARTESIAN_POINT ( 'NONE', ( 6.271009707311050896, 148.6549594042781450, 94.48198805953025214 ) ) ; -#10353 = CIRCLE ( 'NONE', #22115, 2.000000000508086018 ) ; -#10354 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971546251 ) ) ; -#10355 = CARTESIAN_POINT ( 'NONE', ( 45.27824277984586132, 110.5546504301846937, 150.9392683825311394 ) ) ; -#10356 = FACE_OUTER_BOUND ( 'NONE', #12986, .T. ) ; -#10357 = ORIENTED_EDGE ( 'NONE', *, *, #28842, .T. ) ; -#10358 = FACE_BOUND ( 'NONE', #33108, .T. ) ; -#10359 = ORIENTED_EDGE ( 'NONE', *, *, #20517, .T. ) ; -#10360 = ORIENTED_EDGE ( 'NONE', *, *, #13940, .F. ) ; -#10361 = ORIENTED_EDGE ( 'NONE', *, *, #12058, .F. ) ; -#10362 = CARTESIAN_POINT ( 'NONE', ( -6.036367076841044010, 177.5255795168471877, 100.8683065539579076 ) ) ; -#10363 = CARTESIAN_POINT ( 'NONE', ( 39.63114452991690939, 77.60549610642482321, 291.0478473981480647 ) ) ; -#10364 = ORIENTED_EDGE ( 'NONE', *, *, #20042, .T. ) ; -#10365 = CARTESIAN_POINT ( 'NONE', ( 26.00067918362605468, 118.8155664802563791, 90.25207353690788636 ) ) ; -#10366 = CARTESIAN_POINT ( 'NONE', ( 35.66634557559000029, 113.4066539298000009, 87.36246233996999422 ) ) ; -#10367 = CARTESIAN_POINT ( 'NONE', ( 36.03225916190000078, 191.4406869845000188, 103.7002245042999959 ) ) ; -#10368 = CARTESIAN_POINT ( 'NONE', ( 19.99991698292431508, 192.6764903808516749, 103.7970526813206646 ) ) ; -#10369 = CARTESIAN_POINT ( 'NONE', ( 122.4499743256723292, 56.73304889893216796, 171.8750556891886276 ) ) ; -#10370 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10371 = ORIENTED_EDGE ( 'NONE', *, *, #21141, .F. ) ; -#10372 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10373 = PLANE ( 'NONE', #4167 ) ; -#10374 = CARTESIAN_POINT ( 'NONE', ( 28.66581211170679566, 164.1764372810140173, 28.28916630219680073 ) ) ; -#10375 = CARTESIAN_POINT ( 'NONE', ( -32.57214901757254211, 137.3507445002516079, 91.38251427481793598 ) ) ; -#10376 = CARTESIAN_POINT ( 'NONE', ( 15.10714331102995800, 183.1006619385863701, 101.9159176678921312 ) ) ; -#10377 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #22021, #15661, #33865, #31015 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.712388980384688786, 4.732449003942794441 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999664665690304322, 0.9999664665690304322, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#10378 = ORIENTED_EDGE ( 'NONE', *, *, #14491, .F. ) ; -#10379 = CARTESIAN_POINT ( 'NONE', ( 20.00004282447493864, 191.5259056233101091, 103.8580927373495371 ) ) ; -#10380 = AXIS2_PLACEMENT_3D ( 'NONE', #40110, #22130, #25406 ) ; -#10381 = DIRECTION ( 'NONE', ( 0.5398771442070721127, 0.8202413914877526580, 0.1890416061428051298 ) ) ; -#10382 = CARTESIAN_POINT ( 'NONE', ( -29.91502785019211075, 126.8772888668398764, 89.30502066549905749 ) ) ; -#10383 = EDGE_CURVE ( 'NONE', #3644, #10734, #19958, .T. ) ; -#10384 = ADVANCED_FACE ( 'NONE', ( #29391 ), #3549, .F. ) ; -#10385 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971518218 ) ) ; -#10386 = CONICAL_SURFACE ( 'NONE', #582, 6.499999999957590369, 0.7853981633629670833 ) ; -#10387 = ADVANCED_FACE ( 'NONE', ( #17496 ), #29392, .F. ) ; -#10388 = CARTESIAN_POINT ( 'NONE', ( -25.35587684138999975, 191.8276697700999875, 104.5703393706999975 ) ) ; -#10389 = DIRECTION ( 'NONE', ( 0.9914448496661263377, 0.1271951663094869900, 0.02930016617724658101 ) ) ; -#10390 = AXIS2_PLACEMENT_3D ( 'NONE', #19, #606, #3272 ) ; -#10391 = CARTESIAN_POINT ( 'NONE', ( -3.956032534055420324, 168.4008771991734079, 98.96327028634475198 ) ) ; -#10392 = DIRECTION ( 'NONE', ( -0.7933533411653341805, 0.5930537057989598848, 0.1373964268091485141 ) ) ; -#10393 = CARTESIAN_POINT ( 'NONE', ( 27.41878023809479359, 124.6083876202890224, 90.97023811390801029 ) ) ; -#10394 = EDGE_LOOP ( 'NONE', ( #20493, #33862, #5401, #11026 ) ) ; -#10395 = ADVANCED_FACE ( 'NONE', ( #15263 ), #25082, .F. ) ; -#10396 = PLANE ( 'NONE', #31785 ) ; -#10397 = EDGE_CURVE ( 'NONE', #7538, #27242, #20607, .T. ) ; -#10398 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048995327, 130.3419545077157693, 92.84535593379736440 ) ) ; -#10399 = CARTESIAN_POINT ( 'NONE', ( 5.666563139484574130, 181.4015622423786169, 104.2772169685427173 ) ) ; -#10400 = CARTESIAN_POINT ( 'NONE', ( 36.61811095221000301, 191.2758974482999861, 106.4512996302999994 ) ) ; -#10401 = CARTESIAN_POINT ( 'NONE', ( 36.08519291063979750, 192.3728519051840067, 106.4067655339000140 ) ) ; -#10402 = FACE_OUTER_BOUND ( 'NONE', #22081, .T. ) ; -#10403 = FACE_OUTER_BOUND ( 'NONE', #2018, .T. ) ; -#10404 = CARTESIAN_POINT ( 'NONE', ( 36.20259201116000014, 192.7448354070999983, 106.1952316783000043 ) ) ; -#10405 = ORIENTED_EDGE ( 'NONE', *, *, #38604, .F. ) ; -#10406 = EDGE_CURVE ( 'NONE', #17225, #25223, #27752, .T. ) ; -#10408 = VECTOR ( 'NONE', #10618, 1000.000000000000114 ) ; -#10407 = DIRECTION ( 'NONE', ( -0.1305260325596790116, -0.9660514818508153523, -0.2229517643753315681 ) ) ; -#10409 = CARTESIAN_POINT ( 'NONE', ( 8.286289185724438511, 188.3449241355613708, 103.1308165897977887 ) ) ; -#10410 = AXIS2_PLACEMENT_3D ( 'NONE', #904, #10131, #37928 ) ; -#10411 = CARTESIAN_POINT ( 'NONE', ( 40.54493957013273331, 217.7719115632999944, 73.03401595487400755 ) ) ; -#10412 = EDGE_LOOP ( 'NONE', ( #12708, #13236, #36662, #3562 ) ) ; -#10413 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 89.47423874572474745, 291.5876487235610171 ) ) ; -#10414 = AXIS2_PLACEMENT_3D ( 'NONE', #22718, #219, #3280 ) ; -#10415 = CARTESIAN_POINT ( 'NONE', ( 39.79126515168999845, 119.5205125080999977, 89.91298374922000392 ) ) ; -#10416 = VECTOR ( 'NONE', #24389, 1000.000000000000114 ) ; -#10417 = ORIENTED_EDGE ( 'NONE', *, *, #28880, .T. ) ; -#10418 = CYLINDRICAL_SURFACE ( 'NONE', #16903, 9.000000000000003553 ) ; -#10419 = ORIENTED_EDGE ( 'NONE', *, *, #29330, .T. ) ; -#10420 = CARTESIAN_POINT ( 'NONE', ( 16.00151820029350702, 137.8265450205371394, 94.54185288967525480 ) ) ; -#10421 = LINE ( 'NONE', #35322, #40065 ) ; -#10422 = CARTESIAN_POINT ( 'NONE', ( -44.30687190001572162, 185.8858876664870650, 106.9719525047996029 ) ) ; -#10423 = CARTESIAN_POINT ( 'NONE', ( 28.42685679119000142, 142.7284776650000140, 28.07991271570000080 ) ) ; -#10424 = DIRECTION ( 'NONE', ( 0.0006039748319391886151, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#10425 = ORIENTED_EDGE ( 'NONE', *, *, #33859, .T. ) ; -#10426 = PLANE ( 'NONE', #27229 ) ; -#10427 = CARTESIAN_POINT ( 'NONE', ( -10.88124804834476933, 188.3423871091218871, 103.1418072217568493 ) ) ; -#10428 = CARTESIAN_POINT ( 'NONE', ( -22.49823197369664385, 160.0613479605241878, 99.70157044293461013 ) ) ; -#10429 = EDGE_CURVE ( 'NONE', #33081, #9576, #18498, .T. ) ; -#10430 = CARTESIAN_POINT ( 'NONE', ( -36.15032745052999985, 191.7932147525000062, 104.2905027447000066 ) ) ; -#10431 = ORIENTED_EDGE ( 'NONE', *, *, #1065, .F. ) ; -#10432 = EDGE_CURVE ( 'NONE', #20961, #15877, #3290, .T. ) ; -#10433 = EDGE_LOOP ( 'NONE', ( #7430, #3949, #26100, #39973 ) ) ; -#10434 = DIRECTION ( 'NONE', ( 0.6087613505917195411, -0.7729391288371411095, -0.1788147676737769087 ) ) ; -#10435 = EDGE_CURVE ( 'NONE', #39292, #21947, #25487, .T. ) ; -#10436 = VECTOR ( 'NONE', #13728, 1000.000000000000114 ) ; -#10437 = CARTESIAN_POINT ( 'NONE', ( 37.40957686559463014, 117.0607182589398150, 89.68224475837769205 ) ) ; -#10438 = LINE ( 'NONE', #32703, #21516 ) ; -#10439 = ADVANCED_FACE ( 'NONE', ( #11998 ), #24488, .T. ) ; -#10440 = AXIS2_PLACEMENT_3D ( 'NONE', #8579, #20208, #7744 ) ; -#10441 = AXIS2_PLACEMENT_3D ( 'NONE', #23502, #16539, #26186 ) ; -#10442 = CARTESIAN_POINT ( 'NONE', ( 13.49481983871936386, 124.3681642032378534, 88.35737770391504853 ) ) ; -#10443 = CARTESIAN_POINT ( 'NONE', ( 25.64383499035999847, 191.0236203942999964, 106.4328263517000011 ) ) ; -#10444 = ADVANCED_FACE ( 'NONE', ( #28338 ), #27511, .F. ) ; -#10445 = FACE_OUTER_BOUND ( 'NONE', #34178, .T. ) ; -#10446 = CARTESIAN_POINT ( 'NONE', ( -3.093297121992999887, 208.9488293358000419, 72.98050324807999800 ) ) ; -#10447 = CARTESIAN_POINT ( 'NONE', ( 38.69173525550999670, 118.4044799225000020, 89.51251263176000350 ) ) ; -#10448 = ORIENTED_EDGE ( 'NONE', *, *, #31754, .T. ) ; -#10449 = LINE ( 'NONE', #4074, #25091 ) ; -#10450 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363196006660E-14, 0.9999998176071844824 ) ) ; -#10451 = CARTESIAN_POINT ( 'NONE', ( 3.168077837919118345, 126.1295738578562009, 91.84923819592059147 ) ) ; -#10452 = FACE_OUTER_BOUND ( 'NONE', #25911, .T. ) ; -#10453 = ORIENTED_EDGE ( 'NONE', *, *, #19852, .T. ) ; -#10454 = ORIENTED_EDGE ( 'NONE', *, *, #6611, .T. ) ; -#10455 = EDGE_CURVE ( 'NONE', #3485, #16249, #22411, .T. ) ; -#10456 = PRODUCT_DEFINITION_SHAPE ( 'NONE', 'NONE', #14451 ) ; -#10457 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22658, #956, #7091, #32253 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10458 = ORIENTED_EDGE ( 'NONE', *, *, #21006, .T. ) ; -#10459 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319397694222 ) ) ; -#10460 = CARTESIAN_POINT ( 'NONE', ( 5.958856853884591409, 162.8902775912074787, 100.3344200888616200 ) ) ; -#10461 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 137.0112424259995976, 291.5876487235603918 ) ) ; -#10462 = EDGE_LOOP ( 'NONE', ( #18721, #33666, #19341 ) ) ; -#10463 = ORIENTED_EDGE ( 'NONE', *, *, #577, .F. ) ; -#10464 = CARTESIAN_POINT ( 'NONE', ( -35.38988506213597418, 77.14301703112144537, 290.1978808180363671 ) ) ; -#10465 = CARTESIAN_POINT ( 'NONE', ( -38.48030512001000147, 118.7021383040000018, 89.90325869229000944 ) ) ; -#10466 = CARTESIAN_POINT ( 'NONE', ( -38.36245917373000225, 118.8225225366000046, 87.71979598265001243 ) ) ; -#10467 = CARTESIAN_POINT ( 'NONE', ( -28.51213027334999950, 201.2278123622000123, 28.07991271570000080 ) ) ; -#10468 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#10469 = VERTEX_POINT ( 'NONE', #31404 ) ; -#10470 = CARTESIAN_POINT ( 'NONE', ( 5.704725281391000102, 112.1320600213999938, 152.4718672074000381 ) ) ; -#10471 = VECTOR ( 'NONE', #9543, 1000.000000000000227 ) ; -#10472 = AXIS2_PLACEMENT_3D ( 'NONE', #8261, #27293, #8882 ) ; -#10473 = EDGE_LOOP ( 'NONE', ( #9298, #14567, #7075, #39146 ) ) ; -#10474 = DIRECTION ( 'NONE', ( 0.7066905234002724967, 0.1590644375676184552, -0.6894106242563616815 ) ) ; -#10475 = FACE_OUTER_BOUND ( 'NONE', #1969, .T. ) ; -#10476 = CARTESIAN_POINT ( 'NONE', ( 16.83816207964345324, 121.5429834961812645, 177.3963189431576666 ) ) ; -#10477 = DIRECTION ( 'NONE', ( -0.6087611434179117653, 0.7728348325624403437, 0.1792657018023852966 ) ) ; -#10478 = EDGE_LOOP ( 'NONE', ( #11993, #11118, #16265, #37101 ) ) ; -#10479 = CARTESIAN_POINT ( 'NONE', ( -2.208163358325990089, 189.3050797433780019, 103.3573457354410010 ) ) ; -#10480 = CARTESIAN_POINT ( 'NONE', ( 20.50147137495634198, 190.9646546281344683, 106.2940065278771016 ) ) ; -#10481 = CARTESIAN_POINT ( 'NONE', ( 18.99670475096374034, 148.1889770648965623, 184.7135872576050986 ) ) ; -#10482 = VERTEX_POINT ( 'NONE', #19513 ) ; -#10483 = EDGE_CURVE ( 'NONE', #10159, #22555, #25690, .T. ) ; -#10484 = ORIENTED_EDGE ( 'NONE', *, *, #12208, .F. ) ; -#10485 = CARTESIAN_POINT ( 'NONE', ( 20.15797964693969391, 118.1111885588362327, 87.41331544875174586 ) ) ; -#10486 = CARTESIAN_POINT ( 'NONE', ( -23.00006628498088901, 118.1131156702000169, 89.78163987410425761 ) ) ; -#10487 = EDGE_CURVE ( 'NONE', #8706, #27876, #26177, .T. ) ; -#10488 = ORIENTED_EDGE ( 'NONE', *, *, #31106, .T. ) ; -#10489 = CARTESIAN_POINT ( 'NONE', ( -43.83121863444220878, 120.3967290634445249, 90.85147244797772714 ) ) ; -#10490 = EDGE_LOOP ( 'NONE', ( #24952, #22534, #7663, #17651 ) ) ; -#10491 = CARTESIAN_POINT ( 'NONE', ( 22.99181599359000217, 213.5902260771004819, 75.54481431629028521 ) ) ; -#10492 = DIRECTION ( 'NONE', ( 0.7066518061492224057, -1.565012837052518894E-15, -0.7075614636666145429 ) ) ; -#10493 = LINE ( 'NONE', #3516, #13417 ) ; -#10494 = CARTESIAN_POINT ( 'NONE', ( 15.50176591790000025, 153.4317157280000004, 98.14497494459000393 ) ) ; -#10495 = AXIS2_PLACEMENT_3D ( 'NONE', #7467, #38744, #22439 ) ; -#10496 = ORIENTED_EDGE ( 'NONE', *, *, #24003, .T. ) ; -#10497 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36643, #31120, #30917, #36438 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10498 = VECTOR ( 'NONE', #8607, 999.9999999999998863 ) ; -#10499 = CARTESIAN_POINT ( 'NONE', ( 26.00267525357395471, 120.0774130348896591, 90.42205768479676919 ) ) ; -#10500 = AXIS2_PLACEMENT_3D ( 'NONE', #37532, #20233, #1027 ) ; -#10501 = FACE_OUTER_BOUND ( 'NONE', #19795, .T. ) ; -#10503 = DIRECTION ( 'NONE', ( -0.0006039748319387566690, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#10502 = CARTESIAN_POINT ( 'NONE', ( -16.15249828763665363, 151.1189587783885884, 184.8292094970151425 ) ) ; -#10504 = DIRECTION ( 'NONE', ( 0.0005884949961259727845, -0.2249510543439064703, 0.9743698870671262391 ) ) ; -#10505 = LINE ( 'NONE', #22969, #39248 ) ; -#10506 = ORIENTED_EDGE ( 'NONE', *, *, #19811, .T. ) ; -#10507 = LINE ( 'NONE', #3243, #39502 ) ; -#10508 = CARTESIAN_POINT ( 'NONE', ( -36.08484471194226018, 191.9980746492448702, 104.4229788667364716 ) ) ; -#10509 = CARTESIAN_POINT ( 'NONE', ( -22.49962777877401265, 154.4034663070004285, 95.31336199324331915 ) ) ; -#10510 = ORIENTED_EDGE ( 'NONE', *, *, #31664, .F. ) ; -#10511 = ORIENTED_EDGE ( 'NONE', *, *, #62, .T. ) ; -#10512 = LINE ( 'NONE', #22183, #34786 ) ; -#10513 = FACE_OUTER_BOUND ( 'NONE', #37065, .T. ) ; -#10514 = CARTESIAN_POINT ( 'NONE', ( -2.300423297926999844, 191.0118119155000045, 106.1782564142000069 ) ) ; -#10515 = ORIENTED_EDGE ( 'NONE', *, *, #32993, .F. ) ; -#10516 = ORIENTED_EDGE ( 'NONE', *, *, #185, .T. ) ; -#10517 = EDGE_CURVE ( 'NONE', #25046, #5067, #39, .T. ) ; -#10518 = ORIENTED_EDGE ( 'NONE', *, *, #13016, .F. ) ; -#10519 = CARTESIAN_POINT ( 'NONE', ( -23.36142968010071286, 134.4390921883068302, 93.61422517553531009 ) ) ; -#10520 = DIRECTION ( 'NONE', ( 0.9914446895100101909, -0.1270495645017608588, -0.02993051623865213007 ) ) ; -#10521 = ORIENTED_EDGE ( 'NONE', *, *, #30510, .F. ) ; -#10522 = ORIENTED_EDGE ( 'NONE', *, *, #11585, .F. ) ; -#10523 = CARTESIAN_POINT ( 'NONE', ( -21.69818314611236332, 120.0177369536598775, 190.2070442068906573 ) ) ; -#10524 = AXIS2_PLACEMENT_3D ( 'NONE', #37641, #21527, #9246 ) ; -#10525 = CONICAL_SURFACE ( 'NONE', #39898, 2.502999999877876025, 0.7853981634382917187 ) ; -#10526 = CIRCLE ( 'NONE', #5961, 1.750000000000001998 ) ; -#10527 = ORIENTED_EDGE ( 'NONE', *, *, #17925, .T. ) ; -#10528 = EDGE_CURVE ( 'NONE', #34802, #20666, #34443, .T. ) ; -#10529 = CARTESIAN_POINT ( 'NONE', ( 18.98506067126258046, 148.2070439170772431, 184.7168109706149721 ) ) ; -#10530 = EDGE_CURVE ( 'NONE', #6692, #35055, #9733, .T. ) ; -#10531 = CARTESIAN_POINT ( 'NONE', ( -30.07461407415773991, 135.0052377692200025, 90.96298864312910837 ) ) ; -#10532 = EDGE_CURVE ( 'NONE', #18192, #27561, #3930, .T. ) ; -#10533 = CARTESIAN_POINT ( 'NONE', ( -2.293543225787999962, 188.9465872380000064, 106.5163128416999996 ) ) ; -#10534 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#10535 = ADVANCED_FACE ( 'NONE', ( #16246 ), #31393, .F. ) ; -#10536 = ORIENTED_EDGE ( 'NONE', *, *, #35494, .F. ) ; -#10537 = EDGE_LOOP ( 'NONE', ( #11898, #22716, #32397, #17056 ) ) ; -#10538 = CARTESIAN_POINT ( 'NONE', ( 35.56355292868355633, 196.5784392900514206, 103.8536238432368037 ) ) ; -#10539 = CARTESIAN_POINT ( 'NONE', ( 19.98483764167631094, 211.0849390754169974, 73.04592155476974824 ) ) ; -#10540 = CARTESIAN_POINT ( 'NONE', ( -16.27844647470670481, 132.2223051904889246, 155.9713390441192473 ) ) ; -#10541 = CARTESIAN_POINT ( 'NONE', ( -25.82491794804302288, 196.4250218345125631, 103.8255790278501820 ) ) ; -#10542 = ORIENTED_EDGE ( 'NONE', *, *, #30182, .F. ) ; -#10543 = CYLINDRICAL_SURFACE ( 'NONE', #11021, 1.750000000000001998 ) ; -#10544 = VECTOR ( 'NONE', #30078, 1000.000000000000114 ) ; -#10545 = CARTESIAN_POINT ( 'NONE', ( -37.56558860730999783, 118.4361947088000022, 90.44661560864000194 ) ) ; -#10546 = VECTOR ( 'NONE', #26070, 999.9999999999998863 ) ; -#10547 = ORIENTED_EDGE ( 'NONE', *, *, #31813, .T. ) ; -#10548 = ORIENTED_EDGE ( 'NONE', *, *, #5058, .T. ) ; -#10549 = CYLINDRICAL_SURFACE ( 'NONE', #8829, 2.000000000000011546 ) ; -#10550 = CARTESIAN_POINT ( 'NONE', ( 23.68782161451136403, 130.6249251104771645, 90.13785893629349744 ) ) ; -#10551 = CARTESIAN_POINT ( 'NONE', ( -85.24348513260991922, 108.2328939675489039, 25.03902193712222513 ) ) ; -#10552 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319380785005 ) ) ; -#10553 = EDGE_LOOP ( 'NONE', ( #24682, #33272, #13734 ) ) ; -#10554 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7094, #28781, #16103, #13250 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10555 = VERTEX_POINT ( 'NONE', #19111 ) ; -#10556 = FACE_OUTER_BOUND ( 'NONE', #35151, .T. ) ; -#10557 = ORIENTED_EDGE ( 'NONE', *, *, #19376, .T. ) ; -#10558 = EDGE_LOOP ( 'NONE', ( #22245, #14403, #15839, #38587 ) ) ; -#10559 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#10560 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#10561 = ORIENTED_EDGE ( 'NONE', *, *, #17657, .T. ) ; -#10562 = LINE ( 'NONE', #25712, #4281 ) ; -#10563 = CARTESIAN_POINT ( 'NONE', ( 37.93701571562999675, 118.0299904344000055, 87.80017651164999393 ) ) ; -#10564 = CARTESIAN_POINT ( 'NONE', ( 36.18104500945000268, 191.5953453467000145, 103.9690375264000011 ) ) ; -#10565 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35937, #7947, #14294, #20410 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10566 = CARTESIAN_POINT ( 'NONE', ( -25.99151835185281456, 191.8641524188973904, 103.9340199701208292 ) ) ; -#10567 = EDGE_CURVE ( 'NONE', #18222, #3073, #9941, .T. ) ; -#10568 = ORIENTED_EDGE ( 'NONE', *, *, #27759, .T. ) ; -#10569 = DIRECTION ( 'NONE', ( 0.1305262607518133389, -0.9660168937933039102, -0.2231014481353405798 ) ) ; -#10570 = DIRECTION ( 'NONE', ( -0.0002393071182785116774, -0.2252352986010041080, 0.9743043687658491381 ) ) ; -#10571 = VERTEX_POINT ( 'NONE', #28936 ) ; -#10572 = CARTESIAN_POINT ( 'NONE', ( 16.15948502493926853, 156.4779744257297125, 161.5570139484795220 ) ) ; -#10573 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452351231, 0.1781166614240801693 ) ) ; -#10574 = EDGE_CURVE ( 'NONE', #12222, #9881, #618, .T. ) ; -#10575 = AXIS2_PLACEMENT_3D ( 'NONE', #23137, #35564, #28668 ) ; -#10576 = CARTESIAN_POINT ( 'NONE', ( 3.776102309766777410, 175.3027701955228110, 100.3705899655855092 ) ) ; -#10577 = EDGE_CURVE ( 'NONE', #20125, #26354, #7937, .T. ) ; -#10578 = CARTESIAN_POINT ( 'NONE', ( 23.67998985452990368, 134.9222885997251637, 90.78792508986444432 ) ) ; -#10579 = EDGE_CURVE ( 'NONE', #27781, #30934, #15269, .T. ) ; -#10580 = ORIENTED_EDGE ( 'NONE', *, *, #16354, .F. ) ; -#10581 = CARTESIAN_POINT ( 'NONE', ( 21.15670202924908949, 136.2567377786867837, 93.83430039101608600 ) ) ; -#10582 = ADVANCED_FACE ( 'NONE', ( #25887 ), #38331, .F. ) ; -#10583 = VECTOR ( 'NONE', #37394, 1000.000000000000114 ) ; -#10584 = CARTESIAN_POINT ( 'NONE', ( 1.052492825995231751, 189.0609387198332456, 103.7017148797387165 ) ) ; -#10585 = CARTESIAN_POINT ( 'NONE', ( -0.4358427445845766135, 188.3875244028057807, 106.2247867227265630 ) ) ; -#10586 = CARTESIAN_POINT ( 'NONE', ( -4.037441716910447731, 175.2423114651814160, 100.6263891030057778 ) ) ; -#10587 = CARTESIAN_POINT ( 'NONE', ( -25.61313952212999823, 191.8482039261000125, 104.3089394863000052 ) ) ; -#10588 = CARTESIAN_POINT ( 'NONE', ( -13.50000253664885719, 151.9690088118221922, 94.74282098678578734 ) ) ; -#10589 = CARTESIAN_POINT ( 'NONE', ( -3.570188269422462035, 168.4780809577787863, 98.58463426929444040 ) ) ; -#10590 = CARTESIAN_POINT ( 'NONE', ( -2.453916141205511714, 205.5673811410610767, 76.30169882389490965 ) ) ; -#10591 = ORIENTED_EDGE ( 'NONE', *, *, #4080, .T. ) ; -#10592 = DIRECTION ( 'NONE', ( 8.326672684688689830E-15, -0.9743700557921582961, -0.2249510932971575394 ) ) ; -#10593 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#10594 = ORIENTED_EDGE ( 'NONE', *, *, #15764, .T. ) ; -#10595 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10596 = CARTESIAN_POINT ( 'NONE', ( 23.36327396620029262, 181.6167095797193838, 104.1340943760966411 ) ) ; -#10597 = FACE_OUTER_BOUND ( 'NONE', #24603, .T. ) ; -#10598 = CARTESIAN_POINT ( 'NONE', ( 36.06384157275000035, 192.3755910232000019, 104.3313795858999953 ) ) ; -#10599 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33695, #14502, #30237, #39828 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10600 = CARTESIAN_POINT ( 'NONE', ( -25.02288988185319596, 182.0930031294805644, 101.7075183579726456 ) ) ; -#10601 = AXIS2_PLACEMENT_3D ( 'NONE', #7528, #20826, #32875 ) ; -#10602 = CARTESIAN_POINT ( 'NONE', ( 13.76493657109577384, 124.4303889429143624, 178.6692723925305017 ) ) ; -#10603 = ORIENTED_EDGE ( 'NONE', *, *, #39969, .T. ) ; -#10604 = VERTEX_POINT ( 'NONE', #14132 ) ; -#10605 = VECTOR ( 'NONE', #28334, 1000.000000000000114 ) ; -#10606 = CARTESIAN_POINT ( 'NONE', ( -42.55448647980254151, 182.5615766734265719, 104.9051989971102188 ) ) ; -#10607 = CIRCLE ( 'NONE', #23650, 2.499999999915349047 ) ; -#10608 = CARTESIAN_POINT ( 'NONE', ( 18.98511042798971360, 148.3283295584973871, 184.1927148392349807 ) ) ; -#10609 = ADVANCED_FACE ( 'NONE', ( #14328 ), #1850, .T. ) ; -#10610 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#10611 = ORIENTED_EDGE ( 'NONE', *, *, #25948, .T. ) ; -#10612 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; -#10613 = CARTESIAN_POINT ( 'NONE', ( -10.03773492422894620, 168.4955924422535531, 98.55925788101369278 ) ) ; -#10614 = ORIENTED_EDGE ( 'NONE', *, *, #22940, .T. ) ; -#10615 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #960, #26327, #28587, #25736 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 5.793999508258149689, 7.571725326505850617 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7535301471135593676, 0.7535301471135593676, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#10616 = EDGE_CURVE ( 'NONE', #25509, #6189, #31861, .T. ) ; -#10617 = CARTESIAN_POINT ( 'NONE', ( 13.50176625667807428, 157.6312284029801845, 99.11570381321912748 ) ) ; -#10618 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927769878492, -0.0005734119022077161041 ) ) ; -#10619 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10620 = ORIENTED_EDGE ( 'NONE', *, *, #37749, .T. ) ; -#10621 = CARTESIAN_POINT ( 'NONE', ( 23.68575892633012003, 134.8469895808620436, 93.33625697840975022 ) ) ; -#10622 = LINE ( 'NONE', #23089, #38383 ) ; -#10623 = CARTESIAN_POINT ( 'NONE', ( -30.06930367573490059, 176.9314637670682657, 103.3499274907251788 ) ) ; -#10624 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#10625 = ORIENTED_EDGE ( 'NONE', *, *, #36767, .F. ) ; -#10626 = EDGE_CURVE ( 'NONE', #23762, #11575, #26000, .T. ) ; -#10627 = ORIENTED_EDGE ( 'NONE', *, *, #29462, .F. ) ; -#10628 = FACE_OUTER_BOUND ( 'NONE', #26200, .T. ) ; -#10629 = LINE ( 'NONE', #22503, #17238 ) ; -#10630 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#10631 = VERTEX_POINT ( 'NONE', #10460 ) ; -#10632 = CARTESIAN_POINT ( 'NONE', ( -36.12223251268000013, 191.8158961599000349, 104.2940808302000022 ) ) ; -#10633 = ORIENTED_EDGE ( 'NONE', *, *, #38660, .F. ) ; -#10634 = ORIENTED_EDGE ( 'NONE', *, *, #21024, .F. ) ; -#10635 = AXIS2_PLACEMENT_3D ( 'NONE', #2997, #5673, #15480 ) ; -#10636 = DIRECTION ( 'NONE', ( 0.5988683521957647304, -0.8008474865655316188, 0.000000000000000000 ) ) ; -#10637 = DIRECTION ( 'NONE', ( -0.6087611434179115433, 0.7728348325624405657, 0.1792657018023848803 ) ) ; -#10638 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825953469412410, 0.0005734119016186655943 ) ) ; -#10639 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #21545, #34566 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10640 = CARTESIAN_POINT ( 'NONE', ( 18.85494637915880389, 148.3003327196275904, 183.8440936709722848 ) ) ; -#10641 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825829930067965, 0.0005734119044644985386 ) ) ; -#10642 = DIRECTION ( 'NONE', ( -0.7933532970003721596, -0.5930762008556746956, -0.1372995488602881120 ) ) ; -#10643 = CARTESIAN_POINT ( 'NONE', ( -37.93323152093999795, 191.1278711168000086, 106.2274912793999988 ) ) ; -#10644 = ORIENTED_EDGE ( 'NONE', *, *, #36000, .T. ) ; -#10645 = CARTESIAN_POINT ( 'NONE', ( 13.82651559197693913, 124.3675412307241146, 88.35707925228412307 ) ) ; -#10646 = DIRECTION ( 'NONE', ( 0.6087614115774879764, 0.7729348350621345620, 0.1788331191967953704 ) ) ; -#10647 = CARTESIAN_POINT ( 'NONE', ( 24.53348384879791411, 109.6131156702000027, 87.75296677362121045 ) ) ; -#10649 = ORIENTED_EDGE ( 'NONE', *, *, #4582, .F. ) ; -#10648 = CARTESIAN_POINT ( 'NONE', ( 2.879226012311342675, 209.0946219175737610, 75.97922651357153256 ) ) ; -#10650 = ORIENTED_EDGE ( 'NONE', *, *, #5041, .F. ) ; -#10651 = ORIENTED_EDGE ( 'NONE', *, *, #37880, .F. ) ; -#10652 = ORIENTED_EDGE ( 'NONE', *, *, #5378, .T. ) ; -#10653 = CARTESIAN_POINT ( 'NONE', ( -13.50287905500021779, 124.4549746631454497, 88.51738859572765250 ) ) ; -#10654 = AXIS2_PLACEMENT_3D ( 'NONE', #38345, #28553, #13412 ) ; -#10655 = CARTESIAN_POINT ( 'NONE', ( -22.69152947388643682, 213.5901932291387197, 75.57214034997275576 ) ) ; -#10656 = EDGE_CURVE ( 'NONE', #1942, #40336, #2060, .T. ) ; -#10657 = CARTESIAN_POINT ( 'NONE', ( 23.71418063517253216, 115.9567856581436160, 178.7590535630116051 ) ) ; -#10658 = CARTESIAN_POINT ( 'NONE', ( 5.666394801357205857, 124.0804070564130512, 91.04259146090616639 ) ) ; -#10659 = CONICAL_SURFACE ( 'NONE', #33492, 4.999999999857982935, 0.7853981633210400659 ) ; -#10660 = ADVANCED_FACE ( 'NONE', ( #40060 ), #3393, .T. ) ; -#10661 = ORIENTED_EDGE ( 'NONE', *, *, #28849, .T. ) ; -#10662 = CARTESIAN_POINT ( 'NONE', ( -14.29616511099273346, 135.3960512967398984, 93.65700873416508898 ) ) ; -#10663 = AXIS2_PLACEMENT_3D ( 'NONE', #7520, #1804, #11208 ) ; -#10664 = CARTESIAN_POINT ( 'NONE', ( 20.33495252378841656, 118.8155847327597030, 89.92220002530788747 ) ) ; -#10665 = CARTESIAN_POINT ( 'NONE', ( -38.43509036414000235, 118.8935578815000156, 87.72379152730999863 ) ) ; -#10666 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319381707661 ) ) ; -#10667 = ORIENTED_EDGE ( 'NONE', *, *, #28750, .T. ) ; -#10668 = EDGE_CURVE ( 'NONE', #7718, #22341, #34708, .T. ) ; -#10669 = PLANE ( 'NONE', #31706 ) ; -#10670 = CARTESIAN_POINT ( 'NONE', ( 5.665063307604782494, 124.5504061188815683, 88.65505891053771848 ) ) ; -#10671 = CARTESIAN_POINT ( 'NONE', ( -21.79955176292590124, 171.2571027978372342, 152.1817658970814193 ) ) ; -#10672 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#10673 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971565957 ) ) ; -#10674 = EDGE_CURVE ( 'NONE', #25549, #18343, #5988, .T. ) ; -#10675 = VERTEX_POINT ( 'NONE', #37959 ) ; -#10676 = CARTESIAN_POINT ( 'NONE', ( -20.50092100153493746, 194.2771564787859120, 102.9104786413515740 ) ) ; -#10677 = DIRECTION ( 'NONE', ( -7.346163213264980213E-13, -0.9743700555116001638, -0.2249510945123874561 ) ) ; -#10678 = CARTESIAN_POINT ( 'NONE', ( -24.42625685282796510, 109.6131156702000027, 89.78253759511289900 ) ) ; -#10679 = CARTESIAN_POINT ( 'NONE', ( 19.98825758066151081, 204.1052561192695123, 86.13095846269416711 ) ) ; -#10680 = ORIENTED_EDGE ( 'NONE', *, *, #33823, .F. ) ; -#10681 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13413, #16655, #10742, #925 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10682 = PLANE ( 'NONE', #8764 ) ; -#10683 = CARTESIAN_POINT ( 'NONE', ( -26.01597357618275552, 211.4825417517944572, 76.07170175244279164 ) ) ; -#10684 = ORIENTED_EDGE ( 'NONE', *, *, #19261, .F. ) ; -#10685 = VECTOR ( 'NONE', #3669, 1000.000000000000227 ) ; -#10686 = EDGE_LOOP ( 'NONE', ( #36755, #12070, #17354, #38143 ) ) ; -#10687 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#10688 = ORIENTED_EDGE ( 'NONE', *, *, #20147, .T. ) ; -#10689 = CONICAL_SURFACE ( 'NONE', #36806, 55.00273826252905707, 0.7853981633973132759 ) ; -#10690 = CARTESIAN_POINT ( 'NONE', ( 25.49062502244311190, 209.7098837966309475, 73.54308088453358039 ) ) ; -#10691 = DIRECTION ( 'NONE', ( -0.0005884949961217802832, 0.2249510543439081078, -0.9743698870671260170 ) ) ; -#10692 = VECTOR ( 'NONE', #13426, 1000.000000000000114 ) ; -#10693 = VERTEX_POINT ( 'NONE', #34858 ) ; -#10694 = ORIENTED_EDGE ( 'NONE', *, *, #20511, .T. ) ; -#10695 = CARTESIAN_POINT ( 'NONE', ( 26.01380077701120186, 120.4370565852799899, 90.52453431236820336 ) ) ; -#10696 = DIRECTION ( 'NONE', ( -0.6087611434179104331, -0.7731004625452351231, -0.1781166614240846935 ) ) ; -#10697 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5513, #8809, #24559, #30485 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10699 = CARTESIAN_POINT ( 'NONE', ( 30.96384560852109047, 128.5897405105000360, 89.32150042245991983 ) ) ; -#10698 = CARTESIAN_POINT ( 'NONE', ( 20.48202491551230153, 207.9221666367885462, 76.29632206515334758 ) ) ; -#10700 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; -#10701 = VERTEX_POINT ( 'NONE', #28561 ) ; -#10702 = CARTESIAN_POINT ( 'NONE', ( -39.74915155288540092, 182.4989200128275399, 106.8177713122808115 ) ) ; -#10703 = DIRECTION ( 'NONE', ( 0.7933530821293313107, 0.5932640870757662777, 0.1364866662427073052 ) ) ; -#10704 = EDGE_CURVE ( 'NONE', #5512, #33715, #33331, .T. ) ; -#10705 = EDGE_CURVE ( 'NONE', #26211, #7245, #1137, .T. ) ; -#10706 = VERTEX_POINT ( 'NONE', #3995 ) ; -#10707 = CARTESIAN_POINT ( 'NONE', ( 13.46852558400658850, 153.7328115929476269, 98.21571663388800744 ) ) ; -#10708 = CARTESIAN_POINT ( 'NONE', ( -44.75464527753396027, 124.2849483418497414, 93.49415263160652501 ) ) ; -#10709 = FACE_OUTER_BOUND ( 'NONE', #22478, .T. ) ; -#10710 = CIRCLE ( 'NONE', #18502, 2.499999999897516645 ) ; -#10711 = CONICAL_SURFACE ( 'NONE', #8067, 6.502999999995862090, 0.7853981633961898412 ) ; -#10712 = VERTEX_POINT ( 'NONE', #3589 ) ; -#10713 = VERTEX_POINT ( 'NONE', #37748 ) ; -#10714 = DIRECTION ( 'NONE', ( 0.6087611434179120984, -0.7728348325624403437, -0.1792657018023839366 ) ) ; -#10715 = CONICAL_SURFACE ( 'NONE', #31615, 2.503139744998429617, 0.7853981633680950925 ) ; -#10716 = VERTEX_POINT ( 'NONE', #26104 ) ; -#10717 = ORIENTED_EDGE ( 'NONE', *, *, #7366, .F. ) ; -#10718 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; -#10719 = ORIENTED_EDGE ( 'NONE', *, *, #7861, .T. ) ; -#10720 = CARTESIAN_POINT ( 'NONE', ( -22.49852798326972092, 153.3539066485355988, 97.63681037851679889 ) ) ; -#10721 = ORIENTED_EDGE ( 'NONE', *, *, #5566, .T. ) ; -#10722 = LINE ( 'NONE', #35421, #32092 ) ; -#10723 = ADVANCED_FACE ( 'NONE', ( #6867 ), #19340, .T. ) ; -#10724 = CARTESIAN_POINT ( 'NONE', ( -23.36013623391093930, 174.6774582535031186, 103.0734136003139838 ) ) ; -#10725 = CARTESIAN_POINT ( 'NONE', ( 21.10872591445046709, 182.7503592616568824, 104.5682307738507149 ) ) ; -#10726 = ORIENTED_EDGE ( 'NONE', *, *, #33905, .F. ) ; -#10727 = VERTEX_POINT ( 'NONE', #29365 ) ; -#10728 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#10729 = CARTESIAN_POINT ( 'NONE', ( -23.35464359634993770, 177.7881151143831744, 100.7126876897662697 ) ) ; -#10730 = CARTESIAN_POINT ( 'NONE', ( 25.84237761017833535, 191.9398424858814280, 104.0722080153798856 ) ) ; -#10731 = VECTOR ( 'NONE', #30716, 1000.000000000000114 ) ; -#10732 = AXIS2_PLACEMENT_3D ( 'NONE', #27410, #11425, #21043 ) ; -#10733 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.6225145670957882293, 0.7826082121684793114 ) ) ; -#10734 = VERTEX_POINT ( 'NONE', #39556 ) ; -#10735 = FACE_OUTER_BOUND ( 'NONE', #17406, .T. ) ; -#10736 = CIRCLE ( 'NONE', #29688, 4.499999999895906377 ) ; -#10737 = CARTESIAN_POINT ( 'NONE', ( -38.29117464694000006, 118.4625604934000052, 89.85066910585000244 ) ) ; -#10738 = ORIENTED_EDGE ( 'NONE', *, *, #8015, .T. ) ; -#10739 = ORIENTED_EDGE ( 'NONE', *, *, #21094, .T. ) ; -#10740 = DIRECTION ( 'NONE', ( -0.000000000000000000, 1.000000000000000000, -1.110223024625155594E-14 ) ) ; -#10741 = PLANE ( 'NONE', #18319 ) ; -#10742 = CARTESIAN_POINT ( 'NONE', ( 2.897488257060280681, 190.8911024193934054, 106.6291602111235477 ) ) ; -#10743 = EDGE_CURVE ( 'NONE', #18476, #21152, #684, .T. ) ; -#10744 = ORIENTED_EDGE ( 'NONE', *, *, #4304, .F. ) ; -#10745 = EDGE_CURVE ( 'NONE', #7231, #4711, #18134, .T. ) ; -#10746 = ORIENTED_EDGE ( 'NONE', *, *, #22074, .F. ) ; -#10747 = DIRECTION ( 'NONE', ( 0.0005884949961231548347, -0.2249510543439030841, 0.9743698870671270162 ) ) ; -#10748 = ORIENTED_EDGE ( 'NONE', *, *, #27811, .F. ) ; -#10749 = ORIENTED_EDGE ( 'NONE', *, *, #18608, .F. ) ; -#10750 = CARTESIAN_POINT ( 'NONE', ( -12.63780403360086524, 184.0105860366603281, 102.6558995647242227 ) ) ; -#10751 = CARTESIAN_POINT ( 'NONE', ( -31.70535867971752708, 220.4002260770989778, 73.57765341576822493 ) ) ; -#10752 = CARTESIAN_POINT ( 'NONE', ( -12.63780402291296134, 137.2408233462553255, 91.85824708360104296 ) ) ; -#10753 = VERTEX_POINT ( 'NONE', #11565 ) ; -#10754 = ADVANCED_FACE ( 'NONE', ( #23424 ), #36291, .T. ) ; -#10755 = ORIENTED_EDGE ( 'NONE', *, *, #7446, .F. ) ; -#10756 = FACE_OUTER_BOUND ( 'NONE', #39057, .T. ) ; -#10757 = CARTESIAN_POINT ( 'NONE', ( -35.94659742851874284, 109.6131156826799895, 89.78949559170979455 ) ) ; -#10758 = DIRECTION ( 'NONE', ( 0.7857167650892391553, -0.6185862428610305885, -0.0004745532376930816426 ) ) ; -#10759 = CARTESIAN_POINT ( 'NONE', ( -38.40646698065000919, 119.2087085174999999, 90.46070431091000330 ) ) ; -#10760 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455649311516, -31.54510897440487938, 136.4474729010643159 ) ) ; -#10761 = APPROVAL_PERSON_ORGANIZATION ( #36585, #25220, #18362 ) ; -#10762 = AXIS2_PLACEMENT_3D ( 'NONE', #10137, #28736, #7044 ) ; -#10763 = LINE ( 'NONE', #36507, #36733 ) ; -#10764 = ORIENTED_EDGE ( 'NONE', *, *, #34576, .T. ) ; -#10765 = CARTESIAN_POINT ( 'NONE', ( -37.83658563635734851, 190.9636364155839487, 106.3289608523462846 ) ) ; -#10766 = CARTESIAN_POINT ( 'NONE', ( -15.49852919254797179, 185.3436308334966895, 105.0179936564814511 ) ) ; -#10767 = VERTEX_POINT ( 'NONE', #40355 ) ; -#10768 = CIRCLE ( 'NONE', #302, 5.500000000083335117 ) ; -#10769 = AXIS2_PLACEMENT_3D ( 'NONE', #34965, #20053, #26221 ) ; -#10770 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3708, #35169, #38062, #16185, #10065, #32143 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10771 = CARTESIAN_POINT ( 'NONE', ( -20.51860925439517658, 209.4696347946357662, 75.57087777984216359 ) ) ; -#10772 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971528487 ) ) ; -#10773 = DIRECTION ( 'NONE', ( 0.0005884949961236033691, -0.2249510543439074417, 0.9743698870671260170 ) ) ; -#10774 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7872, #32816, #4796, #17255 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999999704799078515 ), - .UNSPECIFIED. ) ; -#10775 = DIRECTION ( 'NONE', ( 0.7856637149787887298, -0.6186538021912810770, 0.000000000000000000 ) ) ; -#10776 = ORIENTED_EDGE ( 'NONE', *, *, #23539, .F. ) ; -#10777 = CARTESIAN_POINT ( 'NONE', ( -2.453444137526474833, 207.4083922041706103, 77.08315768838481574 ) ) ; -#10778 = EDGE_CURVE ( 'NONE', #9171, #16546, #15036, .T. ) ; -#10779 = CARTESIAN_POINT ( 'NONE', ( 1.757321110795265096, 189.3959765346186259, 103.7979996257443105 ) ) ; -#10780 = CARTESIAN_POINT ( 'NONE', ( 3.062734419220130455, 191.5259964270285025, 103.8683342040099831 ) ) ; -#10781 = LINE ( 'NONE', #14048, #13831 ) ; -#10782 = CARTESIAN_POINT ( 'NONE', ( -26.14636603714999907, 191.5356462786000122, 103.7498177085000037 ) ) ; -#10783 = LINE ( 'NONE', #23054, #22509 ) ; -#10784 = CARTESIAN_POINT ( 'NONE', ( -29.20280672794129373, 149.0670272684989186, 94.08539458806572497 ) ) ; -#10785 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319383117124 ) ) ; -#10786 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #7576, #33327, #20446, #11464 ), - ( #17774, #35765, #17169, #17369 ), - ( #1651, #23738, #20039, #36190 ), - ( #29875, #36404, #4504, #23336 ), - ( #8411, #1441, #39054, #13923 ), - ( #26405, #8194, #38852, #26812 ), - ( #14139, #20662, #1857, #26612 ), - ( #39257, #17578, #23950, #2066 ), - ( #27022, #10869, #7772, #39453 ), - ( #20243, #32731, #20869, #37216 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.01667090743663000169, 0.000000000000000000, 0.2499990538965000120, 0.4999981579182999902, 0.7499972619401999996, 0.9999963377155000055, 1.000000000000000000, 1.017542216337000038 ), - ( 2.915096369016000249E-07, 1.000017816366000067 ), - .UNSPECIFIED. ) ; -#10787 = CARTESIAN_POINT ( 'NONE', ( -15.83323285334240360, 138.1594705225070072, 91.73016490536959111 ) ) ; -#10788 = EDGE_LOOP ( 'NONE', ( #21996, #2791, #24028, #19183 ) ) ; -#10789 = EDGE_CURVE ( 'NONE', #14004, #25364, #9502, .T. ) ; -#10790 = AXIS2_PLACEMENT_3D ( 'NONE', #22364, #38085, #34787 ) ; -#10791 = CARTESIAN_POINT ( 'NONE', ( -2.953326078383014419, 207.8686482947481124, 77.27881662713799926 ) ) ; -#10792 = ADVANCED_FACE ( 'NONE', ( #30980 ), #38837, .F. ) ; -#10793 = VECTOR ( 'NONE', #37371, 1000.000000000000000 ) ; -#10794 = CARTESIAN_POINT ( 'NONE', ( -24.94096241724887264, 117.2068880492941787, 170.8291735276115730 ) ) ; -#10795 = LINE ( 'NONE', #14267, #5537 ) ; -#10796 = CARTESIAN_POINT ( 'NONE', ( 37.43538425564999983, 190.5468385801999887, 106.5747605329000010 ) ) ; -#10797 = CARTESIAN_POINT ( 'NONE', ( 36.19056769187381661, 192.0352611420189817, 106.4236211497759967 ) ) ; -#10798 = VECTOR ( 'NONE', #8803, 1000.000000000000114 ) ; -#10799 = PLANE ( 'NONE', #4408 ) ; -#10800 = EDGE_CURVE ( 'NONE', #16069, #2058, #24874, .T. ) ; -#10801 = ADVANCED_FACE ( 'NONE', ( #37260 ), #30733, .T. ) ; -#10802 = FACE_OUTER_BOUND ( 'NONE', #17717, .T. ) ; -#10803 = EDGE_LOOP ( 'NONE', ( #25344, #1692, #38682, #14475 ) ) ; -#10804 = EDGE_CURVE ( 'NONE', #38902, #4989, #9839, .T. ) ; -#10805 = LINE ( 'NONE', #7924, #203 ) ; -#10806 = CARTESIAN_POINT ( 'NONE', ( 28.46531727888097407, 128.0270319182838250, 91.75885866990255124 ) ) ; -#10807 = EDGE_CURVE ( 'NONE', #22883, #20598, #22132, .T. ) ; -#10808 = CARTESIAN_POINT ( 'NONE', ( 36.03695478788529272, 115.8404287910482822, 87.24601887434940295 ) ) ; -#10809 = CARTESIAN_POINT ( 'NONE', ( -20.33314853376290543, 191.4513222512928508, 104.2073383542079625 ) ) ; -#10810 = ORIENTED_EDGE ( 'NONE', *, *, #18840, .F. ) ; -#10811 = CARTESIAN_POINT ( 'NONE', ( -39.60387704732063696, 119.5152883936298025, 90.00593015133101460 ) ) ; -#10812 = CARTESIAN_POINT ( 'NONE', ( 4.035676231980001027, 136.7932109853310010, 93.79744583390555590 ) ) ; -#10813 = ORIENTED_EDGE ( 'NONE', *, *, #15854, .F. ) ; -#10814 = PLANE ( 'NONE', #24564 ) ; -#10815 = CARTESIAN_POINT ( 'NONE', ( 25.17505429875322776, 212.3492621108707965, 73.54312482419744867 ) ) ; -#10816 = ORIENTED_EDGE ( 'NONE', *, *, #37096, .F. ) ; -#10817 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10818 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385907860 ) ) ; -#10819 = CARTESIAN_POINT ( 'NONE', ( 3.064415859742461112, 190.8780989022363883, 106.7976082717191417 ) ) ; -#10820 = AXIS2_PLACEMENT_3D ( 'NONE', #27059, #33561, #8233 ) ; -#10821 = CARTESIAN_POINT ( 'NONE', ( -30.06899859699403876, 176.9708773808299895, 103.4130022359367587 ) ) ; -#10822 = CARTESIAN_POINT ( 'NONE', ( -20.49852834491502307, 151.4051363116404900, 97.18569326181511769 ) ) ; -#10823 = ORIENTED_EDGE ( 'NONE', *, *, #21989, .F. ) ; -#10824 = VECTOR ( 'NONE', #8005, 1000.000000000000114 ) ; -#10825 = EDGE_LOOP ( 'NONE', ( #24172, #11465, #36181, #3128 ) ) ; -#10826 = CARTESIAN_POINT ( 'NONE', ( -23.36013623391100325, 181.0108636162488267, 104.5355957067678219 ) ) ; -#10827 = ADVANCED_FACE ( 'NONE', ( #6766 ), #22901, .F. ) ; -#10828 = CARTESIAN_POINT ( 'NONE', ( 42.83487131658635860, 120.7910107177264081, 92.64688251868899727 ) ) ; -#10829 = VECTOR ( 'NONE', #27262, 1000.000000000000114 ) ; -#10830 = VECTOR ( 'NONE', #2133, 1000.000000000000227 ) ; -#10831 = FACE_OUTER_BOUND ( 'NONE', #1912, .T. ) ; -#10832 = VECTOR ( 'NONE', #7932, 1000.000000000000114 ) ; -#10833 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#10834 = CONICAL_SURFACE ( 'NONE', #32366, 48.00000000001811884, 0.7853981633973075027 ) ; -#10835 = ORIENTED_EDGE ( 'NONE', *, *, #13946, .T. ) ; -#10836 = CARTESIAN_POINT ( 'NONE', ( 25.51044001015309703, 191.4790671403759745, 106.3785283636754855 ) ) ; -#10837 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28053, #6349, #31307, #28441 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10838 = CARTESIAN_POINT ( 'NONE', ( -39.39285454264343400, 114.3643166784735712, 151.6767146082210047 ) ) ; -#10839 = CARTESIAN_POINT ( 'NONE', ( 36.69057616380133879, 165.6296374286519892, 191.7157049021380715 ) ) ; -#10840 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319379670445 ) ) ; -#10841 = ADVANCED_FACE ( 'NONE', ( #35161 ), #39871, .F. ) ; -#10842 = CARTESIAN_POINT ( 'NONE', ( 31.79572351860000978, 225.9002260771066517, 76.03930080930153679 ) ) ; -#10843 = CARTESIAN_POINT ( 'NONE', ( 25.89203641490000507, 191.6305662588000018, 106.7726749487000006 ) ) ; -#10844 = EDGE_CURVE ( 'NONE', #10712, #9444, #9864, .T. ) ; -#10845 = DIRECTION ( 'NONE', ( -0.7857089111626770483, 0.6185964006681257121, 0.000000000000000000 ) ) ; -#10846 = CARTESIAN_POINT ( 'NONE', ( 26.22160995721886323, 122.3003350589623466, 87.87234068927691055 ) ) ; -#10847 = ORIENTED_EDGE ( 'NONE', *, *, #37407, .T. ) ; -#10848 = ADVANCED_FACE ( 'NONE', ( #837 ), #20280, .F. ) ; -#10849 = FACE_OUTER_BOUND ( 'NONE', #8650, .T. ) ; -#10850 = FACE_OUTER_BOUND ( 'NONE', #19328, .T. ) ; -#10851 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319375842127 ) ) ; -#10852 = DIRECTION ( 'NONE', ( 0.0006039748319385504537, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#10853 = VECTOR ( 'NONE', #7713, 1000.000000000000227 ) ; -#10854 = CARTESIAN_POINT ( 'NONE', ( -20.50022561091320128, 193.4754546137064892, 103.9384250774701712 ) ) ; -#10855 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #12748, #16946, #15800, #25437 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.1815409218495399601, 1.571531679974982776 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8453711073098789663, 0.8453711073098789663, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#10856 = AXIS2_PLACEMENT_3D ( 'NONE', #9132, #5858, #18310 ) ; -#10857 = EDGE_LOOP ( 'NONE', ( #39225, #15015, #35584, #1460 ) ) ; -#10858 = ORIENTED_EDGE ( 'NONE', *, *, #15900, .F. ) ; -#10859 = ADVANCED_FACE ( 'NONE', ( #38850 ), #19827, .F. ) ; -#10860 = VERTEX_POINT ( 'NONE', #35978 ) ; -#10861 = CARTESIAN_POINT ( 'NONE', ( -13.50718409113456886, 124.3648481134796242, 88.37302201493642428 ) ) ; -#10862 = CIRCLE ( 'NONE', #24595, 4.999999999999990230 ) ; -#10863 = CARTESIAN_POINT ( 'NONE', ( 5.666454502190154230, 124.0172541041007293, 91.08205378008646846 ) ) ; -#10864 = ORIENTED_EDGE ( 'NONE', *, *, #21383, .T. ) ; -#10865 = FACE_BOUND ( 'NONE', #9722, .T. ) ; -#10866 = DIRECTION ( 'NONE', ( -0.7730662169443226484, -0.5272861007345266415, -0.3526159273084134571 ) ) ; -#10867 = CARTESIAN_POINT ( 'NONE', ( -39.42814403217000319, 120.3902538954999955, 87.47098505926000200 ) ) ; -#10868 = LINE ( 'NONE', #5109, #26848 ) ; -#10869 = CARTESIAN_POINT ( 'NONE', ( -37.80938064989999958, 118.7890831608000042, 87.39100579507000077 ) ) ; -#10870 = ORIENTED_EDGE ( 'NONE', *, *, #18993, .F. ) ; -#10871 = CARTESIAN_POINT ( 'NONE', ( 3.501248163491682774, 185.3093324233526005, 105.1696495633186288 ) ) ; -#10872 = ORIENTED_EDGE ( 'NONE', *, *, #25723, .F. ) ; -#10873 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; -#10874 = CARTESIAN_POINT ( 'NONE', ( -23.04612012923000108, 118.1131156702000169, 13.53038997162000001 ) ) ; -#10875 = DIRECTION ( 'NONE', ( -1.734723476152105595E-15, 0.9743700557921589622, 0.2249510932971544308 ) ) ; -#10876 = ORIENTED_EDGE ( 'NONE', *, *, #27758, .T. ) ; -#10877 = CARTESIAN_POINT ( 'NONE', ( -0.4376699881329659814, 188.6098915369740041, 103.1945603907900164 ) ) ; -#10878 = CARTESIAN_POINT ( 'NONE', ( 3.499876193431697313, 126.7284862091015185, 89.25048713327655037 ) ) ; -#10879 = CARTESIAN_POINT ( 'NONE', ( 8.188077193987783886, 161.3225763900416609, 97.06327911995997226 ) ) ; -#10880 = CIRCLE ( 'NONE', #16085, 8.500000000041749715 ) ; -#10881 = ORIENTED_EDGE ( 'NONE', *, *, #31631, .T. ) ; -#10882 = CARTESIAN_POINT ( 'NONE', ( 22.59408136249981425, 154.4094276889290427, 95.28750111188634264 ) ) ; -#10883 = CARTESIAN_POINT ( 'NONE', ( -23.80390059618266108, 214.0116903629666751, 76.07246561699776066 ) ) ; -#10884 = CONICAL_SURFACE ( 'NONE', #445, 22.50000000000898837, 0.7853981633973132759 ) ; -#10885 = ORIENTED_EDGE ( 'NONE', *, *, #22807, .T. ) ; -#10886 = ORIENTED_EDGE ( 'NONE', *, *, #30881, .T. ) ; -#10887 = VECTOR ( 'NONE', #3375, 1000.000000000000000 ) ; -#10888 = EDGE_CURVE ( 'NONE', #38838, #18878, #26938, .T. ) ; -#10889 = VECTOR ( 'NONE', #3719, 1000.000000000000000 ) ; -#10890 = EDGE_CURVE ( 'NONE', #14788, #39309, #20970, .T. ) ; -#10891 = ORIENTED_EDGE ( 'NONE', *, *, #22108, .T. ) ; -#10892 = EDGE_CURVE ( 'NONE', #38645, #3220, #35131, .T. ) ; -#10893 = ORIENTED_EDGE ( 'NONE', *, *, #31623, .T. ) ; -#10894 = AXIS2_PLACEMENT_3D ( 'NONE', #4255, #22895, #39013 ) ; -#10895 = EDGE_CURVE ( 'NONE', #24926, #34340, #10868, .T. ) ; -#10896 = CARTESIAN_POINT ( 'NONE', ( -28.25302560543209651, 186.4513372582409829, 105.2762999796510002 ) ) ; -#10897 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971562904 ) ) ; -#10898 = CARTESIAN_POINT ( 'NONE', ( 27.87465140964610200, 149.3918682064020516, 291.5417083442604280 ) ) ; -#10899 = ORIENTED_EDGE ( 'NONE', *, *, #37539, .F. ) ; -#10900 = ADVANCED_FACE ( 'NONE', ( #17577 ), #35294, .F. ) ; -#10901 = CARTESIAN_POINT ( 'NONE', ( 26.00069614921000394, 120.1373339117999990, 90.44931475037999746 ) ) ; -#10902 = CARTESIAN_POINT ( 'NONE', ( 20.50029382560668267, 151.8610500380989947, 95.21357841101577435 ) ) ; -#10904 = CARTESIAN_POINT ( 'NONE', ( -10.97961932939787566, 153.8967050738901321, 95.18940742154448742 ) ) ; -#10903 = CARTESIAN_POINT ( 'NONE', ( 25.49185141408513999, 210.1694363959666703, 75.54314407219717964 ) ) ; -#10905 = EDGE_LOOP ( 'NONE', ( #2197, #25394, #20705, #28436, #23646, #28944 ) ) ; -#10906 = EDGE_CURVE ( 'NONE', #27866, #9290, #30322, .T. ) ; -#10907 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927785862613, 0.0005734119022076208027 ) ) ; -#10908 = EDGE_LOOP ( 'NONE', ( #30114, #21930, #16174, #6046, #22839, #2699, #14836, #17113 ) ) ; -#10909 = AXIS2_PLACEMENT_3D ( 'NONE', #6906, #20112, #3630 ) ; -#10910 = DIRECTION ( 'NONE', ( -0.0004161288024545937514, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#10911 = VECTOR ( 'NONE', #9155, 999.9999999999998863 ) ; -#10912 = AXIS2_PLACEMENT_3D ( 'NONE', #28247, #213, #12693 ) ; -#10913 = EDGE_LOOP ( 'NONE', ( #37704, #14419, #37876, #25337 ) ) ; -#10914 = CARTESIAN_POINT ( 'NONE', ( -22.54148966027999990, 176.5965135413000269, 28.07991271570000080 ) ) ; -#10915 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; -#10916 = EDGE_CURVE ( 'NONE', #2346, #37891, #8388, .T. ) ; -#10917 = FACE_OUTER_BOUND ( 'NONE', #16270, .T. ) ; -#10918 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319384230599 ) ) ; -#10919 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#10920 = CARTESIAN_POINT ( 'NONE', ( 36.41644495559000205, 191.8199172630999954, 104.3707800657000178 ) ) ; -#10921 = CIRCLE ( 'NONE', #8279, 2.499999999950359264 ) ; -#10922 = ORIENTED_EDGE ( 'NONE', *, *, #4314, .F. ) ; -#10923 = ORIENTED_EDGE ( 'NONE', *, *, #28791, .F. ) ; -#10924 = LINE ( 'NONE', #20301, #469 ) ; -#10925 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28487, #13150, #31962, #34783 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#10926 = EDGE_LOOP ( 'NONE', ( #3859, #35385, #7448, #7974 ) ) ; -#10927 = PLANE ( 'NONE', #14134 ) ; -#10928 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319388572829 ) ) ; -#10929 = CARTESIAN_POINT ( 'NONE', ( 3.075283387903953614, 190.8485281250639218, 106.8022040810427313 ) ) ; -#10930 = VERTEX_POINT ( 'NONE', #8410 ) ; -#10931 = CARTESIAN_POINT ( 'NONE', ( 37.32820081582953264, 168.0249161464118117, 183.6187219225678859 ) ) ; -#10932 = CARTESIAN_POINT ( 'NONE', ( 15.50029468042244396, 126.6919968860542838, 89.40586344971805488 ) ) ; -#10933 = CARTESIAN_POINT ( 'NONE', ( -25.50111726777775090, 120.6553742016506874, 88.03695713991920968 ) ) ; -#10934 = CARTESIAN_POINT ( 'NONE', ( -14.91027383994646272, 151.7163915728016548, 177.9904694539845025 ) ) ; -#10935 = ADVANCED_FACE ( 'NONE', ( #14537 ), #27635, .T. ) ; -#10936 = AXIS2_PLACEMENT_3D ( 'NONE', #5371, #17825, #12719 ) ; -#10937 = ORIENTED_EDGE ( 'NONE', *, *, #26919, .T. ) ; -#10938 = EDGE_CURVE ( 'NONE', #17057, #33799, #15110, .T. ) ; -#10939 = EDGE_CURVE ( 'NONE', #28499, #28666, #15339, .T. ) ; -#10940 = CARTESIAN_POINT ( 'NONE', ( -13.83205090667458670, 150.4111611012818628, 179.9705989528482917 ) ) ; -#10941 = VECTOR ( 'NONE', #11750, 1000.000000000000114 ) ; -#10942 = CARTESIAN_POINT ( 'NONE', ( -2.437027990547441014, 191.0000000396348128, 104.2633722229568605 ) ) ; -#10943 = VERTEX_POINT ( 'NONE', #3647 ) ; -#10944 = EDGE_CURVE ( 'NONE', #15218, #4804, #32724, .T. ) ; -#10945 = CARTESIAN_POINT ( 'NONE', ( 33.51443528077827239, 81.86012571781209601, 287.9887764040152547 ) ) ; -#10946 = CARTESIAN_POINT ( 'NONE', ( -38.53363287338000021, 118.3434021919999992, 89.55002640806999636 ) ) ; -#10947 = EDGE_CURVE ( 'NONE', #282, #23181, #37414, .T. ) ; -#10948 = ORIENTED_EDGE ( 'NONE', *, *, #18606, .F. ) ; -#10949 = ORIENTED_EDGE ( 'NONE', *, *, #14211, .T. ) ; -#10950 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#10951 = DIRECTION ( 'NONE', ( 0.6087906217132987852, -0.7729786229956010501, -0.1785441886642060716 ) ) ; -#10952 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 82.27946979429644614, 322.5967026918629017 ) ) ; -#10953 = ORIENTED_EDGE ( 'NONE', *, *, #13373, .F. ) ; -#10954 = ORIENTED_EDGE ( 'NONE', *, *, #4816, .T. ) ; -#10955 = CARTESIAN_POINT ( 'NONE', ( -3.170187833920075970, 183.7988232230405572, 102.0881399076664593 ) ) ; -#10956 = ORIENTED_EDGE ( 'NONE', *, *, #25311, .T. ) ; -#10957 = VERTEX_POINT ( 'NONE', #16131 ) ; -#10958 = EDGE_LOOP ( 'NONE', ( #31024, #25795, #33751, #18903 ) ) ; -#10959 = DIRECTION ( 'NONE', ( 0.0002393071182785211099, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#10960 = EDGE_CURVE ( 'NONE', #39311, #38692, #2011, .T. ) ; -#10961 = CONICAL_SURFACE ( 'NONE', #39694, 2.250000000020516921, 0.7853981633778843729 ) ; -#10962 = ORIENTED_EDGE ( 'NONE', *, *, #6902, .F. ) ; -#10963 = CARTESIAN_POINT ( 'NONE', ( -45.37719511632801783, 116.4273876922947153, 122.4606002276863848 ) ) ; -#10964 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#10965 = CARTESIAN_POINT ( 'NONE', ( 38.27613113168000325, 118.4065472851000038, 87.79665044522000983 ) ) ; -#10966 = CARTESIAN_POINT ( 'NONE', ( 25.99858048705007008, 120.0662502775363123, 90.40623698262325547 ) ) ; -#10967 = CARTESIAN_POINT ( 'NONE', ( 1.752038607023885142, 151.6655334627390914, 130.5892090252970661 ) ) ; -#10968 = AXIS2_PLACEMENT_3D ( 'NONE', #38287, #16601, #7403 ) ; -#10969 = EDGE_LOOP ( 'NONE', ( #31980, #37714, #21243, #33549 ) ) ; -#10970 = CARTESIAN_POINT ( 'NONE', ( -21.57293378737277223, 176.1767418382142694, 103.2474204113453879 ) ) ; -#10971 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; -#10972 = ORIENTED_EDGE ( 'NONE', *, *, #6433, .T. ) ; -#10973 = LINE ( 'NONE', #30181, #37524 ) ; -#10974 = CARTESIAN_POINT ( 'NONE', ( -39.79500347691000428, 182.5468005769366187, 106.5836252739005658 ) ) ; -#10975 = CARTESIAN_POINT ( 'NONE', ( 20.49976360197975112, 195.7358879765328936, 104.4182221658072507 ) ) ; -#10976 = CARTESIAN_POINT ( 'NONE', ( -13.54365902012251155, 127.5920554465911607, 178.0186555151901473 ) ) ; -#10977 = VERTEX_POINT ( 'NONE', #35111 ) ; -#10978 = CARTESIAN_POINT ( 'NONE', ( -75.39652672445234316, 196.3653591838614147, 189.1162797731339822 ) ) ; -#10979 = CARTESIAN_POINT ( 'NONE', ( 1.766903094796105966, 189.4031650064154064, 103.8000672188349114 ) ) ; -#10980 = FACE_OUTER_BOUND ( 'NONE', #20554, .T. ) ; -#10981 = ORIENTED_EDGE ( 'NONE', *, *, #13929, .T. ) ; -#10982 = DIRECTION ( 'NONE', ( -7.338309297537026246E-11, -0.9743700557756715952, -0.2249510933685688052 ) ) ; -#10983 = VERTEX_POINT ( 'NONE', #21885 ) ; -#10984 = EDGE_CURVE ( 'NONE', #4954, #6620, #37950, .T. ) ; -#10985 = CARTESIAN_POINT ( 'NONE', ( -26.15746170179000174, 191.4561040044000038, 103.7271919721000017 ) ) ; -#10986 = EDGE_CURVE ( 'NONE', #37514, #7165, #193, .T. ) ; -#10987 = DIRECTION ( 'NONE', ( 0.0005884949961266384847, -0.2249510543439063315, 0.9743698870671264611 ) ) ; -#10988 = CARTESIAN_POINT ( 'NONE', ( 14.78500024124773304, 129.1259577792816629, 89.96821972116190125 ) ) ; -#10989 = DIRECTION ( 'NONE', ( -0.7069397808360943225, 0.6508952239913948778, 0.2767156548816978590 ) ) ; -#10990 = VERTEX_POINT ( 'NONE', #6515 ) ; -#10991 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319394906738 ) ) ; -#10992 = CIRCLE ( 'NONE', #36458, 2.999999999998230304 ) ; -#10993 = ADVANCED_FACE ( 'NONE', ( #17316 ), #29010, .T. ) ; -#10994 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37525, #9524, #22001, #6429 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.001732890349273856316, 0.003708228055068993681 ), - .UNSPECIFIED. ) ; -#10995 = VECTOR ( 'NONE', #39144, 999.9999999999998863 ) ; -#10996 = CARTESIAN_POINT ( 'NONE', ( 16.49964056686251013, 136.6766879063869453, 180.9853436342004898 ) ) ; -#10997 = CARTESIAN_POINT ( 'NONE', ( 15.50147167064367437, 126.2420947773427997, 91.35460322390918009 ) ) ; -#10998 = CARTESIAN_POINT ( 'NONE', ( -18.61079839510214029, 126.0371735097383095, 174.9248182282352957 ) ) ; -#10999 = CARTESIAN_POINT ( 'NONE', ( -3.955049870755343200, 137.2594250647584317, 91.77268855263983482 ) ) ; -#11000 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #40049, #33915, #5913, #18164 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11001 = CARTESIAN_POINT ( 'NONE', ( 38.04963484502000171, 190.2021038149999868, 106.7594576531000001 ) ) ; -#11002 = CARTESIAN_POINT ( 'NONE', ( -42.36217678049914781, 170.6443158288746815, 189.3365560754358228 ) ) ; -#11003 = CARTESIAN_POINT ( 'NONE', ( -5.666923135161506586, 130.1263008745872867, 92.47646040638427678 ) ) ; -#11004 = LINE ( 'NONE', #31878, #4722 ) ; -#11005 = CARTESIAN_POINT ( 'NONE', ( -38.36814232060637408, 118.8282003920224668, 87.72026801873936108 ) ) ; -#11006 = EDGE_LOOP ( 'NONE', ( #261, #11612, #36040, #29996 ) ) ; -#11007 = FACE_OUTER_BOUND ( 'NONE', #21391, .T. ) ; -#11008 = CYLINDRICAL_SURFACE ( 'NONE', #30782, 5.000000000000007994 ) ; -#11009 = DIRECTION ( 'NONE', ( -0.9029530701559865813, -0.4297388226321038340, 0.0005453610282712744936 ) ) ; -#11010 = ORIENTED_EDGE ( 'NONE', *, *, #1673, .T. ) ; -#11011 = CARTESIAN_POINT ( 'NONE', ( 13.50176803619674004, 127.0692004836212448, 92.06300581097160318 ) ) ; -#11012 = VERTEX_POINT ( 'NONE', #32286 ) ; -#11013 = AXIS2_PLACEMENT_3D ( 'NONE', #3443, #30685, #9011 ) ; -#11014 = CARTESIAN_POINT ( 'NONE', ( -16.54520785153081164, 151.9090420533067913, 184.2667482906656460 ) ) ; -#11015 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#11016 = EDGE_LOOP ( 'NONE', ( #9673, #29922, #32507, #29446 ) ) ; -#11017 = FACE_OUTER_BOUND ( 'NONE', #25757, .T. ) ; -#11018 = EDGE_CURVE ( 'NONE', #12044, #21775, #36642, .T. ) ; -#11019 = VECTOR ( 'NONE', #34339, 1000.000000000000000 ) ; -#11020 = FACE_OUTER_BOUND ( 'NONE', #13936, .T. ) ; -#11021 = AXIS2_PLACEMENT_3D ( 'NONE', #3573, #19906, #38335 ) ; -#11022 = DIRECTION ( 'NONE', ( 0.0005884949521151187956, -0.2249510543284071740, 0.9743698870707311332 ) ) ; -#11023 = LINE ( 'NONE', #14703, #11639 ) ; -#11024 = DIRECTION ( 'NONE', ( 0.0005884949961235587000, -0.2249510543439063037, 0.9743698870671264611 ) ) ; -#11025 = CARTESIAN_POINT ( 'NONE', ( 15.99999411728631671, 174.5114300543024513, 99.93239967722463746 ) ) ; -#11026 = ORIENTED_EDGE ( 'NONE', *, *, #22462, .F. ) ; -#11027 = ADVANCED_FACE ( 'NONE', ( #1193 ), #39900, .F. ) ; -#11028 = DIRECTION ( 'NONE', ( 0.0005884949961235587000, -0.2249510543439063037, 0.9743698870671264611 ) ) ; -#11029 = CARTESIAN_POINT ( 'NONE', ( 12.63519044092067567, 181.7451889061886163, 101.6793939867825287 ) ) ; -#11030 = CARTESIAN_POINT ( 'NONE', ( 48.26140840130958054, 61.07709620987316868, 291.5293952538879125 ) ) ; -#11031 = CARTESIAN_POINT ( 'NONE', ( -45.32207284385599877, 123.9952506376050394, 92.99168501725661429 ) ) ; -#11032 = EDGE_CURVE ( 'NONE', #27515, #25396, #20522, .T. ) ; -#11033 = ORIENTED_EDGE ( 'NONE', *, *, #18065, .T. ) ; -#11034 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971540700 ) ) ; -#11035 = ADVANCED_FACE ( 'NONE', ( #30635 ), #2628, .T. ) ; -#11037 = EDGE_CURVE ( 'NONE', #3242, #35968, #40213, .T. ) ; -#11036 = CARTESIAN_POINT ( 'NONE', ( 20.33512933904179221, 151.3759901152849636, 97.32511934184164204 ) ) ; -#11038 = CARTESIAN_POINT ( 'NONE', ( -27.87558292050999853, 125.0785051656000064, 90.97322914094000623 ) ) ; -#11039 = CARTESIAN_POINT ( 'NONE', ( 32.21870153402343817, 137.6089111963648861, 94.31084469150592042 ) ) ; -#11040 = CARTESIAN_POINT ( 'NONE', ( -28.44043104824569923, 124.7785142762178765, 91.38535058895490693 ) ) ; -#11041 = DIRECTION ( 'NONE', ( -0.0005884949961241524091, 0.2249510543439059707, -0.9743698870671263501 ) ) ; -#11042 = CONICAL_SURFACE ( 'NONE', #3837, 8.000000001551294204, 0.7853981633973023957 ) ; -#11043 = CARTESIAN_POINT ( 'NONE', ( 29.20104124104027576, 148.3999055379004517, 96.97501579703776997 ) ) ; -#11044 = DIRECTION ( 'NONE', ( 0.0005734119072319879013, 1.265515853068973323E-14, 0.9999998355993788834 ) ) ; -#11045 = ORIENTED_EDGE ( 'NONE', *, *, #32516, .F. ) ; -#11046 = DIRECTION ( 'NONE', ( -0.0005884949961238380989, 0.2249510543439045829, -0.9743698870671267942 ) ) ; -#11047 = CARTESIAN_POINT ( 'NONE', ( -21.57293377266096357, 129.4069791430369492, 92.44976792907745278 ) ) ; -#11048 = CIRCLE ( 'NONE', #15614, 4.999999999999990230 ) ; -#11049 = PLANE ( 'NONE', #3845 ) ; -#11050 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; -#11051 = AXIS2_PLACEMENT_3D ( 'NONE', #5552, #39901, #18012 ) ; -#11052 = AXIS2_PLACEMENT_3D ( 'NONE', #23200, #16838, #35632 ) ; -#11053 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#11054 = VERTEX_POINT ( 'NONE', #21444 ) ; -#11055 = ORIENTED_EDGE ( 'NONE', *, *, #36552, .F. ) ; -#11056 = EDGE_LOOP ( 'NONE', ( #21112, #3507, #7110, #25063 ) ) ; -#11057 = CARTESIAN_POINT ( 'NONE', ( -13.50128150735577748, 124.5478689764576359, 88.66604936023510675 ) ) ; -#11058 = DIRECTION ( 'NONE', ( -0.4271071565734249620, -0.4480007094940485213, -0.7854138024612203894 ) ) ; -#11059 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32204, #31597, #19507, #19701 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11060 = ORIENTED_EDGE ( 'NONE', *, *, #9685, .T. ) ; -#11061 = DIRECTION ( 'NONE', ( -0.0004161288024657052516, -0.5299192578509964724, -0.8480479980493255132 ) ) ; -#11062 = FACE_OUTER_BOUND ( 'NONE', #24872, .T. ) ; -#11063 = LINE ( 'NONE', #2270, #10544 ) ; -#11064 = VERTEX_POINT ( 'NONE', #30020 ) ; -#11065 = CARTESIAN_POINT ( 'NONE', ( 37.79411860435257609, 218.5902260770999987, 73.03567738180412050 ) ) ; -#11066 = VERTEX_POINT ( 'NONE', #11408 ) ; -#11067 = CARTESIAN_POINT ( 'NONE', ( -25.99154525261003457, 196.5784392977548407, 103.8908015617383995 ) ) ; -#11068 = CARTESIAN_POINT ( 'NONE', ( 35.55462690928660408, 112.7627284812108996, 90.24631073547891447 ) ) ; -#11069 = CARTESIAN_POINT ( 'NONE', ( 30.07478355117409308, 177.7951688118731681, 100.6820556990014950 ) ) ; -#11070 = ORIENTED_EDGE ( 'NONE', *, *, #12188, .T. ) ; -#11071 = ORIENTED_EDGE ( 'NONE', *, *, #2538, .T. ) ; -#11072 = CONICAL_SURFACE ( 'NONE', #26110, 2.503098569411387420, 0.7853981633649038674 ) ; -#11073 = EDGE_CURVE ( 'NONE', #6578, #9198, #23894, .T. ) ; -#11074 = CARTESIAN_POINT ( 'NONE', ( -2.877428494186000218, 190.4461576289999982, 103.6226212142999970 ) ) ; -#11075 = CARTESIAN_POINT ( 'NONE', ( 0.8177663066029530192, 189.0253564221259808, 103.7033406197609793 ) ) ; -#11076 = CARTESIAN_POINT ( 'NONE', ( 34.29442123011752841, 218.5902260770999987, 73.53779120251549273 ) ) ; -#11077 = CIRCLE ( 'NONE', #19548, 51.90509899272669969 ) ; -#11078 = ORIENTED_EDGE ( 'NONE', *, *, #1122, .F. ) ; -#11079 = EDGE_LOOP ( 'NONE', ( #5007, #4783, #4161, #36073 ) ) ; -#11080 = CARTESIAN_POINT ( 'NONE', ( -2.372094777808882782, 209.5677220771418376, 75.55993702015497604 ) ) ; -#11081 = ORIENTED_EDGE ( 'NONE', *, *, #8927, .T. ) ; -#11082 = ADVANCED_FACE ( 'NONE', ( #24099 ), #14699, .T. ) ; -#11083 = ORIENTED_EDGE ( 'NONE', *, *, #2979, .F. ) ; -#11084 = CIRCLE ( 'NONE', #39135, 6.000000000278002510 ) ; -#11085 = EDGE_CURVE ( 'NONE', #26640, #189, #3803, .T. ) ; -#11086 = EDGE_CURVE ( 'NONE', #1525, #19998, #6468, .T. ) ; -#11087 = ORIENTED_EDGE ( 'NONE', *, *, #40274, .F. ) ; -#11088 = ORIENTED_EDGE ( 'NONE', *, *, #5475, .F. ) ; -#11089 = CARTESIAN_POINT ( 'NONE', ( -27.50624184847999842, 187.5021564911999974, 106.0367333465000002 ) ) ; -#11090 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#11091 = ORIENTED_EDGE ( 'NONE', *, *, #33820, .T. ) ; -#11092 = LINE ( 'NONE', #39084, #7439 ) ; -#11093 = ORIENTED_EDGE ( 'NONE', *, *, #5847, .T. ) ; -#11094 = CARTESIAN_POINT ( 'NONE', ( 28.26060338730999888, 125.1349112909999945, 91.09114387335000629 ) ) ; -#11095 = LINE ( 'NONE', #23371, #31303 ) ; -#11097 = CARTESIAN_POINT ( 'NONE', ( -28.52670407937950969, 187.4270078119665754, 102.9410870260050928 ) ) ; -#11096 = LINE ( 'NONE', #27666, #34160 ) ; -#11098 = ORIENTED_EDGE ( 'NONE', *, *, #27736, .T. ) ; -#11099 = VECTOR ( 'NONE', #22090, 1000.000000000000114 ) ; -#11100 = VECTOR ( 'NONE', #13767, 1000.000000000000114 ) ; -#11101 = VERTEX_POINT ( 'NONE', #9764 ) ; -#11102 = AXIS2_PLACEMENT_3D ( 'NONE', #13262, #6702, #16708 ) ; -#11103 = AXIS2_PLACEMENT_3D ( 'NONE', #38393, #7301, #1175 ) ; -#11104 = CONICAL_SURFACE ( 'NONE', #39809, 5.000000517016990109, 0.7853981634346335339 ) ; -#11105 = ORIENTED_EDGE ( 'NONE', *, *, #24527, .F. ) ; -#11106 = CARTESIAN_POINT ( 'NONE', ( 39.38831168086999668, 119.0002552818999959, 89.54346710420000477 ) ) ; -#11107 = PLANE ( 'NONE', #4789 ) ; -#11108 = CARTESIAN_POINT ( 'NONE', ( -38.40287610445658117, 121.6088961281960366, 92.88326245006905424 ) ) ; -#11109 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16872, #13631, #16481, #12835 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11110 = CARTESIAN_POINT ( 'NONE', ( 40.93452692291575090, 180.9368392483152093, 106.5322820562371078 ) ) ; -#11111 = LINE ( 'NONE', #36240, #33941 ) ; -#11112 = ADVANCED_FACE ( 'NONE', ( #24918 ), #4638, .T. ) ; -#11113 = ORIENTED_EDGE ( 'NONE', *, *, #20419, .T. ) ; -#11114 = EDGE_CURVE ( 'NONE', #8051, #32274, #22928, .T. ) ; -#11115 = EDGE_CURVE ( 'NONE', #22787, #15773, #21639, .T. ) ; -#11116 = LINE ( 'NONE', #30325, #31189 ) ; -#11117 = CARTESIAN_POINT ( 'NONE', ( 26.53578290824999897, 123.9660816091000015, 88.77004744939999625 ) ) ; -#11118 = ORIENTED_EDGE ( 'NONE', *, *, #6628, .F. ) ; -#11119 = EDGE_CURVE ( 'NONE', #17425, #25568, #19075, .T. ) ; -#11120 = CARTESIAN_POINT ( 'NONE', ( -35.79968611446999915, 192.2947011702999873, 106.6046827446999998 ) ) ; -#11121 = EDGE_CURVE ( 'NONE', #14482, #11663, #22644, .T. ) ; -#11122 = CARTESIAN_POINT ( 'NONE', ( 2.730734721350000616, 190.9310010506000026, 106.4668547351000143 ) ) ; -#11123 = VERTEX_POINT ( 'NONE', #23042 ) ; -#11124 = CARTESIAN_POINT ( 'NONE', ( -19.99823416871255333, 118.9403737594142854, 90.20346087292681148 ) ) ; -#11125 = ADVANCED_FACE ( 'NONE', ( #35070 ), #23589, .F. ) ; -#11126 = VECTOR ( 'NONE', #28924, 1000.000000000000000 ) ; -#11127 = CIRCLE ( 'NONE', #26808, 6.000000000000007994 ) ; -#11128 = LINE ( 'NONE', #13783, #10830 ) ; -#11129 = CARTESIAN_POINT ( 'NONE', ( -3.168077782478838866, 185.2310913118877238, 105.4977280106237032 ) ) ; -#11130 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#11131 = CIRCLE ( 'NONE', #29434, 2.499999999979101162 ) ; -#11132 = ORIENTED_EDGE ( 'NONE', *, *, #26086, .F. ) ; -#11133 = VECTOR ( 'NONE', #18149, 1000.000000000000227 ) ; -#11134 = CARTESIAN_POINT ( 'NONE', ( 15.89560151159956369, 127.1356608655976004, 179.2951883097113637 ) ) ; -#11135 = CARTESIAN_POINT ( 'NONE', ( 21.73276882011762012, 213.2744563870097352, 75.54536777968174022 ) ) ; -#11136 = ORIENTED_EDGE ( 'NONE', *, *, #28288, .T. ) ; -#11137 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#11139 = CARTESIAN_POINT ( 'NONE', ( -38.89762471436931435, 77.14301703112144537, 288.8348295601788323 ) ) ; -#11138 = CARTESIAN_POINT ( 'NONE', ( 2.519705707365920144, 209.3774083710533489, 75.55686016564037288 ) ) ; -#11140 = ORIENTED_EDGE ( 'NONE', *, *, #10616, .F. ) ; -#11141 = ORIENTED_EDGE ( 'NONE', *, *, #19030, .F. ) ; -#11142 = LINE ( 'NONE', #23822, #12093 ) ; -#11143 = CARTESIAN_POINT ( 'NONE', ( 37.31104746592299648, 191.0675100092497303, 106.2960058513086068 ) ) ; -#11144 = LINE ( 'NONE', #10952, #27971 ) ; -#11145 = ORIENTED_EDGE ( 'NONE', *, *, #15207, .T. ) ; -#11146 = VERTEX_POINT ( 'NONE', #11517 ) ; -#11147 = CARTESIAN_POINT ( 'NONE', ( -5.342929950734402134, 181.6874047080202388, 101.6019927272797645 ) ) ; -#11148 = ORIENTED_EDGE ( 'NONE', *, *, #23925, .F. ) ; -#11149 = ORIENTED_EDGE ( 'NONE', *, *, #5100, .T. ) ; -#11150 = LINE ( 'NONE', #26295, #23061 ) ; -#11151 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.702666754117757870E-16, 0.0006039748319385827629 ) ) ; -#11152 = AXIS2_PLACEMENT_3D ( 'NONE', #7023, #32192, #31992 ) ; -#11153 = CARTESIAN_POINT ( 'NONE', ( 2.480477375137999818, 209.5058064405000096, 73.55699242858000275 ) ) ; -#11154 = ORIENTED_EDGE ( 'NONE', *, *, #20677, .F. ) ; -#11155 = EDGE_CURVE ( 'NONE', #15629, #6504, #12716, .T. ) ; -#11156 = CIRCLE ( 'NONE', #21624, 3.000000000000000888 ) ; -#11157 = ADVANCED_FACE ( 'NONE', ( #16677 ), #3959, .T. ) ; -#11158 = ORIENTED_EDGE ( 'NONE', *, *, #11398, .T. ) ; -#11159 = DIRECTION ( 'NONE', ( 0.0006039748319380209294, 1.272619257381173226E-14, 0.9999998176071845934 ) ) ; -#11160 = AXIS2_PLACEMENT_3D ( 'NONE', #12075, #8608, #33116 ) ; -#11161 = EDGE_CURVE ( 'NONE', #5771, #37119, #36864, .T. ) ; -#11162 = CARTESIAN_POINT ( 'NONE', ( -28.45933928643433575, 130.3430211585376810, 92.84111053953343173 ) ) ; -#11163 = CARTESIAN_POINT ( 'NONE', ( -35.76252955891000340, 191.5251398679000090, 103.7620077331999937 ) ) ; -#11164 = CARTESIAN_POINT ( 'NONE', ( 36.17084115905999653, 191.3515283555000224, 103.6762829166000017 ) ) ; -#11165 = CARTESIAN_POINT ( 'NONE', ( -25.67020520147000084, 120.8710716303999959, 87.91589439144999574 ) ) ; -#11166 = CARTESIAN_POINT ( 'NONE', ( 20.66261634646922118, 151.6624695158917007, 197.7430731246994355 ) ) ; -#11167 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178617807513E-05, -0.0002331579774917555924 ) ) ; -#11168 = ORIENTED_EDGE ( 'NONE', *, *, #30101, .T. ) ; -#11169 = ADVANCED_FACE ( 'NONE', ( #2731 ), #34381, .F. ) ; -#11170 = CARTESIAN_POINT ( 'NONE', ( -20.51855873943445374, 209.2345604776454024, 75.60470198948848974 ) ) ; -#11171 = DIRECTION ( 'NONE', ( 0.0005884949961176016596, -0.2249510543439068588, 0.9743698870671261281 ) ) ; -#11172 = CARTESIAN_POINT ( 'NONE', ( -20.49970533570471787, 160.6243682191729363, 97.26151316895288801 ) ) ; -#11173 = DIRECTION ( 'NONE', ( -1.063726576259922572E-07, -0.9742386546489418819, -0.2255194975779448163 ) ) ; -#11174 = ORIENTED_EDGE ( 'NONE', *, *, #36552, .T. ) ; -#11176 = ADVANCED_FACE ( 'NONE', ( #30937 ), #26204, .F. ) ; -#11175 = FACE_OUTER_BOUND ( 'NONE', #15183, .T. ) ; -#11177 = CARTESIAN_POINT ( 'NONE', ( 2.563555756422899901, 190.9701280411995867, 104.2517884403214197 ) ) ; -#11178 = FACE_OUTER_BOUND ( 'NONE', #14556, .T. ) ; -#11179 = ORIENTED_EDGE ( 'NONE', *, *, #4, .T. ) ; -#11180 = CARTESIAN_POINT ( 'NONE', ( -29.94629656132548590, 104.1131156707188694, 90.28587165215870414 ) ) ; -#11181 = ORIENTED_EDGE ( 'NONE', *, *, #19678, .T. ) ; -#11182 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34285, #15884, #3607, #18949, #28190, #28377, #28582 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 4 ), - ( 2.569378776076547217E-06, 7.549873607158256243E-06, 0.0005638757658064486684 ), - .UNSPECIFIED. ) ; -#11183 = CARTESIAN_POINT ( 'NONE', ( -25.87072552548999838, 191.8632371752999859, 104.0535259812000106 ) ) ; -#11184 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30722, #10207, #22678, #32076 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11185 = CONICAL_SURFACE ( 'NONE', #25004, 6.500001377281787285, 0.7853982184479049167 ) ; -#11186 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560406 ) ) ; -#11187 = CARTESIAN_POINT ( 'NONE', ( 25.88929766374999986, 192.0796316800000056, 104.0269976617999959 ) ) ; -#11188 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178410593438E-05, 0.0002331579774918190453 ) ) ; -#11189 = VECTOR ( 'NONE', #36576, 1000.000000000000000 ) ; -#11190 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559574 ) ) ; -#11191 = ORIENTED_EDGE ( 'NONE', *, *, #8734, .F. ) ; -#11192 = CIRCLE ( 'NONE', #24256, 2.000000000000011546 ) ; -#11193 = VECTOR ( 'NONE', #5734, 1000.000000000000000 ) ; -#11194 = CARTESIAN_POINT ( 'NONE', ( -20.46513762259074909, 138.6415954987478187, 152.4706522797113450 ) ) ; -#11195 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; -#11196 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18270, #27717, #6209, #37097, #39744, #24026, #18665 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 4 ), - ( 0.000000000000000000, 0.004000000000000010492, 0.006447902106031735622 ), - .UNSPECIFIED. ) ; -#11197 = CARTESIAN_POINT ( 'NONE', ( -3.871698300499220480, 137.2778037606856856, 91.69128680615639837 ) ) ; -#11198 = CARTESIAN_POINT ( 'NONE', ( 37.19332676483216460, 178.1386719297145476, 136.6947527228966521 ) ) ; -#11199 = PLANE ( 'NONE', #3266 ) ; -#11200 = CARTESIAN_POINT ( 'NONE', ( 35.54796035643903451, 209.7096538831000032, 78.03703491705788053 ) ) ; -#11201 = CARTESIAN_POINT ( 'NONE', ( -38.66420181945734669, 119.1055528796190686, 87.73959189466469866 ) ) ; -#11202 = ORIENTED_EDGE ( 'NONE', *, *, #13940, .T. ) ; -#11203 = CARTESIAN_POINT ( 'NONE', ( -19.99970578248555597, 118.1172805411119811, 90.27986416034981687 ) ) ; -#11204 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 82.27946979429644614, 322.5967026918628449 ) ) ; -#11205 = VERTEX_POINT ( 'NONE', #15392 ) ; -#11206 = LINE ( 'NONE', #21019, #29119 ) ; -#11207 = ADVANCED_FACE ( 'NONE', ( #21741, #31142 ), #28084, .F. ) ; -#11208 = DIRECTION ( 'NONE', ( -0.0005734119072319609047, 0.000000000000000000, -0.9999998355993788834 ) ) ; -#11209 = CIRCLE ( 'NONE', #39274, 2.500000000021942448 ) ; -#11210 = ADVANCED_FACE ( 'NONE', ( #24211 ), #8669, .F. ) ; -#11211 = EDGE_LOOP ( 'NONE', ( #28862, #12978, #14849, #21914 ) ) ; -#11212 = AXIS2_PLACEMENT_3D ( 'NONE', #21041, #8154, #2033 ) ; -#11213 = CIRCLE ( 'NONE', #30810, 2.499999999804313866 ) ; -#11214 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#11215 = CARTESIAN_POINT ( 'NONE', ( 10.03420218876596692, 144.2154580076550019, 92.93854428129607470 ) ) ; -#11216 = ORIENTED_EDGE ( 'NONE', *, *, #1313, .T. ) ; -#11217 = CARTESIAN_POINT ( 'NONE', ( 36.20178035809213668, 192.0381767638097585, 106.3948639845850010 ) ) ; -#11218 = CARTESIAN_POINT ( 'NONE', ( 1.222756100067673435, 140.3958132876599620, 157.8527939211185753 ) ) ; -#11219 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673442394, 158.6807756965775127, 96.79226424649958460 ) ) ; -#11220 = CARTESIAN_POINT ( 'NONE', ( -40.80896188004905412, 127.4737362100950833, 89.10719945852390822 ) ) ; -#11221 = CARTESIAN_POINT ( 'NONE', ( 29.62326790002893162, 185.7454482597306651, 103.0308995128836216 ) ) ; -#11222 = VERTEX_POINT ( 'NONE', #13133 ) ; -#11223 = ORIENTED_EDGE ( 'NONE', *, *, #36237, .F. ) ; -#11224 = CARTESIAN_POINT ( 'NONE', ( 36.06517739910999865, 192.1776130000999956, 106.5431043960000039 ) ) ; -#11225 = CARTESIAN_POINT ( 'NONE', ( -20.33315071731424339, 120.3151545898319057, 87.78425597831352434 ) ) ; -#11226 = DIRECTION ( 'NONE', ( 0.7933531821996063771, 0.5932639600174075545, 0.1364866368485285197 ) ) ; -#11227 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -7.450515246535590627E-18, -0.0006039748319384396482 ) ) ; -#11228 = VERTEX_POINT ( 'NONE', #15776 ) ; -#11229 = CARTESIAN_POINT ( 'NONE', ( 20.00000279695219874, 118.8155797008581374, 87.25566994753728522 ) ) ; -#11230 = CARTESIAN_POINT ( 'NONE', ( -41.52752186953456004, 120.6413918639734533, 90.60917506750070061 ) ) ; -#11231 = CARTESIAN_POINT ( 'NONE', ( 14.78718619285897518, 182.9114187639047486, 104.4381813414848779 ) ) ; -#11232 = CARTESIAN_POINT ( 'NONE', ( -30.06946242413328108, 177.7873465568342510, 100.7165273984233949 ) ) ; -#11233 = EDGE_CURVE ( 'NONE', #6019, #32811, #10526, .T. ) ; -#11234 = CARTESIAN_POINT ( 'NONE', ( -23.21813688330802705, 214.0904152527463395, 73.07252725527422399 ) ) ; -#11235 = AXIS2_PLACEMENT_3D ( 'NONE', #8819, #27643, #21295 ) ; -#11236 = CARTESIAN_POINT ( 'NONE', ( -25.56982011077967343, 209.7142227182705199, 73.51402136040893254 ) ) ; -#11237 = AXIS2_PLACEMENT_3D ( 'NONE', #25075, #6838, #28537 ) ; -#11238 = AXIS2_PLACEMENT_3D ( 'NONE', #28549, #37943, #20738 ) ; -#11239 = LINE ( 'NONE', #23927, #14685 ) ; -#11240 = CARTESIAN_POINT ( 'NONE', ( 3.652795731156965875, 182.6431225764332567, 101.8172044301328611 ) ) ; -#11241 = VERTEX_POINT ( 'NONE', #38454 ) ; -#11242 = PLANE ( 'NONE', #22453 ) ; -#11243 = CARTESIAN_POINT ( 'NONE', ( -15.10537794304822512, 128.9348610681433911, 92.50791545010099526 ) ) ; -#11244 = DIRECTION ( 'NONE', ( -0.1305262051639064502, 0.9658997602660150950, 0.2236080563923502629 ) ) ; -#11245 = DIRECTION ( 'NONE', ( -0.0005884949961219008464, 0.2249510543439048049, -0.9743698870671267942 ) ) ; -#11247 = ORIENTED_EDGE ( 'NONE', *, *, #12921, .T. ) ; -#11246 = DIRECTION ( 'NONE', ( -0.0002393071182782277790, -0.2252352986010052460, 0.9743043687658488050 ) ) ; -#11248 = VERTEX_POINT ( 'NONE', #1045 ) ; -#11249 = VERTEX_POINT ( 'NONE', #25817 ) ; -#11250 = ORIENTED_EDGE ( 'NONE', *, *, #19324, .F. ) ; -#11251 = CARTESIAN_POINT ( 'NONE', ( -23.36089625005118364, 177.5048766144409171, 100.8897441404802748 ) ) ; -#11252 = CARTESIAN_POINT ( 'NONE', ( -22.49999922076898784, 174.5126133868687930, 99.95592377110770599 ) ) ; -#11253 = EDGE_CURVE ( 'NONE', #38430, #40304, #27543, .T. ) ; -#11254 = ORIENTED_EDGE ( 'NONE', *, *, #2901, .F. ) ; -#11255 = EDGE_CURVE ( 'NONE', #11332, #456, #10770, .T. ) ; -#11256 = VERTEX_POINT ( 'NONE', #13533 ) ; -#11257 = CARTESIAN_POINT ( 'NONE', ( -15.50165717152687073, 187.4006599591204747, 102.9271374898027460 ) ) ; -#11258 = CARTESIAN_POINT ( 'NONE', ( -39.00037151387275713, 161.9658780281123143, 193.3805663919430344 ) ) ; -#11259 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 166.8945455544008780, 183.3579980745095952 ) ) ; -#11260 = CARTESIAN_POINT ( 'NONE', ( -18.98875009441257333, 125.3860450160050277, 176.2394239049030773 ) ) ; -#11261 = VERTEX_POINT ( 'NONE', #39265 ) ; -#11262 = LINE ( 'NONE', #33329, #16033 ) ; -#11263 = VERTEX_POINT ( 'NONE', #2073 ) ; -#11264 = CARTESIAN_POINT ( 'NONE', ( -15.99974174651862313, 174.5231975350379514, 99.95452847233616467 ) ) ; -#11265 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927729918594, -0.0005734119022086387601 ) ) ; -#11266 = CONICAL_SURFACE ( 'NONE', #33462, 2.249999999906822978, 0.7853981633778703841 ) ; -#11267 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971522936 ) ) ; -#11268 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455649311516, -31.54510897440487938, 136.4474729010643159 ) ) ; -#11269 = VERTEX_POINT ( 'NONE', #29677 ) ; -#11270 = CARTESIAN_POINT ( 'NONE', ( -1.678434217228109926, 188.9071424656620195, 103.2652159385340127 ) ) ; -#11271 = CARTESIAN_POINT ( 'NONE', ( 0.9780674619574000195, 188.9146087942000349, 103.5382103106999949 ) ) ; -#11272 = FACE_OUTER_BOUND ( 'NONE', #17085, .T. ) ; -#11273 = CARTESIAN_POINT ( 'NONE', ( -26.69629712807436661, 110.6131156702000027, 90.28390873375987269 ) ) ; -#11274 = ORIENTED_EDGE ( 'NONE', *, *, #2449, .T. ) ; -#11275 = CARTESIAN_POINT ( 'NONE', ( -20.16704315820402726, 118.1226467942143046, 87.44728621956237191 ) ) ; -#11276 = ORIENTED_EDGE ( 'NONE', *, *, #9742, .F. ) ; -#11277 = ORIENTED_EDGE ( 'NONE', *, *, #21973, .T. ) ; -#11278 = EDGE_CURVE ( 'NONE', #7563, #8188, #7782, .T. ) ; -#11279 = ORIENTED_EDGE ( 'NONE', *, *, #807, .T. ) ; -#11280 = CARTESIAN_POINT ( 'NONE', ( -38.59197811685999824, 118.5863865315999988, 89.70884965135999778 ) ) ; -#11281 = ORIENTED_EDGE ( 'NONE', *, *, #39440, .F. ) ; -#11282 = LINE ( 'NONE', #23154, #10824 ) ; -#11283 = CARTESIAN_POINT ( 'NONE', ( -15.99999440082457447, 126.8010213445309660, 88.93691041956509480 ) ) ; -#11284 = ORIENTED_EDGE ( 'NONE', *, *, #26487, .F. ) ; -#11285 = DIRECTION ( 'NONE', ( 0.0006039748319377988848, 1.383702340315400350E-14, 0.9999998176071845934 ) ) ; -#11286 = AXIS2_PLACEMENT_3D ( 'NONE', #31829, #37951, #28948 ) ; -#11287 = VERTEX_POINT ( 'NONE', #27031 ) ; -#11288 = EDGE_CURVE ( 'NONE', #25855, #4296, #1053, .T. ) ; -#11289 = CARTESIAN_POINT ( 'NONE', ( 26.24119167140629827, 121.6923229128020125, 90.81265462304880032 ) ) ; -#11290 = LINE ( 'NONE', #1474, #4516 ) ; -#11291 = AXIS2_PLACEMENT_3D ( 'NONE', #20749, #33205, #8500 ) ; -#11293 = CARTESIAN_POINT ( 'NONE', ( -9.336298587753999456, 176.9278851743999894, 103.3279195673000004 ) ) ; -#11292 = FACE_OUTER_BOUND ( 'NONE', #5825, .T. ) ; -#11294 = ORIENTED_EDGE ( 'NONE', *, *, #14176, .T. ) ; -#11295 = EDGE_CURVE ( 'NONE', #29062, #11382, #32342, .T. ) ; -#11296 = AXIS2_PLACEMENT_3D ( 'NONE', #29612, #11404, #1593 ) ; -#11297 = EDGE_LOOP ( 'NONE', ( #26034, #15828, #14425, #4675 ) ) ; -#11298 = ADVANCED_FACE ( 'NONE', ( #4308 ), #29276, .F. ) ; -#11299 = EDGE_CURVE ( 'NONE', #11987, #34762, #32279, .T. ) ; -#11300 = ORIENTED_EDGE ( 'NONE', *, *, #17296, .T. ) ; -#11301 = EDGE_CURVE ( 'NONE', #39888, #25148, #5937, .T. ) ; -#11302 = CARTESIAN_POINT ( 'NONE', ( -0.02845919973435177830, 93.66652340833722690, 291.5585611238757906 ) ) ; -#11303 = EDGE_CURVE ( 'NONE', #38457, #22508, #15683, .T. ) ; -#11304 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20453, #14547, #39061, #11069 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11305 = DIRECTION ( 'NONE', ( 0.7933532411131101192, 0.5932638852154232811, 0.1364866195435442964 ) ) ; -#11306 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561517 ) ) ; -#11307 = ORIENTED_EDGE ( 'NONE', *, *, #39768, .T. ) ; -#11308 = ORIENTED_EDGE ( 'NONE', *, *, #7780, .T. ) ; -#11309 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825900558579956, 0.0005734119028333956253 ) ) ; -#11310 = CARTESIAN_POINT ( 'NONE', ( 25.99848225943999935, 121.1300010189000034, 87.60220639217000382 ) ) ; -#11311 = ORIENTED_EDGE ( 'NONE', *, *, #5807, .F. ) ; -#11312 = CARTESIAN_POINT ( 'NONE', ( 5.704476631508000217, 114.0103269029000188, 152.4718672074000381 ) ) ; -#11313 = CIRCLE ( 'NONE', #32219, 2.499999999838638409 ) ; -#11314 = VECTOR ( 'NONE', #38050, 1000.000000000000114 ) ; -#11315 = CARTESIAN_POINT ( 'NONE', ( 3.075434283316646145, 190.8748117897712291, 106.8097967079540496 ) ) ; -#11316 = EDGE_LOOP ( 'NONE', ( #2607, #33822, #39822, #6698 ) ) ; -#11317 = CARTESIAN_POINT ( 'NONE', ( -20.51952305719562020, 208.4669380606572986, 73.74576352674176860 ) ) ; -#11318 = CARTESIAN_POINT ( 'NONE', ( 44.87593640572824683, 182.0270868175781516, 126.4518070426717884 ) ) ; -#11319 = CARTESIAN_POINT ( 'NONE', ( 13.53014302533999924, 174.3879284816999871, 152.4718672074000381 ) ) ; -#11320 = CARTESIAN_POINT ( 'NONE', ( 32.54317059607360818, 141.6784348688667308, 281.4642677191529856 ) ) ; -#11321 = ORIENTED_EDGE ( 'NONE', *, *, #20187, .T. ) ; -#11322 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#11323 = CARTESIAN_POINT ( 'NONE', ( 30.05084667745524385, 127.2908262436609164, 89.53532598631991846 ) ) ; -#11324 = ORIENTED_EDGE ( 'NONE', *, *, #12362, .F. ) ; -#11325 = ADVANCED_FACE ( 'NONE', ( #21009 ), #19098, .T. ) ; -#11326 = PLANE ( 'NONE', #35819 ) ; -#11328 = CARTESIAN_POINT ( 'NONE', ( -45.70040756943009086, 187.3695729804526309, 106.0171126674183739 ) ) ; -#11327 = CARTESIAN_POINT ( 'NONE', ( 14.02952888319053848, 135.5741572108938726, 90.94420826922019785 ) ) ; -#11329 = ORIENTED_EDGE ( 'NONE', *, *, #22024, .F. ) ; -#11331 = VERTEX_POINT ( 'NONE', #20383 ) ; -#11330 = EDGE_CURVE ( 'NONE', #30360, #39055, #17101, .T. ) ; -#11332 = VERTEX_POINT ( 'NONE', #17714 ) ; -#11333 = CARTESIAN_POINT ( 'NONE', ( 6.035675884398634672, 174.7938253141263090, 102.5693725772094780 ) ) ; -#11334 = CARTESIAN_POINT ( 'NONE', ( -19.99984748064912665, 127.7403057018771904, 89.15611954941233819 ) ) ; -#11335 = CARTESIAN_POINT ( 'NONE', ( 30.05202364328564713, 126.8409241029907832, 91.48406572326082653 ) ) ; -#11337 = ORIENTED_EDGE ( 'NONE', *, *, #32170, .T. ) ; -#11336 = CIRCLE ( 'NONE', #5474, 2.499999999925774041 ) ; -#11338 = EDGE_LOOP ( 'NONE', ( #35172, #22057, #10923, #9224 ) ) ; -#11339 = CARTESIAN_POINT ( 'NONE', ( -14.55129769642598703, 176.2445762652153007, 103.4298910492225616 ) ) ; -#11340 = ORIENTED_EDGE ( 'NONE', *, *, #19761, .F. ) ; -#11341 = ORIENTED_EDGE ( 'NONE', *, *, #30906, .F. ) ; -#11342 = ORIENTED_EDGE ( 'NONE', *, *, #21841, .T. ) ; -#11343 = EDGE_CURVE ( 'NONE', #11781, #32839, #31516, .T. ) ; -#11344 = PLANE ( 'NONE', #35418 ) ; -#11345 = CARTESIAN_POINT ( 'NONE', ( 3.044143313360999858, 209.0096362941999928, 73.10508458982999969 ) ) ; -#11346 = ORIENTED_EDGE ( 'NONE', *, *, #17823, .T. ) ; -#11347 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #3635, #16120 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11348 = ORIENTED_EDGE ( 'NONE', *, *, #14397, .F. ) ; -#11349 = CARTESIAN_POINT ( 'NONE', ( 28.64561701362920942, 225.5077044868850180, 73.54120293868254521 ) ) ; -#11350 = CARTESIAN_POINT ( 'NONE', ( 30.05352354161590966, 104.1131156705860690, 87.24963271661329145 ) ) ; -#11351 = CARTESIAN_POINT ( 'NONE', ( -35.85345603705000173, 191.4686808538999969, 103.7494084754000028 ) ) ; -#11352 = FACE_OUTER_BOUND ( 'NONE', #2012, .T. ) ; -#11353 = VERTEX_POINT ( 'NONE', #5249 ) ; -#11354 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; -#11355 = CARTESIAN_POINT ( 'NONE', ( -35.94720140322999669, 113.8881156701999942, 88.78949577449999708 ) ) ; -#11356 = ORIENTED_EDGE ( 'NONE', *, *, #9608, .T. ) ; -#11357 = DIRECTION ( 'NONE', ( -0.0005884949961658158049, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#11358 = CARTESIAN_POINT ( 'NONE', ( -3.668404232153524180, 126.2395570190490162, 91.36559546079023164 ) ) ; -#11359 = DIRECTION ( 'NONE', ( -0.0005884949961241434102, 0.2249510543439057764, -0.9743698870671265722 ) ) ; -#11360 = ORIENTED_EDGE ( 'NONE', *, *, #4472, .T. ) ; -#11361 = CARTESIAN_POINT ( 'NONE', ( 0.7125860357380395804, 188.6156347743453523, 103.1978435822155546 ) ) ; -#11362 = DIRECTION ( 'NONE', ( -0.0001408404360371445828, 0.2249510911114003808, -0.9743700461178812500 ) ) ; -#11363 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; -#11364 = FACE_OUTER_BOUND ( 'NONE', #27178, .T. ) ; -#11365 = ORIENTED_EDGE ( 'NONE', *, *, #23172, .F. ) ; -#11366 = CARTESIAN_POINT ( 'NONE', ( -43.19244318869828447, 171.2650756620451773, 189.4798566108720479 ) ) ; -#11367 = CARTESIAN_POINT ( 'NONE', ( 2.562970451984335707, 190.9961858171923552, 104.2592840632188711 ) ) ; -#11368 = VECTOR ( 'NONE', #31909, 1000.000000000000114 ) ; -#11369 = AXIS2_PLACEMENT_3D ( 'NONE', #29620, #32871, #33275 ) ; -#11370 = CARTESIAN_POINT ( 'NONE', ( 40.79509051822999766, 219.0860688542000219, 73.28386491556000237 ) ) ; -#11371 = ORIENTED_EDGE ( 'NONE', *, *, #14397, .T. ) ; -#11372 = CARTESIAN_POINT ( 'NONE', ( 37.65039792813953312, 188.7571058070083154, 106.2871081217155904 ) ) ; -#11373 = ORIENTED_EDGE ( 'NONE', *, *, #26407, .T. ) ; -#11374 = VERTEX_POINT ( 'NONE', #39196 ) ; -#11375 = ORIENTED_EDGE ( 'NONE', *, *, #18793, .T. ) ; -#11376 = AXIS2_PLACEMENT_3D ( 'NONE', #6497, #15710, #15320 ) ; -#11377 = CARTESIAN_POINT ( 'NONE', ( 3.166377416628577190, 128.5876387387983186, 89.33781556475464924 ) ) ; -#11378 = LINE ( 'NONE', #20367, #21893 ) ; -#11379 = CARTESIAN_POINT ( 'NONE', ( -25.52046747694037521, 211.4175358512202649, 73.57353344520571170 ) ) ; -#11380 = CARTESIAN_POINT ( 'NONE', ( 17.08428676098631271, 152.4729553475051773, 182.2640658063840249 ) ) ; -#11381 = CARTESIAN_POINT ( 'NONE', ( -41.62559112316809262, 119.2042779649247137, 92.33005894222831955 ) ) ; -#11382 = VERTEX_POINT ( 'NONE', #2205 ) ; -#11383 = EDGE_CURVE ( 'NONE', #26640, #28773, #23670, .T. ) ; -#11384 = ADVANCED_FACE ( 'NONE', ( #39794 ), #17804, .T. ) ; -#11385 = EDGE_CURVE ( 'NONE', #5211, #7165, #541, .T. ) ; -#11386 = DIRECTION ( 'NONE', ( 0.0005884949961235587000, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#11387 = LINE ( 'NONE', #27369, #22482 ) ; -#11388 = CARTESIAN_POINT ( 'NONE', ( -20.33177681178267093, 119.7903260068696767, 90.05777432457695397 ) ) ; -#11389 = ADVANCED_FACE ( 'NONE', ( #31625 ), #13253, .T. ) ; -#11390 = DIRECTION ( 'NONE', ( 0.0005884949961193586092, -0.2249510543439039167, 0.9743698870671270162 ) ) ; -#11391 = DIRECTION ( 'NONE', ( -0.6087611427424954869, -0.7731004630501228103, -0.1781166615410720300 ) ) ; -#11392 = CARTESIAN_POINT ( 'NONE', ( -46.09662356910047265, 125.3295157413326422, 91.69427356735783974 ) ) ; -#11393 = DIRECTION ( 'NONE', ( 1.142687604679795709E-08, -0.9743700583596238696, -0.2249510821762432111 ) ) ; -#11394 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 1.850371707708593577E-15, 0.0006039748319387284797 ) ) ; -#11395 = ORIENTED_EDGE ( 'NONE', *, *, #695, .T. ) ; -#11396 = AXIS2_PLACEMENT_3D ( 'NONE', #21259, #11855, #39641 ) ; -#11398 = EDGE_CURVE ( 'NONE', #19682, #16029, #6690, .T. ) ; -#11397 = CARTESIAN_POINT ( 'NONE', ( 29.05533563819793486, 110.6131156702000027, 90.25023614447037801 ) ) ; -#11399 = CARTESIAN_POINT ( 'NONE', ( 3.736461764213575343, 144.1696738225713830, 93.14231161134939896 ) ) ; -#11400 = CARTESIAN_POINT ( 'NONE', ( -31.26880281748162105, 135.2089707299881525, 90.88725736883857564 ) ) ; -#11401 = CIRCLE ( 'NONE', #14690, 2.000000034091465650 ) ; -#11402 = ORIENTED_EDGE ( 'NONE', *, *, #5100, .F. ) ; -#11403 = LINE ( 'NONE', #8555, #2978 ) ; -#11404 = DIRECTION ( 'NONE', ( 0.0005884949961239134509, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#11405 = VERTEX_POINT ( 'NONE', #6452 ) ; -#11406 = EDGE_CURVE ( 'NONE', #29469, #34643, #8679, .T. ) ; -#11407 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#11408 = CARTESIAN_POINT ( 'NONE', ( -4.036264727110095762, 167.9338357148023704, 100.9917020970900410 ) ) ; -#11409 = VERTEX_POINT ( 'NONE', #15859 ) ; -#11410 = CARTESIAN_POINT ( 'NONE', ( 36.27518175044473026, 191.8909916473900807, 106.3924565537250686 ) ) ; -#11411 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#11412 = CARTESIAN_POINT ( 'NONE', ( -35.94660609010693264, 113.3342141080062220, 89.77519709294587358 ) ) ; -#11413 = CARTESIAN_POINT ( 'NONE', ( 3.064236136099508290, 190.8512031035150471, 106.7914583158460573 ) ) ; -#11414 = CARTESIAN_POINT ( 'NONE', ( 2.546554931846081615, 207.4083916547160982, 77.08013917124165459 ) ) ; -#11415 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31351, #462, #28878, #18849, #6587, #3724, #13892 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 4 ), - ( 0.0001323339547882564549, 0.0008556500706447302002, 0.002105438866673375268 ), - .UNSPECIFIED. ) ; -#11416 = LINE ( 'NONE', #39412, #14509 ) ; -#11417 = ORIENTED_EDGE ( 'NONE', *, *, #8815, .T. ) ; -#11418 = CARTESIAN_POINT ( 'NONE', ( 39.82218138461000478, 120.0420031177999931, 87.73456314343999907 ) ) ; -#11419 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684999240, 226.4002260771032695, 75.57961659100007523 ) ) ; -#11420 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391903498 ) ) ; -#11421 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20415, #14299, #26989, #11231 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11422 = ORIENTED_EDGE ( 'NONE', *, *, #6902, .T. ) ; -#11423 = CARTESIAN_POINT ( 'NONE', ( -59.73339157696374713, 30.14292508904275891, 149.3998115772221240 ) ) ; -#11424 = ORIENTED_EDGE ( 'NONE', *, *, #35132, .T. ) ; -#11425 = DIRECTION ( 'NONE', ( 0.0005884952295944861867, -0.2249510549294950756, 0.9743698869317913847 ) ) ; -#11426 = CARTESIAN_POINT ( 'NONE', ( -20.24985248663000093, 124.0104318696999997, 88.55179139119999832 ) ) ; -#11427 = VECTOR ( 'NONE', #19901, 1000.000000000000114 ) ; -#11428 = CARTESIAN_POINT ( 'NONE', ( 22.33189175409000171, 176.6322471953999980, 103.4971154297000027 ) ) ; -#11429 = DIRECTION ( 'NONE', ( 0.5605692862036780744, -0.2602880237709899736, -0.7861375325262695002 ) ) ; -#11430 = CARTESIAN_POINT ( 'NONE', ( -25.67969535978464179, 211.0902257898999892, 73.40427696411113345 ) ) ; -#11431 = CIRCLE ( 'NONE', #21250, 2.000000000000011546 ) ; -#11432 = CARTESIAN_POINT ( 'NONE', ( -25.94168657766944719, 211.8745996369106592, 73.07417221104321925 ) ) ; -#11433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #6550, #25193 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11434 = EDGE_CURVE ( 'NONE', #30774, #28807, #37127, .T. ) ; -#11435 = VECTOR ( 'NONE', #7406, 1000.000000000000114 ) ; -#11436 = ADVANCED_FACE ( 'NONE', ( #16261 ), #23214, .F. ) ; -#11437 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971579280 ) ) ; -#11438 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #7778, #39667, #33332, #4918 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.891461175462934463, 6.462631112830672819 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8046497850432340337, 0.8046497850432340337, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#11439 = CARTESIAN_POINT ( 'NONE', ( 18.99767128196905830, 125.6058446513852118, 175.3475295528536151 ) ) ; -#11440 = CARTESIAN_POINT ( 'NONE', ( -30.07171558222000129, 177.1876876990598930, 101.0912387270526125 ) ) ; -#11441 = CARTESIAN_POINT ( 'NONE', ( 39.10206850925001021, 118.7782697286999962, 89.52650283721999358 ) ) ; -#11442 = ORIENTED_EDGE ( 'NONE', *, *, #13168, .F. ) ; -#11443 = CARTESIAN_POINT ( 'NONE', ( 16.21976467472907757, 122.6436220881636814, 172.0961230653717564 ) ) ; -#11444 = CARTESIAN_POINT ( 'NONE', ( -21.70069621149593075, 129.3400573276139482, 92.26334425727345945 ) ) ; -#11445 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22390, #28519, #10114, #4557, #23578, #32780, #29321, #31988, #7420, #1492, #7221, #3951, #4147, #1707 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999985012, 0.3749999999999977796, 0.4999999999999970024, 0.6249999999999962252, 0.6875000000000301981, 0.7500000000000640599, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11446 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218859315, 3.782205735272607244E-12, 297.5295786860754674 ) ) ; -#11447 = CARTESIAN_POINT ( 'NONE', ( 26.01073959733328067, 191.4239670711786516, 106.8751801458234496 ) ) ; -#11448 = CYLINDRICAL_SURFACE ( 'NONE', #29148, 2.250000000000011102 ) ; -#11449 = VERTEX_POINT ( 'NONE', #36066 ) ; -#11450 = ORIENTED_EDGE ( 'NONE', *, *, #28332, .F. ) ; -#11451 = CARTESIAN_POINT ( 'NONE', ( -39.74908053984227507, 182.4717680925825789, 106.9353792437991473 ) ) ; -#11452 = VERTEX_POINT ( 'NONE', #29755 ) ; -#11453 = DIRECTION ( 'NONE', ( -0.9999998142111129473, -1.291838595167527226E-06, 0.0006095703986303101099 ) ) ; -#11454 = CARTESIAN_POINT ( 'NONE', ( -43.94721011010098266, 112.7011882844193309, 88.77749572683383406 ) ) ; -#11455 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26998, #32505, #23713, #4480 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 1.418495674889627305E-09, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11456 = DIRECTION ( 'NONE', ( 0.0005884949961232422214, -0.2249510543439050547, 0.9743698870671266832 ) ) ; -#11457 = VERTEX_POINT ( 'NONE', #7452 ) ; -#11458 = VECTOR ( 'NONE', #13347, 1000.000000000000114 ) ; -#11459 = CARTESIAN_POINT ( 'NONE', ( 40.71170686885982093, 217.7719115883058123, 73.20058192865329261 ) ) ; -#11460 = ADVANCED_FACE ( 'NONE', ( #19916 ), #20122, .F. ) ; -#11461 = CARTESIAN_POINT ( 'NONE', ( -13.49672688080367955, 187.4156453043676436, 105.6637477070206330 ) ) ; -#11462 = AXIS2_PLACEMENT_3D ( 'NONE', #5349, #27054, #39691 ) ; -#11463 = VECTOR ( 'NONE', #18955, 1000.000000000000114 ) ; -#11464 = CARTESIAN_POINT ( 'NONE', ( -36.09575936301000354, 112.8288696677000047, 87.93843057770999394 ) ) ; -#11465 = ORIENTED_EDGE ( 'NONE', *, *, #30320, .F. ) ; -#11466 = CONICAL_SURFACE ( 'NONE', #34300, 59.40509898898601904, 0.7853981633972927368 ) ; -#11467 = CARTESIAN_POINT ( 'NONE', ( -37.15110912804633614, 71.94901892143192867, 323.0119659673088677 ) ) ; -#11468 = ORIENTED_EDGE ( 'NONE', *, *, #27256, .F. ) ; -#11469 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; -#11470 = CARTESIAN_POINT ( 'NONE', ( 4.035676230724123847, 143.6517845921996184, 95.38087260549148994 ) ) ; -#11471 = VECTOR ( 'NONE', #24766, 1000.000000000000227 ) ; -#11472 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 1.018502060646766849E-15, 0.0006039748319386956284 ) ) ; -#11473 = CARTESIAN_POINT ( 'NONE', ( -14.55294119842380063, 130.1498083917327904, 89.70916153464222020 ) ) ; -#11474 = VERTEX_POINT ( 'NONE', #4589 ) ; -#11475 = CARTESIAN_POINT ( 'NONE', ( -18.59008601221150414, 148.0291187291159076, 184.1143154653856868 ) ) ; -#11476 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; -#11477 = CARTESIAN_POINT ( 'NONE', ( -35.48525329021664731, 192.2684899157669349, 106.9345235387465749 ) ) ; -#11478 = ORIENTED_EDGE ( 'NONE', *, *, #12774, .F. ) ; -#11479 = DIRECTION ( 'NONE', ( -0.0005884949961224831714, 0.2249510543439058596, -0.9743698870671263501 ) ) ; -#11480 = VERTEX_POINT ( 'NONE', #17051 ) ; -#11481 = ORIENTED_EDGE ( 'NONE', *, *, #36419, .F. ) ; -#11482 = CIRCLE ( 'NONE', #38904, 48.00000000000465405 ) ; -#11483 = ORIENTED_EDGE ( 'NONE', *, *, #3890, .F. ) ; -#11484 = ADVANCED_FACE ( 'NONE', ( #14010 ), #26693, .T. ) ; -#11485 = CARTESIAN_POINT ( 'NONE', ( -26.12106630525807915, 190.7095951053924239, 103.6974793579260705 ) ) ; -#11487 = EDGE_CURVE ( 'NONE', #6270, #21098, #1946, .T. ) ; -#11486 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23862, #39582, #18905, #18099 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11488 = AXIS2_PLACEMENT_3D ( 'NONE', #10040, #22920, #16758 ) ; -#11489 = CARTESIAN_POINT ( 'NONE', ( 20.99160458755498482, 212.6262139143010188, 73.54599130854555256 ) ) ; -#11490 = CARTESIAN_POINT ( 'NONE', ( 39.36767498017007227, 179.7113605310591140, 119.0972000649790061 ) ) ; -#11491 = CARTESIAN_POINT ( 'NONE', ( -37.51239921474475381, 190.9875310483616033, 106.3313789827213469 ) ) ; -#11492 = EDGE_LOOP ( 'NONE', ( #26455, #8635, #37734, #39959 ) ) ; -#11493 = CARTESIAN_POINT ( 'NONE', ( -21.27838756171884427, 135.9818880619076822, 91.05966546721936083 ) ) ; -#11494 = CARTESIAN_POINT ( 'NONE', ( -20.49921872406353529, 118.1134456025284152, 89.78002774633898753 ) ) ; -#11495 = ORIENTED_EDGE ( 'NONE', *, *, #14675, .T. ) ; -#11496 = CIRCLE ( 'NONE', #28488, 54.50273826250054299 ) ; -#11497 = CARTESIAN_POINT ( 'NONE', ( 28.22659100348150218, 124.4203685683400096, 91.44127834639000696 ) ) ; -#11498 = CARTESIAN_POINT ( 'NONE', ( -26.00939886961985792, 210.1698433795000085, 76.07526738668336463 ) ) ; -#11499 = VECTOR ( 'NONE', #15586, 1000.000000000000227 ) ; -#11501 = CYLINDRICAL_SURFACE ( 'NONE', #26647, 2.000000000000014655 ) ; -#11500 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#11502 = ORIENTED_EDGE ( 'NONE', *, *, #16626, .T. ) ; -#11503 = EDGE_LOOP ( 'NONE', ( #23326, #23724, #7518 ) ) ; -#11504 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #5709, #21467 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11505 = VERTEX_POINT ( 'NONE', #5609 ) ; -#11506 = CARTESIAN_POINT ( 'NONE', ( -35.87604402749855126, 115.6689223804922477, 87.28945252364509599 ) ) ; -#11507 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566790 ) ) ; -#11508 = DIRECTION ( 'NONE', ( 0.1203539036806679369, -1.261872400103888735E-14, -0.9927310501182202707 ) ) ; -#11509 = CARTESIAN_POINT ( 'NONE', ( 36.32277147154000829, 191.7121955142999923, 104.1910060713999968 ) ) ; -#11510 = ORIENTED_EDGE ( 'NONE', *, *, #12587, .F. ) ; -#11511 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #31365, #11753 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11512 = ORIENTED_EDGE ( 'NONE', *, *, #39303, .F. ) ; -#11513 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #11451, #10702, #21271, #8183 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( -4.440892098500626162E-15, 0.1808055686694189090 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9972776337013501413, 0.9972776337013501413, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#11514 = DIRECTION ( 'NONE', ( 0.0005884949961229525225, -0.2249510543439062205, 0.9743698870671264611 ) ) ; -#11515 = LINE ( 'NONE', #26662, #4399 ) ; -#11516 = CIRCLE ( 'NONE', #16720, 2.499999999970894393 ) ; -#11517 = CARTESIAN_POINT ( 'NONE', ( -25.50006284340070906, 118.1130153187805689, 89.78316558933853742 ) ) ; -#11518 = CONICAL_SURFACE ( 'NONE', #21311, 3.003184325552035627, 0.7853589132226472813 ) ; -#11519 = CARTESIAN_POINT ( 'NONE', ( 15.91451890771963384, 186.5505280237283614, 102.7118944487342702 ) ) ; -#11520 = ORIENTED_EDGE ( 'NONE', *, *, #26027, .T. ) ; -#11521 = VERTEX_POINT ( 'NONE', #39951 ) ; -#11522 = CARTESIAN_POINT ( 'NONE', ( -36.31234050319358886, 190.8460812281299752, 106.8195530359479903 ) ) ; -#11523 = VECTOR ( 'NONE', #19848, 1000.000000000000000 ) ; -#11524 = ADVANCED_FACE ( 'NONE', ( #30356 ), #195, .F. ) ; -#11525 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14274, #14069, #8132, #38400, #22877, #7309, #16901, #19974, #35305, #4650 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999688582, 0.3749999999999033551, 0.4374999999998851474, 0.4999999999998669953, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11526 = CIRCLE ( 'NONE', #9544, 4.999999999999990230 ) ; -#11527 = CARTESIAN_POINT ( 'NONE', ( 3.080879273494560255, 190.8603769821775131, 106.8113866482030403 ) ) ; -#11528 = ORIENTED_EDGE ( 'NONE', *, *, #39016, .F. ) ; -#11529 = CARTESIAN_POINT ( 'NONE', ( 44.05441677404904510, 112.7011882844093122, 88.72434494936726423 ) ) ; -#11530 = EDGE_CURVE ( 'NONE', #36212, #27113, #11196, .T. ) ; -#11531 = DIRECTION ( 'NONE', ( -0.0005884949961250770167, 0.2249510543439080523, -0.9743698870671260170 ) ) ; -#11532 = CARTESIAN_POINT ( 'NONE', ( -35.93819496018398496, 196.1181868593052400, 103.7014435179598024 ) ) ; -#11533 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#11534 = ORIENTED_EDGE ( 'NONE', *, *, #39303, .T. ) ; -#11535 = EDGE_CURVE ( 'NONE', #1525, #12760, #24363, .T. ) ; -#11536 = EDGE_CURVE ( 'NONE', #25074, #1952, #9092, .T. ) ; -#11537 = DIRECTION ( 'NONE', ( 0.7075337282838612962, -1.167224528853440884E-08, 0.7066795761451855062 ) ) ; -#11538 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; -#11539 = EDGE_CURVE ( 'NONE', #20406, #31599, #19508, .T. ) ; -#11540 = ORIENTED_EDGE ( 'NONE', *, *, #25031, .F. ) ; -#11541 = CONICAL_SURFACE ( 'NONE', #18031, 2.503203150234936114, 0.7853981633958105890 ) ; -#11542 = CARTESIAN_POINT ( 'NONE', ( 31.99328622544151557, 77.52049695843601285, 291.3934239983018415 ) ) ; -#11543 = CIRCLE ( 'NONE', #12865, 2.499999999978613996 ) ; -#11544 = VECTOR ( 'NONE', #24986, 1000.000000000000000 ) ; -#11546 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927781994451, 0.0005734119022073636300 ) ) ; -#11545 = DIRECTION ( 'NONE', ( 0.7856637144487861324, -0.6186538028643616682, 0.000000000000000000 ) ) ; -#11547 = ORIENTED_EDGE ( 'NONE', *, *, #17207, .F. ) ; -#11548 = VERTEX_POINT ( 'NONE', #34412 ) ; -#11549 = DIRECTION ( 'NONE', ( 5.065392549852286813E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#11550 = CARTESIAN_POINT ( 'NONE', ( 38.73395728598254095, 118.6163391431395269, 89.66332909972722121 ) ) ; -#11551 = EDGE_LOOP ( 'NONE', ( #21286, #33112, #2500, #34214, #6792, #17477, #22705, #17608 ) ) ; -#11552 = CARTESIAN_POINT ( 'NONE', ( 2.594002776560000001, 209.5556663168000000, 75.67900503539999590 ) ) ; -#11553 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 77.27946979429634666, 315.0857197240631535 ) ) ; -#11554 = CARTESIAN_POINT ( 'NONE', ( 12.64143545761593401, 177.6650210183138370, 100.7720088105692611 ) ) ; -#11555 = ORIENTED_EDGE ( 'NONE', *, *, #1356, .T. ) ; -#11556 = VERTEX_POINT ( 'NONE', #22773 ) ; -#11557 = CARTESIAN_POINT ( 'NONE', ( -42.80963178801611235, 120.9007511611746395, 91.83847750760833151 ) ) ; -#11558 = ORIENTED_EDGE ( 'NONE', *, *, #3629, .F. ) ; -#11559 = ORIENTED_EDGE ( 'NONE', *, *, #19900, .F. ) ; -#11560 = DIRECTION ( 'NONE', ( 0.0004161288024567914292, -0.8480480897914314253, 0.5299191110329237731 ) ) ; -#11561 = CARTESIAN_POINT ( 'NONE', ( -33.45586840016203922, 218.5902260770999987, 73.07871058857431024 ) ) ; -#11562 = EDGE_CURVE ( 'NONE', #5503, #40259, #16015, .T. ) ; -#11563 = DIRECTION ( 'NONE', ( -0.0005884949961259294164, 0.2255194585872565272, -0.9742384859325513569 ) ) ; -#11564 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.271205595054999941E-14, -1.000000000000000000 ) ) ; -#11565 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250096516, 130.6631156595383914, 90.34290178553547435 ) ) ; -#11566 = ORIENTED_EDGE ( 'NONE', *, *, #16259, .T. ) ; -#11567 = ORIENTED_EDGE ( 'NONE', *, *, #15057, .T. ) ; -#11568 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#11569 = LINE ( 'NONE', #24260, #3479 ) ; -#11570 = CARTESIAN_POINT ( 'NONE', ( -35.42347339415000107, 191.8427034982000237, 103.8024170491000007 ) ) ; -#11571 = CARTESIAN_POINT ( 'NONE', ( 36.59227142547000255, 191.6001556585999879, 104.2198836891000013 ) ) ; -#11572 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23593, #36045, #37076, #37273 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11573 = ORIENTED_EDGE ( 'NONE', *, *, #21659, .T. ) ; -#11574 = CARTESIAN_POINT ( 'NONE', ( -25.66789927443999986, 120.7343807225000063, 87.88418875662000573 ) ) ; -#11575 = VERTEX_POINT ( 'NONE', #28115 ) ; -#11576 = ORIENTED_EDGE ( 'NONE', *, *, #21131, .T. ) ; -#11577 = CARTESIAN_POINT ( 'NONE', ( -21.44517133422852240, 176.2436636369649534, 103.4338440792942890 ) ) ; -#11578 = CARTESIAN_POINT ( 'NONE', ( -40.30153468720526178, 187.7974083947837585, 108.1652340796715492 ) ) ; -#11579 = ORIENTED_EDGE ( 'NONE', *, *, #28570, .T. ) ; -#11580 = CARTESIAN_POINT ( 'NONE', ( -22.49852798326304537, 127.1804730653442732, 91.59419604361356448 ) ) ; -#11581 = CARTESIAN_POINT ( 'NONE', ( -20.33320694052968847, 160.6589237444172511, 97.09841172752761906 ) ) ; -#11582 = LINE ( 'NONE', #11989, #38573 ) ; -#11583 = EDGE_LOOP ( 'NONE', ( #24434, #39500, #3486, #39572 ) ) ; -#11584 = CARTESIAN_POINT ( 'NONE', ( -19.33628163003497136, 125.2773345192583463, 177.1639040494593473 ) ) ; -#11585 = EDGE_CURVE ( 'NONE', #39651, #12644, #17127, .T. ) ; -#11586 = CARTESIAN_POINT ( 'NONE', ( 1.746097794442228235, 189.3876538975366088, 103.7956058557226413 ) ) ; -#11587 = CARTESIAN_POINT ( 'NONE', ( 45.26991834669612302, 123.8840750961899744, 93.35648333539963062 ) ) ; -#11588 = ADVANCED_FACE ( 'NONE', ( #6407 ), #37903, .F. ) ; -#11589 = ORIENTED_EDGE ( 'NONE', *, *, #30096, .T. ) ; -#11590 = CARTESIAN_POINT ( 'NONE', ( -13.49823529424839386, 151.2934838775255173, 97.66884040908654185 ) ) ; -#11591 = ORIENTED_EDGE ( 'NONE', *, *, #19629, .T. ) ; -#11592 = DIRECTION ( 'NONE', ( 0.6087614115774880874, -0.7730004600455407937, -0.1785492440296700956 ) ) ; -#11593 = EDGE_CURVE ( 'NONE', #26460, #26211, #25547, .T. ) ; -#11594 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#11595 = CARTESIAN_POINT ( 'NONE', ( 37.90425712323814622, 118.7059984729880284, 87.38624778410084559 ) ) ; -#11596 = ADVANCED_FACE ( 'NONE', ( #16215 ), #26856, .F. ) ; -#11597 = EDGE_CURVE ( 'NONE', #15150, #21705, #39295, .T. ) ; -#11598 = CARTESIAN_POINT ( 'NONE', ( 16.04431205530701732, 152.7224556247752503, 181.6155002255999875 ) ) ; -#11599 = CARTESIAN_POINT ( 'NONE', ( 6.028492984770688068, 134.9588829526484801, 90.86045477491234124 ) ) ; -#11600 = ORIENTED_EDGE ( 'NONE', *, *, #15059, .F. ) ; -#11601 = CARTESIAN_POINT ( 'NONE', ( 23.69156854525416733, 130.3499206859899857, 92.81120348820789445 ) ) ; -#11602 = CARTESIAN_POINT ( 'NONE', ( 15.99999299640773209, 127.4309269374402618, 89.06300497221934620 ) ) ; -#11603 = DIRECTION ( 'NONE', ( -0.9914445057216533241, 0.1269824404756555725, 0.03022005766363166854 ) ) ; -#11604 = CARTESIAN_POINT ( 'NONE', ( -16.04788717431955902, 121.9883658730552156, 174.5026492558828295 ) ) ; -#11605 = CONICAL_SURFACE ( 'NONE', #3732, 6.503080769914698855, 0.7853981634031134140 ) ; -#11606 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 132.9726895863779532, 90.34121396988804520 ) ) ; -#11607 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11858, #36997, #37198, #37588, #5716, #40243, #34494, #24747, #39844, #34308 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000363598, 0.3750000000000597855, 0.4375000000000662803, 0.5000000000000728306, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11608 = CARTESIAN_POINT ( 'NONE', ( 32.26714755882673558, 176.5669744895979250, 100.3971325049669474 ) ) ; -#11609 = CARTESIAN_POINT ( 'NONE', ( 6.065815740701999914, 165.2216646563843199, 152.9217693939943388 ) ) ; -#11610 = CARTESIAN_POINT ( 'NONE', ( 20.36364106976845889, 116.6764208835006258, 90.25548571027178468 ) ) ; -#11611 = AXIS2_PLACEMENT_3D ( 'NONE', #20481, #35804, #27479 ) ; -#11612 = ORIENTED_EDGE ( 'NONE', *, *, #15579, .T. ) ; -#11613 = CARTESIAN_POINT ( 'NONE', ( 3.666638755409086681, 184.0129645450027738, 102.6466012127862371 ) ) ; -#11614 = DIRECTION ( 'NONE', ( -4.655231785096015457E-10, 0.9743700556873108320, 0.2249510937513014008 ) ) ; -#11615 = CARTESIAN_POINT ( 'NONE', ( -32.55028072398723538, 136.9683251281930723, 91.29421039092950707 ) ) ; -#11616 = ORIENTED_EDGE ( 'NONE', *, *, #40087, .F. ) ; -#11617 = CARTESIAN_POINT ( 'NONE', ( 5.665497765363915583, 182.0055596162654012, 102.1015474221518105 ) ) ; -#11618 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1157, #26320, #35469, #19748 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11619 = CARTESIAN_POINT ( 'NONE', ( 36.44436247437651133, 190.8511614233640330, 106.7712946021073606 ) ) ; -#11620 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15474, #132, #25098, #28748, #27969, #6259, #31626, #37543, #9545, #22023, #34455, #15860, #6453, #18922, #25295, #28355, #37737, #9749, #29355, #29756 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000079103, 0.1875000000000118794, 0.2187500000000148492, 0.2343750000000163203, 0.2500000000000178191, 0.5000000000000767164, 0.6250000000001121325, 0.6875000000001232348, 0.7187500000001195710, 0.7343750000001172396, 0.7500000000001149081, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11621 = ORIENTED_EDGE ( 'NONE', *, *, #33490, .T. ) ; -#11622 = CARTESIAN_POINT ( 'NONE', ( -17.26178222639411430, 121.7713432978476220, 175.3684242141576703 ) ) ; -#11623 = DIRECTION ( 'NONE', ( 0.6087614810001747978, -0.7729390313185978689, -0.1788147452385885350 ) ) ; -#11624 = CARTESIAN_POINT ( 'NONE', ( -21.86693707914052354, 143.9814420783045819, 28.36825712350903572 ) ) ; -#11625 = ORIENTED_EDGE ( 'NONE', *, *, #35641, .T. ) ; -#11626 = CARTESIAN_POINT ( 'NONE', ( 35.56500850657381108, 192.5994943120849427, 106.8645618244048165 ) ) ; -#11627 = EDGE_CURVE ( 'NONE', #15600, #22159, #22937, .T. ) ; -#11628 = ADVANCED_FACE ( 'NONE', ( #22972 ), #35400, .F. ) ; -#11629 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921579630, 0.2249510932971582611 ) ) ; -#11630 = ADVANCED_FACE ( 'NONE', ( #38896 ), #32371, .T. ) ; -#11631 = CARTESIAN_POINT ( 'NONE', ( -38.54565956053704667, 119.1564759897554211, 90.30561907418552892 ) ) ; -#11632 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#11633 = DIRECTION ( 'NONE', ( 0.0005884949961202267299, -0.2249510543439067478, 0.9743698870671262391 ) ) ; -#11634 = ORIENTED_EDGE ( 'NONE', *, *, #18862, .F. ) ; -#11635 = ORIENTED_EDGE ( 'NONE', *, *, #6623, .F. ) ; -#11636 = EDGE_CURVE ( 'NONE', #36542, #38645, #4083, .T. ) ; -#11637 = DIRECTION ( 'NONE', ( 0.6087613502019254552, -0.7729389820454567461, -0.1788154035167601463 ) ) ; -#11638 = DIRECTION ( 'NONE', ( -0.5988682214889347044, 0.8008475843072014877, 0.000000000000000000 ) ) ; -#11639 = VECTOR ( 'NONE', #27184, 1000.000000000000227 ) ; -#11640 = DIRECTION ( 'NONE', ( 0.0005884949961178157895, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#11641 = ORIENTED_EDGE ( 'NONE', *, *, #25972, .T. ) ; -#11642 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#11643 = CARTESIAN_POINT ( 'NONE', ( -41.28588602987048262, 120.5676951715817040, 90.59201490058906359 ) ) ; -#11644 = CIRCLE ( 'NONE', #9682, 6.000000000000007994 ) ; -#11645 = CARTESIAN_POINT ( 'NONE', ( 20.50147081773584290, 151.4111479308915023, 97.16231817868397513 ) ) ; -#11646 = CARTESIAN_POINT ( 'NONE', ( -28.52057520163999982, 124.7657109742000046, 91.42876534255999843 ) ) ; -#11647 = EDGE_CURVE ( 'NONE', #31352, #37651, #13884, .T. ) ; -#11648 = PLANE ( 'NONE', #39750 ) ; -#11649 = LINE ( 'NONE', #8990, #28083 ) ; -#11650 = DIRECTION ( 'NONE', ( -0.0005884949961246306507, 0.2249510543439059429, -0.9743698870671264611 ) ) ; -#11651 = EDGE_CURVE ( 'NONE', #13604, #5116, #35416, .T. ) ; -#11652 = COORDINATED_UNIVERSAL_TIME_OFFSET ( 8, 0, .AHEAD. ) ; -#11653 = CARTESIAN_POINT ( 'NONE', ( 26.11275506546840575, 121.8657365086856998, 87.77207143543530776 ) ) ; -#11654 = DIRECTION ( 'NONE', ( -0.0005884949961241158715, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#11655 = CARTESIAN_POINT ( 'NONE', ( -20.49960732757744353, 118.8154816606033393, 87.78015075453545535 ) ) ; -#11656 = CARTESIAN_POINT ( 'NONE', ( -36.63401976618238365, 138.1498686812657866, 288.6643242991708007 ) ) ; -#11657 = CARTESIAN_POINT ( 'NONE', ( -23.00127433124000476, 115.6131156702010401, 87.78148031792994743 ) ) ; -#11658 = ORIENTED_EDGE ( 'NONE', *, *, #37164, .F. ) ; -#11659 = CARTESIAN_POINT ( 'NONE', ( 13.46612284730906950, 158.3062971533392158, 96.19268454968825210 ) ) ; -#11660 = ORIENTED_EDGE ( 'NONE', *, *, #38114, .F. ) ; -#11661 = ORIENTED_EDGE ( 'NONE', *, *, #29619, .F. ) ; -#11662 = LINE ( 'NONE', #8604, #11435 ) ; -#11663 = VERTEX_POINT ( 'NONE', #8448 ) ; -#11664 = CARTESIAN_POINT ( 'NONE', ( 47.95567328239271632, 139.9374889060051146, 291.1737358715798791 ) ) ; -#11665 = VECTOR ( 'NONE', #37970, 999.9999999999998863 ) ; -#11666 = CARTESIAN_POINT ( 'NONE', ( 3.166350703034567449, 184.1264558197564156, 102.1599558388959537 ) ) ; -#11667 = AXIS2_PLACEMENT_3D ( 'NONE', #21774, #34800, #27924 ) ; -#11668 = VERTEX_POINT ( 'NONE', #5562 ) ; -#11669 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#11670 = PLANE ( 'NONE', #16877 ) ; -#11671 = FACE_OUTER_BOUND ( 'NONE', #24350, .T. ) ; -#11672 = ORIENTED_EDGE ( 'NONE', *, *, #15362, .T. ) ; -#11673 = CARTESIAN_POINT ( 'NONE', ( 17.25788849119799195, 152.5371962406647413, 182.4889206688251306 ) ) ; -#11674 = EDGE_CURVE ( 'NONE', #22341, #9096, #25785, .T. ) ; -#11675 = EDGE_CURVE ( 'NONE', #30982, #18267, #35060, .T. ) ; -#11676 = CARTESIAN_POINT ( 'NONE', ( 3.166590646707283963, 186.2330553830380211, 102.6462995303112251 ) ) ; -#11677 = EDGE_CURVE ( 'NONE', #39055, #4945, #27879, .T. ) ; -#11678 = DIRECTION ( 'NONE', ( -0.0006039748319386906410, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#11679 = CARTESIAN_POINT ( 'NONE', ( -12.64043733723593022, 181.1121611747635143, 104.4670379097046862 ) ) ; -#11680 = ORIENTED_EDGE ( 'NONE', *, *, #3082, .F. ) ; -#11681 = EDGE_LOOP ( 'NONE', ( #11865, #28280 ) ) ; -#11682 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#11683 = CARTESIAN_POINT ( 'NONE', ( 0.5972205428943000438, 188.8838611128000196, 103.5283297331999961 ) ) ; -#11684 = EDGE_CURVE ( 'NONE', #30982, #1942, #11944, .T. ) ; -#11685 = ORIENTED_EDGE ( 'NONE', *, *, #21557, .T. ) ; -#11686 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -4.437389905419016117E-16, 0.0006039748319385540316 ) ) ; -#11687 = ORIENTED_EDGE ( 'NONE', *, *, #3846, .F. ) ; -#11688 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #26782, #26182, #10839, #13687 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.536617029295737069, 5.967414621972016775 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8365544822326859142, 0.8365544822326859142, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#11689 = ADVANCED_FACE ( 'NONE', ( #6963 ), #28259, .F. ) ; -#11690 = CIRCLE ( 'NONE', #21483, 2.999999999999997335 ) ; -#11691 = AXIS2_PLACEMENT_3D ( 'NONE', #30901, #9423, #18195 ) ; -#11692 = ORIENTED_EDGE ( 'NONE', *, *, #13376, .T. ) ; -#11693 = CARTESIAN_POINT ( 'NONE', ( -25.75626117398395465, 122.6043567611443024, 88.48707144345416964 ) ) ; -#11694 = VECTOR ( 'NONE', #14611, 1000.000000000000000 ) ; -#11695 = ORIENTED_EDGE ( 'NONE', *, *, #9718, .F. ) ; -#11696 = EDGE_CURVE ( 'NONE', #15849, #21074, #4740, .T. ) ; -#11697 = CARTESIAN_POINT ( 'NONE', ( -36.06278304189000039, 192.0164624370000297, 105.0249046332999967 ) ) ; -#11698 = CIRCLE ( 'NONE', #40394, 6.500000000017553070 ) ; -#11699 = DIRECTION ( 'NONE', ( -0.1305262453914154686, 0.9659761156053645603, 0.2232779508683992165 ) ) ; -#11700 = CARTESIAN_POINT ( 'NONE', ( -25.51388077191477066, 211.0902258580313742, 75.57405363378009611 ) ) ; -#11701 = EDGE_CURVE ( 'NONE', #14988, #32614, #31128, .T. ) ; -#11702 = ORIENTED_EDGE ( 'NONE', *, *, #32662, .F. ) ; -#11703 = CARTESIAN_POINT ( 'NONE', ( 44.86515336672585619, 186.3325894068457558, 107.7750559962144905 ) ) ; -#11704 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31086, #22084, #34510, #6514 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11705 = CARTESIAN_POINT ( 'NONE', ( -25.02112439774744246, 181.4181497952224333, 104.6306287658777450 ) ) ; -#11706 = ORIENTED_EDGE ( 'NONE', *, *, #27809, .T. ) ; -#11707 = CARTESIAN_POINT ( 'NONE', ( 26.12522142770999878, 121.2586743417000008, 90.71091124750999768 ) ) ; -#11708 = CARTESIAN_POINT ( 'NONE', ( -35.81215698510654022, 191.6412655454669505, 103.9150230815284459 ) ) ; -#11710 = DIRECTION ( 'NONE', ( -5.204170427930391307E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#11709 = CARTESIAN_POINT ( 'NONE', ( -0.4015627557743999820, 209.0000000000000000, 162.9824824849000322 ) ) ; -#11711 = ORIENTED_EDGE ( 'NONE', *, *, #24206, .F. ) ; -#11712 = ORIENTED_EDGE ( 'NONE', *, *, #36578, .T. ) ; -#11713 = ORIENTED_EDGE ( 'NONE', *, *, #36786, .T. ) ; -#11714 = CARTESIAN_POINT ( 'NONE', ( -30.31843644206924537, 127.1600984872847704, 89.19950512931269770 ) ) ; -#11715 = FACE_OUTER_BOUND ( 'NONE', #13472, .T. ) ; -#11716 = CYLINDRICAL_SURFACE ( 'NONE', #33293, 2.000000000000000000 ) ; -#11717 = ORIENTED_EDGE ( 'NONE', *, *, #38445, .F. ) ; -#11718 = VECTOR ( 'NONE', #32004, 1000.000000000000114 ) ; -#11719 = EDGE_LOOP ( 'NONE', ( #26627, #36132, #39448, #14769, #5538, #18510, #1775, #11959, #8348, #36247, #19931, #25216 ) ) ; -#11721 = EDGE_CURVE ( 'NONE', #37113, #12309, #28287, .T. ) ; -#11720 = CARTESIAN_POINT ( 'NONE', ( -0.4373757873778362781, 189.0000005053102257, 103.6849946747920228 ) ) ; -#11722 = PLANE ( 'NONE', #13552 ) ; -#11723 = EDGE_CURVE ( 'NONE', #8, #31162, #10763, .T. ) ; -#11724 = CIRCLE ( 'NONE', #38468, 2.500000000185293114 ) ; -#11725 = DIRECTION ( 'NONE', ( 0.7856007465113978849, 0.6187337610642675845, 0.000000000000000000 ) ) ; -#11726 = CARTESIAN_POINT ( 'NONE', ( 26.34169637600000158, 122.6976311872000025, 87.96391511826999476 ) ) ; -#11727 = ORIENTED_EDGE ( 'NONE', *, *, #23172, .T. ) ; -#11728 = ORIENTED_EDGE ( 'NONE', *, *, #27201, .T. ) ; -#11729 = CARTESIAN_POINT ( 'NONE', ( 20.00153785277168339, 160.0757089691884971, 99.67622395206049646 ) ) ; -#11730 = CARTESIAN_POINT ( 'NONE', ( -28.55555411531191012, 225.5077044902969021, 75.57575137751560135 ) ) ; -#11731 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31788, #18472, #3540, #16021, #2944, #3147 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11732 = ORIENTED_EDGE ( 'NONE', *, *, #27629, .F. ) ; -#11733 = EDGE_CURVE ( 'NONE', #7935, #19997, #9755, .T. ) ; -#11734 = CARTESIAN_POINT ( 'NONE', ( 2.735590141264424346, 189.5786277718560200, 106.5043399991846371 ) ) ; -#11735 = CARTESIAN_POINT ( 'NONE', ( 30.06862252804693014, 175.3593846892391923, 100.1196662352797802 ) ) ; -#11736 = CARTESIAN_POINT ( 'NONE', ( 39.01961099994073123, 121.1792603210347608, 123.5275808920352603 ) ) ; -#11737 = DIRECTION ( 'NONE', ( -0.0006039748319380209294, -1.272619257381173226E-14, -0.9999998176071845934 ) ) ; -#11738 = CARTESIAN_POINT ( 'NONE', ( 23.68458193633999187, 135.2968916867860685, 91.38751720632269837 ) ) ; -#11739 = VERTEX_POINT ( 'NONE', #14031 ) ; -#11740 = LINE ( 'NONE', #24229, #2952 ) ; -#11741 = CARTESIAN_POINT ( 'NONE', ( 20.50147081420385931, 173.9561948828717561, 102.3672533376207952 ) ) ; -#11742 = AXIS2_PLACEMENT_3D ( 'NONE', #38961, #10971, #7886 ) ; -#11743 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33060, #33465, #32673, #32861 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11744 = EDGE_LOOP ( 'NONE', ( #12813, #11635, #7797, #35818 ) ) ; -#11745 = VECTOR ( 'NONE', #32624, 999.9999999999998863 ) ; -#11746 = VECTOR ( 'NONE', #38917, 1000.000000000000114 ) ; -#11747 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971575949 ) ) ; -#11748 = ORIENTED_EDGE ( 'NONE', *, *, #35575, .F. ) ; -#11750 = DIRECTION ( 'NONE', ( 0.7933533411652596845, -0.5930537057990512562, -0.1373964268091844299 ) ) ; -#11749 = CARTESIAN_POINT ( 'NONE', ( -15.66509696366853710, 185.3064862987275205, 105.1805686752921076 ) ) ; -#11751 = EDGE_LOOP ( 'NONE', ( #38893, #33227, #26737, #10684, #1230, #33937 ) ) ; -#11752 = ORIENTED_EDGE ( 'NONE', *, *, #1987, .F. ) ; -#11753 = CARTESIAN_POINT ( 'NONE', ( 15.05621097240102912, 151.2968320376545819, 177.4259961740748963 ) ) ; -#11754 = ORIENTED_EDGE ( 'NONE', *, *, #19243, .T. ) ; -#11755 = CARTESIAN_POINT ( 'NONE', ( 2.831202620881000165, 209.6616513977000125, 75.93512161779000280 ) ) ; -#11756 = EDGE_CURVE ( 'NONE', #19724, #37514, #31502, .T. ) ; -#11757 = PLANE ( 'NONE', #20278 ) ; -#11758 = DIRECTION ( 'NONE', ( 1.272130549047321246E-14, -1.000000000000000000, 1.387778780778895919E-14 ) ) ; -#11759 = ORIENTED_EDGE ( 'NONE', *, *, #32297, .T. ) ; -#11760 = ORIENTED_EDGE ( 'NONE', *, *, #39072, .T. ) ; -#11761 = CARTESIAN_POINT ( 'NONE', ( 37.33832944776210638, 168.0120548916972041, 183.6157512033705927 ) ) ; -#11762 = EDGE_LOOP ( 'NONE', ( #29501, #12924, #38853, #40347 ) ) ; -#11763 = EDGE_LOOP ( 'NONE', ( #40082, #14765, #9977, #6432 ) ) ; -#11764 = CARTESIAN_POINT ( 'NONE', ( 15.75014751337000263, 127.2185294120999970, 89.27069610494000074 ) ) ; -#11765 = EDGE_CURVE ( 'NONE', #12880, #38531, #25029, .T. ) ; -#11766 = CARTESIAN_POINT ( 'NONE', ( 19.70892818629356569, 149.4293184409359014, 181.7720440811204412 ) ) ; -#11767 = FACE_OUTER_BOUND ( 'NONE', #20745, .T. ) ; -#11768 = CARTESIAN_POINT ( 'NONE', ( 19.46094516130095542, 125.6747539604571813, 178.4426934156100231 ) ) ; -#11769 = CARTESIAN_POINT ( 'NONE', ( 36.07413075020000548, 192.3934985084000004, 104.3746197141000067 ) ) ; -#11770 = EDGE_LOOP ( 'NONE', ( #24644, #40325, #2899, #379 ) ) ; -#11771 = ORIENTED_EDGE ( 'NONE', *, *, #37329, .T. ) ; -#11772 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825907063166864, 0.0005734119026844853358 ) ) ; -#11774 = ADVANCED_FACE ( 'NONE', ( #14436 ), #26921, .F. ) ; -#11773 = FACE_OUTER_BOUND ( 'NONE', #20712, .T. ) ; -#11775 = CARTESIAN_POINT ( 'NONE', ( -35.83164568235000047, 191.4815149080000083, 103.7524294659999953 ) ) ; -#11776 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #35904, #28988 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 0.9999976022235548268 ), - .UNSPECIFIED. ) ; -#11777 = EDGE_CURVE ( 'NONE', #20455, #12963, #21078, .T. ) ; -#11778 = ORIENTED_EDGE ( 'NONE', *, *, #7822, .F. ) ; -#11779 = CARTESIAN_POINT ( 'NONE', ( -25.50947195507000131, 120.9974785633000067, 88.11608534222000344 ) ) ; -#11780 = VECTOR ( 'NONE', #7734, 1000.000000000000114 ) ; -#11781 = VERTEX_POINT ( 'NONE', #19295 ) ; -#11782 = LINE ( 'NONE', #39357, #38883 ) ; -#11783 = CARTESIAN_POINT ( 'NONE', ( -37.83775869339968523, 191.4135373898145360, 104.3802259897112776 ) ) ; -#11784 = CARTESIAN_POINT ( 'NONE', ( 25.99285328131546891, 207.8686442202041746, 77.26134345907178158 ) ) ; -#11785 = AXIS2_PLACEMENT_3D ( 'NONE', #38354, #37958, #9958 ) ; -#11786 = ORIENTED_EDGE ( 'NONE', *, *, #9840, .T. ) ; -#11787 = ADVANCED_FACE ( 'NONE', ( #25668 ), #38120, .T. ) ; -#11788 = CARTESIAN_POINT ( 'NONE', ( 0.7304943002959288778, 188.6176604254382596, 103.1983004245615092 ) ) ; -#11789 = VECTOR ( 'NONE', #30546, 1000.000000000000000 ) ; -#11790 = CYLINDRICAL_SURFACE ( 'NONE', #26807, 2.000000000000001332 ) ; -#11791 = CARTESIAN_POINT ( 'NONE', ( 0.03597117087483431980, -13.74990928990360750, 59.55738949995969023 ) ) ; -#11792 = LINE ( 'NONE', #11366, #15913 ) ; -#11793 = FACE_OUTER_BOUND ( 'NONE', #19536, .T. ) ; -#11794 = CYLINDRICAL_SURFACE ( 'NONE', #19517, 1.999999999999989564 ) ; -#11795 = ORIENTED_EDGE ( 'NONE', *, *, #23111, .F. ) ; -#11796 = CARTESIAN_POINT ( 'NONE', ( 75.31247730783820771, 195.3485392357280261, 195.0764703131155500 ) ) ; -#11797 = EDGE_LOOP ( 'NONE', ( #335, #38675, #34508, #25230 ) ) ; -#11798 = DIRECTION ( 'NONE', ( -0.0004161288024530937577, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#11799 = CARTESIAN_POINT ( 'NONE', ( 15.50029468042244396, 126.6919968860542838, 89.40586344971805488 ) ) ; -#11800 = CARTESIAN_POINT ( 'NONE', ( 36.19118544004999904, 112.3688938107000013, 89.61224238968999600 ) ) ; -#11801 = CARTESIAN_POINT ( 'NONE', ( 6.033442795662184110, 135.0969017969509594, 91.08132727238057669 ) ) ; -#11802 = ORIENTED_EDGE ( 'NONE', *, *, #35093, .T. ) ; -#11803 = LINE ( 'NONE', #27158, #6342 ) ; -#11804 = AXIS2_PLACEMENT_3D ( 'NONE', #497, #28328, #10124 ) ; -#11805 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#11806 = CIRCLE ( 'NONE', #34622, 2.500000000028141489 ) ; -#11807 = CARTESIAN_POINT ( 'NONE', ( 20.89286828480348035, 176.3842452922319524, 100.3618186666556369 ) ) ; -#11808 = DIRECTION ( 'NONE', ( 0.9914448496661263377, 0.1271951663094869622, 0.02930016617724668163 ) ) ; -#11809 = CONICAL_SURFACE ( 'NONE', #9184, 5.999999999758601099, 0.7853981633210409541 ) ; -#11810 = CARTESIAN_POINT ( 'NONE', ( 19.46056981307119926, 126.3953319292994451, 175.3169314365064224 ) ) ; -#11811 = CARTESIAN_POINT ( 'NONE', ( -15.83309504418939717, 151.9366289530009908, 94.91101439893938618 ) ) ; -#11812 = FACE_OUTER_BOUND ( 'NONE', #22378, .T. ) ; -#11813 = DIRECTION ( 'NONE', ( 0.0005884949961299158110, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#11814 = DIRECTION ( 'NONE', ( 2.843962595571598640E-13, 0.9743700556834007376, 0.2249510937682375755 ) ) ; -#11815 = ORIENTED_EDGE ( 'NONE', *, *, #32975, .T. ) ; -#11816 = VERTEX_POINT ( 'NONE', #7024 ) ; -#11817 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#11818 = FACE_OUTER_BOUND ( 'NONE', #35752, .T. ) ; -#11819 = EDGE_CURVE ( 'NONE', #22903, #17689, #34634, .T. ) ; -#11820 = CARTESIAN_POINT ( 'NONE', ( -19.37135277734932259, 148.5061081704852768, 180.6320852586945875 ) ) ; -#11821 = DIRECTION ( 'NONE', ( -9.020562075119553066E-15, 0.9743700557921584071, 0.2249510932971565402 ) ) ; -#11822 = ORIENTED_EDGE ( 'NONE', *, *, #31570, .T. ) ; -#11823 = CARTESIAN_POINT ( 'NONE', ( -20.00000588364686038, 174.5066637885302896, 99.95304239614711150 ) ) ; -#11824 = EDGE_CURVE ( 'NONE', #7776, #13881, #16114, .T. ) ; -#11825 = EDGE_CURVE ( 'NONE', #19078, #9147, #2447, .T. ) ; -#11826 = ORIENTED_EDGE ( 'NONE', *, *, #12369, .T. ) ; -#11827 = CARTESIAN_POINT ( 'NONE', ( -38.51028687318000010, 118.9650807552999936, 87.72827849888000173 ) ) ; -#11828 = EDGE_CURVE ( 'NONE', #2793, #10320, #22962, .T. ) ; -#11829 = EDGE_CURVE ( 'NONE', #16953, #1494, #20272, .T. ) ; -#11830 = CARTESIAN_POINT ( 'NONE', ( -3.566911285291269440, 143.5401626538130984, 95.84111064223441190 ) ) ; -#11831 = ORIENTED_EDGE ( 'NONE', *, *, #18525, .T. ) ; -#11832 = CARTESIAN_POINT ( 'NONE', ( 10.03420395425098555, 168.4982496180797682, 98.54774839024014454 ) ) ; -#11833 = CARTESIAN_POINT ( 'NONE', ( 19.46082894524516149, 125.8979155071039742, 177.4746511243711780 ) ) ; -#11834 = CARTESIAN_POINT ( 'NONE', ( 16.06470767884826500, 121.9811400020297896, 174.6065274053796657 ) ) ; -#11835 = LINE ( 'NONE', #37367, #30697 ) ; -#11836 = CARTESIAN_POINT ( 'NONE', ( -5.670826124484550590, 124.5797135749217546, 88.71086237486835557 ) ) ; -#11837 = VERTEX_POINT ( 'NONE', #1468 ) ; -#11838 = ORIENTED_EDGE ( 'NONE', *, *, #27854, .T. ) ; -#11839 = AXIS2_PLACEMENT_3D ( 'NONE', #29520, #1101, #4362 ) ; -#11840 = DIRECTION ( 'NONE', ( -0.6086215548477215131, -0.7730393818215736124, -0.1788572534946829551 ) ) ; -#11841 = AXIS2_PLACEMENT_3D ( 'NONE', #18610, #34360, #9040 ) ; -#11842 = CARTESIAN_POINT ( 'NONE', ( 42.45642095825782292, 103.5646128624151885, 168.7183387323667887 ) ) ; -#11843 = CARTESIAN_POINT ( 'NONE', ( 37.71832435473301359, 191.4189981270610303, 104.3344995016596073 ) ) ; -#11844 = VECTOR ( 'NONE', #37210, 1000.000000000000000 ) ; -#11845 = AXIS2_PLACEMENT_3D ( 'NONE', #20452, #10672, #23343 ) ; -#11846 = CARTESIAN_POINT ( 'NONE', ( -16.53307911521251583, 121.8496102454072485, 177.5840153248893785 ) ) ; -#11847 = ORIENTED_EDGE ( 'NONE', *, *, #16983, .F. ) ; -#11848 = CARTESIAN_POINT ( 'NONE', ( 3.882702609241409419, 148.0331269928226732, 129.7473673639308345 ) ) ; -#11849 = CARTESIAN_POINT ( 'NONE', ( -42.22554410189300711, 120.8118904731670682, 90.64895936832934353 ) ) ; -#11850 = CARTESIAN_POINT ( 'NONE', ( -19.44534333246823721, 148.3822623830060365, 180.6034369735336895 ) ) ; -#11851 = CARTESIAN_POINT ( 'NONE', ( -36.21067597575999741, 191.7496623399999862, 104.2838814501999991 ) ) ; -#11852 = CARTESIAN_POINT ( 'NONE', ( -25.47195991445609664, 212.8394811963306381, 73.07388850790900392 ) ) ; -#11853 = CARTESIAN_POINT ( 'NONE', ( 8.428362648054749329, 177.5952526073304796, 27.36579594574504526 ) ) ; -#11854 = CARTESIAN_POINT ( 'NONE', ( 14.78600921306619576, 183.3613208809844366, 102.4894415693095340 ) ) ; -#11855 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.000000000000000000, 1.000000000000000000 ) ) ; -#11856 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927732809619, -0.0005734119021876268136 ) ) ; -#11857 = CARTESIAN_POINT ( 'NONE', ( 43.14456005852381537, 112.6780295318855565, 129.4537069268840526 ) ) ; -#11858 = CARTESIAN_POINT ( 'NONE', ( -20.49853057565002601, 184.3993303303604705, 104.8029991440840973 ) ) ; -#11859 = EDGE_CURVE ( 'NONE', #7608, #15505, #13954, .T. ) ; -#11860 = CARTESIAN_POINT ( 'NONE', ( -0.4555724343627732265, 211.0000000000011653, 73.55877932795836216 ) ) ; -#11861 = CARTESIAN_POINT ( 'NONE', ( 39.05648265166797017, 127.5103312055594955, 92.14632397477382142 ) ) ; -#11862 = AXIS2_PLACEMENT_3D ( 'NONE', #39866, #2863, #24764 ) ; -#11863 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142367503004439, 137.4659008082804519, 177.5714312369109393 ) ) ; -#11864 = VERTEX_POINT ( 'NONE', #33545 ) ; -#11865 = ORIENTED_EDGE ( 'NONE', *, *, #11696, .F. ) ; -#11866 = VECTOR ( 'NONE', #20411, 1000.000000000000000 ) ; -#11867 = CARTESIAN_POINT ( 'NONE', ( -2.894529877367415516, 190.6472786124893730, 103.6690642133140017 ) ) ; -#11868 = EDGE_CURVE ( 'NONE', #3485, #4354, #971, .T. ) ; -#11869 = CONICAL_SURFACE ( 'NONE', #38597, 2.500000001920880344, 0.7853981633737419088 ) ; -#11870 = ORIENTED_EDGE ( 'NONE', *, *, #12137, .F. ) ; -#11871 = CARTESIAN_POINT ( 'NONE', ( 20.29463841047894235, 126.8274035292942017, 91.69923547483881521 ) ) ; -#11872 = ADVANCED_FACE ( 'NONE', ( #30508 ), #18458, .F. ) ; -#11873 = CARTESIAN_POINT ( 'NONE', ( -8.472443769278077852, 160.9680296444896328, 99.38619809799159555 ) ) ; -#11874 = LINE ( 'NONE', #5105, #28539 ) ; -#11875 = ORIENTED_EDGE ( 'NONE', *, *, #6117, .T. ) ; -#11876 = CYLINDRICAL_SURFACE ( 'NONE', #36144, 48.00000000000002132 ) ; -#11877 = EDGE_CURVE ( 'NONE', #7892, #7683, #21511, .T. ) ; -#11878 = CARTESIAN_POINT ( 'NONE', ( -15.03362232196302095, 125.0996412702250211, 171.3811097074177212 ) ) ; -#11879 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#11880 = FACE_BOUND ( 'NONE', #30940, .T. ) ; -#11881 = EDGE_LOOP ( 'NONE', ( #20802, #39050, #8107, #26424 ) ) ; -#11882 = CARTESIAN_POINT ( 'NONE', ( -35.95425951642922513, 207.4083918145335588, 77.10339231470923949 ) ) ; -#11883 = CARTESIAN_POINT ( 'NONE', ( 23.36625798079915484, 177.0273801772071636, 103.4614646118997854 ) ) ; -#11884 = FACE_OUTER_BOUND ( 'NONE', #22276, .T. ) ; -#11885 = DIRECTION ( 'NONE', ( -0.0005884949961231549431, 0.2249510543439031118, -0.9743698870671271273 ) ) ; -#11886 = FACE_OUTER_BOUND ( 'NONE', #1030, .T. ) ; -#11887 = ORIENTED_EDGE ( 'NONE', *, *, #12234, .F. ) ; -#11888 = ORIENTED_EDGE ( 'NONE', *, *, #8050, .F. ) ; -#11889 = CARTESIAN_POINT ( 'NONE', ( 44.87054245545689923, 186.3366208751881743, 107.7759764278890486 ) ) ; -#11890 = CARTESIAN_POINT ( 'NONE', ( 1.112032568174920355, 189.0842896917700102, 103.7185439348499898 ) ) ; -#11891 = CARTESIAN_POINT ( 'NONE', ( 40.67360545558243956, 184.2591260079552740, 105.2468408042174275 ) ) ; -#11892 = CARTESIAN_POINT ( 'NONE', ( -12.64523939051215073, 134.9174765714697344, 90.80875027841997849 ) ) ; -#11893 = ORIENTED_EDGE ( 'NONE', *, *, #2929, .T. ) ; -#11894 = VECTOR ( 'NONE', #18435, 1000.000000000000000 ) ; -#11895 = CARTESIAN_POINT ( 'NONE', ( -5.958856852865682896, 148.4703916786008904, 97.01252450521799631 ) ) ; -#11896 = ORIENTED_EDGE ( 'NONE', *, *, #3066, .F. ) ; -#11897 = AXIS2_PLACEMENT_3D ( 'NONE', #39589, #23663, #29594 ) ; -#11898 = ORIENTED_EDGE ( 'NONE', *, *, #38109, .F. ) ; -#11899 = EDGE_LOOP ( 'NONE', ( #31124, #37653, #3366, #4572 ) ) ; -#11900 = FACE_OUTER_BOUND ( 'NONE', #33413, .T. ) ; -#11901 = CARTESIAN_POINT ( 'NONE', ( -37.05748002013000075, 191.5156164059999924, 104.1710418975000039 ) ) ; -#11902 = CARTESIAN_POINT ( 'NONE', ( 14.78718341405425818, 175.4478817342403545, 102.7150877355488063 ) ) ; -#11903 = FACE_OUTER_BOUND ( 'NONE', #27541, .T. ) ; -#11904 = VERTEX_POINT ( 'NONE', #12902 ) ; -#11905 = CARTESIAN_POINT ( 'NONE', ( -12.63752691925692240, 134.5929303039996228, 93.51283432846918231 ) ) ; -#11906 = ORIENTED_EDGE ( 'NONE', *, *, #39114, .F. ) ; -#11907 = EDGE_CURVE ( 'NONE', #11261, #32876, #7774, .T. ) ; -#11908 = CARTESIAN_POINT ( 'NONE', ( 26.18897216877000034, 122.5795457392000003, 90.67356684192000671 ) ) ; -#11909 = EDGE_CURVE ( 'NONE', #25874, #11248, #19201, .T. ) ; -#11910 = CARTESIAN_POINT ( 'NONE', ( -35.98606117377973135, 191.5275217759125894, 103.8920091762606006 ) ) ; -#11911 = EDGE_CURVE ( 'NONE', #1910, #23240, #37052, .T. ) ; -#11912 = EDGE_CURVE ( 'NONE', #7897, #11123, #6143, .T. ) ; -#11914 = CARTESIAN_POINT ( 'NONE', ( -25.50870663471662780, 209.7066555246269104, 75.57407794464953099 ) ) ; -#11913 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; -#11915 = ORIENTED_EDGE ( 'NONE', *, *, #8020, .F. ) ; -#11916 = ORIENTED_EDGE ( 'NONE', *, *, #19273, .F. ) ; -#11917 = ORIENTED_EDGE ( 'NONE', *, *, #10052, .T. ) ; -#11918 = EDGE_CURVE ( 'NONE', #26621, #37534, #23435, .T. ) ; -#11919 = VECTOR ( 'NONE', #25166, 1000.000000000000000 ) ; -#11920 = VERTEX_POINT ( 'NONE', #14108 ) ; -#11922 = AXIS2_PLACEMENT_3D ( 'NONE', #30601, #39987, #11994 ) ; -#11921 = CARTESIAN_POINT ( 'NONE', ( -26.40259126664291145, 122.2015665119480730, 90.96023475316120255 ) ) ; -#11923 = EDGE_CURVE ( 'NONE', #26477, #7666, #39730, .T. ) ; -#11924 = AXIS2_PLACEMENT_3D ( 'NONE', #26894, #15611, #21576 ) ; -#11925 = CARTESIAN_POINT ( 'NONE', ( -39.63286418743903283, 165.2521965586124111, 181.9324630935838343 ) ) ; -#11926 = CARTESIAN_POINT ( 'NONE', ( 15.50147166947062871, 184.4041534623167991, 104.7823749529912760 ) ) ; -#11927 = CARTESIAN_POINT ( 'NONE', ( 12.63561059294855582, 130.7398924310956261, 90.07144258487507216 ) ) ; -#11928 = CARTESIAN_POINT ( 'NONE', ( -12.64058198101836084, 135.0096656203987209, 90.95638429151507864 ) ) ; -#11929 = VERTEX_POINT ( 'NONE', #39230 ) ; -#11930 = ORIENTED_EDGE ( 'NONE', *, *, #10938, .T. ) ; -#11931 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971549027 ) ) ; -#11932 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26236, #36007, #16799, #20688 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#11933 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #26216, #10476, #3360, #32734 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 5.554824330570662383, 6.283664472678903046 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9562204062000201343, 0.9562204062000201343, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#11934 = CARTESIAN_POINT ( 'NONE', ( -17.94609826176000311, 126.0030689618739927, 174.3309067020310010 ) ) ; -#11935 = EDGE_CURVE ( 'NONE', #13773, #37266, #19235, .T. ) ; -#11936 = ORIENTED_EDGE ( 'NONE', *, *, #30227, .T. ) ; -#11937 = CARTESIAN_POINT ( 'NONE', ( 35.80903082173799845, 209.7096537007933534, 75.77443985609707511 ) ) ; -#11938 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#11939 = CARTESIAN_POINT ( 'NONE', ( 3.045834296815999931, 190.5229117821999978, 106.7164120734999955 ) ) ; -#11940 = CARTESIAN_POINT ( 'NONE', ( -16.55838281596989248, 121.8568190709532786, 177.6124637991976272 ) ) ; -#11941 = CARTESIAN_POINT ( 'NONE', ( -36.75835926547845389, 190.5727201303276104, 106.7512168163608806 ) ) ; -#11942 = LINE ( 'NONE', #36463, #9831 ) ; -#11943 = CARTESIAN_POINT ( 'NONE', ( 3.706312568368710814, 145.6625114747673138, 93.27952375833829990 ) ) ; -#11944 = CIRCLE ( 'NONE', #22398, 2.000000000000011546 ) ; -#11945 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #621, #37640, #12491, #32120 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.001725546163888570577, 0.003699931228746131465 ), - .UNSPECIFIED. ) ; -#11946 = ORIENTED_EDGE ( 'NONE', *, *, #25537, .F. ) ; -#11947 = VECTOR ( 'NONE', #8565, 1000.000000000000114 ) ; -#11948 = CARTESIAN_POINT ( 'NONE', ( -61.84220049570045319, 78.72323700374752775, 282.5958934331605406 ) ) ; -#11949 = FACE_OUTER_BOUND ( 'NONE', #18021, .T. ) ; -#11950 = VECTOR ( 'NONE', #13739, 999.9999999999998863 ) ; -#11951 = VERTEX_POINT ( 'NONE', #8164 ) ; -#11952 = CARTESIAN_POINT ( 'NONE', ( -15.03056783443286903, 153.9206520343971079, 95.19738268539683190 ) ) ; -#11953 = VERTEX_POINT ( 'NONE', #20631 ) ; -#11954 = ADVANCED_FACE ( 'NONE', ( #30456 ), #21128, .T. ) ; -#11955 = EDGE_CURVE ( 'NONE', #34643, #796, #24120, .T. ) ; -#11957 = CARTESIAN_POINT ( 'NONE', ( -44.46121984373956337, 189.2577286604973210, 103.8865186576782804 ) ) ; -#11956 = CARTESIAN_POINT ( 'NONE', ( 12.31198009898977297, 134.9205818654068025, 90.79431936396761671 ) ) ; -#11958 = ORIENTED_EDGE ( 'NONE', *, *, #7632, .F. ) ; -#11959 = ORIENTED_EDGE ( 'NONE', *, *, #19273, .T. ) ; -#11960 = VERTEX_POINT ( 'NONE', #28001 ) ; -#11961 = CARTESIAN_POINT ( 'NONE', ( 3.120781379327000060, 209.6077888583999993, 76.19641638420999641 ) ) ; -#11962 = CC_DESIGN_PERSON_AND_ORGANIZATION_ASSIGNMENT ( #30665, #24126, ( #37519 ) ) ; -#11963 = PLANE ( 'NONE', #26174 ) ; -#11964 = DIRECTION ( 'NONE', ( -4.718447854718138476E-14, 0.9743700557921591843, 0.2249510932971532373 ) ) ; -#11965 = ORIENTED_EDGE ( 'NONE', *, *, #7600, .F. ) ; -#11966 = ORIENTED_EDGE ( 'NONE', *, *, #13873, .F. ) ; -#11967 = DIRECTION ( 'NONE', ( -0.7857167650892391553, 0.6185862428610305885, 0.0004745532376930718848 ) ) ; -#11968 = ORIENTED_EDGE ( 'NONE', *, *, #9235, .T. ) ; -#11969 = ORIENTED_EDGE ( 'NONE', *, *, #38572, .T. ) ; -#11970 = CARTESIAN_POINT ( 'NONE', ( 30.44899469349954302, 184.9368092152190002, 105.4094724642501859 ) ) ; -#11971 = CARTESIAN_POINT ( 'NONE', ( 28.70699186420280569, 148.4355579229025750, 96.47039304610791532 ) ) ; -#11972 = CARTESIAN_POINT ( 'NONE', ( 2.620081097049193453, 209.6213299886146331, 73.39025628380156263 ) ) ; -#11973 = AXIS2_PLACEMENT_3D ( 'NONE', #25845, #7811, #39088 ) ; -#11974 = EDGE_LOOP ( 'NONE', ( #18652, #28092, #12596, #35596, #17159, #28310 ) ) ; -#11975 = ORIENTED_EDGE ( 'NONE', *, *, #16495, .T. ) ; -#11976 = CARTESIAN_POINT ( 'NONE', ( -5.668571547460837579, 124.2905521247553366, 90.91684019452070231 ) ) ; -#11977 = CARTESIAN_POINT ( 'NONE', ( -23.40543042926000084, 191.9910753068000133, 28.07991271570000080 ) ) ; -#11978 = CARTESIAN_POINT ( 'NONE', ( -36.18473128549999984, 191.7673265768000022, 104.2866159423000028 ) ) ; -#11979 = AXIS2_PLACEMENT_3D ( 'NONE', #25300, #35058, #34663 ) ; -#11980 = EDGE_LOOP ( 'NONE', ( #30176, #29328, #7764, #5350 ) ) ; -#11981 = CARTESIAN_POINT ( 'NONE', ( 15.10714331102995800, 183.1006619385863701, 101.9159176678921312 ) ) ; -#11982 = EDGE_CURVE ( 'NONE', #288, #367, #33444, .T. ) ; -#11983 = VERTEX_POINT ( 'NONE', #36990 ) ; -#11984 = VECTOR ( 'NONE', #12023, 1000.000000000000000 ) ; -#11985 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265228896, 0.1368326740407718733 ) ) ; -#11986 = CARTESIAN_POINT ( 'NONE', ( -40.98114572698732871, 189.4837074447529233, 107.0019971788270823 ) ) ; -#11987 = VERTEX_POINT ( 'NONE', #12635 ) ; -#11988 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597321 ) ) ; -#11989 = CARTESIAN_POINT ( 'NONE', ( -2.937261516208995893, 196.5784392895002384, 103.8768773715001004 ) ) ; -#11990 = DIRECTION ( 'NONE', ( 0.7072735235867311232, 0.6508952295280636680, 0.2758614924392659429 ) ) ; -#11991 = CARTESIAN_POINT ( 'NONE', ( 40.66653928435549403, 188.1862069274984890, 107.8377757704891167 ) ) ; -#11992 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240802804 ) ) ; -#11993 = ORIENTED_EDGE ( 'NONE', *, *, #17394, .F. ) ; -#11994 = DIRECTION ( 'NONE', ( 0.1305262373691798983, -0.9659583596717404852, -0.2233547598295697878 ) ) ; -#11995 = ORIENTED_EDGE ( 'NONE', *, *, #38117, .F. ) ; -#11996 = CARTESIAN_POINT ( 'NONE', ( 3.166356130869399266, 127.3986506551390789, 89.06331644008139392 ) ) ; -#11997 = CARTESIAN_POINT ( 'NONE', ( 25.74045643010000006, 210.3999399800999868, 73.29295753731000218 ) ) ; -#11998 = FACE_OUTER_BOUND ( 'NONE', #5089, .T. ) ; -#11999 = ORIENTED_EDGE ( 'NONE', *, *, #675, .F. ) ; -#12000 = AXIS2_PLACEMENT_3D ( 'NONE', #26339, #38771, #23258 ) ; -#12001 = CARTESIAN_POINT ( 'NONE', ( 44.97084429314561049, 114.9968340379079166, 129.9902062988158491 ) ) ; -#12002 = ORIENTED_EDGE ( 'NONE', *, *, #6399, .T. ) ; -#12003 = CARTESIAN_POINT ( 'NONE', ( -22.78222448785095011, 163.9594641391059042, 100.5986201911018441 ) ) ; -#12004 = ADVANCED_FACE ( 'NONE', ( #15118 ), #30856, .T. ) ; -#12005 = VECTOR ( 'NONE', #3296, 1000.000000000000227 ) ; -#12007 = EDGE_CURVE ( 'NONE', #21782, #34652, #20259, .T. ) ; -#12006 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5440, #36724, #2392, #30198, #30396, #2192 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 4 ), - ( 0.000000000000000000, 0.3333328623389552048, 0.6666665902675604771, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12008 = CARTESIAN_POINT ( 'NONE', ( -35.95668941153999754, 225.9002260768000099, 73.08022102179975832 ) ) ; -#12009 = CIRCLE ( 'NONE', #22463, 1.750000000000001998 ) ; -#12010 = ORIENTED_EDGE ( 'NONE', *, *, #36312, .F. ) ; -#12011 = CYLINDRICAL_SURFACE ( 'NONE', #948, 8.999999999999996447 ) ; -#12012 = CARTESIAN_POINT ( 'NONE', ( 21.65621127755655095, 154.2664572072626470, 95.25506021940962853 ) ) ; -#12013 = CARTESIAN_POINT ( 'NONE', ( 26.01723252630338123, 191.6619263248034031, 103.8858301454409201 ) ) ; -#12014 = LINE ( 'NONE', #36738, #26786 ) ; -#12015 = CARTESIAN_POINT ( 'NONE', ( -38.01211212650550664, 119.1971871873620472, 87.30118044812934386 ) ) ; -#12016 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #799, #25771, #38223, #35518, #7535, #10232, #7135, #19606, #35726, #32880 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.002038048205810061037, 0.2515285361543575515, 0.5010190241029049973, 0.7505095120514525542, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12017 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#12018 = ORIENTED_EDGE ( 'NONE', *, *, #23399, .F. ) ; -#12019 = CYLINDRICAL_SURFACE ( 'NONE', #15185, 2.000000000000014655 ) ; -#12020 = CYLINDRICAL_SURFACE ( 'NONE', #1365, 7.999999999999993783 ) ; -#12021 = ORIENTED_EDGE ( 'NONE', *, *, #38794, .F. ) ; -#12022 = CARTESIAN_POINT ( 'NONE', ( 30.06438278973887535, 134.2480451416175811, 93.70732421818068758 ) ) ; -#12023 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#12024 = ORIENTED_EDGE ( 'NONE', *, *, #129, .T. ) ; -#12025 = CARTESIAN_POINT ( 'NONE', ( -38.57809401074000988, 119.0279522853000174, 87.73291911440999513 ) ) ; -#12026 = EDGE_CURVE ( 'NONE', #15729, #11269, #7078, .T. ) ; -#12027 = CARTESIAN_POINT ( 'NONE', ( 36.06296285845981942, 194.2771771405940058, 102.8764942496974442 ) ) ; -#12028 = ORIENTED_EDGE ( 'NONE', *, *, #35321, .F. ) ; -#12029 = CARTESIAN_POINT ( 'NONE', ( -38.63917769686599257, 119.2253121530902007, 90.31157676266975898 ) ) ; -#12030 = CIRCLE ( 'NONE', #20490, 6.000000000000001776 ) ; -#12031 = AXIS2_PLACEMENT_3D ( 'NONE', #23044, #19142, #31646 ) ; -#12032 = CARTESIAN_POINT ( 'NONE', ( 19.46071270196222613, 126.1210784313858397, 176.5066029477476377 ) ) ; -#12033 = CARTESIAN_POINT ( 'NONE', ( -25.63981465746000055, 190.7835523455999862, 106.4035544525000034 ) ) ; -#12034 = CARTESIAN_POINT ( 'NONE', ( 25.49921019565536184, 118.1133140256443426, 87.75227232668940758 ) ) ; -#12035 = CARTESIAN_POINT ( 'NONE', ( 0.5441253984803264832, 208.9999999999999716, 73.05817544431644706 ) ) ; -#12036 = ORIENTED_EDGE ( 'NONE', *, *, #13197, .F. ) ; -#12037 = ORIENTED_EDGE ( 'NONE', *, *, #33952, .T. ) ; -#12038 = LINE ( 'NONE', #23698, #24533 ) ; -#12039 = CARTESIAN_POINT ( 'NONE', ( 21.25891409511187291, 128.8498498509368915, 89.90056508924928380 ) ) ; -#12040 = CARTESIAN_POINT ( 'NONE', ( 36.54202398728305212, 191.7331444242542204, 104.3517902021189343 ) ) ; -#12041 = EDGE_CURVE ( 'NONE', #16970, #2805, #28589, .T. ) ; -#12042 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#12043 = VERTEX_POINT ( 'NONE', #7494 ) ; -#12044 = VERTEX_POINT ( 'NONE', #35290 ) ; -#12045 = CARTESIAN_POINT ( 'NONE', ( 18.00176548541284305, 179.0675989394117664, 104.0619768109754943 ) ) ; -#12046 = CARTESIAN_POINT ( 'NONE', ( 15.50029468041065606, 160.6294874787016909, 97.24095194477267512 ) ) ; -#12047 = CARTESIAN_POINT ( 'NONE', ( -19.44510777017706715, 147.9329884748811992, 182.5523163158060527 ) ) ; -#12048 = CARTESIAN_POINT ( 'NONE', ( 6.231540706066161839, 163.7419074641817360, 29.13324844072834452 ) ) ; -#12049 = EDGE_CURVE ( 'NONE', #20521, #25077, #6179, .T. ) ; -#12050 = CARTESIAN_POINT ( 'NONE', ( -37.21052966546948682, 132.5657015190818697, 337.0064682716691777 ) ) ; -#12051 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32499, #20206, #26578, #11229 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 1.425987289115625436E-06, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12052 = CARTESIAN_POINT ( 'NONE', ( 12.64209925790531308, 131.0231129754641302, 89.89439459407216759 ) ) ; -#12053 = EDGE_CURVE ( 'NONE', #35348, #28905, #17161, .T. ) ; -#12054 = EDGE_CURVE ( 'NONE', #3137, #4942, #24207, .T. ) ; -#12055 = CARTESIAN_POINT ( 'NONE', ( -30.05261222213120931, 184.7446961453429424, 104.8885090255323718 ) ) ; -#12056 = EDGE_CURVE ( 'NONE', #11256, #17270, #18475, .T. ) ; -#12057 = CARTESIAN_POINT ( 'NONE', ( 19.15700822158549244, 125.8492576213503185, 175.4093116928347058 ) ) ; -#12058 = EDGE_CURVE ( 'NONE', #9096, #14254, #36860, .T. ) ; -#12059 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25444, #11820, #5675, #18125, #36944, #40393, #39172, #17074 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 4 ), - ( 0.000000000000000000, 0.0004334691909605219921, 0.0008669383819210439842, 0.001733876763842038746 ), - .UNSPECIFIED. ) ; -#12060 = PERSON_AND_ORGANIZATION_ROLE ( 'design_supplier' ) ; -#12061 = DIRECTION ( 'NONE', ( -9.869203562998891317E-14, 0.9743700558298823422, 0.2249510931337564412 ) ) ; -#12062 = AXIS2_PLACEMENT_3D ( 'NONE', #29631, #2029, #14094 ) ; -#12063 = CARTESIAN_POINT ( 'NONE', ( 4.034499240731888037, 144.1016867008996201, 93.43213283136152825 ) ) ; -#12064 = LINE ( 'NONE', #21472, #34874 ) ; -#12065 = CARTESIAN_POINT ( 'NONE', ( -13.46986788395000012, 174.3879284816999871, 152.4718672074000381 ) ) ; -#12066 = CARTESIAN_POINT ( 'NONE', ( 37.68743879864511115, 191.4261428820249762, 104.2800299550340100 ) ) ; -#12067 = AXIS2_PLACEMENT_3D ( 'NONE', #5091, #39436, #24130 ) ; -#12068 = ORIENTED_EDGE ( 'NONE', *, *, #10031, .T. ) ; -#12070 = ORIENTED_EDGE ( 'NONE', *, *, #33343, .F. ) ; -#12069 = CARTESIAN_POINT ( 'NONE', ( 36.67157185893000104, 191.2359882216000244, 106.4438479881000035 ) ) ; -#12071 = ORIENTED_EDGE ( 'NONE', *, *, #39138, .F. ) ; -#12072 = ORIENTED_EDGE ( 'NONE', *, *, #19367, .F. ) ; -#12073 = PLANE ( 'NONE', #7511 ) ; -#12074 = DIRECTION ( 'NONE', ( -0.7075337269410232333, 4.349513441062974412E-15, -0.7066795774896466042 ) ) ; -#12075 = CARTESIAN_POINT ( 'NONE', ( 2.804646158948000068, 201.9934155195000187, 90.47669623104000891 ) ) ; -#12076 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#12077 = ORIENTED_EDGE ( 'NONE', *, *, #15230, .T. ) ; -#12078 = CARTESIAN_POINT ( 'NONE', ( 14.27749844727565076, 135.1700550567618961, 93.92967703643782329 ) ) ; -#12079 = CARTESIAN_POINT ( 'NONE', ( -15.99983570302001468, 128.1046851893773066, 89.23788144415702561 ) ) ; -#12080 = CARTESIAN_POINT ( 'NONE', ( -20.00000737806465523, 151.9608748777371545, 94.74793644920653435 ) ) ; -#12081 = ORIENTED_EDGE ( 'NONE', *, *, #34576, .F. ) ; -#12082 = LINE ( 'NONE', #24565, #25171 ) ; -#12083 = CARTESIAN_POINT ( 'NONE', ( 25.99199080364422443, 211.0901596425212574, 76.04279652306830428 ) ) ; -#12084 = CARTESIAN_POINT ( 'NONE', ( -13.49869758878000070, 124.2895155477322078, 90.92133008163705199 ) ) ; -#12085 = DIRECTION ( 'NONE', ( 0.0005884949961201063834, -0.2249510543439072752, 0.9743698870671261281 ) ) ; -#12086 = CONICAL_SURFACE ( 'NONE', #17266, 2.503114877936384097, 0.7853981634120447142 ) ; -#12087 = VERTEX_POINT ( 'NONE', #23865 ) ; -#12088 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971560961 ) ) ; -#12089 = CARTESIAN_POINT ( 'NONE', ( 2.503116965328639587, 190.4798029275779925, 104.1246707405189937 ) ) ; -#12090 = CONICAL_SURFACE ( 'NONE', #15973, 5.999999999996507682, 0.7853981634382131150 ) ; -#12091 = VECTOR ( 'NONE', #27602, 1000.000000000000114 ) ; -#12092 = CARTESIAN_POINT ( 'NONE', ( 16.19311320487878447, 152.0208732148549586, 180.9787873967511018 ) ) ; -#12093 = VECTOR ( 'NONE', #27107, 1000.000000000000227 ) ; -#12094 = VERTEX_POINT ( 'NONE', #36328 ) ; -#12095 = CARTESIAN_POINT ( 'NONE', ( -37.20408499830807614, 118.8543451047710278, 123.0175147464529886 ) ) ; -#12096 = ORIENTED_EDGE ( 'NONE', *, *, #14189, .T. ) ; -#12097 = EDGE_CURVE ( 'NONE', #38882, #39941, #8326, .T. ) ; -#12098 = EDGE_CURVE ( 'NONE', #33342, #21583, #18308, .T. ) ; -#12099 = LINE ( 'NONE', #24585, #33407 ) ; -#12100 = CARTESIAN_POINT ( 'NONE', ( -37.93576619606000122, 191.2843283846000020, 104.9448776480000021 ) ) ; -#12101 = EDGE_CURVE ( 'NONE', #21459, #22181, #30914, .T. ) ; -#12102 = LINE ( 'NONE', #27470, #10416 ) ; -#12103 = ADVANCED_FACE ( 'NONE', ( #13160 ), #38087, .F. ) ; -#12104 = CARTESIAN_POINT ( 'NONE', ( 15.83996889870756952, 151.8963954173656248, 180.3028429317488133 ) ) ; -#12105 = CARTESIAN_POINT ( 'NONE', ( 12.63852066808000352, 177.1933417920457998, 101.0667481643646539 ) ) ; -#12106 = CARTESIAN_POINT ( 'NONE', ( -36.29559416469999888, 191.0453341742000077, 106.7255111497999991 ) ) ; -#12107 = VERTEX_POINT ( 'NONE', #21202 ) ; -#12108 = CARTESIAN_POINT ( 'NONE', ( -23.02035068621188785, 211.0902260608000347, 73.06925090625777841 ) ) ; -#12109 = CARTESIAN_POINT ( 'NONE', ( -42.84327062420202026, 120.8099927651375936, 92.42850709477329474 ) ) ; -#12110 = CARTESIAN_POINT ( 'NONE', ( 22.50176656780242723, 137.8364378046804575, 94.54354019036699697 ) ) ; -#12112 = CARTESIAN_POINT ( 'NONE', ( 1.561641312891000055, 176.6294975753000074, 103.5090253406000045 ) ) ; -#12111 = LINE ( 'NONE', #22322, #26488 ) ; -#12113 = ORIENTED_EDGE ( 'NONE', *, *, #9045, .F. ) ; -#12114 = ORIENTED_EDGE ( 'NONE', *, *, #27097, .F. ) ; -#12115 = CIRCLE ( 'NONE', #36229, 55.00273826248748321 ) ; -#12116 = AXIS2_PLACEMENT_3D ( 'NONE', #9380, #24936, #28387 ) ; -#12117 = ORIENTED_EDGE ( 'NONE', *, *, #2451, .F. ) ; -#12118 = AXIS2_PLACEMENT_3D ( 'NONE', #19559, #13634, #32834 ) ; -#12119 = AXIS2_PLACEMENT_3D ( 'NONE', #38206, #10212, #12668 ) ; -#12120 = VERTEX_POINT ( 'NONE', #2790 ) ; -#12121 = CARTESIAN_POINT ( 'NONE', ( 39.52184518373000088, 119.8270887776999984, 90.51129334396000559 ) ) ; -#12122 = DIRECTION ( 'NONE', ( -0.0006039748319386177827, -1.312069532538339473E-14, -0.9999998176071847045 ) ) ; -#12123 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#12124 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921579630, -0.2249510932971586774 ) ) ; -#12125 = DIRECTION ( 'NONE', ( 0.9914446600486714889, -0.1270322995874082761, -0.03000468167651997725 ) ) ; -#12126 = EDGE_LOOP ( 'NONE', ( #27468, #18711, #5230, #10378 ) ) ; -#12127 = ORIENTED_EDGE ( 'NONE', *, *, #29507, .F. ) ; -#12128 = CARTESIAN_POINT ( 'NONE', ( -2.437027990547441014, 191.0000000396348128, 104.2633722229568605 ) ) ; -#12129 = LINE ( 'NONE', #25213, #12895 ) ; -#12130 = DIRECTION ( 'NONE', ( -1.227018180789439535E-16, 0.9743700557922200245, 0.2249510932968896981 ) ) ; -#12131 = ORIENTED_EDGE ( 'NONE', *, *, #30878, .T. ) ; -#12132 = CARTESIAN_POINT ( 'NONE', ( 35.82223221909334399, 209.7096535410589695, 75.76122250247870227 ) ) ; -#12133 = EDGE_CURVE ( 'NONE', #11668, #17225, #34984, .T. ) ; -#12134 = CARTESIAN_POINT ( 'NONE', ( -8.332516381469520894, 161.3691698881907541, 97.25506481891379451 ) ) ; -#12135 = EDGE_CURVE ( 'NONE', #5771, #21705, #27568, .T. ) ; -#12136 = VECTOR ( 'NONE', #33266, 1000.000000000000000 ) ; -#12137 = EDGE_CURVE ( 'NONE', #21843, #10701, #38700, .T. ) ; -#12138 = EDGE_CURVE ( 'NONE', #18677, #3193, #16348, .T. ) ; -#12139 = CARTESIAN_POINT ( 'NONE', ( 1.550063599131999981, 189.2339692129000071, 105.8038991500000066 ) ) ; -#12140 = AXIS2_PLACEMENT_3D ( 'NONE', #2716, #24190, #26851 ) ; -#12141 = ORIENTED_EDGE ( 'NONE', *, *, #30797, .T. ) ; -#12142 = CARTESIAN_POINT ( 'NONE', ( 5.667899326860613485, 130.6342804221140739, 90.14085528663672164 ) ) ; -#12143 = CIRCLE ( 'NONE', #34324, 2.000000003389833303 ) ; -#12144 = CYLINDRICAL_SURFACE ( 'NONE', #38222, 6.000000000000008882 ) ; -#12145 = FACE_OUTER_BOUND ( 'NONE', #6025, .T. ) ; -#12146 = CARTESIAN_POINT ( 'NONE', ( 19.23419947629634308, 148.6673374613704084, 183.4523375473061151 ) ) ; -#12147 = CIRCLE ( 'NONE', #8884, 2.500000000000000888 ) ; -#12148 = EDGE_CURVE ( 'NONE', #9446, #10983, #23683, .T. ) ; -#12149 = CARTESIAN_POINT ( 'NONE', ( -19.99931527105535878, 118.1256151686936420, 90.27945241601419468 ) ) ; -#12150 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118071, 107.3101052615539714, 174.7154016153159830 ) ) ; -#12151 = EDGE_CURVE ( 'NONE', #35342, #37208, #3524, .T. ) ; -#12152 = VERTEX_POINT ( 'NONE', #34793 ) ; -#12153 = CARTESIAN_POINT ( 'NONE', ( -5.668308741210207558, 188.0533248580316297, 103.3198754439989813 ) ) ; -#12154 = ORIENTED_EDGE ( 'NONE', *, *, #3690, .T. ) ; -#12156 = CARTESIAN_POINT ( 'NONE', ( 35.64150636403998362, 191.9836673600688357, 103.9000245735707608 ) ) ; -#12155 = DIRECTION ( 'NONE', ( -0.0005884949961245180021, 0.2249510543439046939, -0.9743698870671267942 ) ) ; -#12157 = VERTEX_POINT ( 'NONE', #473 ) ; -#12158 = ADVANCED_FACE ( 'NONE', ( #21964 ), #28943, .F. ) ; -#12159 = ORIENTED_EDGE ( 'NONE', *, *, #36505, .T. ) ; -#12160 = CARTESIAN_POINT ( 'NONE', ( 38.58922224453577599, 118.4807708069047294, 89.66244680221666385 ) ) ; -#12161 = EDGE_LOOP ( 'NONE', ( #33583, #38807, #10548, #11752 ) ) ; -#12162 = CARTESIAN_POINT ( 'NONE', ( 3.083319845196999864, 209.7208286977000000, 76.19224769502000072 ) ) ; -#12163 = CARTESIAN_POINT ( 'NONE', ( -26.74382575616715130, 120.3580507813137075, 171.5572023280520000 ) ) ; -#12164 = CARTESIAN_POINT ( 'NONE', ( 12.63909004533367764, 177.5096400689760685, 100.8691027646205498 ) ) ; -#12165 = ORIENTED_EDGE ( 'NONE', *, *, #20804, .T. ) ; -#12166 = AXIS2_PLACEMENT_3D ( 'NONE', #17104, #23883, #36342 ) ; -#12167 = ORIENTED_EDGE ( 'NONE', *, *, #36679, .F. ) ; -#12168 = ORIENTED_EDGE ( 'NONE', *, *, #23203, .F. ) ; -#12169 = AXIS2_PLACEMENT_3D ( 'NONE', #34156, #6150, #24589 ) ; -#12170 = ORIENTED_EDGE ( 'NONE', *, *, #14707, .T. ) ; -#12171 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971562349 ) ) ; -#12172 = FACE_OUTER_BOUND ( 'NONE', #9624, .T. ) ; -#12173 = LINE ( 'NONE', #6813, #25287 ) ; -#12174 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385906776 ) ) ; -#12175 = VERTEX_POINT ( 'NONE', #16009 ) ; -#12176 = VECTOR ( 'NONE', #28708, 1000.000000000000114 ) ; -#12177 = VERTEX_POINT ( 'NONE', #13166 ) ; -#12178 = ORIENTED_EDGE ( 'NONE', *, *, #13694, .F. ) ; -#12179 = CARTESIAN_POINT ( 'NONE', ( -2.938441475009767156, 191.9759150222000130, 101.9232220854079856 ) ) ; -#12180 = CARTESIAN_POINT ( 'NONE', ( 20.07272550364178798, 128.0187529663550663, 89.19625550058378849 ) ) ; -#12181 = EDGE_LOOP ( 'NONE', ( #825, #17157, #17286, #4749 ) ) ; -#12182 = DIRECTION ( 'NONE', ( 0.0002393071043249488713, 0.2255680020170700018, -0.9742273960416720779 ) ) ; -#12183 = EDGE_LOOP ( 'NONE', ( #36080, #11875, #28358, #9906 ) ) ; -#12184 = EDGE_LOOP ( 'NONE', ( #18244, #11341, #25429, #10652, #20482, #32207, #38788, #28477, #30792, #25954 ) ) ; -#12185 = CARTESIAN_POINT ( 'NONE', ( 19.84759055312880704, 148.9730819504834756, 184.3419776361884885 ) ) ; -#12186 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319356112900 ) ) ; -#12187 = EDGE_LOOP ( 'NONE', ( #4876, #19679, #14364, #20249, #20827, #24572, #25499, #20857, #39139, #5076, #15377 ) ) ; -#12188 = EDGE_CURVE ( 'NONE', #21074, #15849, #5444, .T. ) ; -#12189 = EDGE_CURVE ( 'NONE', #9483, #30394, #1212, .T. ) ; -#12190 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#12191 = CARTESIAN_POINT ( 'NONE', ( -15.91450692093356345, 126.1598053719804255, 88.78881894041531098 ) ) ; -#12192 = DIRECTION ( 'NONE', ( -1.586032892343862782E-14, -1.000000000000000000, 1.586032892343862782E-14 ) ) ; -#12193 = CARTESIAN_POINT ( 'NONE', ( -13.49052885539015278, 188.3420772061585353, 103.1432726234667427 ) ) ; -#12194 = EDGE_CURVE ( 'NONE', #5670, #10712, #29034, .T. ) ; -#12195 = AXIS2_PLACEMENT_3D ( 'NONE', #31461, #31254, #30864 ) ; -#12196 = EDGE_LOOP ( 'NONE', ( #33202, #36370, #3867, #17696 ) ) ; -#12197 = DIRECTION ( 'NONE', ( 0.7933532970003738249, 0.5930762008556724751, 0.1372995488602876402 ) ) ; -#12198 = CARTESIAN_POINT ( 'NONE', ( -30.07053858952056302, 176.7377855889365037, 103.0399784971898498 ) ) ; -#12199 = VECTOR ( 'NONE', #23126, 1000.000000000000000 ) ; -#12200 = CARTESIAN_POINT ( 'NONE', ( -38.02975100090999661, 118.2512589216999999, 87.84359524929000429 ) ) ; -#12201 = VECTOR ( 'NONE', #17956, 1000.000000000000114 ) ; -#12202 = CARTESIAN_POINT ( 'NONE', ( 37.58649206415999799, 117.1725957489999956, 89.52667883109999991 ) ) ; -#12203 = EDGE_CURVE ( 'NONE', #9411, #10555, #6091, .T. ) ; -#12204 = LINE ( 'NONE', #15466, #16722 ) ; -#12205 = ORIENTED_EDGE ( 'NONE', *, *, #24582, .T. ) ; -#12206 = VECTOR ( 'NONE', #38756, 1000.000000000000000 ) ; -#12207 = CARTESIAN_POINT ( 'NONE', ( -38.20662297452999923, 118.7287161886000035, 90.14649827262999793 ) ) ; -#12208 = EDGE_CURVE ( 'NONE', #21584, #29495, #20437, .T. ) ; -#12209 = CARTESIAN_POINT ( 'NONE', ( 5.675840488321574284, 188.3446150673902650, 103.1322824216947396 ) ) ; -#12210 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24963, #9213, #2679, #27443, #12079, #40066 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12211 = VERTEX_POINT ( 'NONE', #38093 ) ; -#12212 = FACE_OUTER_BOUND ( 'NONE', #11770, .T. ) ; -#12213 = CARTESIAN_POINT ( 'NONE', ( 15.99998378901094576, 184.9656665294078266, 102.3459542884652365 ) ) ; -#12214 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971579835 ) ) ; -#12215 = DIRECTION ( 'NONE', ( -0.0001408404391176450643, 0.2255194953501120092, -0.9742386449843803975 ) ) ; -#12216 = FACE_OUTER_BOUND ( 'NONE', #23568, .T. ) ; -#12217 = LINE ( 'NONE', #15083, #10218 ) ; -#12218 = ORIENTED_EDGE ( 'NONE', *, *, #37474, .F. ) ; -#12219 = DIRECTION ( 'NONE', ( 0.0004161288024535961770, 0.5299192578740949955, 0.8480479980348919478 ) ) ; -#12220 = CARTESIAN_POINT ( 'NONE', ( -24.13644154089634952, 149.3966794002155041, 197.0808772690376998 ) ) ; -#12221 = VECTOR ( 'NONE', #17846, 1000.000000000000114 ) ; -#12222 = VERTEX_POINT ( 'NONE', #37688 ) ; -#12223 = CARTESIAN_POINT ( 'NONE', ( 30.06909869252190148, 134.7508913421523289, 93.39317358598317753 ) ) ; -#12224 = VECTOR ( 'NONE', #37802, 1000.000000000000227 ) ; -#12225 = ORIENTED_EDGE ( 'NONE', *, *, #27629, .T. ) ; -#12226 = CARTESIAN_POINT ( 'NONE', ( 15.10588229656246639, 129.6118588884834537, 89.56705289901165656 ) ) ; -#12227 = CIRCLE ( 'NONE', #25953, 2.000000003952151051 ) ; -#12228 = FACE_OUTER_BOUND ( 'NONE', #24776, .T. ) ; -#12229 = ORIENTED_EDGE ( 'NONE', *, *, #22077, .T. ) ; -#12230 = CARTESIAN_POINT ( 'NONE', ( 35.64226591835503655, 192.1362045434372590, 106.8982047678648826 ) ) ; -#12231 = CARTESIAN_POINT ( 'NONE', ( 25.49063000826092562, 211.0902260967494897, 73.54299573436949800 ) ) ; -#12232 = CARTESIAN_POINT ( 'NONE', ( -38.25695912633000262, 118.9336418487000060, 90.29207677415999456 ) ) ; -#12233 = EDGE_CURVE ( 'NONE', #15042, #12808, #26331, .T. ) ; -#12234 = EDGE_CURVE ( 'NONE', #1497, #5410, #36765, .T. ) ; -#12235 = CARTESIAN_POINT ( 'NONE', ( 30.07127320806394977, 177.0037652588377739, 103.4184075945244388 ) ) ; -#12236 = CARTESIAN_POINT ( 'NONE', ( 22.00409069237373316, 127.5719638939032450, 179.3950931670769080 ) ) ; -#12237 = ORIENTED_EDGE ( 'NONE', *, *, #9653, .F. ) ; -#12238 = DIRECTION ( 'NONE', ( 0.0006039748319385504537, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#12239 = CARTESIAN_POINT ( 'NONE', ( 42.36531273491009841, 136.3168495591860392, 337.8274922784121941 ) ) ; -#12240 = CARTESIAN_POINT ( 'NONE', ( 37.96380763661293400, 191.4135383555317844, 104.3344495138068595 ) ) ; -#12241 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14984, #15386, #22754, #657 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12242 = CARTESIAN_POINT ( 'NONE', ( -16.53460274203917635, 121.8354022778151204, 177.5673403339679055 ) ) ; -#12243 = ORIENTED_EDGE ( 'NONE', *, *, #32612, .F. ) ; -#12244 = DIRECTION ( 'NONE', ( -6.167905692338912296E-15, -0.9743700557921579630, -0.2249510932971586219 ) ) ; -#12245 = CARTESIAN_POINT ( 'NONE', ( 12.31324332228320806, 135.0455449219146260, 90.99420773906884108 ) ) ; -#12246 = CARTESIAN_POINT ( 'NONE', ( 25.81316146412230594, 212.1057043653514427, 73.04291357969384535 ) ) ; -#12247 = FACE_OUTER_BOUND ( 'NONE', #35292, .T. ) ; -#12248 = CARTESIAN_POINT ( 'NONE', ( -25.71903582428170409, 189.5947562258769779, 106.0039061072679942 ) ) ; -#12249 = AXIS2_PLACEMENT_3D ( 'NONE', #28915, #13183, #25665 ) ; -#12250 = VECTOR ( 'NONE', #23775, 1000.000000000000114 ) ; -#12251 = CARTESIAN_POINT ( 'NONE', ( -35.38988506213597418, 77.14301703112144537, 290.1978808180363671 ) ) ; -#12252 = EDGE_CURVE ( 'NONE', #39292, #16264, #35437, .T. ) ; -#12253 = APPROVAL_STATUS ( 'not_yet_approved' ) ; -#12254 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#12255 = ORIENTED_EDGE ( 'NONE', *, *, #30837, .F. ) ; -#12256 = CARTESIAN_POINT ( 'NONE', ( -35.94604301394655010, 113.4338301994345386, 87.78258508858034759 ) ) ; -#12257 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524157562, 149.3470289647612219, 130.0514119197758305 ) ) ; -#12258 = CARTESIAN_POINT ( 'NONE', ( 62.08695490598599775, 78.64495961329345164, 282.5210433287024898 ) ) ; -#12259 = CARTESIAN_POINT ( 'NONE', ( 36.36530412196980677, 191.8376229407879805, 104.3480272023119824 ) ) ; -#12261 = ORIENTED_EDGE ( 'NONE', *, *, #22074, .T. ) ; -#12260 = CARTESIAN_POINT ( 'NONE', ( 35.95966625969001029, 191.1315741047999950, 106.9740560316000000 ) ) ; -#12262 = ORIENTED_EDGE ( 'NONE', *, *, #24829, .F. ) ; -#12263 = EDGE_LOOP ( 'NONE', ( #1287, #23797, #15754, #35588 ) ) ; -#12264 = CARTESIAN_POINT ( 'NONE', ( -5.652752471618317287, 134.9384505426030216, 90.80933139859830305 ) ) ; -#12265 = DIRECTION ( 'NONE', ( 0.0006039748319110907569, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#12266 = EDGE_CURVE ( 'NONE', #33548, #16187, #27658, .T. ) ; -#12267 = DIRECTION ( 'NONE', ( -7.677760455958669993E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#12268 = CARTESIAN_POINT ( 'NONE', ( 25.50041447495308233, 118.1134306400200416, 89.75249416949174019 ) ) ; -#12269 = ORIENTED_EDGE ( 'NONE', *, *, #29633, .T. ) ; -#12270 = CARTESIAN_POINT ( 'NONE', ( -38.74767328483999762, 119.4454340065999958, 90.48510276766000970 ) ) ; -#12271 = CARTESIAN_POINT ( 'NONE', ( -38.12831867127404450, 119.0711346055105793, 87.44068710121472066 ) ) ; -#12272 = CARTESIAN_POINT ( 'NONE', ( -15.99999263269153182, 160.7450692216915513, 96.77351201758563093 ) ) ; -#12273 = CARTESIAN_POINT ( 'NONE', ( -21.21281385531639430, 128.6733510584166140, 91.93807758298277122 ) ) ; -#12274 = CARTESIAN_POINT ( 'NONE', ( -15.74838202838000178, 144.4617537176999917, 95.83639389565999522 ) ) ; -#12275 = ORIENTED_EDGE ( 'NONE', *, *, #18837, .F. ) ; -#12276 = CARTESIAN_POINT ( 'NONE', ( 40.79660045530999923, 220.4002260649999982, 75.78386445958000195 ) ) ; -#12277 = CARTESIAN_POINT ( 'NONE', ( 23.36437573944527557, 176.9425577232293278, 103.3257217497975091 ) ) ; -#12278 = EDGE_CURVE ( 'NONE', #28042, #35389, #30501, .T. ) ; -#12279 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37831, #9843, #3677, #22314 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12280 = EDGE_CURVE ( 'NONE', #6206, #22776, #37786, .T. ) ; -#12281 = DIRECTION ( 'NONE', ( -0.0005884949961187157857, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#12282 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251384259, 134.5978788018760497, 93.30392147953956794 ) ) ; -#12283 = AXIS2_PLACEMENT_3D ( 'NONE', #20743, #8900, #20533 ) ; -#12284 = PLANE ( 'NONE', #13199 ) ; -#12285 = EDGE_CURVE ( 'NONE', #26219, #30625, #28315, .T. ) ; -#12286 = EDGE_LOOP ( 'NONE', ( #10948, #40398, #20462, #13181 ) ) ; -#12287 = CARTESIAN_POINT ( 'NONE', ( -26.13862405872000139, 191.6276511288999984, 103.7705029747000083 ) ) ; -#12288 = CARTESIAN_POINT ( 'NONE', ( 2.601069743092999875, 189.8879886073000023, 103.6444425284999937 ) ) ; -#12289 = FACE_OUTER_BOUND ( 'NONE', #17412, .T. ) ; -#12290 = ORIENTED_EDGE ( 'NONE', *, *, #37521, .F. ) ; -#12291 = CARTESIAN_POINT ( 'NONE', ( 3.667815741532966189, 126.2406713581920599, 91.36142183184406917 ) ) ; -#12292 = ORIENTED_EDGE ( 'NONE', *, *, #12921, .F. ) ; -#12293 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25551, #38590, #10003, #22481 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12294 = CARTESIAN_POINT ( 'NONE', ( 37.79502456659257348, 218.5902260770999987, 74.53567710821411652 ) ) ; -#12295 = CARTESIAN_POINT ( 'NONE', ( -20.01961944020480288, 207.8020456100749698, 73.42312337888193952 ) ) ; -#12296 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#12297 = CARTESIAN_POINT ( 'NONE', ( -12.63831731427420202, 134.4151836745020603, 93.62390314900453347 ) ) ; -#12298 = CARTESIAN_POINT ( 'NONE', ( -36.32609607807000174, 191.0210417671000016, 106.7202350431000042 ) ) ; -#12299 = ORIENTED_EDGE ( 'NONE', *, *, #12266, .F. ) ; -#12300 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#12301 = CIRCLE ( 'NONE', #14932, 40.50000000000954259 ) ; -#12302 = DIRECTION ( 'NONE', ( 0.7933532970003733809, 0.5930762008556731413, 0.1372995488602877234 ) ) ; -#12303 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971548194 ) ) ; -#12305 = LINE ( 'NONE', #28061, #17443 ) ; -#12304 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921577410, 0.2249510932971595101 ) ) ; -#12306 = ORIENTED_EDGE ( 'NONE', *, *, #9876, .T. ) ; -#12307 = EDGE_CURVE ( 'NONE', #4523, #7538, #21665, .T. ) ; -#12308 = CARTESIAN_POINT ( 'NONE', ( -3.870875394724502261, 175.2781318081764539, 100.4635098585889921 ) ) ; -#12309 = VERTEX_POINT ( 'NONE', #29499 ) ; -#12310 = CARTESIAN_POINT ( 'NONE', ( -26.93661275769384034, 123.1497222377761744, 91.17945632601555417 ) ) ; -#12311 = EDGE_CURVE ( 'NONE', #33189, #22702, #707, .T. ) ; -#12312 = CARTESIAN_POINT ( 'NONE', ( 1.222756636386816309, 140.3954820326998458, 157.8542268366375652 ) ) ; -#12313 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#12314 = CARTESIAN_POINT ( 'NONE', ( -21.82845866733090290, 176.0428982100538633, 102.8745730682872335 ) ) ; -#12315 = VERTEX_POINT ( 'NONE', #31972 ) ; -#12316 = ORIENTED_EDGE ( 'NONE', *, *, #33974, .T. ) ; -#12317 = DIRECTION ( 'NONE', ( 0.0004270746993296996698, 0.7071067811865993091, 0.7071066522152992251 ) ) ; -#12318 = EDGE_CURVE ( 'NONE', #3145, #7166, #8712, .T. ) ; -#12319 = ADVANCED_FACE ( 'NONE', ( #26648 ), #1496, .F. ) ; -#12320 = CARTESIAN_POINT ( 'NONE', ( 45.36467309445081497, 70.87416510410297121, 322.7139789007268291 ) ) ; -#12321 = DIRECTION ( 'NONE', ( -0.9914446600486714889, -0.1273122826259382445, -0.02879355402772584838 ) ) ; -#12322 = ADVANCED_FACE ( 'NONE', ( #29100 ), #10302, .T. ) ; -#12323 = EDGE_LOOP ( 'NONE', ( #35895, #21306, #9368, #33769 ) ) ; -#12324 = AXIS2_PLACEMENT_3D ( 'NONE', #12502, #12123, #28266 ) ; -#12325 = CARTESIAN_POINT ( 'NONE', ( 6.034202883963867059, 175.3568768315410011, 100.1305289580489557 ) ) ; -#12326 = EDGE_CURVE ( 'NONE', #31407, #23412, #35394, .T. ) ; -#12327 = CARTESIAN_POINT ( 'NONE', ( 3.199984553827000422, 190.8627815815999895, 106.9328179595000137 ) ) ; -#12328 = AXIS2_PLACEMENT_3D ( 'NONE', #26085, #28740, #32015 ) ; -#12329 = ORIENTED_EDGE ( 'NONE', *, *, #7893, .T. ) ; -#12330 = EDGE_LOOP ( 'NONE', ( #9124, #2465, #25284, #32224 ) ) ; -#12331 = CARTESIAN_POINT ( 'NONE', ( 3.051314052528018905, 190.5208653972618436, 106.7217979537678758 ) ) ; -#12332 = CIRCLE ( 'NONE', #33201, 17.00000000000405009 ) ; -#12333 = CARTESIAN_POINT ( 'NONE', ( 13.49907723755937106, 124.5624338866822001, 88.66815556345785865 ) ) ; -#12334 = CYLINDRICAL_SURFACE ( 'NONE', #31359, 4.000000000000000000 ) ; -#12335 = CARTESIAN_POINT ( 'NONE', ( 22.49999746303471682, 151.9741732817970217, 94.72226965095939022 ) ) ; -#12336 = EDGE_LOOP ( 'NONE', ( #9606, #24115, #6326, #24467 ) ) ; -#12337 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989940797, 0.1373964268091562024 ) ) ; -#12338 = FACE_OUTER_BOUND ( 'NONE', #33236, .T. ) ; -#12339 = EDGE_LOOP ( 'NONE', ( #6837, #15134, #24215, #4592 ) ) ; -#12340 = DIRECTION ( 'NONE', ( 0.0005884949961280472970, -0.2249510543439049715, 0.9743698870671265722 ) ) ; -#12341 = VERTEX_POINT ( 'NONE', #34993 ) ; -#12343 = CARTESIAN_POINT ( 'NONE', ( 0.5626164669235433902, 188.9999987160578598, 103.6843922204118940 ) ) ; -#12342 = CARTESIAN_POINT ( 'NONE', ( -10.89647426556150833, 124.3650862926009779, 88.37149036441144290 ) ) ; -#12344 = ORIENTED_EDGE ( 'NONE', *, *, #38625, .T. ) ; -#12345 = VERTEX_POINT ( 'NONE', #10502 ) ; -#12346 = CARTESIAN_POINT ( 'NONE', ( 25.49081330879218044, 207.9931395123781215, 73.86028207133186640 ) ) ; -#12347 = VERTEX_POINT ( 'NONE', #29707 ) ; -#12348 = CARTESIAN_POINT ( 'NONE', ( 3.090413119796000085, 209.7016413904999865, 76.19244424849999575 ) ) ; -#12349 = EDGE_CURVE ( 'NONE', #11263, #20341, #7005, .T. ) ; -#12350 = AXIS2_PLACEMENT_3D ( 'NONE', #23398, #36261, #5173 ) ; -#12351 = CARTESIAN_POINT ( 'NONE', ( 15.59457679776800276, 126.7501638806706126, 179.2035388441636030 ) ) ; -#12352 = AXIS2_PLACEMENT_3D ( 'NONE', #26388, #20428, #10851 ) ; -#12353 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#12354 = ORIENTED_EDGE ( 'NONE', *, *, #39628, .F. ) ; -#12355 = ORIENTED_EDGE ( 'NONE', *, *, #15722, .T. ) ; -#12356 = CIRCLE ( 'NONE', #15618, 9.999999999999996447 ) ; -#12357 = EDGE_LOOP ( 'NONE', ( #13406, #3340, #1868, #24563 ) ) ; -#12358 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971560961 ) ) ; -#12359 = EDGE_CURVE ( 'NONE', #6112, #7629, #16407, .T. ) ; -#12360 = PLANE ( 'NONE', #19391 ) ; -#12361 = CARTESIAN_POINT ( 'NONE', ( 2.780936256401183027, 209.6646845776446639, 73.22349160306428928 ) ) ; -#12362 = EDGE_CURVE ( 'NONE', #1613, #38340, #8039, .T. ) ; -#12363 = VERTEX_POINT ( 'NONE', #22967 ) ; -#12364 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36669, #9074, #2533, #15002 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12365 = ORIENTED_EDGE ( 'NONE', *, *, #9973, .T. ) ; -#12366 = DIRECTION ( 'NONE', ( -0.6974360921310663874, 0.000000000000000000, 0.7166469824069217065 ) ) ; -#12367 = LINE ( 'NONE', #2770, #35027 ) ; -#12368 = CARTESIAN_POINT ( 'NONE', ( -26.93797805943999890, 123.8239009188999944, 88.25611663338999335 ) ) ; -#12369 = EDGE_CURVE ( 'NONE', #37610, #10990, #11313, .T. ) ; -#12370 = EDGE_LOOP ( 'NONE', ( #30935, #1986, #36112, #35541 ) ) ; -#12371 = CARTESIAN_POINT ( 'NONE', ( -6.035970131895957103, 134.2433943441971849, 93.72800934087076996 ) ) ; -#12372 = CARTESIAN_POINT ( 'NONE', ( -10.03626368673879909, 143.6497483427974089, 95.38890159966688032 ) ) ; -#12373 = EDGE_LOOP ( 'NONE', ( #17723, #21380, #37319, #33136 ) ) ; -#12374 = CARTESIAN_POINT ( 'NONE', ( 6.035541027891230925, 134.8446529991751390, 93.34637782540107764 ) ) ; -#12375 = LINE ( 'NONE', #9317, #9853 ) ; -#12376 = CARTESIAN_POINT ( 'NONE', ( -15.97823384701243654, 126.4186299334870682, 88.84861179911453632 ) ) ; -#12377 = VECTOR ( 'NONE', #23433, 999.9999999999998863 ) ; -#12378 = CARTESIAN_POINT ( 'NONE', ( -44.92182064607283820, 181.3727636826805849, 101.7243074837133463 ) ) ; -#12379 = CARTESIAN_POINT ( 'NONE', ( -13.49368727016981317, 188.3420864354374942, 103.1432701936051330 ) ) ; -#12380 = AXIS2_PLACEMENT_3D ( 'NONE', #29844, #11429, #1617 ) ; -#12381 = ORIENTED_EDGE ( 'NONE', *, *, #34047, .T. ) ; -#12382 = CARTESIAN_POINT ( 'NONE', ( -38.95487693986203936, 209.7096538831000316, 76.08203239908557691 ) ) ; -#12383 = ORIENTED_EDGE ( 'NONE', *, *, #37145, .F. ) ; -#12384 = CARTESIAN_POINT ( 'NONE', ( 42.09376931258240262, 76.09060330161743479, 288.9541785520312942 ) ) ; -#12385 = DIRECTION ( 'NONE', ( 0.0005884949961215158462, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#12386 = CONICAL_SURFACE ( 'NONE', #8482, 2.503000005691713437, 0.7853981633624692593 ) ; -#12387 = CARTESIAN_POINT ( 'NONE', ( 36.19070910591000256, 112.4013982383000041, 89.61166937401999633 ) ) ; -#12388 = VERTEX_POINT ( 'NONE', #26242 ) ; -#12389 = DIRECTION ( 'NONE', ( -6.560328681078656304E-13, -0.9743700555413093989, -0.2249510943837032262 ) ) ; -#12390 = ORIENTED_EDGE ( 'NONE', *, *, #4633, .T. ) ; -#12391 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #2455, #14917, #27204, #15125 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 6.279468620546222901, 9.421061274136016905 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.3333333333333330373, 0.3333333333333330373, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#12392 = CARTESIAN_POINT ( 'NONE', ( -13.49852954174878050, 185.3437907798762012, 105.0168226363017823 ) ) ; -#12393 = ORIENTED_EDGE ( 'NONE', *, *, #16046, .T. ) ; -#12394 = ADVANCED_FACE ( 'NONE', ( #23164 ), #35594, .F. ) ; -#12395 = CARTESIAN_POINT ( 'NONE', ( 25.53626815854681098, 191.3673954314083119, 104.3312944428767253 ) ) ; -#12396 = EDGE_CURVE ( 'NONE', #35551, #27237, #11096, .T. ) ; -#12397 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#12398 = CARTESIAN_POINT ( 'NONE', ( -37.29435884442529670, 164.6092402323636463, 198.2106787237848948 ) ) ; -#12399 = ADVANCED_FACE ( 'NONE', ( #39289 ), #36440, .T. ) ; -#12400 = CARTESIAN_POINT ( 'NONE', ( -3.587237990978591196, 174.6869248071862728, 103.0110717490532863 ) ) ; -#12401 = ADVANCED_FACE ( 'NONE', ( #20902 ), #30259, .F. ) ; -#12402 = CARTESIAN_POINT ( 'NONE', ( -0.4540625018068648600, 211.4999999999330385, 76.05877887195120479 ) ) ; -#12403 = ORIENTED_EDGE ( 'NONE', *, *, #24940, .T. ) ; -#12404 = ORIENTED_EDGE ( 'NONE', *, *, #18800, .T. ) ; -#12406 = AXIS2_PLACEMENT_3D ( 'NONE', #37813, #37220, #25165 ) ; -#12405 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#12407 = CIRCLE ( 'NONE', #17617, 2.749999999947594809 ) ; -#12408 = LINE ( 'NONE', #28172, #3324 ) ; -#12409 = EDGE_CURVE ( 'NONE', #2748, #23210, #39697, .T. ) ; -#12410 = CIRCLE ( 'NONE', #15669, 9.499999999959616304 ) ; -#12411 = ORIENTED_EDGE ( 'NONE', *, *, #17107, .F. ) ; -#12412 = CARTESIAN_POINT ( 'NONE', ( 30.06907885326216956, 134.5379029013527372, 93.52626355848663309 ) ) ; -#12413 = AXIS2_PLACEMENT_3D ( 'NONE', #28000, #25132, #21247 ) ; -#12414 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.265515830298980555E-14, 0.9999998176071847045 ) ) ; -#12415 = EDGE_LOOP ( 'NONE', ( #5678, #29420, #25415, #33015 ) ) ; -#12416 = FACE_BOUND ( 'NONE', #29102, .T. ) ; -#12417 = ADVANCED_FACE ( 'NONE', ( #11292 ), #17975, .T. ) ; -#12418 = CARTESIAN_POINT ( 'NONE', ( 36.44436247437651133, 190.8511614233640330, 106.7712946021073606 ) ) ; -#12419 = VERTEX_POINT ( 'NONE', #39492 ) ; -#12420 = CARTESIAN_POINT ( 'NONE', ( 20.00179988782546303, 151.3105026749326498, 97.65252212824069034 ) ) ; -#12421 = LINE ( 'NONE', #14894, #32904 ) ; -#12422 = CARTESIAN_POINT ( 'NONE', ( -26.12776248260999878, 191.4935114680999959, 107.0493518302999973 ) ) ; -#12423 = DIRECTION ( 'NONE', ( -0.9914448496661262267, -0.1271951663094869345, -0.02930016617724677530 ) ) ; -#12424 = DIRECTION ( 'NONE', ( -0.0004161288024423686130, 0.8480480898092171982, -0.5299191110044603192 ) ) ; -#12425 = EDGE_LOOP ( 'NONE', ( #19387, #27381, #32611, #6939 ) ) ; -#12426 = CARTESIAN_POINT ( 'NONE', ( 20.00172860684155296, 119.4205927620089511, 90.29021467756710706 ) ) ; -#12427 = LINE ( 'NONE', #12239, #19231 ) ; -#12428 = CARTESIAN_POINT ( 'NONE', ( 41.20365586323013218, 166.2350915183740199, 182.1795392662229460 ) ) ; -#12429 = CARTESIAN_POINT ( 'NONE', ( -46.09104340708901759, 125.3201889036950121, 91.70237867473788640 ) ) ; -#12430 = VERTEX_POINT ( 'NONE', #8444 ) ; -#12431 = CARTESIAN_POINT ( 'NONE', ( 35.54748823936935764, 207.8686442304273783, 77.25557267514689386 ) ) ; -#12432 = CARTESIAN_POINT ( 'NONE', ( -28.47589466077455356, 181.0102030230047774, 104.5385275604374868 ) ) ; -#12433 = LINE ( 'NONE', #5703, #11133 ) ; -#12434 = CARTESIAN_POINT ( 'NONE', ( 12.63858367850300901, 181.2871484996189224, 104.3452895154150610 ) ) ; -#12435 = VECTOR ( 'NONE', #17433, 1000.000000000000000 ) ; -#12436 = VECTOR ( 'NONE', #9159, 1000.000000000000000 ) ; -#12437 = CARTESIAN_POINT ( 'NONE', ( 43.13643525274928692, 121.2996634179292244, 90.62573206238681678 ) ) ; -#12438 = CARTESIAN_POINT ( 'NONE', ( -36.05289769043999826, 191.5977046145999907, 104.0138136777000000 ) ) ; -#12439 = CARTESIAN_POINT ( 'NONE', ( -27.14198910785439622, 187.2709762456960334, 105.4665680530039964 ) ) ; -#12440 = AXIS2_PLACEMENT_3D ( 'NONE', #17160, #35546, #7359 ) ; -#12441 = VECTOR ( 'NONE', #436, 999.9999999999998863 ) ; -#12442 = CARTESIAN_POINT ( 'NONE', ( -12.63996651235540902, 181.7913221907940056, 101.7730704815222111 ) ) ; -#12443 = CARTESIAN_POINT ( 'NONE', ( 4.661812031426219249, 181.8946891593557496, 101.6438055088770938 ) ) ; -#12444 = ORIENTED_EDGE ( 'NONE', *, *, #28884, .T. ) ; -#12445 = CARTESIAN_POINT ( 'NONE', ( 20.79310939989340667, 105.5805168952036865, 87.25522577498226440 ) ) ; -#12446 = DIRECTION ( 'NONE', ( 0.0005559617641628925759, -0.3907311284886304525, 0.9205046855592415866 ) ) ; -#12447 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; -#12448 = CYLINDRICAL_SURFACE ( 'NONE', #644, 40.00000000000000000 ) ; -#12449 = CARTESIAN_POINT ( 'NONE', ( 36.67679961381649179, 191.6498457339000367, 104.3241930055519902 ) ) ; -#12450 = EDGE_CURVE ( 'NONE', #24015, #410, #36845, .T. ) ; -#12451 = ORIENTED_EDGE ( 'NONE', *, *, #37508, .F. ) ; -#12452 = CARTESIAN_POINT ( 'NONE', ( 36.48844669939000340, 190.9983962132999977, 106.6711395593000020 ) ) ; -#12453 = ORIENTED_EDGE ( 'NONE', *, *, #1364, .T. ) ; -#12454 = ORIENTED_EDGE ( 'NONE', *, *, #4, .F. ) ; -#12455 = CARTESIAN_POINT ( 'NONE', ( -5.886983627058991253, 134.9177829378408546, 90.80470137495024119 ) ) ; -#12456 = CARTESIAN_POINT ( 'NONE', ( -20.00017858637951207, 184.9560350789418237, 102.3655360699851400 ) ) ; -#12457 = CARTESIAN_POINT ( 'NONE', ( -35.79114221331672496, 138.5178166623233267, 284.1865182878368046 ) ) ; -#12458 = LINE ( 'NONE', #27827, #12224 ) ; -#12459 = ORIENTED_EDGE ( 'NONE', *, *, #26815, .T. ) ; -#12460 = CARTESIAN_POINT ( 'NONE', ( 36.19901194252000209, 191.5845064965000120, 103.9677379098999950 ) ) ; -#12461 = VECTOR ( 'NONE', #823, 1000.000000000000000 ) ; -#12462 = CARTESIAN_POINT ( 'NONE', ( -29.20280672789058585, 163.6356169074005038, 97.44881913872031021 ) ) ; -#12463 = CARTESIAN_POINT ( 'NONE', ( 3.534206243108678702, 168.5015396740323581, 98.55243403413919623 ) ) ; -#12464 = DIRECTION ( 'NONE', ( 0.9999998175395372613, 1.407738652158796084E-07, -0.0006040868085093890937 ) ) ; -#12465 = EDGE_LOOP ( 'NONE', ( #6761, #35183, #34498, #10216 ) ) ; -#12466 = DIRECTION ( 'NONE', ( -0.0006039748319391171662, -1.156185249762965862E-14, -0.9999998176071845934 ) ) ; -#12467 = DIRECTION ( 'NONE', ( -0.9999998268370372534, -0.0001323821189253526732, 0.0005734116061135543282 ) ) ; -#12468 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#12469 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319392994206 ) ) ; -#12470 = ORIENTED_EDGE ( 'NONE', *, *, #15151, .F. ) ; -#12471 = EDGE_CURVE ( 'NONE', #37217, #38178, #27185, .T. ) ; -#12472 = CARTESIAN_POINT ( 'NONE', ( 41.48445246824149990, 178.0501759457868047, 154.4334962872288486 ) ) ; -#12473 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21998, #38322, #13191, #35023 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12474 = CARTESIAN_POINT ( 'NONE', ( 1.549369715379940171, 189.2660695586559996, 103.7710140332699922 ) ) ; -#12475 = CARTESIAN_POINT ( 'NONE', ( 21.70411919715960636, 123.1894919172633820, 176.5216962859745138 ) ) ; -#12476 = ORIENTED_EDGE ( 'NONE', *, *, #24386, .F. ) ; -#12477 = CARTESIAN_POINT ( 'NONE', ( -3.787401097931438976, 136.7351866886963307, 94.04403444543387991 ) ) ; -#12478 = ORIENTED_EDGE ( 'NONE', *, *, #20100, .F. ) ; -#12479 = DIRECTION ( 'NONE', ( 0.7933532411498429582, 0.5931841216338330502, 0.1368328637372506207 ) ) ; -#12480 = CARTESIAN_POINT ( 'NONE', ( 20.00075430379012431, 195.1419555450835901, 105.8098312386177611 ) ) ; -#12481 = AXIS2_PLACEMENT_3D ( 'NONE', #6970, #14538, #10666 ) ; -#12482 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700561807850935, -0.2249510916138304228 ) ) ; -#12483 = VECTOR ( 'NONE', #4261, 1000.000000000000114 ) ; -#12484 = LINE ( 'NONE', #28836, #34382 ) ; -#12485 = AXIS2_PLACEMENT_3D ( 'NONE', #38765, #16887, #10785 ) ; -#12486 = FACE_OUTER_BOUND ( 'NONE', #14291, .T. ) ; -#12487 = FACE_OUTER_BOUND ( 'NONE', #26029, .T. ) ; -#12488 = CARTESIAN_POINT ( 'NONE', ( -36.62664004177000265, 191.5516215956000110, 106.2738151150000050 ) ) ; -#12489 = ORIENTED_EDGE ( 'NONE', *, *, #20573, .F. ) ; -#12490 = DIRECTION ( 'NONE', ( 1.110223024658119567E-14, 0.9743700557921588512, 0.2249510932971552357 ) ) ; -#12491 = CARTESIAN_POINT ( 'NONE', ( 18.96935628814378205, 149.0855185795807358, 180.7389095938138723 ) ) ; -#12492 = PLANE ( 'NONE', #13115 ) ; -#12493 = EDGE_CURVE ( 'NONE', #8120, #35545, #3591, .T. ) ; -#12494 = EDGE_CURVE ( 'NONE', #36048, #24997, #17612, .T. ) ; -#12496 = CARTESIAN_POINT ( 'NONE', ( 45.34583945090627566, 78.07328829186270980, 291.5311561844757193 ) ) ; -#12495 = CYLINDRICAL_SURFACE ( 'NONE', #37602, 4.999999999999990230 ) ; -#12497 = EDGE_LOOP ( 'NONE', ( #4849, #11145, #23600, #26347 ) ) ; -#12498 = EDGE_CURVE ( 'NONE', #10320, #33584, #23982, .T. ) ; -#12499 = ORIENTED_EDGE ( 'NONE', *, *, #17365, .F. ) ; -#12500 = ORIENTED_EDGE ( 'NONE', *, *, #533, .T. ) ; -#12501 = LINE ( 'NONE', #19228, #2198 ) ; -#12502 = CARTESIAN_POINT ( 'NONE', ( -35.43925701460831590, 191.9759150222000130, 101.9428517635840308 ) ) ; -#12503 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319378242551 ) ) ; -#12504 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971521271 ) ) ; -#12505 = CARTESIAN_POINT ( 'NONE', ( -5.669876885524050891, 185.9078784969169647, 102.5734907446166488 ) ) ; -#12506 = ORIENTED_EDGE ( 'NONE', *, *, #17648, .T. ) ; -#12507 = CARTESIAN_POINT ( 'NONE', ( 3.667815741540035646, 183.5629855103865964, 104.5953232250576406 ) ) ; -#12508 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8890, #15014, #2747, #6004, #24639, #74 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 3.469446951953614189E-18, 0.0003816501766251246077, 0.0007633003532502457460 ), - .UNSPECIFIED. ) ; -#12509 = ORIENTED_EDGE ( 'NONE', *, *, #4426, .T. ) ; -#12510 = DIRECTION ( 'NONE', ( 0.0001408404346086777274, -0.2255194953558356530, 0.9742386449830560124 ) ) ; -#12511 = AXIS2_PLACEMENT_3D ( 'NONE', #6772, #10477, #15982 ) ; -#12512 = CARTESIAN_POINT ( 'NONE', ( -38.94514605625099080, 127.5103311478221428, 92.19343525405152207 ) ) ; -#12513 = ORIENTED_EDGE ( 'NONE', *, *, #25489, .T. ) ; -#12514 = EDGE_CURVE ( 'NONE', #27328, #1942, #33767, .T. ) ; -#12515 = DIRECTION ( 'NONE', ( 0.0005884950030978173272, -0.2249510543490929049, 0.9743698870659246447 ) ) ; -#12516 = CARTESIAN_POINT ( 'NONE', ( 3.019577864247297683, 190.5696393177559855, 103.6475677936285393 ) ) ; -#12517 = CARTESIAN_POINT ( 'NONE', ( -26.01010085237201608, 207.3561686807771025, 73.63559236472087832 ) ) ; -#12518 = CARTESIAN_POINT ( 'NONE', ( -23.36405564437416160, 181.2107043992663193, 104.4107232363765405 ) ) ; -#12519 = VERTEX_POINT ( 'NONE', #27265 ) ; -#12520 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#12521 = ORIENTED_EDGE ( 'NONE', *, *, #24096, .F. ) ; -#12522 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34920, #4256, #19404, #13681, #20001, #16925, #29230, #6936, #16338, #28824, #1204, #26172, #13289, #38610, #7134, #38221, #10231, #22700, #39416, #14900 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000276168, 0.1875000000000308087, 0.2187500000000323630, 0.2343750000000343892, 0.2500000000000363598, 0.5000000000000545120, 0.6250000000000563993, 0.6875000000000517364, 0.7187500000000448530, 0.7343750000000406342, 0.7500000000000364153, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12523 = CARTESIAN_POINT ( 'NONE', ( 13.49908594566202247, 124.5584662421294411, 88.66180599625475622 ) ) ; -#12524 = DIRECTION ( 'NONE', ( 0.6087614810001803489, -0.7729390313185898753, -0.1788147452386047442 ) ) ; -#12525 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250614502, 179.6252109630515861, 101.6466942236996545 ) ) ; -#12526 = ADVANCED_FACE ( 'NONE', ( #39902 ), #14575, .F. ) ; -#12527 = ORIENTED_EDGE ( 'NONE', *, *, #17883, .T. ) ; -#12528 = CARTESIAN_POINT ( 'NONE', ( -26.00034782847161097, 118.8155664120999973, 94.28348912735243914 ) ) ; -#12529 = CARTESIAN_POINT ( 'NONE', ( 25.01965291402757074, 130.5048960499642874, 90.28039427238843473 ) ) ; -#12530 = ADVANCED_FACE ( 'NONE', ( #14367 ), #24398, .F. ) ; -#12531 = ORIENTED_EDGE ( 'NONE', *, *, #36305, .T. ) ; -#12532 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; -#12533 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2648, #27796, #17742, #2036 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12534 = CARTESIAN_POINT ( 'NONE', ( 3.333124212584731350, 128.5496412282928134, 89.49999704006384604 ) ) ; -#12535 = EDGE_CURVE ( 'NONE', #37266, #24828, #17273, .T. ) ; -#12536 = AXIS2_PLACEMENT_3D ( 'NONE', #30694, #5742, #9223 ) ; -#12537 = EDGE_CURVE ( 'NONE', #32614, #23325, #19293, .T. ) ; -#12539 = CARTESIAN_POINT ( 'NONE', ( -12.63633280681442450, 127.9091152082197596, 92.26961196159911083 ) ) ; -#12538 = CARTESIAN_POINT ( 'NONE', ( 36.28391671458184931, 191.9163365515095450, 104.3733954516321205 ) ) ; -#12540 = EDGE_CURVE ( 'NONE', #26136, #35217, #30442, .T. ) ; -#12541 = ORIENTED_EDGE ( 'NONE', *, *, #1459, .F. ) ; -#12542 = VECTOR ( 'NONE', #33847, 1000.000000000000114 ) ; -#12543 = CARTESIAN_POINT ( 'NONE', ( 25.49062705787940430, 209.2715578566350985, 73.54304421361712230 ) ) ; -#12544 = EDGE_CURVE ( 'NONE', #7316, #25177, #2299, .T. ) ; -#12545 = AXIS2_PLACEMENT_3D ( 'NONE', #10209, #29208, #35099 ) ; -#12546 = EDGE_LOOP ( 'NONE', ( #12984, #22394, #32576, #23357 ) ) ; -#12547 = CARTESIAN_POINT ( 'NONE', ( -14.78542069845082807, 129.1241041573916561, 89.98565157148227911 ) ) ; -#12548 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#12549 = ORIENTED_EDGE ( 'NONE', *, *, #29537, .T. ) ; -#12550 = ORIENTED_EDGE ( 'NONE', *, *, #26635, .T. ) ; -#12551 = FACE_OUTER_BOUND ( 'NONE', #31286, .T. ) ; -#12552 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684999950, 226.4002260771010810, 75.57961659099107976 ) ) ; -#12553 = CARTESIAN_POINT ( 'NONE', ( 36.46831602377621806, 265.1087381855853664, 205.0355407830140848 ) ) ; -#12554 = FACE_OUTER_BOUND ( 'NONE', #36985, .T. ) ; -#12555 = VERTEX_POINT ( 'NONE', #21530 ) ; -#12556 = ORIENTED_EDGE ( 'NONE', *, *, #24110, .T. ) ; -#12557 = ORIENTED_EDGE ( 'NONE', *, *, #36164, .F. ) ; -#12558 = PLANE ( 'NONE', #6302 ) ; -#12559 = CARTESIAN_POINT ( 'NONE', ( 20.48129703347667530, 210.1695351468016213, 75.54578054753540073 ) ) ; -#12560 = CYLINDRICAL_SURFACE ( 'NONE', #3926, 2.000000000000014655 ) ; -#12561 = ORIENTED_EDGE ( 'NONE', *, *, #20337, .F. ) ; -#12562 = CARTESIAN_POINT ( 'NONE', ( -26.58079033504462885, 156.9880731489196535, 180.0252060707828434 ) ) ; -#12563 = CARTESIAN_POINT ( 'NONE', ( -28.70875734540877389, 163.5999644878620245, 97.95344188170561495 ) ) ; -#12564 = VERTEX_POINT ( 'NONE', #19021 ) ; -#12565 = AXIS2_PLACEMENT_3D ( 'NONE', #3605, #16289, #9568 ) ; -#12566 = CARTESIAN_POINT ( 'NONE', ( 3.931232797397531620, 174.7711649246031698, 102.6726659245351669 ) ) ; -#12567 = CARTESIAN_POINT ( 'NONE', ( -5.667065257250070154, 187.5516406194990964, 105.8752373800145250 ) ) ; -#12568 = VECTOR ( 'NONE', #7342, 1000.000000000000227 ) ; -#12569 = CARTESIAN_POINT ( 'NONE', ( 15.05323202847136876, 135.9260618574729165, 94.10374647281754790 ) ) ; -#12570 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178630073228E-05, 0.0002331579774917273760 ) ) ; -#12571 = ADVANCED_FACE ( 'NONE', ( #9643 ), #3616, .F. ) ; -#12572 = ORIENTED_EDGE ( 'NONE', *, *, #34270, .T. ) ; -#12573 = DIRECTION ( 'NONE', ( 0.0006039748319381496242, 1.231904546584163304E-14, 0.9999998176071845934 ) ) ; -#12574 = ORIENTED_EDGE ( 'NONE', *, *, #30483, .F. ) ; -#12575 = CARTESIAN_POINT ( 'NONE', ( 34.60472611796191700, 77.14301703111517838, 291.5376435477833184 ) ) ; -#12576 = CARTESIAN_POINT ( 'NONE', ( -12.59997215317999952, 114.0103269030000064, 152.4718672074000381 ) ) ; -#12577 = CARTESIAN_POINT ( 'NONE', ( 38.28154465117000171, 117.9980501572999998, 89.51170082983999521 ) ) ; -#12578 = EDGE_CURVE ( 'NONE', #4594, #23181, #12111, .T. ) ; -#12579 = CARTESIAN_POINT ( 'NONE', ( -28.47344760044883216, 181.6851202344923308, 101.6154648382260035 ) ) ; -#12580 = ORIENTED_EDGE ( 'NONE', *, *, #30924, .T. ) ; -#12581 = CARTESIAN_POINT ( 'NONE', ( -37.83642973982261282, 190.5638649247831324, 106.5787699739197194 ) ) ; -#12582 = ORIENTED_EDGE ( 'NONE', *, *, #19324, .T. ) ; -#12583 = ADVANCED_FACE ( 'NONE', ( #37445 ), #8222, .T. ) ; -#12584 = PLANE ( 'NONE', #4689 ) ; -#12585 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10028, #9232, #28437, #3670, #6146, #12480, #413, #16155, #38028, #22512 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.1624485751913120335, 0.3718364313934839904, 0.5812242875956560306, 0.7906121437978279598, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12586 = FACE_OUTER_BOUND ( 'NONE', #31239, .T. ) ; -#12587 = EDGE_CURVE ( 'NONE', #13011, #18476, #19219, .T. ) ; -#12588 = AXIS2_PLACEMENT_3D ( 'NONE', #5014, #29971, #1968 ) ; -#12589 = CARTESIAN_POINT ( 'NONE', ( 3.501239785661707238, 126.2036380141990435, 91.52403092931761819 ) ) ; -#12590 = ORIENTED_EDGE ( 'NONE', *, *, #12639, .F. ) ; -#12591 = CARTESIAN_POINT ( 'NONE', ( 37.84431823005125040, 145.7926053428699333, 287.8095652956209847 ) ) ; -#12592 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#12593 = CARTESIAN_POINT ( 'NONE', ( -32.93322112599078366, 163.3558671954971544, 188.7454894968532244 ) ) ; -#12594 = CARTESIAN_POINT ( 'NONE', ( 9.991643147283999937, 184.7670343400000377, 28.07991271570000080 ) ) ; -#12595 = AXIS2_PLACEMENT_3D ( 'NONE', #10751, #29557, #14018 ) ; -#12596 = ORIENTED_EDGE ( 'NONE', *, *, #11935, .F. ) ; -#12597 = CARTESIAN_POINT ( 'NONE', ( -37.91235354210377295, 118.6199237442390313, 90.29068295074328887 ) ) ; -#12598 = EDGE_LOOP ( 'NONE', ( #5660, #36830 ) ) ; -#12599 = VERTEX_POINT ( 'NONE', #2894 ) ; -#12600 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.295171136338797037E-14 ) ) ; -#12601 = AXIS2_PLACEMENT_3D ( 'NONE', #2281, #24167, #2079 ) ; -#12602 = DIRECTION ( 'NONE', ( -0.7947983679126053858, 0.5912140607310470974, 0.1369725839625021979 ) ) ; -#12603 = VERTEX_POINT ( 'NONE', #15375 ) ; -#12604 = CARTESIAN_POINT ( 'NONE', ( 22.78079353263602869, 153.8098031058628692, 95.66210622315543333 ) ) ; -#12605 = CARTESIAN_POINT ( 'NONE', ( -31.19629630733280123, 110.6131156702000027, 90.28662662044676779 ) ) ; -#12606 = ORIENTED_EDGE ( 'NONE', *, *, #854, .F. ) ; -#12607 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927789280832, 0.0005734119022080210902 ) ) ; -#12608 = CARTESIAN_POINT ( 'NONE', ( -20.24985248663000093, 167.5688041279000231, 98.60803583700000274 ) ) ; -#12609 = LINE ( 'NONE', #21832, #2548 ) ; -#12610 = CARTESIAN_POINT ( 'NONE', ( -30.07188603208757627, 134.6282626475015718, 93.49931109589789457 ) ) ; -#12611 = EDGE_LOOP ( 'NONE', ( #50, #12404, #4958, #28066 ) ) ; -#12612 = CARTESIAN_POINT ( 'NONE', ( 28.42171666135000052, 125.3747123081999888, 88.75240862220999816 ) ) ; -#12613 = CARTESIAN_POINT ( 'NONE', ( -0.4015619331524885594, 189.0000000000001705, 162.9824824844031923 ) ) ; -#12614 = DIRECTION ( 'NONE', ( 0.0005884949961247478529, -0.2249510543439059707, 0.9743698870671264611 ) ) ; -#12615 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16093, #12426, #25321, #13041 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12616 = LINE ( 'NONE', #18341, #8509 ) ; -#12617 = CARTESIAN_POINT ( 'NONE', ( 6.026693642215255053, 134.9199437178238838, 90.79804054718465522 ) ) ; -#12618 = ORIENTED_EDGE ( 'NONE', *, *, #32122, .F. ) ; -#12619 = CARTESIAN_POINT ( 'NONE', ( -14.02928418406383493, 177.4085734206051370, 100.6193928479417821 ) ) ; -#12620 = LINE ( 'NONE', #25124, #12091 ) ; -#12621 = VECTOR ( 'NONE', #15264, 1000.000000000000114 ) ; -#12622 = CARTESIAN_POINT ( 'NONE', ( -30.17790789685632546, 126.0796628920969624, 91.85784452133538025 ) ) ; -#12623 = ADVANCED_FACE ( 'NONE', ( #28060 ), #34363, .T. ) ; -#12624 = ADVANCED_FACE ( 'NONE', ( #427 ), #33002, .F. ) ; -#12625 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#12626 = EDGE_CURVE ( 'NONE', #1454, #26218, #22166, .T. ) ; -#12627 = VERTEX_POINT ( 'NONE', #18415 ) ; -#12628 = CIRCLE ( 'NONE', #30262, 5.000000000000007994 ) ; -#12629 = CARTESIAN_POINT ( 'NONE', ( 38.48677490565238202, 119.0290109290786660, 90.25014311654231847 ) ) ; -#12630 = ADVANCED_FACE ( 'NONE', ( #223 ), #35581, .F. ) ; -#12631 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15247, #18681, #31588, #27548 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12632 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; -#12633 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319438170742 ) ) ; -#12634 = AXIS2_PLACEMENT_3D ( 'NONE', #23229, #1963, #17262 ) ; -#12635 = CARTESIAN_POINT ( 'NONE', ( -3.169881913554984720, 185.9062129263137138, 102.5746722649703315 ) ) ; -#12636 = CARTESIAN_POINT ( 'NONE', ( -35.90108692076000096, 191.4428160530999889, 103.7426355487000080 ) ) ; -#12637 = CARTESIAN_POINT ( 'NONE', ( -25.50472234486060330, 190.9264852796360117, 106.3095200974499903 ) ) ; -#12638 = ORIENTED_EDGE ( 'NONE', *, *, #8308, .T. ) ; -#12639 = EDGE_CURVE ( 'NONE', #16029, #37703, #11433, .T. ) ; -#12640 = CARTESIAN_POINT ( 'NONE', ( -19.44498782237791090, 147.7042974102395476, 183.5443419389730479 ) ) ; -#12641 = EDGE_CURVE ( 'NONE', #15470, #20231, #29976, .T. ) ; -#12642 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#12643 = DIRECTION ( 'NONE', ( 0.0006039748319385408043, -1.387778780781445676E-14, 0.9999998176071847045 ) ) ; -#12644 = VERTEX_POINT ( 'NONE', #22120 ) ; -#12645 = FACE_OUTER_BOUND ( 'NONE', #5229, .T. ) ; -#12646 = DIRECTION ( 'NONE', ( 0.6087614115766663003, -0.7730004587899187429, -0.1785492494684860765 ) ) ; -#12647 = CARTESIAN_POINT ( 'NONE', ( 18.58912714118548237, 148.0271172827300177, 184.1229846802908128 ) ) ; -#12648 = CARTESIAN_POINT ( 'NONE', ( 37.96500512368779567, 190.9590560386920401, 106.3030183870149870 ) ) ; -#12649 = CARTESIAN_POINT ( 'NONE', ( 36.28049130005999956, 190.7845793118999893, 106.9053359681000046 ) ) ; -#12650 = VERTEX_POINT ( 'NONE', #3476 ) ; -#12651 = ORIENTED_EDGE ( 'NONE', *, *, #28113, .F. ) ; -#12652 = ORIENTED_EDGE ( 'NONE', *, *, #312, .F. ) ; -#12653 = ADVANCED_FACE ( 'NONE', ( #3093 ), #14772, .T. ) ; -#12654 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#12655 = AXIS2_PLACEMENT_3D ( 'NONE', #23649, #36098, #8101 ) ; -#12656 = CARTESIAN_POINT ( 'NONE', ( -14.55294119842380063, 130.1498083917327904, 89.70916153464222020 ) ) ; -#12657 = AXIS2_PLACEMENT_3D ( 'NONE', #34990, #23318, #264 ) ; -#12658 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971560129 ) ) ; -#12659 = ORIENTED_EDGE ( 'NONE', *, *, #27859, .T. ) ; -#12660 = CARTESIAN_POINT ( 'NONE', ( -1.207315383879569826, 135.0326567407394123, 181.1141214092984910 ) ) ; -#12661 = AXIS2_PLACEMENT_3D ( 'NONE', #28446, #423, #12300 ) ; -#12662 = EDGE_LOOP ( 'NONE', ( #20454, #37305, #5626, #28351 ) ) ; -#12663 = CARTESIAN_POINT ( 'NONE', ( 36.02454694495000354, 114.4457312457000171, 87.61277106880000076 ) ) ; -#12664 = AXIS2_PLACEMENT_3D ( 'NONE', #39658, #5515, #7120 ) ; -#12665 = CARTESIAN_POINT ( 'NONE', ( -14.78542071362066679, 136.5876434558166750, 91.70874570386088465 ) ) ; -#12666 = CARTESIAN_POINT ( 'NONE', ( -36.85476990611584824, 191.5514496331472571, 104.3846969233319584 ) ) ; -#12667 = ORIENTED_EDGE ( 'NONE', *, *, #19120, .F. ) ; -#12668 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#12669 = CARTESIAN_POINT ( 'NONE', ( -43.30038974941377461, 190.4174923657541285, 106.7193308803196601 ) ) ; -#12670 = CARTESIAN_POINT ( 'NONE', ( 26.03373140117899709, 191.5260202047026041, 103.8544635878054976 ) ) ; -#12671 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; -#12672 = CARTESIAN_POINT ( 'NONE', ( -9.336298582408000257, 134.5427877351000063, 93.54254700600999684 ) ) ; -#12673 = CARTESIAN_POINT ( 'NONE', ( -38.95668886436793343, 209.7096538830999748, 73.08203294638809666 ) ) ; -#12674 = ORIENTED_EDGE ( 'NONE', *, *, #13776, .F. ) ; -#12675 = VERTEX_POINT ( 'NONE', #33964 ) ; -#12676 = CARTESIAN_POINT ( 'NONE', ( 42.42192200091505327, 180.1607944338011862, 148.5017479457221441 ) ) ; -#12677 = CARTESIAN_POINT ( 'NONE', ( 1.316965049921220210, 189.1517910606459907, 103.7366099239109900 ) ) ; -#12678 = LINE ( 'NONE', #37031, #33192 ) ; -#12679 = ADVANCED_FACE ( 'NONE', ( #15956 ), #12495, .T. ) ; -#12680 = ORIENTED_EDGE ( 'NONE', *, *, #7127, .F. ) ; -#12681 = FACE_OUTER_BOUND ( 'NONE', #35001, .T. ) ; -#12682 = ADVANCED_FACE ( 'NONE', ( #37841 ), #16693, .F. ) ; -#12683 = ORIENTED_EDGE ( 'NONE', *, *, #27156, .F. ) ; -#12684 = CONICAL_SURFACE ( 'NONE', #11462, 2.503100609244825581, 0.7853981633679828489 ) ; -#12685 = CARTESIAN_POINT ( 'NONE', ( -40.95638651213572956, 220.4002260740000168, 73.58324080466404382 ) ) ; -#12686 = CONICAL_SURFACE ( 'NONE', #25113, 2.503000016660633875, 0.7853981634016408142 ) ; -#12687 = VECTOR ( 'NONE', #29598, 1000.000000000000227 ) ; -#12688 = PLANE ( 'NONE', #39108 ) ; -#12689 = EDGE_CURVE ( 'NONE', #15505, #9438, #16167, .T. ) ; -#12690 = LINE ( 'NONE', #16156, #12568 ) ; -#12691 = VECTOR ( 'NONE', #21262, 999.9999999999998863 ) ; -#12692 = CARTESIAN_POINT ( 'NONE', ( -12.63221799298840864, 177.0485776882449045, 103.5236562007907253 ) ) ; -#12693 = DIRECTION ( 'NONE', ( -0.6974360921310663874, 0.000000000000000000, 0.7166469824069217065 ) ) ; -#12694 = EDGE_CURVE ( 'NONE', #8209, #24036, #23217, .T. ) ; -#12695 = CARTESIAN_POINT ( 'NONE', ( -2.317981455665000023, 208.9360348893000037, 73.76998536309000087 ) ) ; -#12696 = CARTESIAN_POINT ( 'NONE', ( -1.414596400301315615, 189.2545725590069878, 105.8118447122918724 ) ) ; -#12697 = ORIENTED_EDGE ( 'NONE', *, *, #6038, .F. ) ; -#12698 = CARTESIAN_POINT ( 'NONE', ( 35.56237296993458585, 191.9759150222000130, 101.8999685582081582 ) ) ; -#12699 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319385852566 ) ) ; -#12700 = CARTESIAN_POINT ( 'NONE', ( 42.85442617173308832, 113.6598254356972149, 123.5406245648973993 ) ) ; -#12701 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4224, #16891, #29596, #35691 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12702 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921569638, -0.2249510932971630905 ) ) ; -#12703 = ORIENTED_EDGE ( 'NONE', *, *, #6901, .T. ) ; -#12704 = EDGE_CURVE ( 'NONE', #10196, #18677, #36780, .T. ) ; -#12705 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12272, #2862, #34127, #40464 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12706 = VERTEX_POINT ( 'NONE', #4285 ) ; -#12707 = LINE ( 'NONE', #26205, #3674 ) ; -#12708 = ORIENTED_EDGE ( 'NONE', *, *, #18022, .F. ) ; -#12709 = AXIS2_PLACEMENT_3D ( 'NONE', #3821, #10389, #16694 ) ; -#12710 = PLANE ( 'NONE', #16220 ) ; -#12711 = CARTESIAN_POINT ( 'NONE', ( -38.36472071045999854, 118.8248333581999958, 87.72051653428999884 ) ) ; -#12712 = CIRCLE ( 'NONE', #18558, 2.499999999928080641 ) ; -#12713 = AXIS2_PLACEMENT_3D ( 'NONE', #23348, #22549, #10282 ) ; -#12714 = DIRECTION ( 'NONE', ( 0.0004270953949661438322, 0.7071067811864922836, 0.7071066522029061385 ) ) ; -#12715 = ORIENTED_EDGE ( 'NONE', *, *, #8641, .T. ) ; -#12716 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33379, #16476, #28966, #25918 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12717 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#12718 = ORIENTED_EDGE ( 'NONE', *, *, #13565, .F. ) ; -#12719 = DIRECTION ( 'NONE', ( 0.0006039748319389621253, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#12720 = CONICAL_SURFACE ( 'NONE', #23812, 2.503079361083045296, 0.7853981633955212649 ) ; -#12721 = CARTESIAN_POINT ( 'NONE', ( -35.95556595676193723, 218.5902260770999987, 73.58022043445957650 ) ) ; -#12722 = CARTESIAN_POINT ( 'NONE', ( 39.71644276554569331, 128.0354526761064164, 94.31825870285607039 ) ) ; -#12723 = ORIENTED_EDGE ( 'NONE', *, *, #31200, .T. ) ; -#12724 = DIRECTION ( 'NONE', ( -0.0005884949961230211525, 0.2249510543439048049, -0.9743698870671267942 ) ) ; -#12725 = CARTESIAN_POINT ( 'NONE', ( 1.881914426046564559, 188.9882964918864729, 103.2831730894914841 ) ) ; -#12726 = CARTESIAN_POINT ( 'NONE', ( 13.85386899177591680, 154.7523313006220747, 161.1669414970386356 ) ) ; -#12727 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#12728 = ORIENTED_EDGE ( 'NONE', *, *, #33318, .F. ) ; -#12729 = EDGE_CURVE ( 'NONE', #25569, #9483, #13448, .T. ) ; -#12730 = VERTEX_POINT ( 'NONE', #7761 ) ; -#12731 = CARTESIAN_POINT ( 'NONE', ( 3.995985193436066396, 151.9650325797582013, 28.08107861490884716 ) ) ; -#12732 = CARTESIAN_POINT ( 'NONE', ( -36.38548184428417898, 111.7974789269056402, 175.7340771781224475 ) ) ; -#12733 = EDGE_CURVE ( 'NONE', #17327, #3510, #6892, .T. ) ; -#12734 = ORIENTED_EDGE ( 'NONE', *, *, #26774, .T. ) ; -#12735 = CARTESIAN_POINT ( 'NONE', ( 20.50044205129516328, 117.7855619557941509, 89.75569409557486722 ) ) ; -#12736 = CARTESIAN_POINT ( 'NONE', ( -45.39606049366843621, 123.6566771517818637, 91.23024032489176705 ) ) ; -#12737 = CARTESIAN_POINT ( 'NONE', ( -26.20735541984999983, 121.1118354415000056, 90.84748486943999524 ) ) ; -#12738 = ORIENTED_EDGE ( 'NONE', *, *, #26448, .T. ) ; -#12739 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37875, #35185, #28874, #6580 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12740 = CARTESIAN_POINT ( 'NONE', ( -23.02059183176825741, 214.0904033191889084, 73.07235108223721909 ) ) ; -#12741 = CYLINDRICAL_SURFACE ( 'NONE', #27798, 7.000000000000007994 ) ; -#12742 = DIRECTION ( 'NONE', ( 0.0005884949961243167741, -0.2249510543353384351, 0.9743698870691043235 ) ) ; -#12743 = AXIS2_PLACEMENT_3D ( 'NONE', #39377, #24280, #1778 ) ; -#12744 = VECTOR ( 'NONE', #35164, 1000.000000000000114 ) ; -#12745 = AXIS2_PLACEMENT_3D ( 'NONE', #22801, #1105, #25271 ) ; -#12746 = ORIENTED_EDGE ( 'NONE', *, *, #6492, .F. ) ; -#12747 = CARTESIAN_POINT ( 'NONE', ( -22.78369572533207332, 147.9575508264125290, 94.33852688745618309 ) ) ; -#12748 = CARTESIAN_POINT ( 'NONE', ( 42.78873758771006663, 120.8665316288775102, 92.29373204621693105 ) ) ; -#12749 = VECTOR ( 'NONE', #25159, 1000.000000000000227 ) ; -#12751 = CARTESIAN_POINT ( 'NONE', ( 35.66812328572578394, 191.9358431683554898, 103.8995260772395000 ) ) ; -#12750 = CARTESIAN_POINT ( 'NONE', ( -35.98817295377529746, 191.5260130662397273, 103.8919236801626340 ) ) ; -#12752 = ORIENTED_EDGE ( 'NONE', *, *, #14594, .F. ) ; -#12753 = ADVANCED_FACE ( 'NONE', ( #26390 ), #36945, .F. ) ; -#12754 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #31094, #34139 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12755 = LINE ( 'NONE', #34602, #26841 ) ; -#12756 = EDGE_LOOP ( 'NONE', ( #12470, #26300, #1469, #19727 ) ) ; -#12757 = FACE_OUTER_BOUND ( 'NONE', #30636, .T. ) ; -#12758 = CARTESIAN_POINT ( 'NONE', ( 38.46700359482129272, 118.8212168396402717, 87.67371270529410765 ) ) ; -#12759 = LINE ( 'NONE', #9495, #18811 ) ; -#12760 = VERTEX_POINT ( 'NONE', #20226 ) ; -#12761 = EDGE_LOOP ( 'NONE', ( #12957, #3395, #17134, #16143 ) ) ; -#12762 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#12763 = CARTESIAN_POINT ( 'NONE', ( 45.87579465106376375, 187.3127717824060312, 105.4163742558925065 ) ) ; -#12764 = FACE_OUTER_BOUND ( 'NONE', #31573, .T. ) ; -#12765 = CARTESIAN_POINT ( 'NONE', ( 21.96459776557462007, 135.5515918021118011, 90.93420605039376881 ) ) ; -#12766 = CARTESIAN_POINT ( 'NONE', ( 36.13357069258000109, 191.6670482327000116, 104.0248038887000206 ) ) ; -#12767 = EDGE_LOOP ( 'NONE', ( #10744, #25024, #36054, #37558 ) ) ; -#12768 = ADVANCED_FACE ( 'NONE', ( #32123 ), #23900, .T. ) ; -#12769 = ORIENTED_EDGE ( 'NONE', *, *, #37502, .F. ) ; -#12770 = CARTESIAN_POINT ( 'NONE', ( 16.66545457307292111, 121.3218471137176095, 173.8434147940178320 ) ) ; -#12771 = DIRECTION ( 'NONE', ( 2.312964634635739900E-15, 0.9743700557921587402, 0.2249510932971554578 ) ) ; -#12772 = VECTOR ( 'NONE', #5769, 1000.000000000000227 ) ; -#12773 = DIRECTION ( 'NONE', ( -0.0005884949961181157882, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#12774 = EDGE_CURVE ( 'NONE', #39699, #5859, #38833, .T. ) ; -#12775 = ORIENTED_EDGE ( 'NONE', *, *, #34274, .T. ) ; -#12776 = LINE ( 'NONE', #31386, #19300 ) ; -#12777 = CARTESIAN_POINT ( 'NONE', ( -25.82475235543668290, 191.8548145595347592, 104.1003246049598516 ) ) ; -#12778 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#12779 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16557, #38842, #38441, #10658, #830, #10863, #1640, #38249, #23520, #29459 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999381606, 0.3749999999998667177, 0.4374999999998712696, 0.4999999999998757660, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12780 = VERTEX_POINT ( 'NONE', #38435 ) ; -#12781 = CIRCLE ( 'NONE', #6230, 2.000000003776789548 ) ; -#12782 = VECTOR ( 'NONE', #39722, 1000.000000000000000 ) ; -#12783 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30677, #12455, #12264, #380, #24956, #18766, #9400, #21874, #15331, #18978, #34316, #28219, #15717, #2671, #27824, #25345, #186, #34501, #15912, #28410 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000245637, 0.1875000000000348332, 0.2187500000000429934, 0.2343750000000467126, 0.2500000000000504596, 0.5000000000001307843, 0.6250000000001642020, 0.6875000000001809664, 0.7187500000001794120, 0.7343750000001696421, 0.7500000000001598721, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12784 = CIRCLE ( 'NONE', #2991, 2.000002475912143751 ) ; -#12785 = EDGE_CURVE ( 'NONE', #39550, #31534, #28648, .T. ) ; -#12786 = CARTESIAN_POINT ( 'NONE', ( -75.75833988736154367, 195.1192334286142227, 194.9863546504234080 ) ) ; -#12787 = EDGE_CURVE ( 'NONE', #37534, #31170, #19426, .T. ) ; -#12788 = ORIENTED_EDGE ( 'NONE', *, *, #32900, .F. ) ; -#12789 = CARTESIAN_POINT ( 'NONE', ( -14.13091635336139085, 124.4233634052935429, 88.38685240744268867 ) ) ; -#12790 = EDGE_CURVE ( 'NONE', #2217, #37526, #27025, .T. ) ; -#12791 = CARTESIAN_POINT ( 'NONE', ( -0.5977874941283000121, 188.5301565615999948, 106.1048331864000005 ) ) ; -#12792 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; -#12793 = VERTEX_POINT ( 'NONE', #25596 ) ; -#12794 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -5.029098237799274788E-18, 0.0006039748319384018096 ) ) ; -#12795 = ORIENTED_EDGE ( 'NONE', *, *, #26223, .F. ) ; -#12796 = CARTESIAN_POINT ( 'NONE', ( -3.589080272436853125, 149.3464402607426962, 130.0539584787920830 ) ) ; -#12797 = CARTESIAN_POINT ( 'NONE', ( -38.39983927658001051, 118.6516195866999936, 87.83943466679001233 ) ) ; -#12798 = CARTESIAN_POINT ( 'NONE', ( 19.71670726246199123, 125.1288345936551423, 175.0446023669997260 ) ) ; -#12799 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319392650514 ) ) ; -#12800 = ORIENTED_EDGE ( 'NONE', *, *, #22633, .F. ) ; -#12801 = DIRECTION ( 'NONE', ( 0.1943643238945209628, -0.07321898756438961764, 0.9781929714821464561 ) ) ; -#12802 = ORIENTED_EDGE ( 'NONE', *, *, #7770, .T. ) ; -#12803 = AXIS2_PLACEMENT_3D ( 'NONE', #3795, #16669, #935 ) ; -#12804 = CARTESIAN_POINT ( 'NONE', ( 43.53522428377826259, 122.0090548114814766, 87.79422213383789142 ) ) ; -#12805 = AXIS2_PLACEMENT_3D ( 'NONE', #15757, #6751, #31315 ) ; -#12806 = CARTESIAN_POINT ( 'NONE', ( 21.44693687352840783, 182.5616219828937687, 101.7876413893260974 ) ) ; -#12807 = ORIENTED_EDGE ( 'NONE', *, *, #32765, .F. ) ; -#12808 = VERTEX_POINT ( 'NONE', #23119 ) ; -#12809 = LINE ( 'NONE', #7055, #20560 ) ; -#12810 = LINE ( 'NONE', #16654, #37893 ) ; -#12811 = VECTOR ( 'NONE', #25618, 1000.000000000000114 ) ; -#12812 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#12813 = ORIENTED_EDGE ( 'NONE', *, *, #11343, .T. ) ; -#12814 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; -#12815 = VERTEX_POINT ( 'NONE', #10256 ) ; -#12816 = ORIENTED_EDGE ( 'NONE', *, *, #31157, .T. ) ; -#12817 = FACE_OUTER_BOUND ( 'NONE', #10905, .T. ) ; -#12818 = CARTESIAN_POINT ( 'NONE', ( -37.47349530422577857, 212.6956747321397074, 75.91447098462606391 ) ) ; -#12819 = DIRECTION ( 'NONE', ( 0.0005884949961229053597, -0.2249510543439064147, 0.9743698870671262391 ) ) ; -#12820 = EDGE_CURVE ( 'NONE', #23677, #20569, #22720, .T. ) ; -#12821 = ORIENTED_EDGE ( 'NONE', *, *, #35963, .T. ) ; -#12822 = CARTESIAN_POINT ( 'NONE', ( 19.98078417920676486, 207.3564579907497887, 73.60829347036683146 ) ) ; -#12823 = CARTESIAN_POINT ( 'NONE', ( -25.49272541574507756, 191.9759150222000130, 101.9368443076606781 ) ) ; -#12824 = ORIENTED_EDGE ( 'NONE', *, *, #124, .F. ) ; -#12825 = CARTESIAN_POINT ( 'NONE', ( 0.04412548967667000166, 9.379164112032999336E-13, 73.05847743171000275 ) ) ; -#12826 = ADVANCED_FACE ( 'NONE', ( #10452 ), #17323, .F. ) ; -#12827 = CARTESIAN_POINT ( 'NONE', ( -14.72161250470031035, 176.7237221642146778, 100.4617005973079671 ) ) ; -#12828 = VERTEX_POINT ( 'NONE', #31928 ) ; -#12829 = CARTESIAN_POINT ( 'NONE', ( 28.18914615730000151, 125.0573841749000081, 88.50759441822999918 ) ) ; -#12830 = EDGE_CURVE ( 'NONE', #22181, #28955, #25868, .T. ) ; -#12831 = AXIS2_PLACEMENT_3D ( 'NONE', #21590, #5627, #27732 ) ; -#12832 = CARTESIAN_POINT ( 'NONE', ( -12.15421709199686617, 125.0604765512531884, 178.7580882214065525 ) ) ; -#12833 = DIRECTION ( 'NONE', ( -1.713307136766813101E-15, 0.9743700557921585181, 0.2249510932971561239 ) ) ; -#12834 = CIRCLE ( 'NONE', #23247, 7.999999999957683627 ) ; -#12835 = CARTESIAN_POINT ( 'NONE', ( -35.45668950309346457, 209.7097078344999943, 73.07991903445761750 ) ) ; -#12836 = EDGE_CURVE ( 'NONE', #853, #7306, #4490, .T. ) ; -#12837 = CARTESIAN_POINT ( 'NONE', ( 22.16743659223149265, 158.3069173260788034, 96.18756534121445156 ) ) ; -#12838 = EDGE_CURVE ( 'NONE', #23690, #25663, #2179, .T. ) ; -#12839 = ORIENTED_EDGE ( 'NONE', *, *, #37164, .T. ) ; -#12840 = CARTESIAN_POINT ( 'NONE', ( 20.31780324046303221, 211.0873987128438500, 75.70971466294412267 ) ) ; -#12841 = ADVANCED_FACE ( 'NONE', ( #27432 ), #14123, .F. ) ; -#12842 = CARTESIAN_POINT ( 'NONE', ( -37.95406977588713460, 119.1353498738898651, 87.29774169588188215 ) ) ; -#12843 = CARTESIAN_POINT ( 'NONE', ( 23.36350214669958802, 176.7448593272447681, 103.0093387772721485 ) ) ; -#12844 = CIRCLE ( 'NONE', #35646, 59.40509898897001761 ) ; -#12845 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749385498, 179.6299767372515817, 101.6260513915996739 ) ) ; -#12846 = ORIENTED_EDGE ( 'NONE', *, *, #37027, .F. ) ; -#12847 = EDGE_LOOP ( 'NONE', ( #18628, #36866, #18939, #31881 ) ) ; -#12848 = FACE_OUTER_BOUND ( 'NONE', #6153, .T. ) ; -#12849 = CYLINDRICAL_SURFACE ( 'NONE', #4199, 2.250000000000011102 ) ; -#12850 = FACE_OUTER_BOUND ( 'NONE', #17007, .T. ) ; -#12851 = CARTESIAN_POINT ( 'NONE', ( 12.63858181338016173, 181.3023367127953520, 104.3357988664218823 ) ) ; -#12852 = CARTESIAN_POINT ( 'NONE', ( 14.42541055625604507, 182.6274970736112095, 101.9781413242667014 ) ) ; -#12853 = CARTESIAN_POINT ( 'NONE', ( -25.50335236864900068, 190.9443044115478187, 106.3136331412189008 ) ) ; -#12854 = ORIENTED_EDGE ( 'NONE', *, *, #7829, .F. ) ; -#12855 = DIRECTION ( 'NONE', ( -0.0006039748319383107366, -1.234791622901071989E-14, -0.9999998176071845934 ) ) ; -#12856 = DIRECTION ( 'NONE', ( -0.0005884949961242402295, 0.2249510543439063315, -0.9743698870671264611 ) ) ; -#12857 = CARTESIAN_POINT ( 'NONE', ( -12.63810003589398256, 137.3539737265348890, 91.36813903047330143 ) ) ; -#12858 = VERTEX_POINT ( 'NONE', #23513 ) ; -#12859 = CARTESIAN_POINT ( 'NONE', ( 27.29501362713000034, 103.8631156702000027, 90.00129928933000656 ) ) ; -#12860 = CARTESIAN_POINT ( 'NONE', ( 23.35435660873492125, 181.0170614477807476, 104.5088077577469221 ) ) ; -#12861 = CIRCLE ( 'NONE', #38325, 59.40509898896999630 ) ; -#12862 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557843820720, -0.2249510933308394578 ) ) ; -#12863 = CARTESIAN_POINT ( 'NONE', ( 36.36613122512999752, 191.7602783439000120, 105.7174599309999934 ) ) ; -#12864 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33047, #5036, #11599, #29995, #1993, #39785, #14463, #36530, #26946, #39380, #36329, #33242, #11801, #36727, #30609, #15070, #27569 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999178713, 0.1874999999998768208, 0.2187499999998250011, 0.2343749999997991051, 0.2499999999997732092, 0.3749999999998051003, 0.4374999999998210320, 0.4687499999998289701, 0.4999999999998369082, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12865 = AXIS2_PLACEMENT_3D ( 'NONE', #17665, #10747, #5000 ) ; -#12866 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#12867 = CARTESIAN_POINT ( 'NONE', ( 36.35871695389000280, 190.7175962013000117, 106.8891365664000119 ) ) ; -#12868 = VECTOR ( 'NONE', #15948, 1000.000000000000114 ) ; -#12869 = ORIENTED_EDGE ( 'NONE', *, *, #36650, .F. ) ; -#12870 = PLANE ( 'NONE', #2307 ) ; -#12871 = CARTESIAN_POINT ( 'NONE', ( -20.33561058857197068, 184.8849765532865206, 102.6939075168818221 ) ) ; -#12872 = ADVANCED_FACE ( 'NONE', ( #8392 ), #17350, .F. ) ; -#12873 = VECTOR ( 'NONE', #2516, 1000.000000000000114 ) ; -#12874 = EDGE_CURVE ( 'NONE', #25208, #37405, #1656, .T. ) ; -#12875 = CARTESIAN_POINT ( 'NONE', ( -2.455538055765680738, 209.0000002601700544, 73.61629604161946361 ) ) ; -#12876 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901496, 179.0675991013200701, 104.0619761093405771 ) ) ; -#12877 = VERTEX_POINT ( 'NONE', #2255 ) ; -#12878 = CARTESIAN_POINT ( 'NONE', ( 44.90072207509915359, 127.0650837324493523, 92.04000096660296037 ) ) ; -#12879 = EDGE_CURVE ( 'NONE', #11929, #14375, #17762, .T. ) ; -#12880 = VERTEX_POINT ( 'NONE', #8799 ) ; -#12881 = ADVANCED_FACE ( 'NONE', ( #2463 ), #1843, .F. ) ; -#12882 = CARTESIAN_POINT ( 'NONE', ( -3.255264691931540444, 129.2253544352344932, 89.48891097144958451 ) ) ; -#12883 = CARTESIAN_POINT ( 'NONE', ( -13.50000254471398264, 127.7447170053348771, 89.15018747604320026 ) ) ; -#12884 = EDGE_LOOP ( 'NONE', ( #7381, #27441, #40170, #33931 ) ) ; -#12885 = EDGE_CURVE ( 'NONE', #8372, #2746, #32567, .T. ) ; -#12886 = PLANE ( 'NONE', #14065 ) ; -#12887 = FACE_OUTER_BOUND ( 'NONE', #30974, .T. ) ; -#12888 = FACE_OUTER_BOUND ( 'NONE', #8142, .T. ) ; -#12889 = CARTESIAN_POINT ( 'NONE', ( 16.88249520720069441, 127.4209172357130342, 171.9069182253847430 ) ) ; -#12890 = EDGE_CURVE ( 'NONE', #34620, #23353, #33714, .T. ) ; -#12891 = EDGE_LOOP ( 'NONE', ( #17187, #26859, #3368, #2936 ) ) ; -#12892 = CARTESIAN_POINT ( 'NONE', ( 12.64059569365333324, 176.8205385886645331, 103.1388713076008372 ) ) ; -#12893 = DIRECTION ( 'NONE', ( 0.0002393071182785117316, 0.2252352986010040803, -0.9743043687658490271 ) ) ; -#12894 = DIRECTION ( 'NONE', ( 0.0001358647752418049677, 0.9743700647852354679, 0.2249510133144081714 ) ) ; -#12895 = VECTOR ( 'NONE', #21740, 1000.000000000000000 ) ; -#12896 = CARTESIAN_POINT ( 'NONE', ( -36.62841445464000145, 191.5124353941000095, 104.2533201470999984 ) ) ; -#12897 = ORIENTED_EDGE ( 'NONE', *, *, #19954, .F. ) ; -#12898 = FACE_OUTER_BOUND ( 'NONE', #27104, .T. ) ; -#12899 = ORIENTED_EDGE ( 'NONE', *, *, #25005, .T. ) ; -#12900 = VECTOR ( 'NONE', #20076, 1000.000000000000227 ) ; -#12901 = EDGE_CURVE ( 'NONE', #9552, #11960, #4096, .T. ) ; -#12902 = CARTESIAN_POINT ( 'NONE', ( -3.669581230397975791, 128.4724600144964484, 89.82849395191713882 ) ) ; -#12903 = CARTESIAN_POINT ( 'NONE', ( -28.53030869656295110, 124.6043131503039803, 91.51623810099293621 ) ) ; -#12904 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32032, #14017, #16463, #26494 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12905 = CARTESIAN_POINT ( 'NONE', ( -16.42363997277514898, 152.5170915174298329, 181.7137745456617495 ) ) ; -#12906 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#12907 = CARTESIAN_POINT ( 'NONE', ( 20.48231950984458649, 205.5677633305384120, 76.28703242847967658 ) ) ; -#12908 = CARTESIAN_POINT ( 'NONE', ( -1.469607249925116266, 189.2865446493801755, 105.8210556326310297 ) ) ; -#12909 = VERTEX_POINT ( 'NONE', #27217 ) ; -#12910 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#12911 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178617807513E-05, -0.0002331579774917555924 ) ) ; -#12912 = CARTESIAN_POINT ( 'NONE', ( 76.10689632611000377, 156.0355272971999909, 97.17005189866002013 ) ) ; -#12913 = CARTESIAN_POINT ( 'NONE', ( 15.99999439207489615, 185.9093013714976053, 102.5638074086867846 ) ) ; -#12914 = ORIENTED_EDGE ( 'NONE', *, *, #28210, .F. ) ; -#12915 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32452, #17694, #17287, #23860 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12916 = ORIENTED_EDGE ( 'NONE', *, *, #20155, .T. ) ; -#12917 = CARTESIAN_POINT ( 'NONE', ( 5.674778016381245571, 131.0223034755605909, 89.89838139801142347 ) ) ; -#12918 = ADVANCED_FACE ( 'NONE', ( #39848 ), #27215, .F. ) ; -#12919 = AXIS2_PLACEMENT_3D ( 'NONE', #6930, #38009, #28818 ) ; -#12920 = CARTESIAN_POINT ( 'NONE', ( -19.46394794124172023, 125.6806896231740751, 178.4345049239138064 ) ) ; -#12921 = EDGE_CURVE ( 'NONE', #22764, #8895, #23934, .T. ) ; -#12922 = EDGE_CURVE ( 'NONE', #14938, #36888, #18668, .T. ) ; -#12923 = CIRCLE ( 'NONE', #29883, 2.000000000000011546 ) ; -#12924 = ORIENTED_EDGE ( 'NONE', *, *, #14079, .F. ) ; -#12925 = CARTESIAN_POINT ( 'NONE', ( -15.46635816504221772, 147.8788101534005932, 152.4730815186126733 ) ) ; -#12926 = CARTESIAN_POINT ( 'NONE', ( 13.53173156088000084, 162.3883503090999909, 152.4718672074000381 ) ) ; -#12927 = DIRECTION ( 'NONE', ( -0.0005884949961235722525, 0.2249510543439049715, -0.9743698870671265722 ) ) ; -#12928 = CARTESIAN_POINT ( 'NONE', ( -38.14120756220999908, 119.0850948817000017, 87.44152985738000439 ) ) ; -#12929 = DIRECTION ( 'NONE', ( 0.0006039748319383739456, -3.094196748328522329E-15, 0.9999998176071845934 ) ) ; -#12930 = VERTEX_POINT ( 'NONE', #14124 ) ; -#12931 = ADVANCED_FACE ( 'NONE', ( #27005 ), #11448, .F. ) ; -#12932 = CARTESIAN_POINT ( 'NONE', ( 17.27144937936713376, 122.5454421133972289, 172.0731752994966541 ) ) ; -#12933 = ORIENTED_EDGE ( 'NONE', *, *, #7816, .F. ) ; -#12934 = LINE ( 'NONE', #9869, #9623 ) ; -#12935 = CARTESIAN_POINT ( 'NONE', ( -23.35635573182313607, 131.0183818788550241, 89.91503395410319399 ) ) ; -#12936 = EDGE_CURVE ( 'NONE', #40319, #29818, #20646, .T. ) ; -#12937 = ORIENTED_EDGE ( 'NONE', *, *, #36677, .T. ) ; -#12938 = PLANE ( 'NONE', #29804 ) ; -#12939 = CARTESIAN_POINT ( 'NONE', ( 0.8647791692335055069, 188.6306482529823256, 103.2012177966641815 ) ) ; -#12940 = CARTESIAN_POINT ( 'NONE', ( -26.01060144688746689, 209.2224318440115383, 73.07376367569236209 ) ) ; -#12941 = PLANE ( 'NONE', #27363 ) ; -#12942 = VERTEX_POINT ( 'NONE', #36393 ) ; -#12943 = ORIENTED_EDGE ( 'NONE', *, *, #12409, .T. ) ; -#12944 = CARTESIAN_POINT ( 'NONE', ( 20.27054642785542882, 118.1107986174901896, 87.52574972040859791 ) ) ; -#12945 = CARTESIAN_POINT ( 'NONE', ( -37.83775869347861942, 191.4135374006265806, 104.3802260088867513 ) ) ; -#12946 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28284, #12735, #25227, #37676, #9674, #22957, #2038, #14909, #33091, #29842 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12947 = ORIENTED_EDGE ( 'NONE', *, *, #23748, .T. ) ; -#12948 = PLANE ( 'NONE', #22564 ) ; -#12949 = CARTESIAN_POINT ( 'NONE', ( -13.50000253664885719, 151.9690088118221922, 94.74282098678578734 ) ) ; -#12950 = CARTESIAN_POINT ( 'NONE', ( -25.70074763801000017, 121.3279312843000071, 90.36970767171999341 ) ) ; -#12951 = CIRCLE ( 'NONE', #40360, 2.499999999874955137 ) ; -#12952 = ORIENTED_EDGE ( 'NONE', *, *, #22579, .F. ) ; -#12953 = CARTESIAN_POINT ( 'NONE', ( -16.55117160943531118, 121.8277038752011521, 177.5442054669605909 ) ) ; -#12954 = CARTESIAN_POINT ( 'NONE', ( 3.044162730076025447, 208.9211496123335507, 73.11923083669719858 ) ) ; -#12955 = CIRCLE ( 'NONE', #35759, 6.000000000011024071 ) ; -#12956 = CARTESIAN_POINT ( 'NONE', ( 41.04584544117999911, 220.4002260691000004, 74.53371369385999401 ) ) ; -#12957 = ORIENTED_EDGE ( 'NONE', *, *, #34092, .F. ) ; -#12958 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #34359, #19019 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.02271787902114467267, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#12959 = DIRECTION ( 'NONE', ( -0.7069397806862420808, 0.6508951186658792354, 0.2767159030128537589 ) ) ; -#12960 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#12962 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#12961 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319364164186 ) ) ; -#12963 = VERTEX_POINT ( 'NONE', #20852 ) ; -#12964 = CARTESIAN_POINT ( 'NONE', ( -48.18910981145552341, 141.1918910709570980, 290.9667924317506049 ) ) ; -#12965 = CARTESIAN_POINT ( 'NONE', ( -0.09191864964710037833, 291.0964424001293196, 217.1925188927256158 ) ) ; -#12966 = LINE ( 'NONE', #28701, #19497 ) ; -#12967 = EDGE_CURVE ( 'NONE', #25568, #35358, #37404, .T. ) ; -#12968 = EDGE_LOOP ( 'NONE', ( #35314, #28779, #36597, #1674 ) ) ; -#12969 = ADVANCED_FACE ( 'NONE', ( #28214 ), #14052, .F. ) ; -#12970 = VERTEX_POINT ( 'NONE', #16899 ) ; -#12971 = CYLINDRICAL_SURFACE ( 'NONE', #19153, 4.999999999999990230 ) ; -#12972 = AXIS2_PLACEMENT_3D ( 'NONE', #7368, #19825, #4298 ) ; -#12973 = DIRECTION ( 'NONE', ( 0.7075229308291650643, 0.000000000000000000, 0.7066903864854172657 ) ) ; -#12974 = DIRECTION ( 'NONE', ( -0.9999998268365983822, -0.0001323826716410795928, 0.0005734122438485214851 ) ) ; -#12975 = CARTESIAN_POINT ( 'NONE', ( 35.89709686227286056, 192.3543251505955141, 104.2022112152945965 ) ) ; -#12976 = ORIENTED_EDGE ( 'NONE', *, *, #40132, .F. ) ; -#12977 = CIRCLE ( 'NONE', #11691, 5.000000000000007994 ) ; -#12978 = ORIENTED_EDGE ( 'NONE', *, *, #6354, .F. ) ; -#12979 = CARTESIAN_POINT ( 'NONE', ( -6.036122723735069862, 176.7409673271154702, 103.0261968760796378 ) ) ; -#12980 = VECTOR ( 'NONE', #37633, 1000.000000000000114 ) ; -#12981 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#12982 = DIRECTION ( 'NONE', ( -0.0005884949961265727820, 0.2249510543439056931, -0.9743698870671265722 ) ) ; -#12983 = CIRCLE ( 'NONE', #11667, 2.000000000000011546 ) ; -#12984 = ORIENTED_EDGE ( 'NONE', *, *, #15875, .F. ) ; -#12985 = CARTESIAN_POINT ( 'NONE', ( -25.65798556230555505, 191.8454707520358227, 104.2666281073695984 ) ) ; -#12986 = EDGE_LOOP ( 'NONE', ( #30966, #31758, #2055, #21333 ) ) ; -#12987 = CARTESIAN_POINT ( 'NONE', ( -36.73835199021345943, 116.0420298664398757, 89.74139269884751968 ) ) ; -#12988 = ORIENTED_EDGE ( 'NONE', *, *, #35082, .T. ) ; -#12989 = FACE_OUTER_BOUND ( 'NONE', #40076, .T. ) ; -#12990 = ORIENTED_EDGE ( 'NONE', *, *, #16046, .F. ) ; -#12991 = CARTESIAN_POINT ( 'NONE', ( -37.28133731252471961, 166.8593197691344017, 188.5736935233141196 ) ) ; -#12992 = EDGE_CURVE ( 'NONE', #520, #15252, #4319, .T. ) ; -#12993 = CARTESIAN_POINT ( 'NONE', ( -2.303974314047999794, 190.8754367445000071, 106.1362474393000213 ) ) ; -#12994 = CARTESIAN_POINT ( 'NONE', ( -2.435784540106990192, 190.9902839124212335, 106.3131295316380545 ) ) ; -#12995 = ORIENTED_EDGE ( 'NONE', *, *, #37605, .F. ) ; -#12996 = CARTESIAN_POINT ( 'NONE', ( 22.78281254372720355, 153.7346105515276804, 98.21050616309901216 ) ) ; -#12997 = ORIENTED_EDGE ( 'NONE', *, *, #3663, .F. ) ; -#12998 = CARTESIAN_POINT ( 'NONE', ( 32.02693021685336561, 77.14301703111976849, 291.5392004719097372 ) ) ; -#12999 = FACE_OUTER_BOUND ( 'NONE', #18831, .T. ) ; -#13000 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #31207, #6447, #15657, #27961 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.603140784247877537, 4.612408630352550887 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9169010176874472506, 0.9169010176874472506, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#13001 = CARTESIAN_POINT ( 'NONE', ( 13.49642010767728095, 123.7543391407038769, 91.24249921288263465 ) ) ; -#13002 = VECTOR ( 'NONE', #13274, 1000.000000000000227 ) ; -#13003 = LINE ( 'NONE', #25485, #25892 ) ; -#13004 = ORIENTED_EDGE ( 'NONE', *, *, #9133, .T. ) ; -#13005 = EDGE_CURVE ( 'NONE', #10050, #39311, #29412, .T. ) ; -#13006 = CIRCLE ( 'NONE', #31926, 6.000000000154989799 ) ; -#13007 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#13008 = CIRCLE ( 'NONE', #35822, 22.00000000001089973 ) ; -#13009 = CARTESIAN_POINT ( 'NONE', ( -38.55398926386000369, 118.3669049012000016, 89.55270650478000505 ) ) ; -#13010 = EDGE_CURVE ( 'NONE', #12930, #20721, #11516, .T. ) ; -#13011 = VERTEX_POINT ( 'NONE', #1376 ) ; -#13012 = ORIENTED_EDGE ( 'NONE', *, *, #12058, .T. ) ; -#13013 = FACE_OUTER_BOUND ( 'NONE', #1933, .T. ) ; -#13014 = DIRECTION ( 'NONE', ( 0.0004161288024548960270, 0.5299192578740949955, 0.8480479980348919478 ) ) ; -#13015 = FACE_OUTER_BOUND ( 'NONE', #32596, .T. ) ; -#13016 = EDGE_CURVE ( 'NONE', #14032, #9488, #23596, .T. ) ; -#13017 = ADVANCED_FACE ( 'NONE', ( #10802 ), #34347, .F. ) ; -#13018 = CARTESIAN_POINT ( 'NONE', ( -0.4558744329272819695, 211.4999999999972431, 73.05877941915380802 ) ) ; -#13019 = ORIENTED_EDGE ( 'NONE', *, *, #39788, .T. ) ; -#13020 = VERTEX_POINT ( 'NONE', #4235 ) ; -#13021 = CARTESIAN_POINT ( 'NONE', ( 1.936912818046955476, 189.5456747395250545, 105.8934727691335382 ) ) ; -#13022 = LINE ( 'NONE', #28757, #30107 ) ; -#13023 = EDGE_CURVE ( 'NONE', #31407, #4383, #11347, .T. ) ; -#13024 = ORIENTED_EDGE ( 'NONE', *, *, #40, .T. ) ; -#13025 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#13026 = VERTEX_POINT ( 'NONE', #10602 ) ; -#13027 = DIRECTION ( 'NONE', ( 0.0006039748319385908944, 1.293414132305980107E-14, 0.9999998176071845934 ) ) ; -#13028 = CIRCLE ( 'NONE', #30009, 2.499999999899970682 ) ; -#13029 = CARTESIAN_POINT ( 'NONE', ( -39.82458058703250003, 191.0388296339007752, 103.7817683317120867 ) ) ; -#13030 = ORIENTED_EDGE ( 'NONE', *, *, #6758, .T. ) ; -#13031 = CARTESIAN_POINT ( 'NONE', ( 28.33128032238000316, 125.4735004498999871, 88.94656419544999437 ) ) ; -#13032 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10442, #22909, #1621, #1830 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13033 = VECTOR ( 'NONE', #20103, 1000.000000000000227 ) ; -#13034 = DIRECTION ( 'NONE', ( 0.6087614115774880874, -0.7730004600455407937, -0.1785492440296700956 ) ) ; -#13035 = AXIS2_PLACEMENT_3D ( 'NONE', #27428, #5301, #14730 ) ; -#13036 = CARTESIAN_POINT ( 'NONE', ( -20.00000588364686038, 174.5066637885302896, 99.95304239614711150 ) ) ; -#13037 = FACE_OUTER_BOUND ( 'NONE', #37792, .T. ) ; -#13038 = AXIS2_PLACEMENT_3D ( 'NONE', #29293, #32358, #8006 ) ; -#13039 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#13040 = VERTEX_POINT ( 'NONE', #13854 ) ; -#13041 = CARTESIAN_POINT ( 'NONE', ( 20.00175897098971589, 118.8155681873422651, 90.25573236258343002 ) ) ; -#13042 = CARTESIAN_POINT ( 'NONE', ( 1.084781822741140100, 189.0693601363920493, 103.7040955045087571 ) ) ; -#13043 = CARTESIAN_POINT ( 'NONE', ( -2.421071065100592001, 189.3597238620783685, 106.4504356505698013 ) ) ; -#13044 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7909, #8329, #4636, #5236 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13045 = PLANE ( 'NONE', #5336 ) ; -#13046 = DIRECTION ( 'NONE', ( -0.0004161288024286937878, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#13047 = CARTESIAN_POINT ( 'NONE', ( 13.55543936442901476, 163.9642746141201144, 100.5777837385402904 ) ) ; -#13048 = DIRECTION ( 'NONE', ( -0.0001408422045155705395, 0.2255194951287508853, -0.9742386450353663907 ) ) ; -#13049 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38751, #13825, #29574, #20148, #20770, #32439, #5217, #36093, #39569, #1975, #1761 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000963118, 0.3750000000000788258, 0.4375000000001090794, 0.4687500000001241784, 0.5000000000001392220, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13050 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #15203, #27691, #24825, #27896 ), - ( #12327, #37269, #9269, #3116 ), - ( #16978, #26020, #29478, #6984 ), - ( #26222, #32544, #31953, #34967 ), - ( #13334, #16788, #38268, #34775 ), - ( #13939, #35569, #32153, #26422 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 4 ), - ( 4, 4 ), - ( -0.01998966095620999944, 0.000000000000000000, 1.000000000000000000, 1.019805502689000054 ), - ( -3.010002734666000098E-05, 0.9999999646031000333 ), - .UNSPECIFIED. ) ; -#13051 = CARTESIAN_POINT ( 'NONE', ( -20.49893885638800128, 193.5513712071386863, 106.1813727900049571 ) ) ; -#13052 = CARTESIAN_POINT ( 'NONE', ( -25.70739151542000300, 190.4681821343999957, 106.3783065876999956 ) ) ; -#13053 = ORIENTED_EDGE ( 'NONE', *, *, #31754, .F. ) ; -#13054 = EDGE_CURVE ( 'NONE', #39862, #18015, #22599, .T. ) ; -#13055 = CARTESIAN_POINT ( 'NONE', ( -11.79198343374907054, 125.9681876107315333, 176.0676422622361770 ) ) ; -#13056 = CARTESIAN_POINT ( 'NONE', ( -12.64495593087849024, 181.7027899428717888, 101.6313931463716216 ) ) ; -#13057 = ADVANCED_FACE ( 'NONE', ( #28800 ), #26152, .F. ) ; -#13058 = AXIS2_PLACEMENT_3D ( 'NONE', #35409, #25859, #16817 ) ; -#13059 = ORIENTED_EDGE ( 'NONE', *, *, #37789, .T. ) ; -#13060 = CARTESIAN_POINT ( 'NONE', ( 21.74023251323743011, 115.9285818112440865, 87.75444016076374965 ) ) ; -#13061 = CARTESIAN_POINT ( 'NONE', ( -25.99148323931970594, 191.8512832710823091, 103.9333748356177978 ) ) ; -#13062 = VECTOR ( 'NONE', #5588, 1000.000000000000114 ) ; -#13063 = DIRECTION ( 'NONE', ( 0.7947985590179719173, -0.5913221741348984040, -0.1365039814779489546 ) ) ; -#13064 = CARTESIAN_POINT ( 'NONE', ( -20.01839671862364867, 211.0902260915352429, 76.07059681904712534 ) ) ; -#13065 = AXIS2_PLACEMENT_3D ( 'NONE', #36793, #20848, #8796 ) ; -#13066 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17487, #14448, #11584, #20986, #39772, #30389, #15058, #5027, #21948, #34392 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( -0.0009603588719864617927, 0.0001952418026493195910, 0.0007730421399672324006, 0.001061942308626189022, 0.001350842477285145535 ), - .UNSPECIFIED. ) ; -#13067 = EDGE_CURVE ( 'NONE', #21490, #39537, #26501, .T. ) ; -#13068 = EDGE_CURVE ( 'NONE', #7608, #1836, #6913, .T. ) ; -#13069 = CARTESIAN_POINT ( 'NONE', ( -21.10694955292148478, 136.4999052006739078, 91.52125896335103050 ) ) ; -#13070 = VERTEX_POINT ( 'NONE', #35100 ) ; -#13071 = EDGE_CURVE ( 'NONE', #40304, #38430, #2391, .T. ) ; -#13072 = CARTESIAN_POINT ( 'NONE', ( -2.370405409122252394, 209.5734236807777222, 75.55993826224245424 ) ) ; -#13073 = EDGE_CURVE ( 'NONE', #2542, #19255, #35637, .T. ) ; -#13074 = CARTESIAN_POINT ( 'NONE', ( 20.33262371326216567, 196.2720655916053261, 103.7314557283780232 ) ) ; -#13075 = DIRECTION ( 'NONE', ( -0.7933533411653341805, -0.5931840316264885837, -0.1368326740407639630 ) ) ; -#13076 = ORIENTED_EDGE ( 'NONE', *, *, #9351, .T. ) ; -#13077 = CARTESIAN_POINT ( 'NONE', ( 5.666342389698421300, 128.5870658017565233, 89.33308585708306282 ) ) ; -#13078 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #14791, #36447, #5363, #5973 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.832522679881611438, 4.832536753587069356 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999834942033, 0.9999999999834942033, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#13079 = VERTEX_POINT ( 'NONE', #8548 ) ; -#13080 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825955341562035, 0.0005734119015741466268 ) ) ; -#13081 = FACE_OUTER_BOUND ( 'NONE', #23531, .T. ) ; -#13082 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#13083 = CYLINDRICAL_SURFACE ( 'NONE', #12919, 51.40509898897001051 ) ; -#13084 = CARTESIAN_POINT ( 'NONE', ( -30.06924898906426691, 176.9473508903192283, 103.3753521668471507 ) ) ; -#13085 = PLANE ( 'NONE', #32140 ) ; -#13086 = VERTEX_POINT ( 'NONE', #7922 ) ; -#13087 = AXIS2_PLACEMENT_3D ( 'NONE', #27341, #36713, #21603 ) ; -#13088 = CARTESIAN_POINT ( 'NONE', ( 21.23573982155677697, 129.5657464465189150, 89.55270472066885645 ) ) ; -#13089 = AXIS2_PLACEMENT_3D ( 'NONE', #37259, #14793, #33977 ) ; -#13090 = CARTESIAN_POINT ( 'NONE', ( -18.98875009441257333, 125.3860450160050277, 176.2394239049030773 ) ) ; -#13091 = FACE_OUTER_BOUND ( 'NONE', #10788, .T. ) ; -#13092 = AXIS2_PLACEMENT_3D ( 'NONE', #38201, #38394, #35097 ) ; -#13093 = CONICAL_SURFACE ( 'NONE', #14, 2.502986300332882497, 0.7853981634574371817 ) ; -#13094 = CARTESIAN_POINT ( 'NONE', ( -22.78268303310043308, 158.0258324527692366, 98.88663196571921787 ) ) ; -#13095 = VERTEX_POINT ( 'NONE', #5046 ) ; -#13096 = FACE_OUTER_BOUND ( 'NONE', #14889, .T. ) ; -#13097 = VERTEX_POINT ( 'NONE', #26546 ) ; -#13098 = CARTESIAN_POINT ( 'NONE', ( -39.76913700811847718, 108.4405668372959468, 169.8253437122761795 ) ) ; -#13099 = EDGE_CURVE ( 'NONE', #16908, #31409, #5997, .T. ) ; -#13100 = CARTESIAN_POINT ( 'NONE', ( 37.96499143901794326, 190.9636352903536363, 106.2831835502989719 ) ) ; -#13101 = CARTESIAN_POINT ( 'NONE', ( 20.00178331300101320, 191.9758063960465790, 106.9093738487591736 ) ) ; -#13102 = LINE ( 'NONE', #15947, #5185 ) ; -#13103 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714601725811, 0.5299193037554699170 ) ) ; -#13104 = EDGE_CURVE ( 'NONE', #25100, #12107, #39664, .T. ) ; -#13105 = CARTESIAN_POINT ( 'NONE', ( 20.48162925447415716, 206.2142141259708694, 75.21199830249389606 ) ) ; -#13106 = CARTESIAN_POINT ( 'NONE', ( 38.66209724894999766, 118.3740667178000194, 89.51289815417000284 ) ) ; -#13107 = EDGE_LOOP ( 'NONE', ( #19022, #2054, #487, #28413 ) ) ; -#13108 = ADVANCED_FACE ( 'NONE', ( #17513 ), #4840, .T. ) ; -#13109 = CARTESIAN_POINT ( 'NONE', ( 19.71691057019783955, 124.7851487048555725, 176.5356473463300233 ) ) ; -#13110 = CARTESIAN_POINT ( 'NONE', ( -58.64525294468500505, 246.4771452095119741, 202.1493000143418328 ) ) ; -#13111 = CARTESIAN_POINT ( 'NONE', ( 3.045988519791387628, 209.1419319775010877, 76.13893608185537687 ) ) ; -#13112 = ORIENTED_EDGE ( 'NONE', *, *, #5909, .F. ) ; -#13113 = EDGE_CURVE ( 'NONE', #21410, #18912, #14473, .T. ) ; -#13114 = AXIS2_PLACEMENT_3D ( 'NONE', #39365, #26317, #32832 ) ; -#13115 = AXIS2_PLACEMENT_3D ( 'NONE', #37443, #3281, #9441 ) ; -#13116 = ORIENTED_EDGE ( 'NONE', *, *, #507, .T. ) ; -#13117 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; -#13118 = CIRCLE ( 'NONE', #2685, 8.499999999969023889 ) ; -#13119 = LINE ( 'NONE', #25800, #16699 ) ; -#13120 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18957, #24735, #6688, #6099 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13121 = VECTOR ( 'NONE', #18674, 1000.000000000000227 ) ; -#13122 = CARTESIAN_POINT ( 'NONE', ( 21.44693687352840783, 182.5616219828937687, 101.7876413893260974 ) ) ; -#13123 = ORIENTED_EDGE ( 'NONE', *, *, #38518, .T. ) ; -#13124 = CARTESIAN_POINT ( 'NONE', ( 44.00666834743777400, 122.5942585552269577, 87.99047523027837769 ) ) ; -#13125 = CARTESIAN_POINT ( 'NONE', ( -33.63391334482336958, 159.2148480992196937, 186.9798810687557875 ) ) ; -#13126 = CARTESIAN_POINT ( 'NONE', ( -38.75768410615999926, 118.9340794893000037, 89.91572363038000049 ) ) ; -#13127 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -3.486209987973606947E-16, -0.0006039748319386279742 ) ) ; -#13128 = DIRECTION ( 'NONE', ( 0.7856246208753498994, 0.6187034467937467808, 0.000000000000000000 ) ) ; -#13129 = VERTEX_POINT ( 'NONE', #14067 ) ; -#13130 = CARTESIAN_POINT ( 'NONE', ( -19.40408387590019501, 124.8181396720960237, 178.2503323773021293 ) ) ; -#13131 = ORIENTED_EDGE ( 'NONE', *, *, #29064, .F. ) ; -#13132 = DIRECTION ( 'NONE', ( 0.7933531821996063771, 0.5932639600174075545, 0.1364866368485285197 ) ) ; -#13133 = CARTESIAN_POINT ( 'NONE', ( -3.537737212824113353, 144.2088358181959222, 92.94829169108382416 ) ) ; -#13134 = CARTESIAN_POINT ( 'NONE', ( -2.454301921840380096, 209.0000005845445230, 75.66282330657800514 ) ) ; -#13135 = ORIENTED_EDGE ( 'NONE', *, *, #35404, .T. ) ; -#13136 = ORIENTED_EDGE ( 'NONE', *, *, #12874, .F. ) ; -#13137 = CARTESIAN_POINT ( 'NONE', ( -15.66646917381426718, 160.6657006905813034, 97.09708742826067862 ) ) ; -#13138 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33212, #1538, #17675, #29562 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.8698163993620108281, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13139 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001722, 123.6868832756552479, 91.30891139640304743 ) ) ; -#13140 = CARTESIAN_POINT ( 'NONE', ( 33.10386533810220300, 142.0583947864083711, 287.8124284103819264 ) ) ; -#13141 = ORIENTED_EDGE ( 'NONE', *, *, #9141, .F. ) ; -#13142 = CIRCLE ( 'NONE', #5952, 4.500000000047791104 ) ; -#13143 = CARTESIAN_POINT ( 'NONE', ( -20.90347901032547639, 150.8128521043120429, 179.9383906111355031 ) ) ; -#13144 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#13145 = VERTEX_POINT ( 'NONE', #39797 ) ; -#13146 = AXIS2_PLACEMENT_3D ( 'NONE', #23188, #26461, #10928 ) ; -#13147 = AXIS2_PLACEMENT_3D ( 'NONE', #18746, #31247, #31866 ) ; -#13148 = DIRECTION ( 'NONE', ( -4.622231023467483304E-33, 1.000000000000000000, 2.791711714772432647E-36 ) ) ; -#13149 = CARTESIAN_POINT ( 'NONE', ( 36.22406557370990754, 191.4555988477227402, 103.8320530264872588 ) ) ; -#13150 = CARTESIAN_POINT ( 'NONE', ( -25.99977928218365264, 118.3467192240666748, 90.28348805439438252 ) ) ; -#13151 = EDGE_CURVE ( 'NONE', #24779, #20395, #1581, .T. ) ; -#13152 = CIRCLE ( 'NONE', #28158, 17.00000000000405009 ) ; -#13153 = EDGE_CURVE ( 'NONE', #12157, #28955, #13814, .T. ) ; -#13154 = ORIENTED_EDGE ( 'NONE', *, *, #4112, .T. ) ; -#13155 = VECTOR ( 'NONE', #8354, 999.9999999999998863 ) ; -#13156 = ADVANCED_FACE ( 'NONE', ( #134 ), #9546, .F. ) ; -#13157 = EDGE_CURVE ( 'NONE', #11960, #39810, #29903, .T. ) ; -#13158 = DIRECTION ( 'NONE', ( -0.7933533411653069800, 0.5930537057989941907, 0.1373964268091563412 ) ) ; -#13159 = CARTESIAN_POINT ( 'NONE', ( 35.04494061520995274, 225.9002260770261330, 73.03733781633900435 ) ) ; -#13160 = FACE_OUTER_BOUND ( 'NONE', #3577, .T. ) ; -#13161 = ORIENTED_EDGE ( 'NONE', *, *, #30659, .F. ) ; -#13162 = EDGE_CURVE ( 'NONE', #33001, #1519, #30411, .T. ) ; -#13163 = CARTESIAN_POINT ( 'NONE', ( 25.83456707447000156, 120.2191799910000185, 90.30159152596000638 ) ) ; -#13164 = FACE_OUTER_BOUND ( 'NONE', #12161, .T. ) ; -#13165 = CARTESIAN_POINT ( 'NONE', ( -15.99998595512920652, 185.9065961375156348, 102.5825112407314634 ) ) ; -#13167 = CARTESIAN_POINT ( 'NONE', ( -13.49829986130884762, 187.9919729796256149, 103.3620544560183845 ) ) ; -#13166 = CARTESIAN_POINT ( 'NONE', ( 5.675516847681189248, 187.6699105947183170, 106.0554762087619025 ) ) ; -#13168 = EDGE_CURVE ( 'NONE', #1098, #17766, #27964, .T. ) ; -#13169 = CARTESIAN_POINT ( 'NONE', ( 38.97204648811698036, 118.8228816124465368, 89.67376701884533929 ) ) ; -#13170 = ORIENTED_EDGE ( 'NONE', *, *, #18579, .F. ) ; -#13171 = DIRECTION ( 'NONE', ( 0.7933533411653341805, 0.5931840316264885837, 0.1368326740407639630 ) ) ; -#13172 = LINE ( 'NONE', #16412, #6421 ) ; -#13173 = CIRCLE ( 'NONE', #4011, 6.500000000041539217 ) ; -#13174 = ORIENTED_EDGE ( 'NONE', *, *, #18524, .T. ) ; -#13176 = VECTOR ( 'NONE', #26669, 1000.000000000000227 ) ; -#13175 = CARTESIAN_POINT ( 'NONE', ( 46.04655628321543759, 186.9737579288344307, 105.3571666265285245 ) ) ; -#13177 = EDGE_CURVE ( 'NONE', #36287, #11904, #31423, .T. ) ; -#13178 = CARTESIAN_POINT ( 'NONE', ( -46.16183276324471763, 125.5709539201926503, 91.75005335738366341 ) ) ; -#13179 = DIRECTION ( 'NONE', ( 0.0006039748319356123742, -6.151140898304641511E-15, 0.9999998176071847045 ) ) ; -#13180 = ORIENTED_EDGE ( 'NONE', *, *, #30939, .T. ) ; -#13181 = ORIENTED_EDGE ( 'NONE', *, *, #2730, .F. ) ; -#13182 = CARTESIAN_POINT ( 'NONE', ( -15.99819964153972585, 151.3054952985143302, 97.67310904513065850 ) ) ; -#13183 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#13184 = PLANE ( 'NONE', #39893 ) ; -#13185 = ORIENTED_EDGE ( 'NONE', *, *, #17890, .T. ) ; -#13186 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049046486, 177.1117171982197931, 103.6430084149422015 ) ) ; -#13187 = ORIENTED_EDGE ( 'NONE', *, *, #1956, .F. ) ; -#13188 = CARTESIAN_POINT ( 'NONE', ( -37.82797334295766944, 117.7727065943990112, 89.71767059357158303 ) ) ; -#13189 = ORIENTED_EDGE ( 'NONE', *, *, #32353, .T. ) ; -#13190 = FACE_OUTER_BOUND ( 'NONE', #8556, .T. ) ; -#13191 = CARTESIAN_POINT ( 'NONE', ( -20.49970531360714787, 187.0374610874570465, 103.3594676856533283 ) ) ; -#13192 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6086, #15301, #8975, #21451, #33891, #5887, #18342, #24925, #40220, #18537, #31042, #37368, #3410, #19556, #25925, #25319, #28375, #4013, #6677, #10179 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000030531, 0.1874999999999939770, 0.2187499999999790168, 0.2343749999999714950, 0.2499999999999639733, 0.4999999999999984457, 0.6250000000000148770, 0.6875000000000194289, 0.7187500000000219824, 0.7343750000000217604, 0.7500000000000214273, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13193 = CARTESIAN_POINT ( 'NONE', ( -2.280577236607999936, 189.8748397010000133, 106.1357350437999969 ) ) ; -#13194 = FACE_OUTER_BOUND ( 'NONE', #17209, .T. ) ; -#13195 = ORIENTED_EDGE ( 'NONE', *, *, #39299, .T. ) ; -#13196 = LINE ( 'NONE', #38135, #17106 ) ; -#13197 = EDGE_CURVE ( 'NONE', #38073, #35348, #12217, .T. ) ; -#13198 = FACE_OUTER_BOUND ( 'NONE', #9532, .T. ) ; -#13199 = AXIS2_PLACEMENT_3D ( 'NONE', #2483, #37221, #6133 ) ; -#13200 = EDGE_CURVE ( 'NONE', #35545, #22722, #12834, .T. ) ; -#13201 = CARTESIAN_POINT ( 'NONE', ( 20.53366021055622070, 212.8322404055747370, 73.04610226615776014 ) ) ; -#13202 = CARTESIAN_POINT ( 'NONE', ( 13.50019380982689832, 123.9831134393972292, 91.09954329858136646 ) ) ; -#13203 = CIRCLE ( 'NONE', #20357, 2.499999999980931698 ) ; -#13204 = CIRCLE ( 'NONE', #36028, 51.90509899264980476 ) ; -#13205 = CARTESIAN_POINT ( 'NONE', ( 13.24378962342656685, 148.9487049838880637, 184.3347202634957682 ) ) ; -#13206 = ORIENTED_EDGE ( 'NONE', *, *, #1500, .T. ) ; -#13207 = CC_DESIGN_PERSON_AND_ORGANIZATION_ASSIGNMENT ( #17756, #2456, ( #16623 ) ) ; -#13208 = CARTESIAN_POINT ( 'NONE', ( 22.49960432933178822, 158.3069096095373993, 96.18736459073451783 ) ) ; -#13209 = CARTESIAN_POINT ( 'NONE', ( -36.39978358780000178, 116.8027791505000010, 90.44031726887999412 ) ) ; -#13210 = ORIENTED_EDGE ( 'NONE', *, *, #1191, .F. ) ; -#13211 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28175, #3000, #9553, #336, #24507, #31223, #3197, #27773, #30629, #22239, #34463, #40016 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000004773959, 0.3750000000007719936, 0.4375000000009254819, 0.4687500000010021983, 0.4843750000009852674, 0.5000000000009683365, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13212 = ORIENTED_EDGE ( 'NONE', *, *, #14918, .T. ) ; -#13213 = CARTESIAN_POINT ( 'NONE', ( -28.45933928643433575, 130.3430211585376810, 92.84111053953343173 ) ) ; -#13214 = DIRECTION ( 'NONE', ( -0.0004161288024629910599, 0.8480480897827221698, -0.5299191110468615129 ) ) ; -#13215 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319388572829 ) ) ; -#13216 = CARTESIAN_POINT ( 'NONE', ( 25.28576755642145457, 131.0248848368917436, 89.88715223900155138 ) ) ; -#13217 = CARTESIAN_POINT ( 'NONE', ( -3.725674215038269566, 174.7211706731201275, 102.8770674905540119 ) ) ; -#13218 = FACE_BOUND ( 'NONE', #3812, .T. ) ; -#13219 = ORIENTED_EDGE ( 'NONE', *, *, #26033, .T. ) ; -#13220 = VERTEX_POINT ( 'NONE', #30820 ) ; -#13221 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#13222 = LINE ( 'NONE', #25708, #6065 ) ; -#13223 = ADVANCED_FACE ( 'NONE', ( #37351 ), #27578, .T. ) ; -#13224 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#13225 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; -#13226 = ORIENTED_EDGE ( 'NONE', *, *, #38111, .T. ) ; -#13227 = ORIENTED_EDGE ( 'NONE', *, *, #27708, .F. ) ; -#13228 = CARTESIAN_POINT ( 'NONE', ( -48.18911509790819991, 84.56867427379300750, 290.9580396635383863 ) ) ; -#13230 = AXIS2_PLACEMENT_3D ( 'NONE', #17517, #8552, #27173 ) ; -#13229 = CARTESIAN_POINT ( 'NONE', ( -39.01171000390000643, 118.7866544936999986, 89.56593668563999699 ) ) ; -#13231 = CARTESIAN_POINT ( 'NONE', ( 25.50773797008787369, 191.9759150222000130, 101.9060413058080030 ) ) ; -#13232 = VECTOR ( 'NONE', #27748, 1000.000000000000000 ) ; -#13233 = AXIS2_PLACEMENT_3D ( 'NONE', #31605, #35036, #12799 ) ; -#13234 = FACE_OUTER_BOUND ( 'NONE', #10279, .T. ) ; -#13235 = CARTESIAN_POINT ( 'NONE', ( -30.07362172845426684, 134.3271078994470429, 93.68749433934327442 ) ) ; -#13236 = ORIENTED_EDGE ( 'NONE', *, *, #14543, .F. ) ; -#13237 = CARTESIAN_POINT ( 'NONE', ( 28.43625476560000109, 125.3820951366000145, 88.75569124208999483 ) ) ; -#13238 = CARTESIAN_POINT ( 'NONE', ( -20.51753249963060455, 207.4552029855167916, 76.98361244602996578 ) ) ; -#13239 = CARTESIAN_POINT ( 'NONE', ( 35.80367347626000196, 111.2706431035999941, 87.49615981601000669 ) ) ; -#13240 = CARTESIAN_POINT ( 'NONE', ( 20.33352814078489601, 120.3153187450193116, 87.75972018744413106 ) ) ; -#13241 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #297, #12991, #3963 ), - ( #902, #25880, #16434 ), - ( #22402, #19305, #31191 ), - ( #16039, #13387, #25270 ) ), - .UNSPECIFIED., .F., .F., .T. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), - ( 3, 3 ), - ( 0.01799787490942297841, 0.02199506981245743717 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.7107876194677253956, 1.000000000000000000), - ( 1.000000000000000000, 0.7107793587187216655, 1.000000000000000000), - ( 1.000000000000000000, 0.7107710978257031353, 1.000000000000000000), - ( 1.000000000000000000, 0.7107628367886674736, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#13242 = EDGE_LOOP ( 'NONE', ( #655, #7189, #27497, #1980, #35753, #19527 ) ) ; -#13243 = CARTESIAN_POINT ( 'NONE', ( -22.64275039132591871, 134.9913333339589485, 90.83180188821697243 ) ) ; -#13244 = CARTESIAN_POINT ( 'NONE', ( 1.328729308773376472, 189.1484174852507465, 103.7267930124833697 ) ) ; -#13245 = LINE ( 'NONE', #32251, #40420 ) ; -#13246 = LINE ( 'NONE', #4021, #9264 ) ; -#13247 = ADVANCED_FACE ( 'NONE', ( #40008 ), #24298, .F. ) ; -#13248 = CARTESIAN_POINT ( 'NONE', ( 22.50029346826248755, 174.4060950772428953, 100.4173051754387416 ) ) ; -#13249 = EDGE_CURVE ( 'NONE', #26876, #13602, #5868, .T. ) ; -#13250 = CARTESIAN_POINT ( 'NONE', ( -26.01326056281665089, 211.0902258159713085, 76.07393268928584007 ) ) ; -#13251 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319392653766 ) ) ; -#13252 = CARTESIAN_POINT ( 'NONE', ( -43.16067970895235106, 137.0136042933273472, 338.0369414682852494 ) ) ; -#13253 = CONICAL_SURFACE ( 'NONE', #11286, 5.999999999954156671, 0.7853981633778982507 ) ; -#13254 = ORIENTED_EDGE ( 'NONE', *, *, #38254, .F. ) ; -#13255 = CONICAL_SURFACE ( 'NONE', #831, 2.503080759942041489, 0.7853981634198553552 ) ; -#13256 = CARTESIAN_POINT ( 'NONE', ( -12.64148697623542361, 181.7671068035208179, 101.7343189441936318 ) ) ; -#13257 = AXIS2_PLACEMENT_3D ( 'NONE', #24301, #2615, #40011 ) ; -#13258 = ORIENTED_EDGE ( 'NONE', *, *, #20389, .T. ) ; -#13259 = CARTESIAN_POINT ( 'NONE', ( -20.00017858637951207, 184.9560350789418237, 102.3655360699851400 ) ) ; -#13260 = CARTESIAN_POINT ( 'NONE', ( -25.99133652784204429, 191.8610009691903713, 103.9342624301125966 ) ) ; -#13261 = CYLINDRICAL_SURFACE ( 'NONE', #28734, 6.000000000000001776 ) ; -#13262 = CARTESIAN_POINT ( 'NONE', ( -34.95638760652207822, 217.7719116313999734, 73.57961695566920923 ) ) ; -#13263 = CARTESIAN_POINT ( 'NONE', ( -15.94527486429822538, 152.8203387458500231, 181.6302711725483050 ) ) ; -#13264 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 183.4515543678114966, 105.0773313099630855 ) ) ; -#13265 = EDGE_LOOP ( 'NONE', ( #17593, #9336, #31929, #7871, #31512 ) ) ; -#13266 = CARTESIAN_POINT ( 'NONE', ( -2.529975153310015212, 209.6207340275237527, 75.72670148088266728 ) ) ; -#13267 = EDGE_CURVE ( 'NONE', #901, #11474, #15283, .T. ) ; -#13268 = CARTESIAN_POINT ( 'NONE', ( 36.33494249648424557, 116.5913739965880751, 87.24583889724033270 ) ) ; -#13269 = CARTESIAN_POINT ( 'NONE', ( 25.65860266051481631, 211.0903045274443173, 75.70969401306156499 ) ) ; -#13270 = CARTESIAN_POINT ( 'NONE', ( -23.35807327067712080, 130.8185406474264312, 90.03995946608934275 ) ) ; -#13271 = ORIENTED_EDGE ( 'NONE', *, *, #33674, .F. ) ; -#13272 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319350647437 ) ) ; -#13273 = ORIENTED_EDGE ( 'NONE', *, *, #20222, .F. ) ; -#13274 = DIRECTION ( 'NONE', ( -0.7857167656192555194, 0.6185862421878133288, 0.0004745532380132049107 ) ) ; -#13275 = CARTESIAN_POINT ( 'NONE', ( 36.04678028602679518, 205.1071438019688458, 76.08304422344946261 ) ) ; -#13276 = AXIS2_PLACEMENT_3D ( 'NONE', #2603, #27753, #40187 ) ; -#13277 = CARTESIAN_POINT ( 'NONE', ( -21.82845866733090290, 176.0428982100538633, 102.8745730682872335 ) ) ; -#13278 = ADVANCED_FACE ( 'NONE', ( #3191 ), #19334, .T. ) ; -#13279 = DIRECTION ( 'NONE', ( 0.1305262453914154408, 0.9659620447682105704, 0.2233388173409121547 ) ) ; -#13280 = CONICAL_SURFACE ( 'NONE', #13951, 2.750000000041938453, 0.7853981633679587571 ) ; -#13281 = DIRECTION ( 'NONE', ( -0.6075492010474002891, 0.7738441339353229198, 0.1790229724939113032 ) ) ; -#13282 = LINE ( 'NONE', #28424, #7956 ) ; -#13283 = EDGE_LOOP ( 'NONE', ( #25466, #6605, #29593, #37619, #8181, #34946, #9027, #15524, #37093, #20080, #32287 ) ) ; -#13284 = ORIENTED_EDGE ( 'NONE', *, *, #36326, .T. ) ; -#13285 = EDGE_CURVE ( 'NONE', #18594, #349, #40218, .T. ) ; -#13286 = CARTESIAN_POINT ( 'NONE', ( 36.05503269261969734, 112.4664341864257437, 89.74600809124632406 ) ) ; -#13287 = AXIS2_PLACEMENT_3D ( 'NONE', #39799, #8956, #23886 ) ; -#13288 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24030, #32615, #33414, #11339 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13289 = CARTESIAN_POINT ( 'NONE', ( -4.839724896237716401, 177.4959176714667421, 100.6340075972825616 ) ) ; -#13290 = CARTESIAN_POINT ( 'NONE', ( -19.08360871869851039, 124.9158349820489349, 178.1622335866570950 ) ) ; -#13291 = CARTESIAN_POINT ( 'NONE', ( -37.18120336268000159, 191.3637114862000033, 104.2412399317999956 ) ) ; -#13292 = EDGE_CURVE ( 'NONE', #9277, #23170, #4532, .T. ) ; -#13293 = ORIENTED_EDGE ( 'NONE', *, *, #12733, .T. ) ; -#13294 = CARTESIAN_POINT ( 'NONE', ( -0.4373757873778362781, 189.0000005053102257, 103.6849946747920228 ) ) ; -#13295 = ORIENTED_EDGE ( 'NONE', *, *, #28882, .F. ) ; -#13296 = EDGE_CURVE ( 'NONE', #37740, #27991, #927, .T. ) ; -#13297 = EDGE_CURVE ( 'NONE', #15583, #31524, #26527, .T. ) ; -#13298 = EDGE_CURVE ( 'NONE', #39751, #33391, #33797, .T. ) ; -#13299 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178618805657E-05, -0.0002331579774917534240 ) ) ; -#13300 = CARTESIAN_POINT ( 'NONE', ( -12.63525319458499752, 176.9910806365248277, 103.4316440411400322 ) ) ; -#13301 = FACE_OUTER_BOUND ( 'NONE', #17253, .T. ) ; -#13302 = CARTESIAN_POINT ( 'NONE', ( -2.748867548853000109, 209.6363855390999902, 73.18061884123000027 ) ) ; -#13303 = CARTESIAN_POINT ( 'NONE', ( 38.31168112654999902, 118.7311881360000001, 90.10289129768000294 ) ) ; -#13304 = AXIS2_PLACEMENT_3D ( 'NONE', #19475, #7753, #32710 ) ; -#13305 = EDGE_LOOP ( 'NONE', ( #15341, #14539, #21103, #12021 ) ) ; -#13306 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066458952, 126.2392922536184869, 91.36674228553239629 ) ) ; -#13307 = CARTESIAN_POINT ( 'NONE', ( -36.40188783471693768, 191.5470103046220345, 106.4089595008395150 ) ) ; -#13308 = FACE_OUTER_BOUND ( 'NONE', #15654, .T. ) ; -#13309 = AXIS2_PLACEMENT_3D ( 'NONE', #22931, #1854, #7572 ) ; -#13310 = DIRECTION ( 'NONE', ( -0.0001408404346090450009, 0.2249510911124607548, -0.9743700461176366678 ) ) ; -#13311 = ORIENTED_EDGE ( 'NONE', *, *, #28727, .T. ) ; -#13312 = EDGE_LOOP ( 'NONE', ( #37222, #9851, #8321, #1735, #14960, #38253, #22134, #5355 ) ) ; -#13313 = AXIS2_PLACEMENT_3D ( 'NONE', #9355, #21827, #28176 ) ; -#13314 = ORIENTED_EDGE ( 'NONE', *, *, #35824, .T. ) ; -#13315 = CARTESIAN_POINT ( 'NONE', ( -13.50162388572643124, 124.5064902939847968, 88.59982987611769545 ) ) ; -#13316 = ORIENTED_EDGE ( 'NONE', *, *, #22760, .F. ) ; -#13317 = CARTESIAN_POINT ( 'NONE', ( -29.20280672789058585, 163.6356169074005038, 97.44881913872031021 ) ) ; -#13318 = CARTESIAN_POINT ( 'NONE', ( -38.46043494895000237, 118.4609868918000188, 89.70915274816999840 ) ) ; -#13319 = CARTESIAN_POINT ( 'NONE', ( -3.336458024821733037, 184.0854103654658331, 102.3254692012155260 ) ) ; -#13320 = DIRECTION ( 'NONE', ( -0.0005884949961189823910, 0.2249510543439030286, -0.9743698870671271273 ) ) ; -#13321 = DIRECTION ( 'NONE', ( 0.0005884949961213717558, -0.2249510543439036392, 0.9743698870671270162 ) ) ; -#13322 = ORIENTED_EDGE ( 'NONE', *, *, #12471, .F. ) ; -#13323 = CYLINDRICAL_SURFACE ( 'NONE', #31054, 22.50000000000000000 ) ; -#13324 = EDGE_CURVE ( 'NONE', #9812, #8915, #28850, .T. ) ; -#13325 = VERTEX_POINT ( 'NONE', #25297 ) ; -#13326 = CARTESIAN_POINT ( 'NONE', ( -34.30586824512814559, 218.5902260770999987, 73.07922396718733182 ) ) ; -#13327 = CARTESIAN_POINT ( 'NONE', ( 25.74914801116624830, 120.7206697623000053, 87.76455777158000160 ) ) ; -#13328 = CARTESIAN_POINT ( 'NONE', ( 3.499881331114640393, 185.8339625544691955, 102.8960692981967640 ) ) ; -#13329 = ORIENTED_EDGE ( 'NONE', *, *, #36972, .T. ) ; -#13330 = CARTESIAN_POINT ( 'NONE', ( -20.00025960434743766, 196.3511145673583655, 104.4227265746208815 ) ) ; -#13331 = CARTESIAN_POINT ( 'NONE', ( 18.59950176168990055, 126.0162487695453706, 174.9291204768238117 ) ) ; -#13332 = CIRCLE ( 'NONE', #30964, 2.499999999945713647 ) ; -#13333 = CIRCLE ( 'NONE', #15941, 22.50000000000899902 ) ; -#13334 = CARTESIAN_POINT ( 'NONE', ( 3.199692528962999827, 190.8181581636000033, 106.9231685249999941 ) ) ; -#13335 = EDGE_CURVE ( 'NONE', #16835, #10860, #37953, .T. ) ; -#13336 = ORIENTED_EDGE ( 'NONE', *, *, #39368, .T. ) ; -#13337 = VECTOR ( 'NONE', #27818, 1000.000000000000114 ) ; -#13338 = ORIENTED_EDGE ( 'NONE', *, *, #7766, .T. ) ; -#13339 = LINE ( 'NONE', #1055, #8066 ) ; -#13340 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#13341 = ADVANCED_FACE ( 'NONE', ( #10556 ), #20645, .F. ) ; -#13342 = ORIENTED_EDGE ( 'NONE', *, *, #10895, .T. ) ; -#13343 = EDGE_CURVE ( 'NONE', #19998, #40342, #1710, .T. ) ; -#13344 = FACE_OUTER_BOUND ( 'NONE', #22506, .T. ) ; -#13345 = CARTESIAN_POINT ( 'NONE', ( 36.49309513148966744, 191.3168920464451332, 103.7998675452271158 ) ) ; -#13346 = ORIENTED_EDGE ( 'NONE', *, *, #27675, .F. ) ; -#13347 = DIRECTION ( 'NONE', ( 3.880623682586550903E-28, -0.9743043966640312359, -0.2252353050503803078 ) ) ; -#13348 = CARTESIAN_POINT ( 'NONE', ( -3.169906973602109712, 126.7999172216492099, 88.92891361563410157 ) ) ; -#13349 = ORIENTED_EDGE ( 'NONE', *, *, #29825, .F. ) ; -#13350 = ORIENTED_EDGE ( 'NONE', *, *, #33062, .F. ) ; -#13351 = CARTESIAN_POINT ( 'NONE', ( 26.00137002222999882, 120.1094979734999981, 90.45180985473000135 ) ) ; -#13352 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2249510911124609769, 0.9743700461176366678 ) ) ; -#13354 = CARTESIAN_POINT ( 'NONE', ( -8.727334286726934565, 152.3139937905420709, 94.82264934010972013 ) ) ; -#13353 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#13355 = CONICAL_SURFACE ( 'NONE', #30342, 2.503080714813746166, 0.7853981633849203003 ) ; -#13356 = ORIENTED_EDGE ( 'NONE', *, *, #1595, .F. ) ; -#13357 = VECTOR ( 'NONE', #2390, 1000.000000000000114 ) ; -#13358 = VECTOR ( 'NONE', #2827, 1000.000000000000114 ) ; -#13359 = ORIENTED_EDGE ( 'NONE', *, *, #24803, .T. ) ; -#13360 = DIRECTION ( 'NONE', ( -0.2818286787186916609, -1.219892887796611130E-14, -0.9594647444547802495 ) ) ; -#13361 = LINE ( 'NONE', #25853, #39721 ) ; -#13363 = ORIENTED_EDGE ( 'NONE', *, *, #33316, .F. ) ; -#13362 = AXIS2_PLACEMENT_3D ( 'NONE', #821, #32317, #25791 ) ; -#13364 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18650, #21959, #8686, #21143, #33597, #5593 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000005551, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13365 = ORIENTED_EDGE ( 'NONE', *, *, #39066, .F. ) ; -#13366 = CARTESIAN_POINT ( 'NONE', ( 38.87252441036000050, 118.8954899181000116, 89.82344399277999969 ) ) ; -#13367 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927890451260, 0.0005734119022042158658 ) ) ; -#13368 = LINE ( 'NONE', #38304, #17358 ) ; -#13369 = FACE_OUTER_BOUND ( 'NONE', #14012, .T. ) ; -#13370 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; -#13371 = ADVANCED_FACE ( 'NONE', ( #7060 ), #19529, .T. ) ; -#13372 = ORIENTED_EDGE ( 'NONE', *, *, #19504, .T. ) ; -#13373 = EDGE_CURVE ( 'NONE', #19816, #16466, #6895, .T. ) ; -#13374 = EDGE_LOOP ( 'NONE', ( #34021, #3641, #30473, #8403 ) ) ; -#13375 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319397694222 ) ) ; -#13376 = EDGE_CURVE ( 'NONE', #7683, #1393, #32226, .T. ) ; -#13377 = PLANE ( 'NONE', #27246 ) ; -#13378 = DIRECTION ( 'NONE', ( 0.0006039748319386881474, 1.110222822128452674E-14, 0.9999998176071845934 ) ) ; -#13379 = ORIENTED_EDGE ( 'NONE', *, *, #23390, .F. ) ; -#13380 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #16825, #20498, #1291, #32783, #26263, #38699, #20093 ), - ( #7630, #4561, #35825, #26459, #4759, #38909, #29928 ), - ( #23386, #17224, #14197, #26665, #39111, #11120, #23585 ), - ( #32972, #1918, #14386, #3113, #2734, #2325, #33988 ), - ( #9266, #14804, #30740, #20926, #15201, #24620, #33789 ), - ( #40321, #18636, #18240, #28088, #39713, #36867, #5984 ), - ( #11522, #27894, #33383, #8873, #37268, #15395, #18437 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 4 ), - ( 4, 3, 4 ), - ( -1.202773222734000081E-12, 0.2500001068580000041, 0.5000004772762000060, 0.7500008476944000080, 0.9999999999962000397 ), - ( 0.1691542049473759857, 0.1756413776277999939, 0.8243586456702000076 ), - .UNSPECIFIED. ) ; -#13381 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971553467 ) ) ; -#13382 = ORIENTED_EDGE ( 'NONE', *, *, #5620, .T. ) ; -#13383 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22966, #20479, #19863, #1267, #13753, #35592, #32759, #35802, #17408, #39288 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13384 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971570121 ) ) ; -#13385 = CARTESIAN_POINT ( 'NONE', ( 3.666638747404721066, 185.7959654146000048, 103.0582394725000484 ) ) ; -#13386 = EDGE_LOOP ( 'NONE', ( #23574, #3014, #24308, #2986 ) ) ; -#13387 = CARTESIAN_POINT ( 'NONE', ( -39.71467534445723402, 163.7699042215536736, 187.8581907678305924 ) ) ; -#13388 = VECTOR ( 'NONE', #8265, 1000.000000000000114 ) ; -#13389 = ADVANCED_FACE ( 'NONE', ( #25905, #35254, #34852, #6860, #16658, #7456, #19921, #32424, #16460, #9750, #13415, #22229, #28751, #38348, #731, #13218, #10358, #29159 ), #2156, .F. ) ; -#13390 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#13391 = CONICAL_SURFACE ( 'NONE', #33601, 51.90509899263999927, 0.7853981633973041721 ) ; -#13392 = CONICAL_SURFACE ( 'NONE', #36230, 40.50000000002201972, 0.7853981633973078358 ) ; -#13393 = CARTESIAN_POINT ( 'NONE', ( 21.98714844736955243, 135.4477026564043740, 93.64701903591871712 ) ) ; -#13394 = ORIENTED_EDGE ( 'NONE', *, *, #13931, .T. ) ; -#13395 = LINE ( 'NONE', #37930, #34735 ) ; -#13396 = CIRCLE ( 'NONE', #6839, 4.499999999969371167 ) ; -#13397 = CARTESIAN_POINT ( 'NONE', ( -3.787588882752000341, 171.8694235010999876, 99.59096943880000197 ) ) ; -#13398 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490313130397, 156.2427122711478091, 96.23754757943613924 ) ) ; -#13399 = EDGE_CURVE ( 'NONE', #7067, #4804, #13288, .T. ) ; -#13400 = CARTESIAN_POINT ( 'NONE', ( -20.01841854128525711, 211.0875725380936103, 76.07063535483980843 ) ) ; -#13401 = VERTEX_POINT ( 'NONE', #5408 ) ; -#13402 = CARTESIAN_POINT ( 'NONE', ( 20.36743396996683941, 212.5991294476698101, 76.04826320807023876 ) ) ; -#13403 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23275, #38790, #13671, #23474, #4244, #36134, #26160, #4657, #2014, #20600, #10812 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000436873, 0.3750000000000741074, 0.4375000000001029177, 0.4687500000000824341, 0.5000000000000618394, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13404 = CARTESIAN_POINT ( 'NONE', ( 3.535970564804119753, 118.9434892789997917, 90.18996607748785266 ) ) ; -#13405 = CARTESIAN_POINT ( 'NONE', ( -37.43154220387000208, 117.0188670058000184, 89.57389268545000505 ) ) ; -#13406 = ORIENTED_EDGE ( 'NONE', *, *, #22353, .T. ) ; -#13407 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323826013271822287, 0.0005734119002331236311 ) ) ; -#13408 = ORIENTED_EDGE ( 'NONE', *, *, #25916, .T. ) ; -#13409 = PLANE ( 'NONE', #30347 ) ; -#13410 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 135.6474414654788347, 90.98047230848234790 ) ) ; -#13411 = CARTESIAN_POINT ( 'NONE', ( 23.68479074154343778, 130.4250414336578956, 90.26276162004360515 ) ) ; -#13412 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825906579923590, 0.0005734119026970681526 ) ) ; -#13413 = CARTESIAN_POINT ( 'NONE', ( 2.563994175896955774, 190.9709097722040099, 106.3045652864306874 ) ) ; -#13414 = ORIENTED_EDGE ( 'NONE', *, *, #211, .F. ) ; -#13415 = FACE_BOUND ( 'NONE', #11719, .T. ) ; -#13416 = ORIENTED_EDGE ( 'NONE', *, *, #16094, .T. ) ; -#13417 = VECTOR ( 'NONE', #13546, 1000.000000000000114 ) ; -#13418 = ORIENTED_EDGE ( 'NONE', *, *, #19600, .F. ) ; -#13419 = CARTESIAN_POINT ( 'NONE', ( 2.253991699705380825, 189.8990359204371430, 105.9958700672874983 ) ) ; -#13420 = CARTESIAN_POINT ( 'NONE', ( 24.53348384866004395, 103.6131156702660689, 87.75296677367606435 ) ) ; -#13421 = AXIS2_PLACEMENT_3D ( 'NONE', #27902, #5384, #5794 ) ; -#13422 = AXIS2_PLACEMENT_3D ( 'NONE', #19186, #17911, #27372 ) ; -#13423 = ORIENTED_EDGE ( 'NONE', *, *, #19804, .F. ) ; -#13424 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927779577222, 0.0005734119022075498959 ) ) ; -#13425 = EDGE_CURVE ( 'NONE', #39311, #27561, #415, .T. ) ; -#13426 = DIRECTION ( 'NONE', ( -3.908872061551316070E-11, 0.9743700557833805398, 0.2249510933351778486 ) ) ; -#13427 = CARTESIAN_POINT ( 'NONE', ( 35.94024013554000163, 116.1452443049000038, 87.11107922145001226 ) ) ; -#13428 = CARTESIAN_POINT ( 'NONE', ( 36.49039500768999744, 191.9046741359000237, 104.5106012823000015 ) ) ; -#13429 = EDGE_CURVE ( 'NONE', #4808, #9107, #23306, .T. ) ; -#13430 = CARTESIAN_POINT ( 'NONE', ( -32.37402305083713827, 138.3010815212902855, 91.60179504951790364 ) ) ; -#13431 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950931402, 137.3532831589782575, 178.0585834213011083 ) ) ; -#13432 = ORIENTED_EDGE ( 'NONE', *, *, #19216, .F. ) ; -#13433 = CARTESIAN_POINT ( 'NONE', ( 28.27269073377999931, 125.4370674547000135, 88.93739120006000576 ) ) ; -#13434 = EDGE_CURVE ( 'NONE', #14237, #1746, #35195, .T. ) ; -#13435 = DIRECTION ( 'NONE', ( 0.5987322044655852826, 0.8009492788783697526, 0.000000000000000000 ) ) ; -#13436 = DIRECTION ( 'NONE', ( -0.9914447998358270064, 0.1272259275658111088, 0.02916800016312352112 ) ) ; -#13437 = CARTESIAN_POINT ( 'NONE', ( -25.99968311866292225, 117.7306449258491483, 90.28348799631405086 ) ) ; -#13438 = LINE ( 'NONE', #35076, #24367 ) ; -#13439 = VERTEX_POINT ( 'NONE', #29959 ) ; -#13441 = EDGE_CURVE ( 'NONE', #17381, #17579, #10138, .T. ) ; -#13440 = CARTESIAN_POINT ( 'NONE', ( 20.94993391244204872, 135.9271259092254240, 94.10042936185872975 ) ) ; -#13442 = CARTESIAN_POINT ( 'NONE', ( 0.7287958894040964530, 189.0068360157825964, 103.6850172550924469 ) ) ; -#13443 = LINE ( 'NONE', #12843, #30638 ) ; -#13444 = AXIS2_PLACEMENT_3D ( 'NONE', #15720, #40459, #28222 ) ; -#13445 = CARTESIAN_POINT ( 'NONE', ( 39.77179625607292479, 161.6649588975980407, 197.0595923755708441 ) ) ; -#13446 = ORIENTED_EDGE ( 'NONE', *, *, #5058, .F. ) ; -#13447 = CARTESIAN_POINT ( 'NONE', ( -25.61544293745999923, 191.6801840824000180, 104.2956903261000008 ) ) ; -#13448 = CIRCLE ( 'NONE', #36282, 51.40509898895388119 ) ; -#13449 = CARTESIAN_POINT ( 'NONE', ( -21.82963564516986210, 182.7566075890955517, 102.3719474125277458 ) ) ; -#13450 = CARTESIAN_POINT ( 'NONE', ( -38.81660742513911089, 106.4213634552623517, 168.3324163836322782 ) ) ; -#13451 = LINE ( 'NONE', #26530, #36664 ) ; -#13452 = ADVANCED_FACE ( 'NONE', ( #1527 ), #13807, .F. ) ; -#13453 = CARTESIAN_POINT ( 'NONE', ( -15.99999411491280199, 138.1989450468032601, 91.56832761027415302 ) ) ; -#13454 = EDGE_LOOP ( 'NONE', ( #26534, #25520, #40455, #5235 ) ) ; -#13455 = AXIS2_PLACEMENT_3D ( 'NONE', #6710, #15719, #12658 ) ; -#13456 = VECTOR ( 'NONE', #14850, 1000.000000000000000 ) ; -#13457 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30701, #3265, #28238, #31491 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13458 = LINE ( 'NONE', #16702, #14821 ) ; -#13459 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971528487 ) ) ; -#13460 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385907860 ) ) ; -#13461 = CARTESIAN_POINT ( 'NONE', ( 39.85586901997003650, 129.5283103249424244, 336.2586849593528768 ) ) ; -#13462 = CARTESIAN_POINT ( 'NONE', ( 20.21383991100996269, 118.1108300582164787, 90.04354866822440329 ) ) ; -#13463 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971557353 ) ) ; -#13464 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#13465 = ORIENTED_EDGE ( 'NONE', *, *, #11859, .F. ) ; -#13466 = EDGE_LOOP ( 'NONE', ( #48, #12167, #32698, #27467 ) ) ; -#13467 = LINE ( 'NONE', #13663, #5563 ) ; -#13468 = CARTESIAN_POINT ( 'NONE', ( 45.79149803454951950, 77.27946979429611929, 297.5308881122152798 ) ) ; -#13469 = CARTESIAN_POINT ( 'NONE', ( 25.82532183281839266, 211.0902320845221425, 75.87621191852036873 ) ) ; -#13470 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#13471 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9278, #18648, #33999, #5999 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 2.912571049175206390E-08, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13472 = EDGE_LOOP ( 'NONE', ( #18762, #6214, #39946, #29126 ) ) ; -#13473 = CARTESIAN_POINT ( 'NONE', ( 17.25788849119799195, 152.5371962406647413, 182.4889206688251306 ) ) ; -#13474 = EDGE_CURVE ( 'NONE', #29279, #22385, #35693, .T. ) ; -#13475 = CARTESIAN_POINT ( 'NONE', ( 39.80472786507999672, 119.2917643122000158, 89.59599340385000232 ) ) ; -#13476 = EDGE_CURVE ( 'NONE', #35219, #8838, #31835, .T. ) ; -#13477 = ORIENTED_EDGE ( 'NONE', *, *, #23868, .F. ) ; -#13478 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #15495, #11833, #12032, #24515 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.442050030669437266, 1.442144067228308790 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999992630936863, 0.9999999992630936863, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#13479 = AXIS2_PLACEMENT_3D ( 'NONE', #33956, #27862, #12296 ) ; -#13480 = CARTESIAN_POINT ( 'NONE', ( 30.51059426112559336, 120.3902231267471592, 87.42876608316004194 ) ) ; -#13481 = ORIENTED_EDGE ( 'NONE', *, *, #25163, .F. ) ; -#13482 = CARTESIAN_POINT ( 'NONE', ( -14.16859888750098406, 182.3077195333686120, 104.3162949350999185 ) ) ; -#13483 = VECTOR ( 'NONE', #8710, 1000.000000000000227 ) ; -#13484 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319387939655 ) ) ; -#13485 = VECTOR ( 'NONE', #31996, 1000.000000000000114 ) ; -#13486 = CARTESIAN_POINT ( 'NONE', ( -12.63667137007742447, 130.6318338952480929, 90.15136591905226737 ) ) ; -#13487 = DIRECTION ( 'NONE', ( -6.234967242035079160E-13, 0.9743700560306142178, 0.2249510922642907751 ) ) ; -#13488 = ORIENTED_EDGE ( 'NONE', *, *, #34058, .T. ) ; -#13489 = CARTESIAN_POINT ( 'NONE', ( 6.034498894405269098, 175.2437274227258683, 100.6206328031571076 ) ) ; -#13490 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672195685, 160.1796136994820188, 99.19090620720055540 ) ) ; -#13491 = LINE ( 'NONE', #31906, #38431 ) ; -#13492 = CARTESIAN_POINT ( 'NONE', ( -20.51839817635225316, 206.2481896911439492, 75.19525730861990098 ) ) ; -#13493 = EDGE_LOOP ( 'NONE', ( #8610, #28117, #27267, #1897, #10726, #2258, #1150, #33265, #27983, #37683, #28663, #13941 ) ) ; -#13494 = CARTESIAN_POINT ( 'NONE', ( -29.41449785468654810, 161.0344709224577571, 187.1181755728296423 ) ) ; -#13495 = ADVANCED_FACE ( 'NONE', ( #20959 ), #10884, .T. ) ; -#13496 = CARTESIAN_POINT ( 'NONE', ( -2.937264483321980979, 191.5260295968394928, 103.8719657109621295 ) ) ; -#13497 = FACE_OUTER_BOUND ( 'NONE', #7053, .T. ) ; -#13498 = VECTOR ( 'NONE', #24356, 1000.000000000000000 ) ; -#13499 = FACE_OUTER_BOUND ( 'NONE', #7226, .T. ) ; -#13500 = CONICAL_SURFACE ( 'NONE', #15463, 2.503010214050041427, 0.7853981633707861620 ) ; -#13501 = CARTESIAN_POINT ( 'NONE', ( 25.62904724343999874, 191.3389271896000139, 106.4877437237000066 ) ) ; -#13502 = CARTESIAN_POINT ( 'NONE', ( 20.48202276548138201, 205.7984546665913399, 75.80227489523332451 ) ) ; -#13503 = CARTESIAN_POINT ( 'NONE', ( -37.40461156464999704, 191.1585361456999976, 106.2295896655000007 ) ) ; -#13504 = ORIENTED_EDGE ( 'NONE', *, *, #34326, .T. ) ; -#13505 = VECTOR ( 'NONE', #11305, 1000.000000000000114 ) ; -#13506 = EDGE_CURVE ( 'NONE', #12780, #19918, #11543, .T. ) ; -#13507 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 108.4362817545589905, 169.8438797714867405 ) ) ; -#13508 = CARTESIAN_POINT ( 'NONE', ( -36.33415831625617898, 191.6212860434504535, 106.4173599585499090 ) ) ; -#13509 = LINE ( 'NONE', #29251, #15725 ) ; -#13510 = CARTESIAN_POINT ( 'NONE', ( 2.545697083959657991, 209.0000005535759158, 75.65980364788404700 ) ) ; -#13511 = VERTEX_POINT ( 'NONE', #5196 ) ; -#13512 = ORIENTED_EDGE ( 'NONE', *, *, #30527, .F. ) ; -#13513 = ORIENTED_EDGE ( 'NONE', *, *, #4238, .T. ) ; -#13514 = CARTESIAN_POINT ( 'NONE', ( 25.49919833444198858, 118.8155663768459505, 87.75236248755290092 ) ) ; -#13515 = FACE_OUTER_BOUND ( 'NONE', #3885, .T. ) ; -#13516 = CARTESIAN_POINT ( 'NONE', ( -48.18910981145552341, 141.1918910709570980, 290.9667924317506049 ) ) ; -#13517 = ADVANCED_FACE ( 'NONE', ( #23419 ), #7665, .F. ) ; -#13518 = ADVANCED_FACE ( 'NONE', ( #29759 ), #33067, .F. ) ; -#13519 = ORIENTED_EDGE ( 'NONE', *, *, #31112, .F. ) ; -#13520 = EDGE_CURVE ( 'NONE', #16377, #27102, #29944, .T. ) ; -#13521 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999894129, 177.0581688370111522, 100.5408937737905859 ) ) ; -#13522 = FACE_OUTER_BOUND ( 'NONE', #30306, .T. ) ; -#13523 = CARTESIAN_POINT ( 'NONE', ( -38.24391925948000193, 118.9459941488999988, 87.57943140326000275 ) ) ; -#13524 = CARTESIAN_POINT ( 'NONE', ( 15.10890892604210478, 182.4258086152457849, 104.8390273514353481 ) ) ; -#13525 = ORIENTED_EDGE ( 'NONE', *, *, #30273, .F. ) ; -#13526 = CARTESIAN_POINT ( 'NONE', ( 19.45260910890439021, 147.6922889574200042, 183.5326060071998597 ) ) ; -#13527 = AXIS2_PLACEMENT_3D ( 'NONE', #15903, #19377, #7654 ) ; -#13528 = ORIENTED_EDGE ( 'NONE', *, *, #36129, .F. ) ; -#13529 = CARTESIAN_POINT ( 'NONE', ( 19.98251549220767487, 208.2807073928345858, 76.59383503248129443 ) ) ; -#13530 = VECTOR ( 'NONE', #20655, 1000.000000000000114 ) ; -#13531 = CARTESIAN_POINT ( 'NONE', ( 22.50143696189732267, 158.0318282207045968, 98.86066492189580401 ) ) ; -#13532 = FACE_OUTER_BOUND ( 'NONE', #34997, .T. ) ; -#13533 = CARTESIAN_POINT ( 'NONE', ( -15.94429972368852866, 121.8869921648800698, 174.4792395813007886 ) ) ; -#13534 = VECTOR ( 'NONE', #23664, 1000.000000000000114 ) ; -#13535 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596097999, 128.5887768395806177, 89.32567453967637050 ) ) ; -#13536 = VERTEX_POINT ( 'NONE', #34951 ) ; -#13537 = CARTESIAN_POINT ( 'NONE', ( -0.4376690092978329782, 188.6111834483369876, 103.1961845456950186 ) ) ; -#13538 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066962549, 129.9712533186751102, 92.22833354197516087 ) ) ; -#13539 = CARTESIAN_POINT ( 'NONE', ( 18.98894481338223272, 148.2010240902047542, 184.7157352475513221 ) ) ; -#13540 = ORIENTED_EDGE ( 'NONE', *, *, #21332, .T. ) ; -#13541 = CARTESIAN_POINT ( 'NONE', ( -20.39898617289156491, 212.6029615956409771, 73.07082455888718187 ) ) ; -#13542 = DIRECTION ( 'NONE', ( 0.0006039748319417797499, -6.167438909947000466E-15, 0.9999998176071845934 ) ) ; -#13543 = VERTEX_POINT ( 'NONE', #19225 ) ; -#13544 = CARTESIAN_POINT ( 'NONE', ( -38.93638499369696149, 190.3639747423779340, 106.7043395007530364 ) ) ; -#13545 = ORIENTED_EDGE ( 'NONE', *, *, #24272, .F. ) ; -#13546 = DIRECTION ( 'NONE', ( 0.0005885022774582036268, -0.2255194047039537075, 0.9742384984012096849 ) ) ; -#13547 = FACE_OUTER_BOUND ( 'NONE', #22637, .T. ) ; -#13548 = ORIENTED_EDGE ( 'NONE', *, *, #8463, .F. ) ; -#13549 = EDGE_LOOP ( 'NONE', ( #32905, #12590, #1090, #14864 ) ) ; -#13550 = EDGE_CURVE ( 'NONE', #15877, #19871, #10048, .T. ) ; -#13551 = CARTESIAN_POINT ( 'NONE', ( 25.50038493774000159, 120.2145571406999949, 89.95686844560999873 ) ) ; -#13552 = AXIS2_PLACEMENT_3D ( 'NONE', #14591, #14383, #20494 ) ; -#13553 = LINE ( 'NONE', #25842, #37140 ) ; -#13554 = AXIS2_PLACEMENT_3D ( 'NONE', #13851, #17913, #15082 ) ; -#13556 = CARTESIAN_POINT ( 'NONE', ( -15.49852919541870655, 185.3436308333990610, 105.0179936569041388 ) ) ; -#13555 = CARTESIAN_POINT ( 'NONE', ( 20.48239712991395933, 207.5021835839149560, 76.84848341814188188 ) ) ; -#13557 = EDGE_CURVE ( 'NONE', #15824, #19888, #22126, .T. ) ; -#13558 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501099925, 179.0628333272265138, 104.0826189413126741 ) ) ; -#13559 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#13560 = ORIENTED_EDGE ( 'NONE', *, *, #11385, .F. ) ; -#13561 = CARTESIAN_POINT ( 'NONE', ( -2.931788836712827084, 190.9017055503348104, 103.7278258144194041 ) ) ; -#13562 = CARTESIAN_POINT ( 'NONE', ( 21.70383481884618959, 176.1155659730582101, 103.0361080479357696 ) ) ; -#13563 = CARTESIAN_POINT ( 'NONE', ( 22.49960432933178822, 158.3069096095373993, 96.18736459073451783 ) ) ; -#13564 = ORIENTED_EDGE ( 'NONE', *, *, #26538, .F. ) ; -#13565 = EDGE_CURVE ( 'NONE', #25223, #19007, #6946, .T. ) ; -#13566 = ORIENTED_EDGE ( 'NONE', *, *, #13794, .T. ) ; -#13568 = EDGE_CURVE ( 'NONE', #38935, #27317, #6559, .T. ) ; -#13567 = CARTESIAN_POINT ( 'NONE', ( 38.52585389698000284, 119.2305566313000043, 90.41527115060999620 ) ) ; -#13569 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#13570 = ADVANCED_FACE ( 'NONE', ( #25400, #28655 ), #9859, .F. ) ; -#13571 = CARTESIAN_POINT ( 'NONE', ( 42.83827273200019903, 189.3718331974772582, 106.4258958018896095 ) ) ; -#13572 = CARTESIAN_POINT ( 'NONE', ( -46.22230826977606455, 125.8520600549444595, 91.81498836011172671 ) ) ; -#13573 = CARTESIAN_POINT ( 'NONE', ( 29.05352371370200615, 110.6131156702000027, 87.25023669171606855 ) ) ; -#13574 = CARTESIAN_POINT ( 'NONE', ( 35.74400150684999744, 192.1411023891000127, 104.0582773893000024 ) ) ; -#13575 = ORIENTED_EDGE ( 'NONE', *, *, #44, .F. ) ; -#13576 = CARTESIAN_POINT ( 'NONE', ( 19.73921667059327234, 149.8473492619755802, 180.1939462582248836 ) ) ; -#13577 = FACE_OUTER_BOUND ( 'NONE', #31318, .T. ) ; -#13578 = CARTESIAN_POINT ( 'NONE', ( 20.33485220578245745, 160.1455537809930547, 99.35001776957351183 ) ) ; -#13579 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -1.739499925770551072E-30, -0.0006039748319385906776 ) ) ; -#13580 = VERTEX_POINT ( 'NONE', #3291 ) ; -#13581 = CARTESIAN_POINT ( 'NONE', ( -3.501631960585971814, 127.9846833621704718, 91.93944743130187192 ) ) ; -#13582 = VERTEX_POINT ( 'NONE', #15030 ) ; -#13583 = VECTOR ( 'NONE', #36562, 1000.000000000000000 ) ; -#13584 = DIRECTION ( 'NONE', ( -0.0006039748319388209621, 4.551467604553135559E-16, -0.9999998176071845934 ) ) ; -#13585 = ORIENTED_EDGE ( 'NONE', *, *, #35580, .T. ) ; -#13586 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684792472, 217.7719116314000303, 75.57961659108507035 ) ) ; -#13587 = AXIS2_PLACEMENT_3D ( 'NONE', #15027, #33411, #30159 ) ; -#13588 = CARTESIAN_POINT ( 'NONE', ( -2.057474463150999799, 190.0654621610999868, 105.8854108991000089 ) ) ; -#13589 = FACE_OUTER_BOUND ( 'NONE', #14777, .T. ) ; -#13590 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921591843, -0.2249510932971527932 ) ) ; -#13591 = VERTEX_POINT ( 'NONE', #13122 ) ; -#13592 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; -#13593 = CARTESIAN_POINT ( 'NONE', ( 23.00039803961572460, 115.6131156701970895, 89.75408929892711285 ) ) ; -#13594 = CARTESIAN_POINT ( 'NONE', ( 13.50018918953322000, 123.9730592991513447, 91.10582582559948150 ) ) ; -#13595 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319380397945 ) ) ; -#13596 = EDGE_LOOP ( 'NONE', ( #31071, #16433, #2774, #11566 ) ) ; -#13597 = EDGE_CURVE ( 'NONE', #30815, #7776, #33248, .T. ) ; -#13598 = DIRECTION ( 'NONE', ( -0.0006039748319387941823, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#13599 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25014, #646, #13529, #38262, #3706, #20045 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13600 = CARTESIAN_POINT ( 'NONE', ( -38.13628578597000285, 117.9293585046000175, 89.55828210560000002 ) ) ; -#13602 = VERTEX_POINT ( 'NONE', #16172 ) ; -#13601 = ADVANCED_FACE ( 'NONE', ( #31519 ), #431, .T. ) ; -#13603 = CARTESIAN_POINT ( 'NONE', ( -20.33172310711824693, 118.8155446846155030, 89.94669117714120432 ) ) ; -#13604 = VERTEX_POINT ( 'NONE', #15963 ) ; -#13605 = CARTESIAN_POINT ( 'NONE', ( 9.888071695018501472, 159.3809512100619372, 96.44294207514620609 ) ) ; -#13606 = ADVANCED_FACE ( 'NONE', ( #30361 ), #27531, .F. ) ; -#13607 = AXIS2_PLACEMENT_3D ( 'NONE', #13630, #29379, #35465 ) ; -#13608 = FACE_OUTER_BOUND ( 'NONE', #18483, .T. ) ; -#13609 = CARTESIAN_POINT ( 'NONE', ( -31.70415073005798590, 220.4002260771000294, 75.57765305097056796 ) ) ; -#13610 = ORIENTED_EDGE ( 'NONE', *, *, #37597, .F. ) ; -#13611 = VERTEX_POINT ( 'NONE', #11761 ) ; -#13612 = CARTESIAN_POINT ( 'NONE', ( -2.935318997662724971, 190.8645861742403724, 106.7981712751157062 ) ) ; -#13613 = AXIS2_PLACEMENT_3D ( 'NONE', #22577, #16607, #35602 ) ; -#13614 = ORIENTED_EDGE ( 'NONE', *, *, #33672, .T. ) ; -#13615 = ORIENTED_EDGE ( 'NONE', *, *, #16182, .T. ) ; -#13616 = EDGE_LOOP ( 'NONE', ( #13322, #20484, #16290, #18062 ) ) ; -#13617 = EDGE_CURVE ( 'NONE', #33385, #28425, #31784, .T. ) ; -#13618 = CARTESIAN_POINT ( 'NONE', ( 1.424924794764945934, 189.1901564357632424, 105.7919554375150426 ) ) ; -#13619 = CARTESIAN_POINT ( 'NONE', ( -19.99848660742553008, 137.5076853405834072, 94.48997979116353463 ) ) ; -#13620 = ORIENTED_EDGE ( 'NONE', *, *, #2303, .F. ) ; -#13621 = CARTESIAN_POINT ( 'NONE', ( -45.07185612124388996, 188.2470601034457047, 105.6714885308213923 ) ) ; -#13622 = CARTESIAN_POINT ( 'NONE', ( 5.666342389540173663, 188.3482258674228547, 103.1300390205756656 ) ) ; -#13623 = CARTESIAN_POINT ( 'NONE', ( 36.33597607651999795, 191.7504636063000021, 104.2398877987999981 ) ) ; -#13624 = CARTESIAN_POINT ( 'NONE', ( 2.948063066966874590, 209.6962674796563704, 76.05661796956628962 ) ) ; -#13625 = ORIENTED_EDGE ( 'NONE', *, *, #26864, .F. ) ; -#13626 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772234801672, 136.6775772631780796, 180.9814965275865575 ) ) ; -#13627 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#13628 = ORIENTED_EDGE ( 'NONE', *, *, #16135, .F. ) ; -#13629 = PLANE ( 'NONE', #25114 ) ; -#13630 = CARTESIAN_POINT ( 'NONE', ( -25.91449223605999919, 130.7183056500000191, 90.10384766008000668 ) ) ; -#13631 = CARTESIAN_POINT ( 'NONE', ( -35.78982145051634234, 209.7096690542524016, 73.41345363205269337 ) ) ; -#13632 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319392907469 ) ) ; -#13633 = ORIENTED_EDGE ( 'NONE', *, *, #36644, .T. ) ; -#13634 = DIRECTION ( 'NONE', ( 0.0005884949961187157857, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#13635 = CARTESIAN_POINT ( 'NONE', ( 0.5988030922453946303, 189.0003911261687222, 103.6820589494512177 ) ) ; -#13636 = CARTESIAN_POINT ( 'NONE', ( -2.600533005549065635, 189.6267769006977346, 106.5121981042907748 ) ) ; -#13637 = VECTOR ( 'NONE', #8571, 1000.000000000000227 ) ; -#13638 = CARTESIAN_POINT ( 'NONE', ( -21.70206949589963230, 176.6347057442738731, 100.7874671074596904 ) ) ; -#13639 = CARTESIAN_POINT ( 'NONE', ( -26.12824141520999888, 191.8139679239000088, 103.7943665811000074 ) ) ; -#13640 = CARTESIAN_POINT ( 'NONE', ( 10.03567519175098255, 143.6524055185811619, 95.37739210866408257 ) ) ; -#13641 = VECTOR ( 'NONE', #27415, 1000.000000000000227 ) ; -#13642 = CARTESIAN_POINT ( 'NONE', ( 15.59065710780919289, 127.6518116315415483, 175.3064835111600814 ) ) ; -#13643 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621343400, 0.1788331191967954814 ) ) ; -#13644 = CARTESIAN_POINT ( 'NONE', ( 18.98781633385216239, 148.3617834207654766, 184.0293870428388345 ) ) ; -#13645 = ORIENTED_EDGE ( 'NONE', *, *, #37329, .F. ) ; -#13646 = EDGE_CURVE ( 'NONE', #11837, #6503, #28508, .T. ) ; -#13647 = EDGE_CURVE ( 'NONE', #26191, #34430, #31320, .T. ) ; -#13648 = ADVANCED_FACE ( 'NONE', ( #24451 ), #20681, .F. ) ; -#13649 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30627, #21435, #27770, #37548 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13650 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552080 ) ) ; -#13651 = CARTESIAN_POINT ( 'NONE', ( -0.4558744329272819695, 211.4999999999972431, 73.05877941915380802 ) ) ; -#13652 = VERTEX_POINT ( 'NONE', #18817 ) ; -#13653 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#13654 = CARTESIAN_POINT ( 'NONE', ( 23.35732905683231309, 181.2169419930002903, 104.3838998314656550 ) ) ; -#13655 = EDGE_CURVE ( 'NONE', #35994, #38340, #597, .T. ) ; -#13656 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927780347819, 0.0005734119022075944566 ) ) ; -#13657 = CARTESIAN_POINT ( 'NONE', ( 20.50100932471902482, 118.1127835883590365, 89.75563873136169946 ) ) ; -#13658 = FACE_OUTER_BOUND ( 'NONE', #11751, .T. ) ; -#13659 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#13660 = CARTESIAN_POINT ( 'NONE', ( 13.50156990940217483, 188.0525492886318943, 103.3109536029596711 ) ) ; -#13661 = ORIENTED_EDGE ( 'NONE', *, *, #26967, .F. ) ; -#13662 = EDGE_CURVE ( 'NONE', #27919, #14260, #12707, .T. ) ; -#13664 = CIRCLE ( 'NONE', #15610, 2.250000000000011102 ) ; -#13663 = CARTESIAN_POINT ( 'NONE', ( 20.24454251694270468, 122.4704376898559417, 162.2874104829967052 ) ) ; -#13665 = DIRECTION ( 'NONE', ( 0.0005884949961233868539, -0.2249510543439054988, 0.9743698870671265722 ) ) ; -#13666 = CARTESIAN_POINT ( 'NONE', ( 14.55482866507330009, 176.2484294118512196, 103.4132012473699973 ) ) ; -#13667 = FACE_OUTER_BOUND ( 'NONE', #33605, .T. ) ; -#13668 = EDGE_LOOP ( 'NONE', ( #38593, #30804, #3336, #10257 ) ) ; -#13669 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#13670 = AXIS2_PLACEMENT_3D ( 'NONE', #24795, #18413, #36844 ) ; -#13671 = CARTESIAN_POINT ( 'NONE', ( 3.656823241034720340, 136.7104492278974419, 94.16761506169929419 ) ) ; -#13672 = VERTEX_POINT ( 'NONE', #29051 ) ; -#13673 = DIRECTION ( 'NONE', ( 0.0006039748319386962789, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#13674 = ORIENTED_EDGE ( 'NONE', *, *, #35788, .T. ) ; -#13675 = FACE_OUTER_BOUND ( 'NONE', #32020, .T. ) ; -#13676 = CARTESIAN_POINT ( 'NONE', ( -45.29507009204370860, 186.0024229835559026, 106.1116092119197134 ) ) ; -#13677 = DIRECTION ( 'NONE', ( -0.0005884949961236880453, 0.2249510543439056931, -0.9743698870671265722 ) ) ; -#13678 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; -#13679 = ORIENTED_EDGE ( 'NONE', *, *, #5092, .T. ) ; -#13680 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567345 ) ) ; -#13681 = CARTESIAN_POINT ( 'NONE', ( -3.622252842473525192, 175.9919634367300318, 100.2860570176304975 ) ) ; -#13682 = DIRECTION ( 'NONE', ( -0.0005884949961256741953, 0.2249510543439056931, -0.9743698870671265722 ) ) ; -#13683 = ORIENTED_EDGE ( 'NONE', *, *, #491, .F. ) ; -#13684 = CARTESIAN_POINT ( 'NONE', ( -37.63792967983999915, 191.1259926255999915, 103.9223442539999951 ) ) ; -#13685 = ORIENTED_EDGE ( 'NONE', *, *, #38958, .T. ) ; -#13686 = CARTESIAN_POINT ( 'NONE', ( 4.034499241909815126, 137.2431130921461886, 91.84870606007839910 ) ) ; -#13687 = CARTESIAN_POINT ( 'NONE', ( 37.26954635975619823, 164.8944657675721999, 196.8584033196613916 ) ) ; -#13688 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31854, #22045, #34474, #31443 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 1.036004206351064581E-06, 0.001197053906935750247 ), - .UNSPECIFIED. ) ; -#13689 = CARTESIAN_POINT ( 'NONE', ( -2.436970329118646639, 191.4135392062368908, 104.3588452342733603 ) ) ; -#13690 = AXIS2_PLACEMENT_3D ( 'NONE', #25428, #19253, #6388 ) ; -#13691 = CARTESIAN_POINT ( 'NONE', ( -23.36043047071902734, 128.0201710902839807, 91.78857617566187344 ) ) ; -#13692 = AXIS2_PLACEMENT_3D ( 'NONE', #3831, #34700, #25747 ) ; -#13693 = EDGE_CURVE ( 'NONE', #1598, #15246, #12779, .T. ) ; -#13694 = EDGE_CURVE ( 'NONE', #25578, #1519, #8270, .T. ) ; -#13695 = CIRCLE ( 'NONE', #23501, 10.00000000000000355 ) ; -#13696 = LINE ( 'NONE', #1011, #2624 ) ; -#13697 = CARTESIAN_POINT ( 'NONE', ( 25.88624728018999832, 191.3092799362999870, 106.7436193634000006 ) ) ; -#13698 = CARTESIAN_POINT ( 'NONE', ( 38.11368864623999997, 119.4135589946000096, 87.13882848846000684 ) ) ; -#13699 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950931402, 137.3532831589782575, 178.0585834213011083 ) ) ; -#13700 = CARTESIAN_POINT ( 'NONE', ( 38.56668844754000247, 118.6267379033999987, 89.80763822784000183 ) ) ; -#13701 = ORIENTED_EDGE ( 'NONE', *, *, #27348, .T. ) ; -#13702 = CARTESIAN_POINT ( 'NONE', ( 13.49481983871936386, 124.3681642032378534, 88.35737770391504853 ) ) ; -#13703 = CARTESIAN_POINT ( 'NONE', ( 13.55544112991404582, 163.9635997609409799, 100.5807068482711486 ) ) ; -#13704 = CC_DESIGN_PERSON_AND_ORGANIZATION_ASSIGNMENT ( #27206, #8790, ( #26440 ) ) ; -#13705 = CARTESIAN_POINT ( 'NONE', ( -36.05314369314938716, 192.0743240283865987, 106.4401673789308802 ) ) ; -#13706 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082098698, 3.303940607880318766E-12, 297.5876476292050938 ) ) ; -#13707 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474981270974893, 155.7928101626038426, 98.18628735352585579 ) ) ; -#13708 = ORIENTED_EDGE ( 'NONE', *, *, #30561, .T. ) ; -#13709 = ORIENTED_EDGE ( 'NONE', *, *, #24984, .T. ) ; -#13710 = ORIENTED_EDGE ( 'NONE', *, *, #26780, .F. ) ; -#13711 = CARTESIAN_POINT ( 'NONE', ( -4.037441715711888257, 137.2418790766001280, 91.85329641528940670 ) ) ; -#13712 = CARTESIAN_POINT ( 'NONE', ( -31.75344637200825559, 110.2231456982486719, 198.5388746951014411 ) ) ; -#13713 = VERTEX_POINT ( 'NONE', #10262 ) ; -#13714 = FACE_BOUND ( 'NONE', #35784, .T. ) ; -#13715 = AXIS2_PLACEMENT_3D ( 'NONE', #17324, #21033, #24107 ) ; -#13716 = EDGE_CURVE ( 'NONE', #39471, #28651, #104, .T. ) ; -#13717 = CIRCLE ( 'NONE', #24194, 2.249999999984611421 ) ; -#13718 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319364164186 ) ) ; -#13719 = CARTESIAN_POINT ( 'NONE', ( -38.81769244209999670, 118.7847089182999980, 89.71781930851000197 ) ) ; -#13720 = CARTESIAN_POINT ( 'NONE', ( -38.35427756623000306, 119.0557098913999994, 87.58667636674000789 ) ) ; -#13721 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#13722 = ORIENTED_EDGE ( 'NONE', *, *, #3942, .F. ) ; -#13723 = CARTESIAN_POINT ( 'NONE', ( 19.30878489618914884, 148.2440988583769581, 183.5073535031560823 ) ) ; -#13724 = AXIS2_PLACEMENT_3D ( 'NONE', #31211, #3187, #28160 ) ; -#13725 = ORIENTED_EDGE ( 'NONE', *, *, #3079, .F. ) ; -#13726 = CARTESIAN_POINT ( 'NONE', ( -3.169886595064320467, 185.3115511372765241, 102.4373918823009291 ) ) ; -#13727 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319364155512 ) ) ; -#13728 = DIRECTION ( 'NONE', ( -0.0005884961822832421958, 0.2249510528375106844, -0.9743698874141887289 ) ) ; -#13729 = FACE_OUTER_BOUND ( 'NONE', #15356, .T. ) ; -#13730 = ORIENTED_EDGE ( 'NONE', *, *, #15852, .T. ) ; -#13731 = CARTESIAN_POINT ( 'NONE', ( -20.00100377755662961, 193.8169056301028945, 102.7149817412491473 ) ) ; -#13732 = CARTESIAN_POINT ( 'NONE', ( 20.00158012229879745, 184.2984082083453359, 105.2684676661315422 ) ) ; -#13733 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#13734 = ORIENTED_EDGE ( 'NONE', *, *, #15850, .T. ) ; -#13735 = DIRECTION ( 'NONE', ( 0.0005884949961203652909, -0.2249510543439047217, 0.9743698870671267942 ) ) ; -#13736 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -3.519737327345223780E-16, 0.0006039748319385488274 ) ) ; -#13737 = EDGE_LOOP ( 'NONE', ( #27829, #23631, #135, #23327 ) ) ; -#13738 = ORIENTED_EDGE ( 'NONE', *, *, #14263, .T. ) ; -#13739 = DIRECTION ( 'NONE', ( -0.0004161288024407980377, -0.5299192578934008857, -0.8480479980228282644 ) ) ; -#13740 = ORIENTED_EDGE ( 'NONE', *, *, #25084, .F. ) ; -#13741 = ADVANCED_FACE ( 'NONE', ( #19821 ), #22727, .F. ) ; -#13742 = EDGE_CURVE ( 'NONE', #15246, #27781, #19434, .T. ) ; -#13743 = DIRECTION ( 'NONE', ( 0.1305263947813612435, 0.9659212020967549162, 0.2235153050807487662 ) ) ; -#13744 = CARTESIAN_POINT ( 'NONE', ( 37.96420214258163384, 191.2635690687931742, 104.9840277876370180 ) ) ; -#13745 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825996983, 153.3598638654817989, 97.61100683840648173 ) ) ; -#13746 = CONICAL_SURFACE ( 'NONE', #6553, 3.002820406140098264, 0.7853589219061751781 ) ; -#13747 = AXIS2_PLACEMENT_3D ( 'NONE', #31035, #28178, #19137 ) ; -#13748 = EDGE_LOOP ( 'NONE', ( #29263, #15765, #7923, #33892 ) ) ; -#13749 = ORIENTED_EDGE ( 'NONE', *, *, #26027, .F. ) ; -#13750 = AXIS2_PLACEMENT_3D ( 'NONE', #32515, #1636, #38247 ) ; -#13751 = CARTESIAN_POINT ( 'NONE', ( 25.51085356005999927, 120.5811326495000060, 90.04130476496999336 ) ) ; -#13752 = VECTOR ( 'NONE', #1991, 1000.000000000000000 ) ; -#13753 = CARTESIAN_POINT ( 'NONE', ( -25.01815341717926700, 212.6267852834324401, 75.57388427013228238 ) ) ; -#13755 = DIRECTION ( 'NONE', ( 5.912089982110409952E-14, -0.9743700558141253909, -0.2249510932020070131 ) ) ; -#13754 = DIRECTION ( 'NONE', ( 1.179611963740366523E-14, 0.9743700557921581851, 0.2249510932971575672 ) ) ; -#13756 = ORIENTED_EDGE ( 'NONE', *, *, #354, .F. ) ; -#13757 = CARTESIAN_POINT ( 'NONE', ( -2.937820978892512702, 191.0281591032251356, 103.7570235660240598 ) ) ; -#13758 = CARTESIAN_POINT ( 'NONE', ( -36.11753663195067077, 191.9605956618226799, 104.4202166091810113 ) ) ; -#13759 = CARTESIAN_POINT ( 'NONE', ( 13.53838462004999954, 112.1320600213999938, 152.4718672074000381 ) ) ; -#13760 = CARTESIAN_POINT ( 'NONE', ( 25.53626815854681098, 191.3673954314083119, 104.3312944428767253 ) ) ; -#13761 = ORIENTED_EDGE ( 'NONE', *, *, #20486, .F. ) ; -#13762 = ORIENTED_EDGE ( 'NONE', *, *, #14443, .T. ) ; -#13763 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; -#13764 = EDGE_CURVE ( 'NONE', #32491, #22722, #38638, .T. ) ; -#13765 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15728, #38215, #25560, #3648 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13766 = CARTESIAN_POINT ( 'NONE', ( -46.02853908287293905, 123.4020261228890831, 92.97376805818757362 ) ) ; -#13767 = DIRECTION ( 'NONE', ( 0.9914446424033197536, 0.1273124132179038470, 0.02879358418792420105 ) ) ; -#13768 = CARTESIAN_POINT ( 'NONE', ( 36.12678806294000111, 191.5105650374999868, 103.8364947623000063 ) ) ; -#13769 = VERTEX_POINT ( 'NONE', #6964 ) ; -#13770 = ORIENTED_EDGE ( 'NONE', *, *, #26643, .F. ) ; -#13771 = ORIENTED_EDGE ( 'NONE', *, *, #36637, .T. ) ; -#13772 = CARTESIAN_POINT ( 'NONE', ( -23.36327211083497346, 134.3782720072525194, 93.65223075065752312 ) ) ; -#13773 = VERTEX_POINT ( 'NONE', #31933 ) ; -#13774 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749388340, 179.6299767372406109, 101.6260513916472377 ) ) ; -#13775 = AXIS2_PLACEMENT_3D ( 'NONE', #16822, #19496, #3547 ) ; -#13776 = EDGE_CURVE ( 'NONE', #19429, #7059, #5969, .T. ) ; -#13777 = VECTOR ( 'NONE', #14689, 1000.000000000000000 ) ; -#13778 = AXIS2_PLACEMENT_3D ( 'NONE', #36609, #14941, #33731 ) ; -#13779 = CARTESIAN_POINT ( 'NONE', ( 3.064469710411337644, 190.8904254212934291, 106.8027684456671551 ) ) ; -#13780 = VERTEX_POINT ( 'NONE', #26001 ) ; -#13781 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#13782 = EDGE_CURVE ( 'NONE', #20598, #18222, #16765, .T. ) ; -#13783 = CARTESIAN_POINT ( 'NONE', ( 33.54411937952203715, 218.5902260770999987, 73.03824427483984039 ) ) ; -#13784 = DIRECTION ( 'NONE', ( 0.6087613508141339613, -0.7729392138727744221, -0.1788143993438125190 ) ) ; -#13785 = CARTESIAN_POINT ( 'NONE', ( -6.081258327431999788, 191.9910753068000133, 28.07991271570000080 ) ) ; -#13786 = VERTEX_POINT ( 'NONE', #7568 ) ; -#13788 = EDGE_CURVE ( 'NONE', #36179, #20168, #2016, .T. ) ; -#13787 = CARTESIAN_POINT ( 'NONE', ( -25.50819987922450238, 205.5673820219388688, 76.31562095576882143 ) ) ; -#13789 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34446, #12581, #508, #6056 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13790 = EDGE_CURVE ( 'NONE', #15694, #35219, #29259, .T. ) ; -#13791 = LINE ( 'NONE', #34640, #33600 ) ; -#13792 = CARTESIAN_POINT ( 'NONE', ( 20.49234192179615377, 211.4170906440259898, 75.54575476972884474 ) ) ; -#13793 = ADVANCED_FACE ( 'NONE', ( #16370 ), #40247, .T. ) ; -#13794 = EDGE_CURVE ( 'NONE', #20853, #15440, #35002, .T. ) ; -#13795 = PLANE ( 'NONE', #16059 ) ; -#13796 = VERTEX_POINT ( 'NONE', #1434 ) ; -#13797 = CARTESIAN_POINT ( 'NONE', ( 33.03711258942921347, 80.00316997518478956, 289.8488960917472355 ) ) ; -#13798 = VECTOR ( 'NONE', #36140, 1000.000000000000114 ) ; -#13799 = CARTESIAN_POINT ( 'NONE', ( -36.84971820185000269, 116.5573134774000010, 89.86943891287999975 ) ) ; -#13800 = ORIENTED_EDGE ( 'NONE', *, *, #17883, .F. ) ; -#13801 = ORIENTED_EDGE ( 'NONE', *, *, #30313, .T. ) ; -#13802 = CARTESIAN_POINT ( 'NONE', ( 17.36823235697561074, 148.6268409572465430, 177.2656691734900107 ) ) ; -#13803 = FACE_OUTER_BOUND ( 'NONE', #9490, .T. ) ; -#13804 = CARTESIAN_POINT ( 'NONE', ( -13.49869758878028669, 124.2895155517476127, 90.92133008179847309 ) ) ; -#13805 = EDGE_LOOP ( 'NONE', ( #7405, #23020, #17310, #2387 ) ) ; -#13806 = ORIENTED_EDGE ( 'NONE', *, *, #22462, .T. ) ; -#13807 = PLANE ( 'NONE', #25278 ) ; -#13808 = ORIENTED_EDGE ( 'NONE', *, *, #2466, .T. ) ; -#13809 = ORIENTED_EDGE ( 'NONE', *, *, #24148, .T. ) ; -#13810 = ORIENTED_EDGE ( 'NONE', *, *, #39333, .F. ) ; -#13811 = PLANE ( 'NONE', #4763 ) ; -#13812 = EDGE_CURVE ( 'NONE', #34012, #20666, #1078, .T. ) ; -#13813 = CARTESIAN_POINT ( 'NONE', ( 19.56366993370219731, 124.7014302495635718, 177.5100158285456473 ) ) ; -#13814 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20176, #32671, #4648, #30006, #11005, #23465, #35914, #39199, #17305, #26958, #20385, #32858, #29812, #1795, #11201, #23676, #8129, #40203, #5669, #37154 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 0.000000000000000000, 0.001296679741553215769, 0.002598800354045131822, 0.005203041579031965000, 0.01041152402900263028, 0.01562000647896829436, 0.02082848892894396259, 0.03124545382888529316, 0.04166241872883661573, 0.06249634852871927687, 0.08333027832861193696, 0.1249981379283372634, 0.1666659975281625794, 0.2500017167276132324, 0.3333374359272638920, 0.5000030656840478427, 0.6666686954407318177, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13815 = ORIENTED_EDGE ( 'NONE', *, *, #6121, .T. ) ; -#13816 = CARTESIAN_POINT ( 'NONE', ( -25.50973903412187127, 207.9962874668275106, 73.88968492455964565 ) ) ; -#13817 = CARTESIAN_POINT ( 'NONE', ( 37.87388331012000009, 118.7446573730999972, 87.34471339006999813 ) ) ; -#13818 = CARTESIAN_POINT ( 'NONE', ( 36.34244127707000160, 191.7459956895999937, 104.2392664664999984 ) ) ; -#13819 = CARTESIAN_POINT ( 'NONE', ( -19.99999816303952471, 191.5261162992163690, 103.8822987450886046 ) ) ; -#13820 = ORIENTED_EDGE ( 'NONE', *, *, #15798, .T. ) ; -#13821 = CARTESIAN_POINT ( 'NONE', ( 19.99941580399983110, 118.1025156334579265, 87.25545403306659864 ) ) ; -#13822 = DIRECTION ( 'NONE', ( -0.0005884949961256741953, 0.2249510543439056931, -0.9743698870671265722 ) ) ; -#13823 = ORIENTED_EDGE ( 'NONE', *, *, #12054, .F. ) ; -#13824 = EDGE_CURVE ( 'NONE', #39966, #38112, #10242, .T. ) ; -#13825 = CARTESIAN_POINT ( 'NONE', ( -6.040498933618321686, 134.3049593577467249, 93.68954146900784963 ) ) ; -#13826 = DIRECTION ( 'NONE', ( -4.163336342552578951E-15, 0.9743700557921590732, 0.2249510932971538202 ) ) ; -#13827 = AXIS2_PLACEMENT_3D ( 'NONE', #22139, #18237, #3496 ) ; -#13828 = CARTESIAN_POINT ( 'NONE', ( -20.34617778358973439, 105.2139170254723695, 89.78007332956207165 ) ) ; -#13829 = CARTESIAN_POINT ( 'NONE', ( -12.72941739898650759, 126.5535087042000413, 177.7865292237629546 ) ) ; -#13830 = ORIENTED_EDGE ( 'NONE', *, *, #2132, .T. ) ; -#13831 = VECTOR ( 'NONE', #39578, 1000.000000000000114 ) ; -#13832 = CARTESIAN_POINT ( 'NONE', ( 20.00000725255388545, 187.1558174806605450, 102.8491768177758132 ) ) ; -#13833 = ADVANCED_FACE ( 'NONE', ( #15143 ), #4905, .F. ) ; -#13834 = CARTESIAN_POINT ( 'NONE', ( 2.210820436746682827, 189.8667456244558309, 103.9335390899887557 ) ) ; -#13835 = CARTESIAN_POINT ( 'NONE', ( 30.71594229360967887, 134.9841247066007668, 90.79791033182986837 ) ) ; -#13836 = ADVANCED_FACE ( 'NONE', ( #30481 ), #36805, .T. ) ; -#13837 = DIRECTION ( 'NONE', ( -0.5605692862037219282, -0.5785653851274223936, 0.5924729280713232349 ) ) ; -#13838 = CARTESIAN_POINT ( 'NONE', ( -25.36572124470999867, 191.4570433652999952, 104.5200422399999951 ) ) ; -#13839 = LINE ( 'NONE', #4427, #4843 ) ; -#13840 = CARTESIAN_POINT ( 'NONE', ( -19.37107429462388453, 124.6247342938447247, 178.2160518200376771 ) ) ; -#13841 = EDGE_CURVE ( 'NONE', #25077, #14950, #39252, .T. ) ; -#13842 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18952, #25932, #26128, #7287, #16294, #38567, #22456, #35284, #31655, #15888, #758, #4214, #16691, #29192, #355 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999418243, 0.3749999999998815392, 0.4374999999998763212, 0.4999999999998711031, 0.6249999999998721023, 0.6874999999998725464, 0.7499999999998729905, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13843 = LINE ( 'NONE', #4632, #40194 ) ; -#13844 = VERTEX_POINT ( 'NONE', #18178 ) ; -#13845 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989907490, 0.1373964268091706076 ) ) ; -#13846 = DIRECTION ( 'NONE', ( -3.965082230941001926E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; -#13847 = PLANE ( 'NONE', #12000 ) ; -#13848 = DIRECTION ( 'NONE', ( 0.7933535320750287889, -0.5931614265262138419, -0.1369295264925107780 ) ) ; -#13849 = LINE ( 'NONE', #17099, #28079 ) ; -#13850 = CARTESIAN_POINT ( 'NONE', ( 36.08518065169000266, 192.3710643713000081, 106.3864685818000027 ) ) ; -#13851 = CARTESIAN_POINT ( 'NONE', ( 53.45676556571323346, 4.842704760271224096, 161.2945539060282272 ) ) ; -#13852 = CIRCLE ( 'NONE', #26304, 7.499999999930377470 ) ; -#13853 = LINE ( 'NONE', #20799, #23007 ) ; -#13854 = CARTESIAN_POINT ( 'NONE', ( -34.20435832628550088, 218.5902260770999987, 75.57916311368344964 ) ) ; -#13855 = VERTEX_POINT ( 'NONE', #20438 ) ; -#13856 = ORIENTED_EDGE ( 'NONE', *, *, #37283, .F. ) ; -#13857 = AXIS2_PLACEMENT_3D ( 'NONE', #25809, #13721, #38448 ) ; -#13858 = DIRECTION ( 'NONE', ( 0.0002071431143271135504, -0.2252353002181516628, 0.9743043757611731248 ) ) ; -#13859 = CARTESIAN_POINT ( 'NONE', ( -2.851226056375999907, 209.7096532013000001, 76.06022722036999539 ) ) ; -#13860 = CIRCLE ( 'NONE', #17754, 2.000000000000011546 ) ; -#13861 = CARTESIAN_POINT ( 'NONE', ( -15.83166609114682721, 127.1075544891181153, 91.91543601929998886 ) ) ; -#13862 = CARTESIAN_POINT ( 'NONE', ( -12.63809837006106918, 177.7897768145701036, 100.7065200156251166 ) ) ; -#13863 = CARTESIAN_POINT ( 'NONE', ( -12.72918671000827295, 126.9094993052254381, 176.2474024732752582 ) ) ; -#13864 = ORIENTED_EDGE ( 'NONE', *, *, #5860, .T. ) ; -#13865 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927351710658, 0.0005734119022173938011 ) ) ; -#13866 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5800, #27701, #18253, #12149 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13867 = EDGE_LOOP ( 'NONE', ( #18300, #5407, #15456, #32386, #8970, #29606 ) ) ; -#13868 = FACE_OUTER_BOUND ( 'NONE', #36275, .T. ) ; -#13869 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971548471 ) ) ; -#13870 = VERTEX_POINT ( 'NONE', #17972 ) ; -#13871 = CARTESIAN_POINT ( 'NONE', ( 36.48161985942883234, 191.5996263034041647, 106.3711761288207498 ) ) ; -#13872 = EDGE_CURVE ( 'NONE', #12341, #6247, #36601, .T. ) ; -#13873 = EDGE_CURVE ( 'NONE', #17992, #39104, #6306, .T. ) ; -#13874 = PLANE ( 'NONE', #23144 ) ; -#13875 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971555410 ) ) ; -#13876 = LINE ( 'NONE', #23899, #5738 ) ; -#13877 = ADVANCED_FACE ( 'NONE', ( #39655 ), #16747, .F. ) ; -#13878 = LINE ( 'NONE', #38801, #33939 ) ; -#13879 = DIRECTION ( 'NONE', ( -0.0005559617643623586706, 0.3907311284892681646, -0.9205046855589708032 ) ) ; -#13880 = ORIENTED_EDGE ( 'NONE', *, *, #28578, .T. ) ; -#13881 = VERTEX_POINT ( 'NONE', #30681 ) ; -#13882 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319356122658 ) ) ; -#13883 = CARTESIAN_POINT ( 'NONE', ( -30.06885891806713573, 177.7007475763269326, 100.7706418980082930 ) ) ; -#13884 = CIRCLE ( 'NONE', #38674, 2.000000003952151051 ) ; -#13885 = FACE_OUTER_BOUND ( 'NONE', #37882, .T. ) ; -#13886 = EDGE_CURVE ( 'NONE', #5875, #39158, #33723, .T. ) ; -#13887 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36175, #23321, #26796, #7351 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13888 = CARTESIAN_POINT ( 'NONE', ( 30.06906075427019331, 177.1956492900629598, 101.0567532827656123 ) ) ; -#13889 = ORIENTED_EDGE ( 'NONE', *, *, #24272, .T. ) ; -#13890 = CIRCLE ( 'NONE', #23035, 2.000000000000011546 ) ; -#13891 = DIRECTION ( 'NONE', ( 0.0005884949961244146776, -0.2249510543439057209, 0.9743698870671265722 ) ) ; -#13892 = CARTESIAN_POINT ( 'NONE', ( 17.25783335673383689, 152.2632692426403196, 183.6728012514050477 ) ) ; -#13893 = EDGE_CURVE ( 'NONE', #22830, #11457, #1532, .T. ) ; -#13894 = AXIS2_PLACEMENT_3D ( 'NONE', #7146, #16743, #1211 ) ; -#13895 = DIRECTION ( 'NONE', ( -0.0002265441438622214161, 0.9034129951719994667, -0.4287713946056891934 ) ) ; -#13896 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 3.370379598151327408E-34, -0.0006039748319386880390 ) ) ; -#13897 = CARTESIAN_POINT ( 'NONE', ( 36.06386299210247870, 192.3813622508035905, 104.3665697773190715 ) ) ; -#13898 = CARTESIAN_POINT ( 'NONE', ( -20.49852834815464320, 160.1744661120611681, 99.21025293621499941 ) ) ; -#13899 = CARTESIAN_POINT ( 'NONE', ( 26.14714473431000386, 191.5389999363000015, 107.0224641065999975 ) ) ; -#13900 = EDGE_CURVE ( 'NONE', #9107, #4808, #20015, .T. ) ; -#13901 = CARTESIAN_POINT ( 'NONE', ( -45.38028798438312350, 123.7560755211207351, 91.33058355487838753 ) ) ; -#13902 = CARTESIAN_POINT ( 'NONE', ( -37.97047246110000174, 190.2037002657999949, 106.8058008725000150 ) ) ; -#13903 = ORIENTED_EDGE ( 'NONE', *, *, #27357, .F. ) ; -#13904 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#13905 = CARTESIAN_POINT ( 'NONE', ( -28.70875735419499364, 148.8778593096899669, 94.55457546971690874 ) ) ; -#13906 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #40412, #27177, #37161, #9157 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13907 = FACE_OUTER_BOUND ( 'NONE', #8002, .T. ) ; -#13908 = CARTESIAN_POINT ( 'NONE', ( -28.47344760044883216, 181.6851202344923308, 101.6154648382260035 ) ) ; -#13910 = ORIENTED_EDGE ( 'NONE', *, *, #31011, .F. ) ; -#13909 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 92.27946979429611929, 297.5967072516831422 ) ) ; -#13911 = ORIENTED_EDGE ( 'NONE', *, *, #17313, .T. ) ; -#13912 = ORIENTED_EDGE ( 'NONE', *, *, #362, .T. ) ; -#13913 = ORIENTED_EDGE ( 'NONE', *, *, #22620, .T. ) ; -#13914 = DIRECTION ( 'NONE', ( 0.0006039748319395907457, 1.291365685536980287E-14, 0.9999998176071847045 ) ) ; -#13915 = VECTOR ( 'NONE', #31660, 1000.000000000000227 ) ; -#13916 = DIRECTION ( 'NONE', ( -0.0006039748319384964604, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#13917 = CIRCLE ( 'NONE', #36770, 2.500000000068288042 ) ; -#13918 = EDGE_LOOP ( 'NONE', ( #12168, #2831, #17430, #37000 ) ) ; -#13919 = FACE_BOUND ( 'NONE', #19819, .T. ) ; -#13920 = AXIS2_PLACEMENT_3D ( 'NONE', #8962, #6074, #14888 ) ; -#13921 = CARTESIAN_POINT ( 'NONE', ( 28.46561152637904257, 183.4536495838093231, 105.0682559342871798 ) ) ; -#13922 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606776115838874, 137.3532831589803322, 178.0585834212922123 ) ) ; -#13923 = CARTESIAN_POINT ( 'NONE', ( -36.59501409695999996, 115.9050424665000065, 87.88340683977000367 ) ) ; -#13924 = ORIENTED_EDGE ( 'NONE', *, *, #33543, .F. ) ; -#13925 = CARTESIAN_POINT ( 'NONE', ( -26.00142186005520983, 120.7678123865047297, 87.55007858260474052 ) ) ; -#13926 = EDGE_CURVE ( 'NONE', #35367, #18185, #11874, .T. ) ; -#13927 = EDGE_LOOP ( 'NONE', ( #2053, #3177, #16960, #33322 ) ) ; -#13929 = EDGE_CURVE ( 'NONE', #1201, #23181, #2470, .T. ) ; -#13928 = CARTESIAN_POINT ( 'NONE', ( 12.31198009898977297, 134.9205818654068025, 90.79431936396761671 ) ) ; -#13930 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927775520409, 0.0005734119022077229346 ) ) ; -#13931 = EDGE_CURVE ( 'NONE', #14171, #10767, #23730, .T. ) ; -#13932 = CARTESIAN_POINT ( 'NONE', ( 20.23520089091118734, 184.3460486268157581, 105.0395362574031850 ) ) ; -#13933 = CARTESIAN_POINT ( 'NONE', ( -34.20496230111741909, 218.5902260770999987, 74.57916329611410333 ) ) ; -#13934 = CARTESIAN_POINT ( 'NONE', ( -20.33179760611627529, 190.9257021876913711, 106.4806516276633488 ) ) ; -#13935 = EDGE_LOOP ( 'NONE', ( #658, #3538, #28744, #32266, #27255, #32321 ) ) ; -#13936 = EDGE_LOOP ( 'NONE', ( #14844, #34451, #12170, #9291 ) ) ; -#13937 = CARTESIAN_POINT ( 'NONE', ( -2.882312078823639823, 190.4459497224870006, 103.6177516974930057 ) ) ; -#13938 = LINE ( 'NONE', #35176, #21861 ) ; -#13939 = CARTESIAN_POINT ( 'NONE', ( 3.199688738393000609, 190.8178714546999970, 106.9231052872000021 ) ) ; -#13940 = EDGE_CURVE ( 'NONE', #28905, #19509, #32917, .T. ) ; -#13941 = ORIENTED_EDGE ( 'NONE', *, *, #24289, .F. ) ; -#13942 = DIRECTION ( 'NONE', ( -0.9999998175971751557, 0.000000000000000000, 0.0006039914041785637844 ) ) ; -#13943 = CARTESIAN_POINT ( 'NONE', ( -25.50005604804929149, 118.3471990083214962, 89.78317637797779582 ) ) ; -#13944 = ORIENTED_EDGE ( 'NONE', *, *, #9556, .T. ) ; -#13945 = VERTEX_POINT ( 'NONE', #8187 ) ; -#13946 = EDGE_CURVE ( 'NONE', #921, #33034, #18109, .T. ) ; -#13947 = VECTOR ( 'NONE', #12446, 1000.000000000000000 ) ; -#13948 = VERTEX_POINT ( 'NONE', #11666 ) ; -#13949 = ORIENTED_EDGE ( 'NONE', *, *, #30879, .T. ) ; -#13950 = CARTESIAN_POINT ( 'NONE', ( 3.040951859482069697, 190.5315687460202128, 106.7176784835704524 ) ) ; -#13951 = AXIS2_PLACEMENT_3D ( 'NONE', #27674, #2514, #21116 ) ; -#13952 = CARTESIAN_POINT ( 'NONE', ( -28.25482047719070167, 186.4533228041470068, 105.2801804772170016 ) ) ; -#13953 = CARTESIAN_POINT ( 'NONE', ( -6.273952178503699351, 163.8304651410298334, 97.99310710002680480 ) ) ; -#13954 = LINE ( 'NONE', #32752, #38045 ) ; -#13955 = ADVANCED_FACE ( 'NONE', ( #27014 ), #40192, .F. ) ; -#13956 = VECTOR ( 'NONE', #6328, 1000.000000000000000 ) ; -#13957 = ORIENTED_EDGE ( 'NONE', *, *, #26188, .F. ) ; -#13958 = LINE ( 'NONE', #20476, #36850 ) ; -#13959 = ORIENTED_EDGE ( 'NONE', *, *, #23015, .F. ) ; -#13960 = CARTESIAN_POINT ( 'NONE', ( 26.00101267970367047, 120.0777975675569422, 90.42043399727945996 ) ) ; -#13961 = CARTESIAN_POINT ( 'NONE', ( 23.36350214670024172, 176.7448593257297773, 103.0093387781554384 ) ) ; -#13963 = LINE ( 'NONE', #22572, #12900 ) ; -#13962 = CARTESIAN_POINT ( 'NONE', ( 20.48140489407852272, 209.4114369237129551, 75.55886289686685586 ) ) ; -#13964 = ORIENTED_EDGE ( 'NONE', *, *, #39925, .T. ) ; -#13965 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#13966 = ORIENTED_EDGE ( 'NONE', *, *, #30375, .T. ) ; -#13967 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15217, #39731, #17844, #5596 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13968 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#13969 = EDGE_LOOP ( 'NONE', ( #33776, #26680, #23793, #23273 ) ) ; -#13970 = CARTESIAN_POINT ( 'NONE', ( -22.49970497330916075, 127.6303751971628060, 89.64545616911016168 ) ) ; -#13971 = CARTESIAN_POINT ( 'NONE', ( -44.54363022636869118, 124.4565585485832173, 93.47074073741023881 ) ) ; -#13972 = CARTESIAN_POINT ( 'NONE', ( -37.36309420899848277, 111.9429838260873851, 150.4031338454339561 ) ) ; -#13973 = ORIENTED_EDGE ( 'NONE', *, *, #37267, .T. ) ; -#13974 = AXIS2_PLACEMENT_3D ( 'NONE', #14657, #39369, #27344 ) ; -#13975 = VECTOR ( 'NONE', #20401, 1000.000000000000000 ) ; -#13976 = ORIENTED_EDGE ( 'NONE', *, *, #5449, .T. ) ; -#13977 = EDGE_LOOP ( 'NONE', ( #9670, #26652, #4491, #20399 ) ) ; -#13978 = ADVANCED_FACE ( 'NONE', ( #33321 ), #36943, .F. ) ; -#13979 = CARTESIAN_POINT ( 'NONE', ( -30.07038801301978026, 136.6761377446520385, 94.30416869769356936 ) ) ; -#13980 = CONICAL_SURFACE ( 'NONE', #37471, 2.749999999702389175, 0.7853981633701920817 ) ; -#13981 = EDGE_CURVE ( 'NONE', #31429, #15784, #3642, .T. ) ; -#13982 = VERTEX_POINT ( 'NONE', #15918 ) ; -#13983 = FACE_OUTER_BOUND ( 'NONE', #15162, .T. ) ; -#13984 = EDGE_CURVE ( 'NONE', #1363, #1746, #40283, .T. ) ; -#13985 = CARTESIAN_POINT ( 'NONE', ( 2.564171575070496534, 190.9919204788867262, 106.3097368431030532 ) ) ; -#13986 = ORIENTED_EDGE ( 'NONE', *, *, #35485, .T. ) ; -#13987 = LINE ( 'NONE', #38508, #9910 ) ; -#13988 = CARTESIAN_POINT ( 'NONE', ( 23.68587874345097077, 128.0263992037866103, 91.76159925728045152 ) ) ; -#13989 = CARTESIAN_POINT ( 'NONE', ( 20.19466032994544946, 152.9152984434986706, 94.94400332294932809 ) ) ; -#13990 = CARTESIAN_POINT ( 'NONE', ( -12.63766980425072184, 130.4202329703295788, 90.28358935384768813 ) ) ; -#13991 = ORIENTED_EDGE ( 'NONE', *, *, #39299, .F. ) ; -#13992 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#13993 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; -#13994 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082099409, 87.27946979429613350, 297.5876476292038433 ) ) ; -#13995 = VECTOR ( 'NONE', #36813, 1000.000000000000114 ) ; -#13996 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21403, #33438, #17688, #5430, #2964, #14856, #2584, #24677, #27945, #39571, #30186 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000464628, 0.3750000000000897060, 0.4375000000001306177, 0.4687500000001419420, 0.5000000000001533218, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#13997 = AXIS2_PLACEMENT_3D ( 'NONE', #36157, #13891, #32889 ) ; -#13998 = VECTOR ( 'NONE', #37969, 1000.000000000000114 ) ; -#13999 = ORIENTED_EDGE ( 'NONE', *, *, #13557, .T. ) ; -#14000 = CARTESIAN_POINT ( 'NONE', ( 12.64524319930002783, 177.7928828500099598, 100.6920447773197225 ) ) ; -#14001 = AXIS2_PLACEMENT_3D ( 'NONE', #13507, #29249, #32508 ) ; -#14003 = CARTESIAN_POINT ( 'NONE', ( -36.43486607269000643, 114.9103894214999997, 89.61052565925000124 ) ) ; -#14002 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971561517 ) ) ; -#14004 = VERTEX_POINT ( 'NONE', #9208 ) ; -#14005 = ORIENTED_EDGE ( 'NONE', *, *, #7350, .T. ) ; -#14006 = DIRECTION ( 'NONE', ( -0.7933532411131104523, -0.5932638852154226150, -0.1364866195435462393 ) ) ; -#14007 = EDGE_CURVE ( 'NONE', #629, #31589, #32755, .T. ) ; -#14008 = FACE_OUTER_BOUND ( 'NONE', #24439, .T. ) ; -#14009 = CARTESIAN_POINT ( 'NONE', ( 25.50046716662595969, 119.8278461341035523, 89.86771791572004986 ) ) ; -#14010 = FACE_OUTER_BOUND ( 'NONE', #12415, .T. ) ; -#14011 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971544308 ) ) ; -#14012 = EDGE_LOOP ( 'NONE', ( #9511, #26726, #21323, #33396 ) ) ; -#14013 = ORIENTED_EDGE ( 'NONE', *, *, #25465, .F. ) ; -#14014 = CARTESIAN_POINT ( 'NONE', ( -4.139184126008303544, 182.1714396567753909, 101.7130139884077096 ) ) ; -#14015 = ORIENTED_EDGE ( 'NONE', *, *, #32091, .F. ) ; -#14016 = ORIENTED_EDGE ( 'NONE', *, *, #15371, .T. ) ; -#14017 = CARTESIAN_POINT ( 'NONE', ( 20.33360375042520118, 118.8156395306597801, 87.58882291287987698 ) ) ; -#14018 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 1.387778780781445202E-14, 0.0006039748319484430396 ) ) ; -#14019 = EDGE_CURVE ( 'NONE', #27523, #5067, #12458, .T. ) ; -#14020 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971548194 ) ) ; -#14021 = CARTESIAN_POINT ( 'NONE', ( -22.49970497326000185, 153.8038087566390857, 95.68807060344595072 ) ) ; -#14023 = EDGE_CURVE ( 'NONE', #37130, #20447, #4430, .T. ) ; -#14022 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; -#14024 = CARTESIAN_POINT ( 'NONE', ( 36.43722455489999845, 115.9580984249000011, 87.59694388343000071 ) ) ; -#14025 = CARTESIAN_POINT ( 'NONE', ( 36.70584045868999823, 191.7769508183999960, 104.5054429551999959 ) ) ; -#14027 = ADVANCED_FACE ( 'NONE', ( #9404 ), #31271, .F. ) ; -#14026 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7476, #33223, #2180, #26927 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.007919380345415786421, 0.009892895677996241255 ), - .UNSPECIFIED. ) ; -#14028 = CARTESIAN_POINT ( 'NONE', ( -28.70758036415549697, 148.4279572010033519, 96.50331524374598757 ) ) ; -#14029 = AXIS2_PLACEMENT_3D ( 'NONE', #32405, #38329, #505 ) ; -#14030 = ADVANCED_FACE ( 'NONE', ( #40257 ), #24553, .T. ) ; -#14031 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 130.2884061588697477, 89.74324129540521255 ) ) ; -#14032 = VERTEX_POINT ( 'NONE', #25352 ) ; -#14033 = LINE ( 'NONE', #10765, #34952 ) ; -#14034 = CARTESIAN_POINT ( 'NONE', ( -0.09096142117404142080, 291.9973835945268661, 213.2953014176902684 ) ) ; -#14035 = ORIENTED_EDGE ( 'NONE', *, *, #33466, .T. ) ; -#14036 = CIRCLE ( 'NONE', #22538, 59.40509898897000340 ) ; -#14037 = CIRCLE ( 'NONE', #2904, 2.250000000000011102 ) ; -#14038 = CARTESIAN_POINT ( 'NONE', ( 0.5623190733617040582, 188.6124699482102756, 103.1972064621602527 ) ) ; -#14039 = CONICAL_SURFACE ( 'NONE', #38202, 2.503010280774284446, 0.7853981633971977017 ) ; -#14040 = DIRECTION ( 'NONE', ( -0.0008702664949568214786, 0.2253087660099396816, -0.9742870226967542679 ) ) ; -#14041 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26313, #4415, #38965, #39362 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.002706531821497740360, 0.003412669838136366852 ), - .UNSPECIFIED. ) ; -#14042 = CARTESIAN_POINT ( 'NONE', ( 9.336298587753999456, 177.4927349323999977, 100.8812869146999986 ) ) ; -#14043 = ORIENTED_EDGE ( 'NONE', *, *, #21751, .T. ) ; -#14044 = CARTESIAN_POINT ( 'NONE', ( -13.46474670641307192, 153.6042747584635890, 98.03125767508242916 ) ) ; -#14045 = CARTESIAN_POINT ( 'NONE', ( 1.500298425804543090, 189.2323929059827208, 103.7509457637548991 ) ) ; -#14046 = CARTESIAN_POINT ( 'NONE', ( 1.169582293534972672, 154.1625274373266166, 98.32235243253177259 ) ) ; -#14047 = ORIENTED_EDGE ( 'NONE', *, *, #29618, .F. ) ; -#14048 = CARTESIAN_POINT ( 'NONE', ( 40.24910017280793539, 69.86439126638083508, 297.5342355816429745 ) ) ; -#14049 = CARTESIAN_POINT ( 'NONE', ( -25.35703419792000091, 191.6937711645000206, 104.5554867752999968 ) ) ; -#14050 = CARTESIAN_POINT ( 'NONE', ( -44.96472012149743591, 114.9735949632774634, 130.1287737409121235 ) ) ; -#14051 = CARTESIAN_POINT ( 'NONE', ( -25.50772789673414920, 207.4083919362629160, 77.09708259040941414 ) ) ; -#14052 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #28405, #9396, #378, #18369 ), - ( #24750, #31262, #12069, #3240 ), - ( #3042, #15909, #30673, #2848 ), - ( #12867, #24545, #18568, #25343 ), - ( #9803, #182, #9199, #31072 ), - ( #27821, #15713, #15523, #37205 ), - ( #21677, #12452, #6309, #33918 ), - ( #5721, #37002, #9001, #28013 ), - ( #12649, #40451, #21478, #22275 ), - ( #30871, #24950, #18975, #5915 ), - ( #25145, #37791, #40248, #3433 ), - ( #18167, #2668, #15132, #15327 ), - ( #12260, #21869, #34115, #9593 ), - ( #6110, #27623, #37591, #6502 ), - ( #34313, #34497, #31466, #18763 ), - ( #571, #4037, #34900, #29209 ), - ( #35495, #22875, #26346, #6704 ), - ( #16506, #1180, #7513, #10404 ), - ( #16316, #32079, #7305, #25952 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -8.647373113754999534E-05, 0.0009118153858942000143, 0.001910104502926000033, 0.003906682736990000140, 0.007812926453889999789, 0.01562541388768999909, 0.03125038875529000115, 0.04687536362289999869, 0.06250033849048999834, 0.09375028822570000142, 0.1250002379609000125, 0.2500000369016999735, 0.3750000857495000006, 0.5000001345972999722, 0.7500002322929999465, 1.000000000000000000, 1.066647782683000090 ), - ( -2.826277697986999871E-08, 1.000838866515000092 ), - .UNSPECIFIED. ) ; -#14053 = CARTESIAN_POINT ( 'NONE', ( -45.98534017754115411, 187.3083424662111725, 103.4373877126195680 ) ) ; -#14054 = DIRECTION ( 'NONE', ( -0.0005884949961259294164, 0.2255194585872565272, -0.9742384859325513569 ) ) ; -#14055 = VERTEX_POINT ( 'NONE', #6511 ) ; -#14056 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20785, #31158, #31767, #12953, #16201, #34981, #19059 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 4 ), - ( 8.578795829086378872E-07, 3.033693725176223621E-05, 0.001294842039712246987 ), - .UNSPECIFIED. ) ; -#14057 = AXIS2_PLACEMENT_3D ( 'NONE', #6996, #38281, #22162 ) ; -#14058 = CARTESIAN_POINT ( 'NONE', ( -22.78364630492483656, 153.8037711675519859, 95.68823341888959533 ) ) ; -#14059 = CARTESIAN_POINT ( 'NONE', ( -35.94552286447999734, 192.4337292808999962, 104.1697190562999964 ) ) ; -#14061 = CARTESIAN_POINT ( 'NONE', ( -2.921522756988824465, 209.4523253363161075, 73.06026897222399441 ) ) ; -#14060 = CIRCLE ( 'NONE', #3590, 1.999999999999994893 ) ; -#14062 = EDGE_CURVE ( 'NONE', #29586, #16868, #38966, .T. ) ; -#14063 = CARTESIAN_POINT ( 'NONE', ( 36.76623636621000202, 191.1626283010999998, 106.4305375327000007 ) ) ; -#14064 = CARTESIAN_POINT ( 'NONE', ( 32.56861805024679768, 175.3596280205372011, 100.1182146692571138 ) ) ; -#14065 = AXIS2_PLACEMENT_3D ( 'NONE', #6928, #37418, #18989 ) ; -#14066 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319369175368 ) ) ; -#14067 = CARTESIAN_POINT ( 'NONE', ( -27.01791081220863333, 113.9384843682444739, 176.2313260275029734 ) ) ; -#14068 = ORIENTED_EDGE ( 'NONE', *, *, #9008, .T. ) ; -#14069 = CARTESIAN_POINT ( 'NONE', ( -5.674054448684419327, 181.0562813008041019, 104.4985371984615909 ) ) ; -#14070 = CARTESIAN_POINT ( 'NONE', ( 26.73277628323574717, 120.3821797830261033, 171.5759152015846496 ) ) ; -#14071 = EDGE_CURVE ( 'NONE', #7856, #18111, #7241, .T. ) ; -#14072 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; -#14073 = ORIENTED_EDGE ( 'NONE', *, *, #36025, .F. ) ; -#14074 = DIRECTION ( 'NONE', ( 0.7933532970003738249, 0.5930762008556724751, 0.1372995488602876402 ) ) ; -#14075 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474978710144656, 155.7928101624881663, 98.18628735359372683 ) ) ; -#14076 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29304, #1279, #25182, #31301 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14077 = EDGE_CURVE ( 'NONE', #19947, #12930, #3707, .T. ) ; -#14078 = ORIENTED_EDGE ( 'NONE', *, *, #25080, .T. ) ; -#14079 = EDGE_CURVE ( 'NONE', #31188, #27747, #36151, .T. ) ; -#14080 = EDGE_CURVE ( 'NONE', #18912, #32718, #37608, .T. ) ; -#14081 = PLANE ( 'NONE', #4829 ) ; -#14082 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319386956284 ) ) ; -#14083 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29374, #1971, #26924, #30179 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14084 = VERTEX_POINT ( 'NONE', #3050 ) ; -#14085 = CARTESIAN_POINT ( 'NONE', ( 36.47117602849728257, 191.6114442409242429, 106.3724499118136180 ) ) ; -#14086 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319370729030 ) ) ; -#14087 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#14088 = CARTESIAN_POINT ( 'NONE', ( -25.50111726777775090, 120.6553742016506874, 88.03695713991920968 ) ) ; -#14089 = LINE ( 'NONE', #26766, #18256 ) ; -#14090 = DIRECTION ( 'NONE', ( 1.017704439249174122E-14, -0.9743700557921587402, -0.2249510932971553467 ) ) ; -#14091 = AXIS2_PLACEMENT_3D ( 'NONE', #7495, #10989, #16888 ) ; -#14092 = ORIENTED_EDGE ( 'NONE', *, *, #6810, .T. ) ; -#14093 = CARTESIAN_POINT ( 'NONE', ( -12.63088703835403237, 131.0198726340251199, 89.90887950976862442 ) ) ; -#14094 = DIRECTION ( 'NONE', ( 0.7856007465113965527, 0.6187337610642694719, 0.000000000000000000 ) ) ; -#14095 = CIRCLE ( 'NONE', #17298, 2.500000000068516748 ) ; -#14096 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#14097 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #37686, #6796 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14098 = AXIS2_PLACEMENT_3D ( 'NONE', #25164, #9819, #34723 ) ; -#14099 = ORIENTED_EDGE ( 'NONE', *, *, #1941, .F. ) ; -#14100 = LINE ( 'NONE', #11423, #7958 ) ; -#14101 = ORIENTED_EDGE ( 'NONE', *, *, #9315, .T. ) ; -#14102 = AXIS2_PLACEMENT_3D ( 'NONE', #31798, #4152, #18886 ) ; -#14103 = VERTEX_POINT ( 'NONE', #15530 ) ; -#14104 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, -1.295171136338797037E-14 ) ) ; -#14105 = CARTESIAN_POINT ( 'NONE', ( 20.16857011096831442, 151.3424427607513678, 97.48851605858358482 ) ) ; -#14106 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#14107 = CARTESIAN_POINT ( 'NONE', ( 4.133313241595669041, 130.5370971685930499, 89.78728818282839086 ) ) ; -#14108 = CARTESIAN_POINT ( 'NONE', ( -22.49862694078846559, 157.6261014233649576, 99.13627282167615817 ) ) ; -#14109 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971555410 ) ) ; -#14110 = CYLINDRICAL_SURFACE ( 'NONE', #33268, 2.000000000000014655 ) ; -#14111 = CARTESIAN_POINT ( 'NONE', ( 25.90038763860000159, 190.9907937845999868, 106.6889637737999976 ) ) ; -#14112 = CARTESIAN_POINT ( 'NONE', ( 26.80533604859723340, 110.6131156702000027, 90.25159508795590568 ) ) ; -#14113 = CARTESIAN_POINT ( 'NONE', ( 3.312971681818163372, 183.3029474176353233, 101.9697422706757521 ) ) ; -#14114 = EDGE_LOOP ( 'NONE', ( #7645, #1442, #1435, #26801 ) ) ; -#14115 = ADVANCED_FACE ( 'NONE', ( #18769 ), #28020, .F. ) ; -#14116 = CARTESIAN_POINT ( 'NONE', ( 16.57679466784161804, 122.7580812988415460, 172.1226709236619286 ) ) ; -#14117 = DIRECTION ( 'NONE', ( -0.0005884949961245359998, 0.2249510543439058319, -0.9743698870671265722 ) ) ; -#14118 = EDGE_CURVE ( 'NONE', #25759, #25751, #188, .T. ) ; -#14119 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32681, #14698, #36137, #10815, #35713, #1806, #29614, #2017, #39206, #20191 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14120 = CARTESIAN_POINT ( 'NONE', ( 19.27401778716228620, 148.4626371618211067, 184.5957245738844961 ) ) ; -#14121 = CARTESIAN_POINT ( 'NONE', ( -23.36013443277664692, 183.4461002756636674, 105.1009555742510031 ) ) ; -#14122 = ADVANCED_FACE ( 'NONE', ( #38002 ), #15398, .F. ) ; -#14123 = CONICAL_SURFACE ( 'NONE', #37632, 2.502994747345931970, 0.7853981633840819709 ) ; -#14124 = CARTESIAN_POINT ( 'NONE', ( -20.89133279417689337, 135.6510826495900517, 94.06197212497137627 ) ) ; -#14125 = AXIS2_PLACEMENT_3D ( 'NONE', #8438, #27471, #9238 ) ; -#14126 = ORIENTED_EDGE ( 'NONE', *, *, #30497, .F. ) ; -#14127 = ORIENTED_EDGE ( 'NONE', *, *, #21094, .F. ) ; -#14128 = ADVANCED_FACE ( 'NONE', ( #25554 ), #22882, .T. ) ; -#14129 = ORIENTED_EDGE ( 'NONE', *, *, #15628, .F. ) ; -#14130 = CARTESIAN_POINT ( 'NONE', ( -13.50129746631583849, 124.5395215374018818, 88.65269067405510839 ) ) ; -#14131 = CIRCLE ( 'NONE', #34330, 2.500000093254001854 ) ; -#14132 = CARTESIAN_POINT ( 'NONE', ( -23.01879311717446086, 214.0903458147471383, 76.07243274013872281 ) ) ; -#14133 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391912172 ) ) ; -#14134 = AXIS2_PLACEMENT_3D ( 'NONE', #36038, #17636, #10718 ) ; -#14135 = VERTEX_POINT ( 'NONE', #10413 ) ; -#14136 = FACE_BOUND ( 'NONE', #29096, .T. ) ; -#14137 = EDGE_CURVE ( 'NONE', #38350, #1132, #36596, .T. ) ; -#14138 = CARTESIAN_POINT ( 'NONE', ( -28.46590577390901444, 183.5585884066778419, 104.6137160372684036 ) ) ; -#14139 = CARTESIAN_POINT ( 'NONE', ( -37.22196800321000154, 118.5277161940000212, 87.16415279387000226 ) ) ; -#14140 = EDGE_LOOP ( 'NONE', ( #12476, #27171, #4135, #17178 ) ) ; -#14141 = CARTESIAN_POINT ( 'NONE', ( -13.50000076883903510, 154.4042507776735818, 95.30811371979322644 ) ) ; -#14142 = ORIENTED_EDGE ( 'NONE', *, *, #1929, .T. ) ; -#14143 = DIRECTION ( 'NONE', ( -0.0005559617644274909235, 0.3907311284892684422, -0.9205046855589705812 ) ) ; -#14144 = CARTESIAN_POINT ( 'NONE', ( 35.55533445361766098, 112.4664342211686971, 90.24631030758727945 ) ) ; -#14145 = DIRECTION ( 'NONE', ( 0.0006039748319378934272, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#14146 = ORIENTED_EDGE ( 'NONE', *, *, #21101, .F. ) ; -#14147 = EDGE_CURVE ( 'NONE', #38809, #9250, #26585, .T. ) ; -#14148 = ORIENTED_EDGE ( 'NONE', *, *, #36265, .T. ) ; -#14149 = CARTESIAN_POINT ( 'NONE', ( -20.00002391410913560, 191.9758546681010785, 103.9335315410770448 ) ) ; -#14150 = CARTESIAN_POINT ( 'NONE', ( 0.6435323986543000085, 188.8721228995999866, 103.5282549655999986 ) ) ; -#14151 = CARTESIAN_POINT ( 'NONE', ( -35.43583965384924994, 192.6933639929883668, 106.8920161462278315 ) ) ; -#14152 = AXIS2_PLACEMENT_3D ( 'NONE', #9505, #21785, #34422 ) ; -#14153 = ORIENTED_EDGE ( 'NONE', *, *, #20901, .F. ) ; -#14154 = VERTEX_POINT ( 'NONE', #7519 ) ; -#14155 = CARTESIAN_POINT ( 'NONE', ( 16.88249520720069441, 127.4209172357130342, 171.9069182253847430 ) ) ; -#14156 = CARTESIAN_POINT ( 'NONE', ( -25.50005904708520887, 118.5813826976429937, 89.78317938063858605 ) ) ; -#14157 = AXIS2_PLACEMENT_3D ( 'NONE', #17163, #35549, #14133 ) ; -#14158 = VERTEX_POINT ( 'NONE', #19779 ) ; -#14159 = EDGE_LOOP ( 'NONE', ( #40414, #11754, #1095, #37824 ) ) ; -#14160 = CIRCLE ( 'NONE', #8271, 2.749999999950412999 ) ; -#14161 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34221, #31379, #33832, #9108 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14162 = CIRCLE ( 'NONE', #37638, 2.000000000015665691 ) ; -#14163 = ORIENTED_EDGE ( 'NONE', *, *, #27291, .F. ) ; -#14164 = ORIENTED_EDGE ( 'NONE', *, *, #9148, .T. ) ; -#14165 = VECTOR ( 'NONE', #31704, 1000.000000000000227 ) ; -#14166 = CARTESIAN_POINT ( 'NONE', ( -27.00166637643960854, 188.8391338125088907, 103.2661811242819141 ) ) ; -#14167 = DIRECTION ( 'NONE', ( -0.0006039748319385316970, -1.156831349449291921E-15, -0.9999998176071845934 ) ) ; -#14168 = DIRECTION ( 'NONE', ( 0.0005884949961216158097, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#14169 = ORIENTED_EDGE ( 'NONE', *, *, #14118, .F. ) ; -#14170 = LINE ( 'NONE', #1684, #4257 ) ; -#14171 = VERTEX_POINT ( 'NONE', #32678 ) ; -#14172 = EDGE_CURVE ( 'NONE', #30682, #26180, #38239, .T. ) ; -#14173 = CARTESIAN_POINT ( 'NONE', ( 25.86001714968000087, 120.6927307848000197, 90.40934820274000572 ) ) ; -#14174 = EDGE_CURVE ( 'NONE', #16794, #7173, #35709, .T. ) ; -#14175 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971558741 ) ) ; -#14176 = EDGE_CURVE ( 'NONE', #39055, #21097, #4656, .T. ) ; -#14177 = ADVANCED_FACE ( 'NONE', ( #7719 ), #38594, .F. ) ; -#14179 = FACE_OUTER_BOUND ( 'NONE', #29927, .T. ) ; -#14178 = CARTESIAN_POINT ( 'NONE', ( 20.48226435717378990, 207.6251565648111921, 76.64532538342577084 ) ) ; -#14180 = VERTEX_POINT ( 'NONE', #17114 ) ; -#14181 = ORIENTED_EDGE ( 'NONE', *, *, #22259, .F. ) ; -#14182 = ADVANCED_FACE ( 'NONE', ( #29611 ), #1676, .F. ) ; -#14183 = VECTOR ( 'NONE', #27709, 1000.000000000000227 ) ; -#14184 = CARTESIAN_POINT ( 'NONE', ( -36.20294578993510015, 191.8784110327004271, 104.4126546692563124 ) ) ; -#14185 = AXIS2_PLACEMENT_3D ( 'NONE', #11011, #20808, #14693 ) ; -#14186 = AXIS2_PLACEMENT_3D ( 'NONE', #23060, #35484, #38770 ) ; -#14187 = ORIENTED_EDGE ( 'NONE', *, *, #816, .T. ) ; -#14188 = CARTESIAN_POINT ( 'NONE', ( -35.58577006176208357, 114.4949262162575394, 87.28927720544345448 ) ) ; -#14189 = EDGE_CURVE ( 'NONE', #8395, #35627, #23078, .T. ) ; -#14190 = LINE ( 'NONE', #23572, #1772 ) ; -#14191 = CARTESIAN_POINT ( 'NONE', ( -25.86759374482710783, 189.1478801855697327, 105.9025369694237355 ) ) ; -#14192 = VERTEX_POINT ( 'NONE', #6922 ) ; -#14193 = ORIENTED_EDGE ( 'NONE', *, *, #32607, .F. ) ; -#14194 = CARTESIAN_POINT ( 'NONE', ( -55.13842001341838284, 70.21991383836160594, 291.5918461592676181 ) ) ; -#14195 = CARTESIAN_POINT ( 'NONE', ( 26.67362535667000145, 123.9118361340999996, 88.58630574830999649 ) ) ; -#14196 = ORIENTED_EDGE ( 'NONE', *, *, #6628, .T. ) ; -#14197 = CARTESIAN_POINT ( 'NONE', ( -35.47012669195299850, 192.2364783050030042, 106.9476611020870109 ) ) ; -#14198 = CARTESIAN_POINT ( 'NONE', ( -38.25678666646345505, 118.2563848851881261, 89.71134074324241681 ) ) ; -#14199 = ORIENTED_EDGE ( 'NONE', *, *, #13550, .F. ) ; -#14200 = CARTESIAN_POINT ( 'NONE', ( 2.897488390111000012, 190.8910838861999935, 106.6291555332999934 ) ) ; -#14201 = CARTESIAN_POINT ( 'NONE', ( -30.07323323487542410, 135.0982449750613057, 91.11183024367421979 ) ) ; -#14202 = CARTESIAN_POINT ( 'NONE', ( 6.034204648359921208, 177.7921235470974466, 100.6958268401488539 ) ) ; -#14203 = CARTESIAN_POINT ( 'NONE', ( 20.21154621427845655, 152.9536990292900782, 94.95285859969516196 ) ) ; -#14204 = CARTESIAN_POINT ( 'NONE', ( 32.66389061773956826, 141.7118122376935219, 282.5421777876526335 ) ) ; -#14205 = AXIS2_PLACEMENT_3D ( 'NONE', #19445, #6975, #37863 ) ; -#14206 = ORIENTED_EDGE ( 'NONE', *, *, #29260, .T. ) ; -#14207 = FACE_OUTER_BOUND ( 'NONE', #12373, .T. ) ; -#14208 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -1.540743955509788340E-33, -0.0006039748319384538513 ) ) ; -#14209 = ORIENTED_EDGE ( 'NONE', *, *, #33030, .T. ) ; -#14210 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#14211 = EDGE_CURVE ( 'NONE', #12603, #8692, #35107, .T. ) ; -#14212 = EDGE_CURVE ( 'NONE', #35056, #10693, #35110, .T. ) ; -#14214 = CARTESIAN_POINT ( 'NONE', ( 13.79955906167705315, 158.3019397583766192, 96.19147016730026678 ) ) ; -#14213 = DIRECTION ( 'NONE', ( -1.249000902737679666E-14, 0.9743700557921584071, 0.2249510932971565957 ) ) ; -#14215 = ORIENTED_EDGE ( 'NONE', *, *, #37836, .T. ) ; -#14216 = ORIENTED_EDGE ( 'NONE', *, *, #10574, .F. ) ; -#14217 = DIRECTION ( 'NONE', ( 0.6087614115774527823, 0.7729348350621608743, 0.1788331191968013101 ) ) ; -#14218 = LINE ( 'NONE', #4587, #23907 ) ; -#14219 = CARTESIAN_POINT ( 'NONE', ( -20.16649829641212577, 127.7037111234754008, 89.31880475177413814 ) ) ; -#14220 = CARTESIAN_POINT ( 'NONE', ( -13.49989043803929434, 124.0147166309723019, 91.09304410618094039 ) ) ; -#14221 = ORIENTED_EDGE ( 'NONE', *, *, #36480, .F. ) ; -#14222 = ORIENTED_EDGE ( 'NONE', *, *, #31106, .F. ) ; -#14223 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#14224 = ORIENTED_EDGE ( 'NONE', *, *, #11677, .F. ) ; -#14225 = ORIENTED_EDGE ( 'NONE', *, *, #16354, .T. ) ; -#14226 = DIRECTION ( 'NONE', ( -0.6075492010474002891, 0.7738441339353229198, 0.1790229724939113032 ) ) ; -#14227 = CARTESIAN_POINT ( 'NONE', ( 2.964187886207000133, 209.6236585254000317, 73.05669866528999989 ) ) ; -#14228 = CONICAL_SURFACE ( 'NONE', #37079, 2.502993756986731100, 0.7853981634153905933 ) ; -#14229 = VERTEX_POINT ( 'NONE', #3844 ) ; -#14230 = CARTESIAN_POINT ( 'NONE', ( 42.94254652958284879, 102.0785988256732679, 173.5067946477687144 ) ) ; -#14231 = DIRECTION ( 'NONE', ( 0.0004161288024536310341, -0.8480480897965216869, 0.5299191110247775116 ) ) ; -#14232 = CARTESIAN_POINT ( 'NONE', ( -36.19263021343000020, 191.7617955707000021, 104.2857773767999987 ) ) ; -#14233 = CARTESIAN_POINT ( 'NONE', ( 38.04191701154000071, 190.9293984182999964, 103.5603850786000066 ) ) ; -#14234 = CARTESIAN_POINT ( 'NONE', ( -15.49970618472456074, 126.6879451655382809, 89.42365126055415203 ) ) ; -#14235 = VECTOR ( 'NONE', #15279, 1000.000000000000114 ) ; -#14236 = ADVANCED_FACE ( 'NONE', ( #29006 ), #16909, .T. ) ; -#14237 = VERTEX_POINT ( 'NONE', #32088 ) ; -#14238 = LINE ( 'NONE', #20978, #2961 ) ; -#14239 = DIRECTION ( 'NONE', ( 0.0006039748319292907166, 1.314021223879979485E-14, 0.9999998176071844824 ) ) ; -#14240 = CARTESIAN_POINT ( 'NONE', ( 20.00000279695219874, 118.8155797008581374, 87.25566994753728522 ) ) ; -#14241 = EDGE_LOOP ( 'NONE', ( #29637, #6593, #11495, #6728 ) ) ; -#14242 = CARTESIAN_POINT ( 'NONE', ( 0.6175806947401220048, 188.6158791694291494, 103.1979573861220985 ) ) ; -#14243 = CARTESIAN_POINT ( 'NONE', ( 24.99841341575277553, 116.5768525021753561, 87.75250987812781034 ) ) ; -#14244 = CARTESIAN_POINT ( 'NONE', ( 20.16677047258863098, 191.4881498579996162, 104.0203231957113843 ) ) ; -#14245 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #40002, #11811, #8951, #9144 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14246 = CARTESIAN_POINT ( 'NONE', ( -14.22274084689574636, 128.8778062397453539, 177.5848030100378026 ) ) ; -#14247 = ORIENTED_EDGE ( 'NONE', *, *, #11647, .F. ) ; -#14248 = DIRECTION ( 'NONE', ( 0.0005884949961232421129, -0.2249510543439050270, 0.9743698870671265722 ) ) ; -#14249 = DIRECTION ( 'NONE', ( 0.0002393071182785211099, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#14250 = CARTESIAN_POINT ( 'NONE', ( 8.708510873816388553, 191.5259668330004104, 103.8649174644812661 ) ) ; -#14251 = ORIENTED_EDGE ( 'NONE', *, *, #12053, .T. ) ; -#14252 = DIRECTION ( 'NONE', ( -9.842052273231448302E-18, 0.9743043966640313469, 0.2252353050503801690 ) ) ; -#14253 = EDGE_LOOP ( 'NONE', ( #18335, #23584, #29046, #34500 ) ) ; -#14254 = VERTEX_POINT ( 'NONE', #13473 ) ; -#14255 = CARTESIAN_POINT ( 'NONE', ( -25.61303419248000068, 191.8414174858999957, 104.3130003953999960 ) ) ; -#14256 = CARTESIAN_POINT ( 'NONE', ( -6.273952199476604541, 148.6532986828639480, 94.48918149448384440 ) ) ; -#14257 = CARTESIAN_POINT ( 'NONE', ( 26.18467446761999895, 191.4585183799999868, 103.6969400202000031 ) ) ; -#14258 = CARTESIAN_POINT ( 'NONE', ( 5.704476631508000217, 115.9590670144843330, 152.9217693939943388 ) ) ; -#14259 = DIRECTION ( 'NONE', ( -0.0005884949961233675551, 0.2249510543439052490, -0.9743698870671265722 ) ) ; -#14260 = VERTEX_POINT ( 'NONE', #30428 ) ; -#14261 = AXIS2_PLACEMENT_3D ( 'NONE', #19654, #19452, #32347 ) ; -#14262 = EDGE_CURVE ( 'NONE', #23190, #18594, #39398, .T. ) ; -#14263 = EDGE_CURVE ( 'NONE', #25850, #28145, #11403, .T. ) ; -#14264 = VECTOR ( 'NONE', #38346, 1000.000000000000114 ) ; -#14265 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7151642779479941980, -0.6989564046112777262 ) ) ; -#14266 = CARTESIAN_POINT ( 'NONE', ( 20.61224087687466167, 176.1547247241071261, 100.3089964015452438 ) ) ; -#14267 = CARTESIAN_POINT ( 'NONE', ( 29.35770870545113809, 112.1779706540911974, 175.8381852828548801 ) ) ; -#14268 = ADVANCED_FACE ( 'NONE', ( #30216 ), #29752, .F. ) ; -#14269 = FACE_OUTER_BOUND ( 'NONE', #12184, .T. ) ; -#14270 = DIRECTION ( 'NONE', ( 0.0006039748549143392599, 0.000000000000000000, 0.9999998176071707157 ) ) ; -#14271 = CARTESIAN_POINT ( 'NONE', ( -5.667212792806153310, 130.0468365392308669, 92.34929107833154660 ) ) ; -#14272 = CARTESIAN_POINT ( 'NONE', ( 21.92247057211630690, 115.3137257461056322, 90.25454421631332025 ) ) ; -#14273 = ORIENTED_EDGE ( 'NONE', *, *, #38887, .F. ) ; -#14274 = CARTESIAN_POINT ( 'NONE', ( -5.676543322760370991, 181.0132184317505448, 104.5254537842582323 ) ) ; -#14275 = CARTESIAN_POINT ( 'NONE', ( 3.621429004694512788, 144.1998115149939679, 93.03134972452090778 ) ) ; -#14276 = CARTESIAN_POINT ( 'NONE', ( -31.13495665264160195, 135.1452985083338092, 90.87247663578949641 ) ) ; -#14277 = ORIENTED_EDGE ( 'NONE', *, *, #20637, .T. ) ; -#14278 = CARTESIAN_POINT ( 'NONE', ( 5.666638401078098575, 182.0642691150555663, 102.1955013913653545 ) ) ; -#14279 = ORIENTED_EDGE ( 'NONE', *, *, #40373, .T. ) ; -#14280 = VECTOR ( 'NONE', #8811, 1000.000000000000000 ) ; -#14281 = ADVANCED_FACE ( 'NONE', ( #26752 ), #21361, .F. ) ; -#14282 = LINE ( 'NONE', #11624, #24124 ) ; -#14283 = ORIENTED_EDGE ( 'NONE', *, *, #34317, .F. ) ; -#14284 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#14285 = AXIS2_PLACEMENT_3D ( 'NONE', #25572, #7334, #28825 ) ; -#14286 = CARTESIAN_POINT ( 'NONE', ( 12.35250447105000049, 123.2470639583000178, 152.4718672074000381 ) ) ; -#14287 = CONICAL_SURFACE ( 'NONE', #7092, 6.500002426223412400, 0.7853981633557588493 ) ; -#14288 = CARTESIAN_POINT ( 'NONE', ( 3.667815737293329548, 128.0237491601668012, 91.77307785500387638 ) ) ; -#14289 = CARTESIAN_POINT ( 'NONE', ( -12.63674275953259496, 130.7062907115098085, 90.10484016673494523 ) ) ; -#14290 = CARTESIAN_POINT ( 'NONE', ( 15.83342902163363242, 174.4759206640733282, 100.0953537165829772 ) ) ; -#14291 = EDGE_LOOP ( 'NONE', ( #34207, #30362, #14662, #26393 ) ) ; -#14292 = CYLINDRICAL_SURFACE ( 'NONE', #10894, 9.000000000000001776 ) ; -#14293 = CARTESIAN_POINT ( 'NONE', ( 12.63725345198346517, 181.8075844171357573, 101.7792460855116161 ) ) ; -#14294 = CARTESIAN_POINT ( 'NONE', ( 15.66824001305769443, 127.1447710819307275, 91.73395621462609029 ) ) ; -#14295 = EDGE_CURVE ( 'NONE', #26075, #4793, #18540, .T. ) ; -#14296 = CARTESIAN_POINT ( 'NONE', ( 62.95950931629634795, 77.27946979429611929, 297.5205190635956001 ) ) ; -#14297 = ORIENTED_EDGE ( 'NONE', *, *, #36454, .F. ) ; -#14298 = DIRECTION ( 'NONE', ( 0.0005884949961248158324, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#14299 = CARTESIAN_POINT ( 'NONE', ( 15.00166796934059299, 182.5876787558734975, 104.7054119478550547 ) ) ; -#14300 = CARTESIAN_POINT ( 'NONE', ( -14.29617623337722065, 129.3410249522306685, 92.25909571682996102 ) ) ; -#14301 = EDGE_CURVE ( 'NONE', #13582, #38246, #23890, .T. ) ; -#14302 = CARTESIAN_POINT ( 'NONE', ( 36.36947947310116547, 114.8200176383737414, 89.71357137054673103 ) ) ; -#14303 = CARTESIAN_POINT ( 'NONE', ( -21.21359846303053232, 183.2065877321888081, 103.1596643249062311 ) ) ; -#14304 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1123, #9950, #3783, #19524, #38151, #6647, #4177, #22623, #13605, #28945, #28745, #22020, #22225, #16258, #922, #35048, #16653, #29153 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999931721, 0.1874999999999952538, 0.2187499999999965583, 0.2499999999999978906, 0.4999999999999957812, 0.6249999999999951150, 0.6874999999999952260, 0.7187499999999952260, 0.7499999999999953371, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14305 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27361, #18102, #8530, #8327 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14306 = EDGE_CURVE ( 'NONE', #15784, #27638, #6888, .T. ) ; -#14307 = CARTESIAN_POINT ( 'NONE', ( 36.06237288317970524, 191.9759150222000130, 101.8996665707895204 ) ) ; -#14308 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #1628, #14120, #26597, #39039 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.591006494801850302, 3.611425299555533375 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999652563361538515, 0.9999652563361538515, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#14309 = EDGE_CURVE ( 'NONE', #23839, #29253, #37106, .T. ) ; -#14310 = CARTESIAN_POINT ( 'NONE', ( 12.31735976862525561, 136.6810573082978806, 94.28285972987136176 ) ) ; -#14311 = CONICAL_SURFACE ( 'NONE', #5812, 2.500000007006496716, 0.7853647137678984036 ) ; -#14312 = ADVANCED_FACE ( 'NONE', ( #1591 ), #34939, .T. ) ; -#14313 = FACE_OUTER_BOUND ( 'NONE', #5595, .T. ) ; -#14314 = CARTESIAN_POINT ( 'NONE', ( 38.54800172934000102, 119.2278403673000184, 90.41095816630999593 ) ) ; -#14315 = ORIENTED_EDGE ( 'NONE', *, *, #38013, .F. ) ; -#14316 = LINE ( 'NONE', #4895, #8739 ) ; -#14317 = CYLINDRICAL_SURFACE ( 'NONE', #11376, 5.999999999913002036 ) ; -#14318 = CARTESIAN_POINT ( 'NONE', ( -36.12795248578809293, 191.9248856836622394, 106.4372973041314339 ) ) ; -#14319 = CARTESIAN_POINT ( 'NONE', ( -18.92878511345999826, 153.5793303521000155, 96.66039321965999420 ) ) ; -#14320 = AXIS2_PLACEMENT_3D ( 'NONE', #18809, #19424, #25191 ) ; -#14321 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18250, #21754, #2135, #40330, #36464, #39935, #30336, #24632, #18445, #2919, #30751, #14605, #27088, #39521, #11943, #37078, #15406, #2741 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000073552, 0.1875000000000110467, 0.2187500000000071054, 0.2500000000000031641, 0.4999999999999666933, 0.6249999999999483746, 0.6874999999999465983, 0.7187499999999532596, 0.7499999999999598099, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14322 = CIRCLE ( 'NONE', #11052, 2.500000000078602902 ) ; -#14323 = CARTESIAN_POINT ( 'NONE', ( 37.28339173517426985, 124.9819308969460963, 93.36952625978587150 ) ) ; -#14324 = VERTEX_POINT ( 'NONE', #14887 ) ; -#14325 = VERTEX_POINT ( 'NONE', #35919 ) ; -#14326 = VERTEX_POINT ( 'NONE', #14480 ) ; -#14327 = CARTESIAN_POINT ( 'NONE', ( -23.36060660365039965, 177.5900848626628203, 100.8364999699883242 ) ) ; -#14328 = FACE_OUTER_BOUND ( 'NONE', #5541, .T. ) ; -#14329 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606773498981405, 136.6775772631814618, 180.9814965275718919 ) ) ; -#14330 = ORIENTED_EDGE ( 'NONE', *, *, #14913, .F. ) ; -#14331 = ORIENTED_EDGE ( 'NONE', *, *, #18499, .T. ) ; -#14332 = FACE_BOUND ( 'NONE', #21887, .T. ) ; -#14333 = CARTESIAN_POINT ( 'NONE', ( -38.51617849441122132, 161.8621938076236120, 192.1757404333372392 ) ) ; -#14334 = CARTESIAN_POINT ( 'NONE', ( -13.49694984184264079, 187.4841345813676128, 105.7733536678242530 ) ) ; -#14335 = CARTESIAN_POINT ( 'NONE', ( 16.58107005088550778, 121.6542341450989682, 177.3392501854816601 ) ) ; -#14336 = ORIENTED_EDGE ( 'NONE', *, *, #8050, .T. ) ; -#14337 = CARTESIAN_POINT ( 'NONE', ( 43.53522428377826259, 122.0090548114814766, 87.79422213383789142 ) ) ; -#14338 = ORIENTED_EDGE ( 'NONE', *, *, #29117, .F. ) ; -#14339 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#14340 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319383098692 ) ) ; -#14341 = CARTESIAN_POINT ( 'NONE', ( -32.57215250014812113, 175.3511933304038735, 100.1556091465108267 ) ) ; -#14342 = ORIENTED_EDGE ( 'NONE', *, *, #24602, .F. ) ; -#14343 = AXIS2_PLACEMENT_3D ( 'NONE', #33432, #40169, #12186 ) ; -#14344 = CARTESIAN_POINT ( 'NONE', ( -2.880684217277760251, 190.4460190246579998, 103.6193748697619981 ) ) ; -#14345 = CARTESIAN_POINT ( 'NONE', ( 38.54261875449868313, 119.6497881189073098, 87.27962667045721901 ) ) ; -#14346 = CARTESIAN_POINT ( 'NONE', ( 27.63271442396334621, 123.9176737634356869, 91.32379343171399455 ) ) ; -#14347 = EDGE_CURVE ( 'NONE', #34668, #19846, #1022, .T. ) ; -#14348 = AXIS2_PLACEMENT_3D ( 'NONE', #21556, #36670, #33996 ) ; -#14349 = ORIENTED_EDGE ( 'NONE', *, *, #18247, .T. ) ; -#14350 = CARTESIAN_POINT ( 'NONE', ( 0.5638615432932998495, 189.0000000000009095, 105.7369977312999936 ) ) ; -#14351 = ORIENTED_EDGE ( 'NONE', *, *, #24427, .F. ) ; -#14352 = ORIENTED_EDGE ( 'NONE', *, *, #5287, .T. ) ; -#14353 = AXIS2_PLACEMENT_3D ( 'NONE', #31966, #28886, #9683 ) ; -#14354 = EDGE_CURVE ( 'NONE', #35226, #5278, #7834, .T. ) ; -#14355 = EDGE_CURVE ( 'NONE', #1948, #5506, #11206, .T. ) ; -#14356 = VERTEX_POINT ( 'NONE', #5464 ) ; -#14357 = CARTESIAN_POINT ( 'NONE', ( 36.05503237417247675, 109.6131156919999938, 89.74600841171526611 ) ) ; -#14358 = ORIENTED_EDGE ( 'NONE', *, *, #29121, .F. ) ; -#14359 = CARTESIAN_POINT ( 'NONE', ( 20.55610212782154278, 211.7441870009438105, 73.54640939689545576 ) ) ; -#14360 = DIRECTION ( 'NONE', ( 0.0004161288024237092768, 0.5299192578742120130, 0.8480479980348188951 ) ) ; -#14361 = EDGE_CURVE ( 'NONE', #22046, #29247, #23685, .T. ) ; -#14362 = ORIENTED_EDGE ( 'NONE', *, *, #9036, .T. ) ; -#14363 = CARTESIAN_POINT ( 'NONE', ( 32.37049208148693680, 138.3096525682149718, 91.56466976714693828 ) ) ; -#14364 = ORIENTED_EDGE ( 'NONE', *, *, #37069, .T. ) ; -#14365 = CARTESIAN_POINT ( 'NONE', ( 26.07999776147000048, 121.7789252111000025, 90.65991193330999920 ) ) ; -#14366 = CARTESIAN_POINT ( 'NONE', ( 20.48231950984458649, 205.5677633305384120, 76.28703242847967658 ) ) ; -#14368 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319388572829 ) ) ; -#14367 = FACE_OUTER_BOUND ( 'NONE', #15182, .T. ) ; -#14369 = VERTEX_POINT ( 'NONE', #30013 ) ; -#14370 = CIRCLE ( 'NONE', #37224, 6.500000000014392043 ) ; -#14371 = VECTOR ( 'NONE', #6217, 1000.000000000000000 ) ; -#14372 = ORIENTED_EDGE ( 'NONE', *, *, #19769, .T. ) ; -#14373 = CARTESIAN_POINT ( 'NONE', ( -36.01285274962783234, 192.1029632286222011, 104.4278060014889178 ) ) ; -#14374 = AXIS2_PLACEMENT_3D ( 'NONE', #18745, #31246, #37577 ) ; -#14375 = VERTEX_POINT ( 'NONE', #2013 ) ; -#14376 = CARTESIAN_POINT ( 'NONE', ( 26.03373140117899709, 191.5260202047026041, 103.8544635878054976 ) ) ; -#14377 = DIRECTION ( 'NONE', ( 0.7075337269410274521, -4.361037875614716654E-15, 0.7066795774896423854 ) ) ; -#14378 = CARTESIAN_POINT ( 'NONE', ( -14.55306118018871508, 176.9194272080598296, 100.5067835523781667 ) ) ; -#14379 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971551247 ) ) ; -#14380 = ORIENTED_EDGE ( 'NONE', *, *, #21206, .T. ) ; -#14381 = ORIENTED_EDGE ( 'NONE', *, *, #4068, .T. ) ; -#14382 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8366, #33485, #8568, #36366 ), - .UNSPECIFIED., .F., .F. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.1808055686694189090, 1.570796326794853925 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8453711073098807427, 0.8453711073098807427, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#14383 = DIRECTION ( 'NONE', ( -0.0004161288024549092543, -0.5299192578742120130, -0.8480479980348188951 ) ) ; -#14384 = CARTESIAN_POINT ( 'NONE', ( 14.95238230675068891, 187.9053326462071425, 103.0252569047014504 ) ) ; -#14385 = ORIENTED_EDGE ( 'NONE', *, *, #30881, .F. ) ; -#14386 = CARTESIAN_POINT ( 'NONE', ( -35.64618537060330539, 191.6897546418510103, 106.9457646653179950 ) ) ; -#14387 = EDGE_CURVE ( 'NONE', #3120, #15609, #15090, .T. ) ; -#14388 = EDGE_CURVE ( 'NONE', #34191, #5671, #2501, .T. ) ; -#14389 = EDGE_CURVE ( 'NONE', #11374, #12730, #35616, .T. ) ; -#14390 = EDGE_CURVE ( 'NONE', #5203, #20831, #13211, .T. ) ; -#14391 = FACE_OUTER_BOUND ( 'NONE', #20534, .T. ) ; -#14392 = VERTEX_POINT ( 'NONE', #34666 ) ; -#14393 = AXIS2_PLACEMENT_3D ( 'NONE', #22736, #34760, #3299 ) ; -#14394 = DIRECTION ( 'NONE', ( -1.110223024594729071E-14, 0.9743700557921585181, 0.2249510932971564570 ) ) ; -#14395 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#14396 = FACE_OUTER_BOUND ( 'NONE', #30474, .T. ) ; -#14397 = EDGE_CURVE ( 'NONE', #6135, #7666, #38530, .T. ) ; -#14398 = AXIS2_PLACEMENT_3D ( 'NONE', #15139, #8398, #36182 ) ; -#14399 = EDGE_LOOP ( 'NONE', ( #5518, #23739, #668, #38843, #32105, #24506 ) ) ; -#14400 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#14401 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066409214, 128.0225132068638629, 91.77843135565319699 ) ) ; -#14402 = EDGE_CURVE ( 'NONE', #20118, #10469, #27863, .T. ) ; -#14403 = ORIENTED_EDGE ( 'NONE', *, *, #37024, .T. ) ; -#14404 = CARTESIAN_POINT ( 'NONE', ( 44.83246798001460576, 186.3081475081992551, 107.7694328794118377 ) ) ; -#14405 = CARTESIAN_POINT ( 'NONE', ( 13.55543936441898722, 147.3999836656304865, 96.75361515240540200 ) ) ; -#14406 = ORIENTED_EDGE ( 'NONE', *, *, #11923, .F. ) ; -#14407 = EDGE_CURVE ( 'NONE', #24100, #27561, #26906, .T. ) ; -#14408 = EDGE_LOOP ( 'NONE', ( #33160, #37458, #10954, #31436 ) ) ; -#14409 = CARTESIAN_POINT ( 'NONE', ( 38.60969634338000134, 118.5004358133784734, 89.66230393877533800 ) ) ; -#14410 = ORIENTED_EDGE ( 'NONE', *, *, #6165, .F. ) ; -#14411 = CARTESIAN_POINT ( 'NONE', ( 2.827185577763999813, 209.6732794012000056, 75.93458852445999696 ) ) ; -#14412 = CARTESIAN_POINT ( 'NONE', ( -39.69437836998564251, 161.5619712970498085, 197.5056430804474985 ) ) ; -#14413 = CARTESIAN_POINT ( 'NONE', ( 3.168110071474127043, 118.9434405806601802, 90.19017701310836799 ) ) ; -#14414 = CARTESIAN_POINT ( 'NONE', ( 12.63950535549863652, 177.3888402134530224, 100.9445866960912213 ) ) ; -#14415 = ORIENTED_EDGE ( 'NONE', *, *, #13335, .F. ) ; -#14416 = ORIENTED_EDGE ( 'NONE', *, *, #31818, .F. ) ; -#14417 = CARTESIAN_POINT ( 'NONE', ( -42.57436895466741333, 120.8400402992461409, 90.73486113234849881 ) ) ; -#14418 = ORIENTED_EDGE ( 'NONE', *, *, #28480, .F. ) ; -#14419 = ORIENTED_EDGE ( 'NONE', *, *, #33646, .T. ) ; -#14420 = LINE ( 'NONE', #39552, #38088 ) ; -#14421 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; -#14422 = CONICAL_SURFACE ( 'NONE', #6584, 5.999999999872287937, 0.7853981633778843729 ) ; -#14423 = FACE_OUTER_BOUND ( 'NONE', #34661, .T. ) ; -#14424 = CARTESIAN_POINT ( 'NONE', ( -2.954012481561790970, 209.1419323005786737, 76.14255792608456375 ) ) ; -#14425 = ORIENTED_EDGE ( 'NONE', *, *, #2265, .T. ) ; -#14426 = VECTOR ( 'NONE', #15668, 1000.000000000000000 ) ; -#14427 = ORIENTED_EDGE ( 'NONE', *, *, #23255, .F. ) ; -#14428 = CARTESIAN_POINT ( 'NONE', ( 12.64524319930002783, 177.7928828500099598, 100.6920447773197225 ) ) ; -#14429 = AXIS2_PLACEMENT_3D ( 'NONE', #21028, #17929, #30435 ) ; -#14430 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25481, #37932, #38327, #25688 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.8322218205202811525, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14431 = CARTESIAN_POINT ( 'NONE', ( 12.63809651561488856, 184.1270825474425408, 102.1512978314866871 ) ) ; -#14432 = CARTESIAN_POINT ( 'NONE', ( -35.87826735977000681, 191.4545805699000027, 103.7459785212000014 ) ) ; -#14433 = CARTESIAN_POINT ( 'NONE', ( 36.44204974789000318, 191.6821620213000017, 104.2306019315000043 ) ) ; -#14434 = VERTEX_POINT ( 'NONE', #37751 ) ; -#14435 = CARTESIAN_POINT ( 'NONE', ( -8.624838525067689332, 191.5260590501553395, 103.8754076631924761 ) ) ; -#14436 = FACE_OUTER_BOUND ( 'NONE', #39513, .T. ) ; -#14437 = ORIENTED_EDGE ( 'NONE', *, *, #9560, .F. ) ; -#14438 = LINE ( 'NONE', #21179, #6232 ) ; -#14439 = CARTESIAN_POINT ( 'NONE', ( -23.35287815472955941, 177.1132788188974132, 103.6357243926429135 ) ) ; -#14440 = ORIENTED_EDGE ( 'NONE', *, *, #21656, .T. ) ; -#14441 = CARTESIAN_POINT ( 'NONE', ( 0.6766601747610884177, 188.6125597266506873, 103.1971553497070317 ) ) ; -#14442 = PLANE ( 'NONE', #13607 ) ; -#14443 = EDGE_CURVE ( 'NONE', #15229, #24908, #30826, .T. ) ; -#14444 = ADVANCED_FACE ( 'NONE', ( #40410 ), #24913, .F. ) ; -#14445 = CARTESIAN_POINT ( 'NONE', ( -20.00029466087617180, 160.7280592933503556, 96.77210435901376684 ) ) ; -#14446 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.387778782212949593E-14 ) ) ; -#14447 = ORIENTED_EDGE ( 'NONE', *, *, #10626, .F. ) ; -#14448 = CARTESIAN_POINT ( 'NONE', ( -19.36440797352090470, 125.0913135789122634, 177.5037349333331917 ) ) ; -#14449 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#14450 = DIRECTION ( 'NONE', ( -0.7933530821293309776, -0.5932640870757666107, -0.1364866662427072774 ) ) ; -#14451 = PRODUCT_DEFINITION ( '', '', #37519, #36332 ) ; -#14452 = ORIENTED_EDGE ( 'NONE', *, *, #10344, .F. ) ; -#14453 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000092726, 182.4219699178716780, 101.7574819546388056 ) ) ; -#14454 = EDGE_LOOP ( 'NONE', ( #16657, #30962, #1229, #18429 ) ) ; -#14455 = ORIENTED_EDGE ( 'NONE', *, *, #1083, .F. ) ; -#14456 = CARTESIAN_POINT ( 'NONE', ( -16.85990575226742649, 148.9750591898919652, 176.9023370295861355 ) ) ; -#14457 = AXIS2_PLACEMENT_3D ( 'NONE', #25761, #28615, #6718 ) ; -#14458 = DIRECTION ( 'NONE', ( -0.7933533411653064249, -0.5931840316265241109, -0.1368326740407707076 ) ) ; -#14459 = CARTESIAN_POINT ( 'NONE', ( 25.89979282503000135, 191.5662133788000006, 103.9958839436000204 ) ) ; -#14460 = CARTESIAN_POINT ( 'NONE', ( -20.00659823406155624, 197.5803004199711097, 93.84897518597676935 ) ) ; -#14461 = VECTOR ( 'NONE', #15835, 1000.000000000000000 ) ; -#14462 = AXIS2_PLACEMENT_3D ( 'NONE', #24784, #2495, #40088 ) ; -#14463 = CARTESIAN_POINT ( 'NONE', ( 6.031425049375666703, 135.0095535936824263, 90.94154247174608940 ) ) ; -#14464 = ORIENTED_EDGE ( 'NONE', *, *, #898, .T. ) ; -#14465 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250902867, 132.4055461762854407, 92.79778151958552712 ) ) ; -#14466 = EDGE_CURVE ( 'NONE', #12388, #26352, #17416, .T. ) ; -#14467 = CARTESIAN_POINT ( 'NONE', ( 23.36209697621999126, 182.0666116861889066, 102.1853546028664397 ) ) ; -#14468 = CARTESIAN_POINT ( 'NONE', ( -25.92534507918878361, 117.3327747928809828, 87.28344255082397751 ) ) ; -#14469 = CARTESIAN_POINT ( 'NONE', ( -3.573670504831215400, 137.3406645800012313, 91.39957200407195614 ) ) ; -#14470 = FACE_OUTER_BOUND ( 'NONE', #18121, .T. ) ; -#14471 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971558463 ) ) ; -#14472 = CARTESIAN_POINT ( 'NONE', ( 27.38311190280685992, 155.9299021785007824, 179.7938373981314157 ) ) ; -#14473 = LINE ( 'NONE', #27377, #32412 ) ; -#14474 = ORIENTED_EDGE ( 'NONE', *, *, #23083, .T. ) ; -#14475 = ORIENTED_EDGE ( 'NONE', *, *, #18967, .T. ) ; -#14476 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319414569829 ) ) ; -#14477 = CARTESIAN_POINT ( 'NONE', ( 3.554793938553518107, 144.2181838125568447, 92.96728390614413229 ) ) ; -#14478 = CARTESIAN_POINT ( 'NONE', ( -32.42517106839203933, 136.5274910919899867, 91.19236025274476276 ) ) ; -#14479 = ORIENTED_EDGE ( 'NONE', *, *, #18019, .T. ) ; -#14480 = CARTESIAN_POINT ( 'NONE', ( -20.49970645903284705, 184.8492302318938698, 102.8542671896393301 ) ) ; -#14481 = CONICAL_SURFACE ( 'NONE', #22344, 4.999999999816541418, 0.7853981632964557313 ) ; -#14482 = VERTEX_POINT ( 'NONE', #18722 ) ; -#14483 = AXIS2_PLACEMENT_3D ( 'NONE', #30035, #29436, #36570 ) ; -#14484 = AXIS2_PLACEMENT_3D ( 'NONE', #24692, #31410, #9337 ) ; -#14485 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#14486 = ORIENTED_EDGE ( 'NONE', *, *, #9102, .F. ) ; -#14487 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 1.540743955509789367E-33, -0.0006039748319385908944 ) ) ; -#14488 = CARTESIAN_POINT ( 'NONE', ( 0.03687779169341001001, 7.827067153267001387E-13, 61.05847962042000887 ) ) ; -#14489 = CARTESIAN_POINT ( 'NONE', ( -35.94659742830589266, 112.4664344042326576, 89.78949559119494950 ) ) ; -#14490 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#14491 = EDGE_CURVE ( 'NONE', #6212, #17763, #37356, .T. ) ; -#14492 = CARTESIAN_POINT ( 'NONE', ( -12.19159238061602579, 125.0219911001496058, 178.7972028438273071 ) ) ; -#14493 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#14494 = ORIENTED_EDGE ( 'NONE', *, *, #3514, .T. ) ; -#14495 = ORIENTED_EDGE ( 'NONE', *, *, #37178, .F. ) ; -#14496 = DIRECTION ( 'NONE', ( 0.6337890847338583100, -0.7735059121120007042, 0.000000000000000000 ) ) ; -#14497 = FACE_OUTER_BOUND ( 'NONE', #29895, .T. ) ; -#14498 = CARTESIAN_POINT ( 'NONE', ( 9.337769825243999122, 176.9303572965000058, 103.3172116324000029 ) ) ; -#14499 = EDGE_LOOP ( 'NONE', ( #780, #766, #33447, #25657 ) ) ; -#14500 = CARTESIAN_POINT ( 'NONE', ( 16.45208125514326625, 152.1628593551957067, 181.3637068811612210 ) ) ; -#14501 = ORIENTED_EDGE ( 'NONE', *, *, #33859, .F. ) ; -#14502 = CARTESIAN_POINT ( 'NONE', ( -20.51208494570645513, 201.8037239448619573, 85.17910946014715989 ) ) ; -#14503 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#14504 = CARTESIAN_POINT ( 'NONE', ( -42.21450392588476319, 136.3064398602169263, 337.8725216998488463 ) ) ; -#14505 = CARTESIAN_POINT ( 'NONE', ( -14.42375247838731411, 129.4079016531295849, 92.44566340157058448 ) ) ; -#14506 = CARTESIAN_POINT ( 'NONE', ( -20.02016821360482268, 211.0854730039747267, 73.07052224373646254 ) ) ; -#14507 = CARTESIAN_POINT ( 'NONE', ( 14.30095350739092019, 209.7097330701937494, 73.04986666540851559 ) ) ; -#14508 = CARTESIAN_POINT ( 'NONE', ( 20.00007381421711372, 125.0896753410343507, 88.52014447053112178 ) ) ; -#14509 = VECTOR ( 'NONE', #13879, 1000.000000000000114 ) ; -#14510 = CARTESIAN_POINT ( 'NONE', ( -25.94414642037533625, 209.7102642087664321, 73.14014518873486281 ) ) ; -#14511 = AXIS2_PLACEMENT_3D ( 'NONE', #19441, #12929, #1238 ) ; -#14512 = CARTESIAN_POINT ( 'NONE', ( -2.454787986789333853, 158.3159520769750372, 101.3360438597573676 ) ) ; -#14513 = VECTOR ( 'NONE', #39198, 1000.000000000000000 ) ; -#14514 = CARTESIAN_POINT ( 'NONE', ( 37.53774977936000568, 118.7416573867000125, 87.12150836029999823 ) ) ; -#14515 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36759, #24517, #3210, #8974, #22044, #15300, #25119, #33684, #30641, #21450, #27785, #24723, #7478, #32444, #25725, #34875, #35466, #750, #13437, #28771 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999718836, 0.1874999999999578115, 0.2187499999999484024, 0.2343749999999451827, 0.2499999999999419353, 0.4999999999999288347, 0.6249999999999253930, 0.6874999999999236167, 0.7187499999999227285, 0.7343749999999260591, 0.7499999999999293898, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14516 = CARTESIAN_POINT ( 'NONE', ( -22.50035831641348949, 136.6787900224432235, 180.9762504730929891 ) ) ; -#14517 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552150381, 77.14301703112145958, 291.5584375788748162 ) ) ; -#14518 = ORIENTED_EDGE ( 'NONE', *, *, #38505, .T. ) ; -#14519 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988183502364, 156.3551877983796885, 95.75036263594044783 ) ) ; -#14520 = CARTESIAN_POINT ( 'NONE', ( -14.89128843831085192, 128.7610883624478788, 92.12556600355759429 ) ) ; -#14521 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#14522 = DIRECTION ( 'NONE', ( 1.396487634731935332E-14, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#14524 = VERTEX_POINT ( 'NONE', #6268 ) ; -#14523 = DIRECTION ( 'NONE', ( -0.0005884949961175196939, 0.2249510543439042221, -0.9743698870671267942 ) ) ; -#14525 = ORIENTED_EDGE ( 'NONE', *, *, #15875, .T. ) ; -#14526 = VERTEX_POINT ( 'NONE', #7266 ) ; -#14527 = CARTESIAN_POINT ( 'NONE', ( -2.243981616595559725, 189.3845921353988615, 103.3771571023711573 ) ) ; -#14528 = VERTEX_POINT ( 'NONE', #29367 ) ; -#14529 = CARTESIAN_POINT ( 'NONE', ( -23.35632100188561822, 177.7257551712265524, 100.7517216405086629 ) ) ; -#14530 = EDGE_CURVE ( 'NONE', #14135, #30803, #33878, .T. ) ; -#14531 = CARTESIAN_POINT ( 'NONE', ( 5.666344154467410910, 131.0223139869003148, 89.89838483048988849 ) ) ; -#14532 = CARTESIAN_POINT ( 'NONE', ( -43.33927092660995584, 121.3466802566939720, 90.52108273551040440 ) ) ; -#14533 = EDGE_LOOP ( 'NONE', ( #3202, #4007 ) ) ; -#14534 = CARTESIAN_POINT ( 'NONE', ( -76.10866181110002060, 155.9999951364999902, 97.25378303438999694 ) ) ; -#14535 = ADVANCED_FACE ( 'NONE', ( #35265 ), #38739, .F. ) ; -#14536 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2252353050503803633, 0.9743043966640312359 ) ) ; -#14537 = FACE_OUTER_BOUND ( 'NONE', #39367, .T. ) ; -#14538 = DIRECTION ( 'NONE', ( 0.0006039748319381690314, -1.159276051261448636E-15, 0.9999998176071845934 ) ) ; -#14539 = ORIENTED_EDGE ( 'NONE', *, *, #35578, .F. ) ; -#14540 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#14541 = VERTEX_POINT ( 'NONE', #19135 ) ; -#14542 = CARTESIAN_POINT ( 'NONE', ( -17.94609826154884402, 149.1879437481332502, 179.6906816993704581 ) ) ; -#14543 = EDGE_CURVE ( 'NONE', #2464, #40344, #19055, .T. ) ; -#14544 = AXIS2_PLACEMENT_3D ( 'NONE', #14897, #21235, #15498 ) ; -#14545 = ADVANCED_FACE ( 'NONE', ( #10756 ), #16467, .T. ) ; -#14546 = CARTESIAN_POINT ( 'NONE', ( 15.99998384348811875, 126.8035267017516787, 88.91816380576780432 ) ) ; -#14547 = CARTESIAN_POINT ( 'NONE', ( 25.60452841390158696, 177.7947404061257544, 100.6845902703070408 ) ) ; -#14548 = EDGE_CURVE ( 'NONE', #26442, #25364, #10562, .T. ) ; -#14549 = VECTOR ( 'NONE', #21494, 1000.000000000000227 ) ; -#14550 = ORIENTED_EDGE ( 'NONE', *, *, #1139, .F. ) ; -#14551 = DIRECTION ( 'NONE', ( -0.7933530821293314217, -0.5932640870757660556, -0.1364866662427072774 ) ) ; -#14552 = EDGE_CURVE ( 'NONE', #19871, #23412, #26301, .T. ) ; -#14553 = CONICAL_SURFACE ( 'NONE', #22404, 2.503104886457119260, 0.7853981634085609453 ) ; -#14554 = CARTESIAN_POINT ( 'NONE', ( 0.5749182425858000434, 188.7228409958999862, 103.3572403391000023 ) ) ; -#14555 = CARTESIAN_POINT ( 'NONE', ( 26.00790306097016469, 120.3826516281573049, 90.50865046224697608 ) ) ; -#14556 = EDGE_LOOP ( 'NONE', ( #31779, #10516, #30220, #8284, #4286, #12131 ) ) ; -#14557 = CARTESIAN_POINT ( 'NONE', ( 28.46561152637904257, 181.0177244442795654, 104.5058782010328855 ) ) ; -#14558 = EDGE_LOOP ( 'NONE', ( #36243, #31241, #3763, #1449 ) ) ; -#14559 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25125, #22049, #24324, #21456 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.740660174422384188, 5.205610502464788070 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9820660875108615517, 0.9820660875108615517, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#14560 = CARTESIAN_POINT ( 'NONE', ( 25.49063000826092562, 211.0902260967494897, 73.54299573436949800 ) ) ; -#14561 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30658, #11234, #8378, #5489, #17952, #40040, #26993, #14721, #11852, #21465, #17748, #36991, #23709, #11432, #18359, #23920 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000007494, 0.2500000000000014988, 0.5000000000000049960, 0.6250000000000067724, 0.6874999999999996669, 0.7187499999999961142, 0.7499999999999924505, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14562 = ORIENTED_EDGE ( 'NONE', *, *, #37470, .F. ) ; -#14563 = ORIENTED_EDGE ( 'NONE', *, *, #12318, .F. ) ; -#14564 = DIRECTION ( 'NONE', ( -0.0005884949961254435855, 0.2249510543439056098, -0.9743698870671265722 ) ) ; -#14565 = CARTESIAN_POINT ( 'NONE', ( 5.667983148730973753, 187.2950682031916472, 105.4557345104930022 ) ) ; -#14566 = LINE ( 'NONE', #16248, #19325 ) ; -#14567 = ORIENTED_EDGE ( 'NONE', *, *, #16356, .F. ) ; -#14568 = CARTESIAN_POINT ( 'NONE', ( 44.86430789981690026, 186.7819473042679022, 105.8267500767360758 ) ) ; -#14569 = CARTESIAN_POINT ( 'NONE', ( -5.670520111846581557, 181.9848756317858260, 102.0773479366436618 ) ) ; -#14570 = AXIS2_PLACEMENT_3D ( 'NONE', #32768, #33567, #39909 ) ; -#14571 = VERTEX_POINT ( 'NONE', #22434 ) ; -#14572 = CARTESIAN_POINT ( 'NONE', ( 25.96215568107999871, 121.3312454849999966, 90.55664172145999657 ) ) ; -#14573 = CARTESIAN_POINT ( 'NONE', ( 15.50029467954679596, 184.8540555714758966, 102.8336351796044426 ) ) ; -#14574 = CONICAL_SURFACE ( 'NONE', #8016, 6.500002405954553808, 0.7853981634096851572 ) ; -#14576 = DIRECTION ( 'NONE', ( -0.0004270746993317995526, -0.7071067811865993091, -0.7071066522152992251 ) ) ; -#14575 = CYLINDRICAL_SURFACE ( 'NONE', #34322, 2.000000000000000444 ) ; -#14577 = VERTEX_POINT ( 'NONE', #16272 ) ; -#14578 = AXIS2_PLACEMENT_3D ( 'NONE', #2565, #27322, #12171 ) ; -#14579 = EDGE_LOOP ( 'NONE', ( #18526, #1625, #29692, #18078 ) ) ; -#14580 = EDGE_CURVE ( 'NONE', #1633, #18145, #15658, .T. ) ; -#14581 = ORIENTED_EDGE ( 'NONE', *, *, #16319, .F. ) ; -#14582 = CARTESIAN_POINT ( 'NONE', ( 39.30108583578999770, 119.4692335736999951, 90.16757951597999465 ) ) ; -#14583 = CARTESIAN_POINT ( 'NONE', ( -36.00927514734391366, 116.0444906973774835, 87.28953299190300186 ) ) ; -#14584 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #97, #30786, #12559, #34423 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14585 = CARTESIAN_POINT ( 'NONE', ( -20.34678176212189982, 105.2139170220364974, 88.78007351195603292 ) ) ; -#14586 = DIRECTION ( 'NONE', ( 0.0005884949961292186690, -0.2249510543439060262, 0.9743698870671263501 ) ) ; -#14587 = EDGE_CURVE ( 'NONE', #35968, #17219, #4401, .T. ) ; -#14588 = ORIENTED_EDGE ( 'NONE', *, *, #30265, .T. ) ; -#14589 = ORIENTED_EDGE ( 'NONE', *, *, #9189, .F. ) ; -#14590 = CARTESIAN_POINT ( 'NONE', ( -10.03596943924101659, 167.8207392792327539, 101.4823675419857807 ) ) ; -#14591 = CARTESIAN_POINT ( 'NONE', ( 26.07427389743000035, 130.7251880588000006, 90.07403667762000055 ) ) ; -#14592 = EDGE_CURVE ( 'NONE', #24828, #39497, #16586, .T. ) ; -#14593 = CARTESIAN_POINT ( 'NONE', ( 27.24249485256000014, 124.7921279242000168, 88.96032778548000408 ) ) ; -#14594 = EDGE_CURVE ( 'NONE', #26903, #29957, #11482, .T. ) ; -#14595 = ORIENTED_EDGE ( 'NONE', *, *, #40184, .F. ) ; -#14596 = CARTESIAN_POINT ( 'NONE', ( 30.06790633150233205, 135.1102819760833142, 91.08386653316209447 ) ) ; -#14597 = AXIS2_PLACEMENT_3D ( 'NONE', #7611, #20075, #32952 ) ; -#14598 = VECTOR ( 'NONE', #4138, 1000.000000000000000 ) ; -#14599 = CARTESIAN_POINT ( 'NONE', ( -39.66922356035500741, 107.0867199669675358, 184.9165548509024006 ) ) ; -#14600 = ORIENTED_EDGE ( 'NONE', *, *, #17537, .T. ) ; -#14601 = CARTESIAN_POINT ( 'NONE', ( 5.667840232159853109, 130.6974365609393942, 90.10139097600442426 ) ) ; -#14602 = CIRCLE ( 'NONE', #15894, 4.999999999999990230 ) ; -#14603 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749094291, 179.1800746285969410, 103.5747911657857685 ) ) ; -#14604 = LINE ( 'NONE', #27087, #34595 ) ; -#14605 = CARTESIAN_POINT ( 'NONE', ( 3.799034111884631137, 146.0103245760286086, 93.35976675303339789 ) ) ; -#14606 = VERTEX_POINT ( 'NONE', #7463 ) ; -#14607 = CYLINDRICAL_SURFACE ( 'NONE', #1615, 2.000000000000014655 ) ; -#14608 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16560, #230, #34556, #6763 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14609 = CARTESIAN_POINT ( 'NONE', ( 22.99060780684998662, 213.5902260770751866, 73.54442216390444287 ) ) ; -#14610 = ORIENTED_EDGE ( 'NONE', *, *, #25899, .T. ) ; -#14611 = DIRECTION ( 'NONE', ( -0.0005884949961222158072, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#14613 = LINE ( 'NONE', #33402, #29851 ) ; -#14612 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#14614 = ORIENTED_EDGE ( 'NONE', *, *, #27450, .F. ) ; -#14615 = EDGE_LOOP ( 'NONE', ( #25409, #10746, #3957, #40296 ) ) ; -#14616 = VECTOR ( 'NONE', #35297, 1000.000000000000114 ) ; -#14617 = CARTESIAN_POINT ( 'NONE', ( 38.70058063102342771, 118.5858079959231901, 89.66270157713385913 ) ) ; -#14618 = ORIENTED_EDGE ( 'NONE', *, *, #4359, .T. ) ; -#14619 = EDGE_CURVE ( 'NONE', #6941, #22970, #37961, .T. ) ; -#14620 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858247, 183.1686750955933292, 104.5300206044594091 ) ) ; -#14621 = EDGE_CURVE ( 'NONE', #29487, #30923, #5375, .T. ) ; -#14622 = LINE ( 'NONE', #8280, #7566 ) ; -#14623 = CARTESIAN_POINT ( 'NONE', ( 16.81962279843222063, 125.7520086040206877, 179.0304986527600022 ) ) ; -#14624 = EDGE_CURVE ( 'NONE', #35118, #13652, #28760, .T. ) ; -#14625 = CARTESIAN_POINT ( 'NONE', ( 12.64524319930002783, 177.7928828500099598, 100.6920447773197225 ) ) ; -#14627 = EDGE_LOOP ( 'NONE', ( #29636, #32323, #29486, #12846, #27844, #7027, #32629 ) ) ; -#14626 = AXIS2_PLACEMENT_3D ( 'NONE', #31508, #3471, #7155 ) ; -#14628 = ORIENTED_EDGE ( 'NONE', *, *, #18022, .T. ) ; -#14629 = CARTESIAN_POINT ( 'NONE', ( -42.69001132698595313, 120.8765335464027686, 91.24842851203827365 ) ) ; -#14630 = ORIENTED_EDGE ( 'NONE', *, *, #30724, .T. ) ; -#14631 = ORIENTED_EDGE ( 'NONE', *, *, #37980, .F. ) ; -#14632 = DIRECTION ( 'NONE', ( -0.0005559617475465704339, 0.3907311284739450885, -0.9205046855654851479 ) ) ; -#14633 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825994489843006, 0.0005734119006650908101 ) ) ; -#14634 = AXIS2_PLACEMENT_3D ( 'NONE', #12926, #10053, #32132 ) ; -#14635 = EDGE_CURVE ( 'NONE', #13611, #36914, #7068, .T. ) ; -#14636 = CARTESIAN_POINT ( 'NONE', ( 3.045964837636964795, 205.1071438018522315, 76.10297588899729249 ) ) ; -#14637 = CARTESIAN_POINT ( 'NONE', ( 21.70887161542509247, 149.1053605161909559, 190.1067871781723966 ) ) ; -#14638 = VERTEX_POINT ( 'NONE', #39347 ) ; -#14639 = ORIENTED_EDGE ( 'NONE', *, *, #13647, .F. ) ; -#14640 = ORIENTED_EDGE ( 'NONE', *, *, #30419, .T. ) ; -#14641 = DIRECTION ( 'NONE', ( 0.7933533411653070910, -0.5930537057989941907, -0.1373964268091563690 ) ) ; -#14642 = CARTESIAN_POINT ( 'NONE', ( -36.04853124241000017, 191.6002292608999937, 104.0141960793000209 ) ) ; -#14643 = CARTESIAN_POINT ( 'NONE', ( 38.08169783580999734, 190.9297002386000202, 103.5605195629999997 ) ) ; -#14644 = CARTESIAN_POINT ( 'NONE', ( -26.00023137339078616, 120.7179891544659398, 87.50601697937879919 ) ) ; -#14645 = VERTEX_POINT ( 'NONE', #17261 ) ; -#14646 = EDGE_CURVE ( 'NONE', #30574, #32344, #34320, .T. ) ; -#14647 = ORIENTED_EDGE ( 'NONE', *, *, #5055, .F. ) ; -#14648 = CARTESIAN_POINT ( 'NONE', ( -21.70069623175950468, 176.1098200292445881, 103.0609967409726693 ) ) ; -#14649 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; -#14650 = ORIENTED_EDGE ( 'NONE', *, *, #35277, .T. ) ; -#14651 = CARTESIAN_POINT ( 'NONE', ( -20.51834749416153159, 208.5969270407305487, 75.82589319295023245 ) ) ; -#14652 = CARTESIAN_POINT ( 'NONE', ( -5.958856854636191969, 162.8886998924887166, 100.3412538487635857 ) ) ; -#14653 = CARTESIAN_POINT ( 'NONE', ( -15.51350684690919834, 125.3182505903097592, 88.59428848080469265 ) ) ; -#14654 = AXIS2_PLACEMENT_3D ( 'NONE', #13699, #26381, #33303 ) ; -#14655 = ORIENTED_EDGE ( 'NONE', *, *, #11597, .F. ) ; -#14656 = EDGE_CURVE ( 'NONE', #17766, #9823, #10215, .T. ) ; -#14657 = CARTESIAN_POINT ( 'NONE', ( -31.70384874264191311, 220.4002260771000294, 76.07765295995241672 ) ) ; -#14658 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971560406 ) ) ; -#14659 = CARTESIAN_POINT ( 'NONE', ( -15.99999411491280199, 138.1989450468032601, 91.56832761027415302 ) ) ; -#14660 = ORIENTED_EDGE ( 'NONE', *, *, #21141, .T. ) ; -#14661 = CARTESIAN_POINT ( 'NONE', ( 13.50147201673061481, 153.3583215346567670, 97.61608654020172082 ) ) ; -#14662 = ORIENTED_EDGE ( 'NONE', *, *, #31476, .T. ) ; -#14663 = ORIENTED_EDGE ( 'NONE', *, *, #5331, .F. ) ; -#14664 = CIRCLE ( 'NONE', #30326, 2.500000000022430502 ) ; -#14665 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265228896, 0.1368326740407719844 ) ) ; -#14666 = CARTESIAN_POINT ( 'NONE', ( 36.04796026513668039, 209.7096538831000032, 78.03673292965197561 ) ) ; -#14667 = CARTESIAN_POINT ( 'NONE', ( -25.51533646434189961, 211.0902259025884007, 73.57326538444725372 ) ) ; -#14668 = CARTESIAN_POINT ( 'NONE', ( 44.97133202873805402, 133.3536190811915958, 337.1387376220093302 ) ) ; -#14669 = FACE_OUTER_BOUND ( 'NONE', #23123, .T. ) ; -#14670 = VERTEX_POINT ( 'NONE', #11349 ) ; -#14671 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27498, #13137, #35175, #28276 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14672 = CARTESIAN_POINT ( 'NONE', ( -116.6809178989064293, 205.2853165843886245, 191.1682151682985307 ) ) ; -#14673 = LINE ( 'NONE', #35908, #4818 ) ; -#14674 = CARTESIAN_POINT ( 'NONE', ( -45.17838929977841644, 181.0906312430929574, 102.0014284585363669 ) ) ; -#14675 = EDGE_CURVE ( 'NONE', #5306, #39311, #32623, .T. ) ; -#14676 = CARTESIAN_POINT ( 'NONE', ( -38.46044104337040181, 118.4609804511839286, 89.70916240556151422 ) ) ; -#14677 = CARTESIAN_POINT ( 'NONE', ( 30.69859387782648596, 177.7369147060027217, 100.6681819028367073 ) ) ; -#14678 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265227786, -0.1368326740407718733 ) ) ; -#14679 = EDGE_CURVE ( 'NONE', #38924, #7297, #14770, .T. ) ; -#14680 = CARTESIAN_POINT ( 'NONE', ( 14.74085912557288403, 200.6198490733034987, 27.73455667519232293 ) ) ; -#14681 = ADVANCED_FACE ( 'NONE', ( #5205 ), #20755, .T. ) ; -#14682 = CARTESIAN_POINT ( 'NONE', ( -17.26247767858138005, 152.5342161776122225, 182.4800534808789791 ) ) ; -#14683 = CARTESIAN_POINT ( 'NONE', ( 20.23379851175398514, 116.9546646491199482, 90.25556413192329330 ) ) ; -#14684 = ORIENTED_EDGE ( 'NONE', *, *, #28156, .T. ) ; -#14685 = VECTOR ( 'NONE', #32901, 999.9999999999998863 ) ; -#14686 = AXIS2_PLACEMENT_3D ( 'NONE', #13047, #25527, #32256 ) ; -#14687 = CARTESIAN_POINT ( 'NONE', ( -19.99931527105535878, 118.1256151686936420, 90.27945241601419468 ) ) ; -#14688 = AXIS2_PLACEMENT_3D ( 'NONE', #11848, #8373, #8576 ) ; -#14689 = DIRECTION ( 'NONE', ( 0.0005559617642597537886, -0.3907311284892686643, 0.9205046855589705812 ) ) ; -#14690 = AXIS2_PLACEMENT_3D ( 'NONE', #11580, #35670, #23436 ) ; -#14691 = ADVANCED_FACE ( 'NONE', ( #24040 ), #32820, .F. ) ; -#14692 = EDGE_LOOP ( 'NONE', ( #39948, #38977, #19988, #21479 ) ) ; -#14693 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971535981 ) ) ; -#14694 = VECTOR ( 'NONE', #35852, 1000.000000000000227 ) ; -#14695 = EDGE_LOOP ( 'NONE', ( #22984, #23988, #36395, #37406 ) ) ; -#14696 = CARTESIAN_POINT ( 'NONE', ( -38.32031438860001060, 119.0223062448000064, 87.58457824427000560 ) ) ; -#14697 = EDGE_CURVE ( 'NONE', #2318, #8264, #4605, .T. ) ; -#14698 = CARTESIAN_POINT ( 'NONE', ( 25.49057710600703786, 211.4174709902825668, 73.54294251055145537 ) ) ; -#14699 = PLANE ( 'NONE', #14429 ) ; -#14700 = ORIENTED_EDGE ( 'NONE', *, *, #31507, .F. ) ; -#14701 = DIRECTION ( 'NONE', ( 1.868163743340544790E-15, 0.9743700557921586292, 0.2249510932971554855 ) ) ; -#14702 = FACE_OUTER_BOUND ( 'NONE', #3918, .T. ) ; -#14703 = CARTESIAN_POINT ( 'NONE', ( -40.70502761438000761, 217.7719116314000019, 75.83308940067001913 ) ) ; -#14704 = CARTESIAN_POINT ( 'NONE', ( -22.50072399476195528, 158.3009599602069954, 96.21317557253242114 ) ) ; -#14705 = CARTESIAN_POINT ( 'NONE', ( 39.79720373659698396, 141.5291680805872829, 284.4357792904225448 ) ) ; -#14706 = ORIENTED_EDGE ( 'NONE', *, *, #13520, .F. ) ; -#14707 = EDGE_CURVE ( 'NONE', #13769, #36287, #38269, .T. ) ; -#14708 = CARTESIAN_POINT ( 'NONE', ( 38.15196370523000269, 119.0569874929000207, 87.35187028091000627 ) ) ; -#14709 = LINE ( 'NONE', #27191, #8136 ) ; -#14710 = CARTESIAN_POINT ( 'NONE', ( 41.93030479274874978, 83.05956246986023928, 287.6687500667571840 ) ) ; -#14711 = CARTESIAN_POINT ( 'NONE', ( 28.46414028889297043, 128.4769340270111400, 89.81011889579673380 ) ) ; -#14712 = VERTEX_POINT ( 'NONE', #39153 ) ; -#14713 = DIRECTION ( 'NONE', ( 0.0005884949961262129353, -0.2249510543439086074, 0.9743698870671257950 ) ) ; -#14714 = PLANE ( 'NONE', #39519 ) ; -#14715 = AXIS2_PLACEMENT_3D ( 'NONE', #25081, #25279, #31403 ) ; -#14716 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#14717 = CARTESIAN_POINT ( 'NONE', ( -28.24856439448000245, 125.3059185480999957, 91.02595693825000467 ) ) ; -#14718 = CARTESIAN_POINT ( 'NONE', ( 3.047144816548554402, 209.7096538831000032, 78.05666459525210144 ) ) ; -#14719 = VECTOR ( 'NONE', #34763, 1000.000000000000114 ) ; -#14720 = AXIS2_PLACEMENT_3D ( 'NONE', #15060, #21605, #34048 ) ; -#14721 = CARTESIAN_POINT ( 'NONE', ( -25.28450265369502148, 213.0681446531329470, 73.07377528842077652 ) ) ; -#14722 = AXIS2_PLACEMENT_3D ( 'NONE', #28602, #22878, #16902 ) ; -#14723 = DIRECTION ( 'NONE', ( 0.6087611427424952648, 0.7731004630501231434, 0.1781166615410721132 ) ) ; -#14724 = CARTESIAN_POINT ( 'NONE', ( -36.54247293543086528, 78.99824749864018258, 288.8334071075194629 ) ) ; -#14725 = LINE ( 'NONE', #27205, #8632 ) ; -#14726 = CALENDAR_DATE ( 2025, 24, 6 ) ; -#14727 = CARTESIAN_POINT ( 'NONE', ( 26.77347080001853286, 123.5272686467274781, 88.15526736885951209 ) ) ; -#14728 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971544308 ) ) ; -#14729 = LINE ( 'NONE', #33508, #34213 ) ; -#14730 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825900929177606, 0.0005734119028281910212 ) ) ; -#14731 = CARTESIAN_POINT ( 'NONE', ( 35.93657474780000172, 112.8616927727999979, 87.62913976238999680 ) ) ; -#14732 = ADVANCED_FACE ( 'NONE', ( #5008 ), #6920, .T. ) ; -#14733 = ORIENTED_EDGE ( 'NONE', *, *, #34134, .T. ) ; -#14734 = CARTESIAN_POINT ( 'NONE', ( -22.50000098316691677, 138.1924791438345892, 91.56768502647121011 ) ) ; -#14735 = ORIENTED_EDGE ( 'NONE', *, *, #30055, .F. ) ; -#14736 = ORIENTED_EDGE ( 'NONE', *, *, #39531, .F. ) ; -#14737 = CARTESIAN_POINT ( 'NONE', ( -0.4376666143244844487, 188.6124751099401351, 103.1978086576974221 ) ) ; -#14738 = ORIENTED_EDGE ( 'NONE', *, *, #4027, .F. ) ; -#14739 = CARTESIAN_POINT ( 'NONE', ( -14.39900080767387358, 134.4949918206585551, 152.5558619512717371 ) ) ; -#14740 = CARTESIAN_POINT ( 'NONE', ( 16.54378305514588732, 151.9109168242012515, 184.2735515932985777 ) ) ; -#14741 = CARTESIAN_POINT ( 'NONE', ( -13.53688746037999913, 141.8439034424000056, 28.07991271570000080 ) ) ; -#14742 = EDGE_CURVE ( 'NONE', #31506, #7683, #2371, .T. ) ; -#14743 = ORIENTED_EDGE ( 'NONE', *, *, #2216, .T. ) ; -#14744 = VECTOR ( 'NONE', #3923, 1000.000000000000227 ) ; -#14745 = FACE_OUTER_BOUND ( 'NONE', #14825, .T. ) ; -#14746 = CARTESIAN_POINT ( 'NONE', ( 14.54953207236175139, 130.1535194663153447, 89.69244121379192336 ) ) ; -#14747 = AXIS2_PLACEMENT_3D ( 'NONE', #32948, #23157, #14778 ) ; -#14748 = AXIS2_PLACEMENT_3D ( 'NONE', #29526, #23396, #1721 ) ; -#14749 = CARTESIAN_POINT ( 'NONE', ( 21.44870230457277316, 181.8867687911781559, 104.7107509713525388 ) ) ; -#14750 = ORIENTED_EDGE ( 'NONE', *, *, #37276, .F. ) ; -#14751 = CONICAL_SURFACE ( 'NONE', #27163, 4.999999999930255790, 0.7853981633714466337 ) ; -#14752 = CARTESIAN_POINT ( 'NONE', ( 32.56861805024679768, 175.3596280205372011, 100.1182146692571138 ) ) ; -#14753 = CARTESIAN_POINT ( 'NONE', ( 3.484080676294788681, 187.1397425093524873, 102.8554330292374601 ) ) ; -#14754 = CONICAL_SURFACE ( 'NONE', #28458, 5.250000000064561689, 0.7853981633647640903 ) ; -#14755 = CARTESIAN_POINT ( 'NONE', ( -8.283690339216027709, 6.323265155852981323, 291.5635470766264348 ) ) ; -#14756 = CARTESIAN_POINT ( 'NONE', ( -12.64386474322367526, 181.0124094291204528, 104.5294403572958544 ) ) ; -#14757 = ORIENTED_EDGE ( 'NONE', *, *, #17142, .F. ) ; -#14758 = ADVANCED_FACE ( 'NONE', ( #20969 ), #7555, .T. ) ; -#14759 = CARTESIAN_POINT ( 'NONE', ( -28.51673990053000196, 187.2657903049000083, 103.0285994297999963 ) ) ; -#14760 = CARTESIAN_POINT ( 'NONE', ( 0.8619687770521999859, 188.7597673114000258, 103.3660920736000008 ) ) ; -#14761 = CARTESIAN_POINT ( 'NONE', ( 26.11627784374346106, 121.2164058409220786, 90.70107236864649281 ) ) ; -#14762 = ORIENTED_EDGE ( 'NONE', *, *, #5377, .F. ) ; -#14763 = EDGE_LOOP ( 'NONE', ( #25617, #16678, #30021, #15390 ) ) ; -#14764 = FACE_OUTER_BOUND ( 'NONE', #1949, .T. ) ; -#14765 = ORIENTED_EDGE ( 'NONE', *, *, #5944, .F. ) ; -#14766 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #18921, #15080 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14768 = EDGE_CURVE ( 'NONE', #16912, #12564, #13138, .T. ) ; -#14767 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16886, #7699, #11595, #17089 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999986321218314878 ), - .UNSPECIFIED. ) ; -#14769 = ORIENTED_EDGE ( 'NONE', *, *, #8155, .T. ) ; -#14770 = CIRCLE ( 'NONE', #25222, 2.000000000000011546 ) ; -#14771 = VERTEX_POINT ( 'NONE', #23632 ) ; -#14772 = CONICAL_SURFACE ( 'NONE', #18642, 4.999999999928862238, 0.7853981633813337249 ) ; -#14773 = CARTESIAN_POINT ( 'NONE', ( 23.36690039798400420, 177.7945729690129610, 100.6859215232942262 ) ) ; -#14774 = CARTESIAN_POINT ( 'NONE', ( -29.31840044800755862, 107.1313895729742853, 197.8236157141470812 ) ) ; -#14775 = AXIS2_PLACEMENT_3D ( 'NONE', #9786, #34692, #559 ) ; -#14776 = CARTESIAN_POINT ( 'NONE', ( -36.94217276719289345, 191.1469244249373958, 106.3510002446024174 ) ) ; -#14777 = EDGE_LOOP ( 'NONE', ( #28223, #23940, #31908, #6027 ) ) ; -#14778 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971539312 ) ) ; -#14779 = ORIENTED_EDGE ( 'NONE', *, *, #1126, .F. ) ; -#14780 = AXIS2_PLACEMENT_3D ( 'NONE', #12965, #19676, #6804 ) ; -#14781 = CARTESIAN_POINT ( 'NONE', ( 26.24278765071260011, 121.6914654643040166, 90.81416692690758907 ) ) ; -#14782 = CARTESIAN_POINT ( 'NONE', ( -35.96501400986333152, 191.5393548104552792, 103.8949329600032456 ) ) ; -#14783 = CONICAL_SURFACE ( 'NONE', #37617, 2.500000002031119717, 0.7853981634283228042 ) ; -#14784 = EDGE_CURVE ( 'NONE', #7826, #662, #20343, .T. ) ; -#14785 = EDGE_CURVE ( 'NONE', #29758, #12650, #34121, .T. ) ; -#14787 = LINE ( 'NONE', #20284, #12250 ) ; -#14786 = CARTESIAN_POINT ( 'NONE', ( 6.034364035348996680, 135.2945551047479853, 91.39763805309847555 ) ) ; -#14788 = VERTEX_POINT ( 'NONE', #10963 ) ; -#14789 = ORIENTED_EDGE ( 'NONE', *, *, #31023, .T. ) ; -#14790 = ORIENTED_EDGE ( 'NONE', *, *, #10674, .F. ) ; -#14791 = CARTESIAN_POINT ( 'NONE', ( -11.79198343374907054, 125.9681876107315333, 176.0676422622361770 ) ) ; -#14792 = CARTESIAN_POINT ( 'NONE', ( -32.37402305108282263, 174.4007230276914697, 99.93605550448263841 ) ) ; -#14793 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#14794 = CARTESIAN_POINT ( 'NONE', ( 6.035970131895862956, 136.6809175985756895, 94.28346487865485415 ) ) ; -#14795 = ORIENTED_EDGE ( 'NONE', *, *, #21131, .F. ) ; -#14796 = ORIENTED_EDGE ( 'NONE', *, *, #19430, .T. ) ; -#14797 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781609017, 0.0005734119022076547383 ) ) ; -#14798 = AXIS2_PLACEMENT_3D ( 'NONE', #5252, #24085, #11394 ) ; -#14799 = CARTESIAN_POINT ( 'NONE', ( -45.16400980236513618, 70.91888486856629470, 322.7789803297500839 ) ) ; -#14800 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #30955, #3129, #27300, #28099 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 2.390890780862696019, 2.519620269850888938 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9986195365718029127, 0.9986195365718029127, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#14801 = CARTESIAN_POINT ( 'NONE', ( 26.36788054911000145, 123.4245874620000052, 88.47400024127000506 ) ) ; -#14802 = ORIENTED_EDGE ( 'NONE', *, *, #23404, .F. ) ; -#14803 = ADVANCED_FACE ( 'NONE', ( #30171 ), #7878, .T. ) ; -#14804 = CARTESIAN_POINT ( 'NONE', ( -35.93471605327420093, 191.2065812678220311, 106.8934977285220072 ) ) ; -#14805 = AXIS2_PLACEMENT_3D ( 'NONE', #402, #15546, #6526 ) ; -#14806 = CARTESIAN_POINT ( 'NONE', ( 0.7417211779368000357, 188.7943872467999995, 105.8988894614000174 ) ) ; -#14807 = CARTESIAN_POINT ( 'NONE', ( -14.59022374134706901, 128.1503308081717876, 179.4782974412063936 ) ) ; -#14808 = CARTESIAN_POINT ( 'NONE', ( 13.50046316316999828, 187.7460073535528124, 103.5025028262052018 ) ) ; -#14809 = CARTESIAN_POINT ( 'NONE', ( -77.80920708077799475, 191.9373083000641316, 194.2502677903374604 ) ) ; -#14810 = ADVANCED_FACE ( 'NONE', ( #2166 ), #11541, .F. ) ; -#14811 = ORIENTED_EDGE ( 'NONE', *, *, #1202, .F. ) ; -#14812 = LINE ( 'NONE', #23199, #32954 ) ; -#14813 = DIRECTION ( 'NONE', ( 0.0006039748319388209621, -4.551467604553135559E-16, 0.9999998176071845934 ) ) ; -#14814 = EDGE_CURVE ( 'NONE', #31941, #1633, #37504, .T. ) ; -#14815 = ORIENTED_EDGE ( 'NONE', *, *, #15156, .F. ) ; -#14816 = CARTESIAN_POINT ( 'NONE', ( 25.99030105615392827, 209.7097546603872900, 73.04280869622928662 ) ) ; -#14817 = EDGE_LOOP ( 'NONE', ( #11324, #35988, #17629, #13356 ) ) ; -#14818 = ADVANCED_FACE ( 'NONE', ( #5833 ), #15241, .T. ) ; -#14819 = VECTOR ( 'NONE', #25802, 1000.000000000000000 ) ; -#14820 = ADVANCED_FACE ( 'NONE', ( #30983 ), #12558, .T. ) ; -#14821 = VECTOR ( 'NONE', #29805, 1000.000000000000114 ) ; -#14823 = CARTESIAN_POINT ( 'NONE', ( -42.29775297821973368, 68.10033796042301901, 322.1267884147291625 ) ) ; -#14822 = LINE ( 'NONE', #9082, #4370 ) ; -#14824 = EDGE_CURVE ( 'NONE', #2542, #17419, #40244, .T. ) ; -#14825 = EDGE_LOOP ( 'NONE', ( #37744, #38666, #31997, #28679 ) ) ; -#14826 = ORIENTED_EDGE ( 'NONE', *, *, #20794, .F. ) ; -#14827 = EDGE_CURVE ( 'NONE', #32124, #9285, #21969, .T. ) ; -#14828 = ORIENTED_EDGE ( 'NONE', *, *, #33734, .T. ) ; -#14830 = VECTOR ( 'NONE', #23380, 1000.000000000000114 ) ; -#14829 = DIRECTION ( 'NONE', ( -3.469446951953594073E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#14831 = PLANE ( 'NONE', #27867 ) ; -#14832 = CARTESIAN_POINT ( 'NONE', ( -37.22291683779299376, 185.3309949534769601, 105.5413495680464564 ) ) ; -#14833 = DIRECTION ( 'NONE', ( -0.0005884949961193586092, 0.2249510543439039167, -0.9743698870671270162 ) ) ; -#14834 = CARTESIAN_POINT ( 'NONE', ( 12.63911368426781223, 177.4999195067232449, 100.8751768350861795 ) ) ; -#14835 = ORIENTED_EDGE ( 'NONE', *, *, #33534, .F. ) ; -#14836 = ORIENTED_EDGE ( 'NONE', *, *, #29144, .T. ) ; -#14837 = DIRECTION ( 'NONE', ( -0.0005884949916165789496, 0.2249510543496076598, -0.9743698870658127342 ) ) ; -#14838 = ORIENTED_EDGE ( 'NONE', *, *, #20811, .F. ) ; -#14839 = ORIENTED_EDGE ( 'NONE', *, *, #24353, .F. ) ; -#14840 = CARTESIAN_POINT ( 'NONE', ( -19.32395937428486477, 125.1232359887470835, 178.1040707223516506 ) ) ; -#14841 = DIRECTION ( 'NONE', ( 0.0005559617638584173809, -0.3907311284892690528, 0.9205046855589706922 ) ) ; -#14842 = CARTESIAN_POINT ( 'NONE', ( 19.34464905661442913, 125.4224474659459361, 178.3484596968724247 ) ) ; -#14843 = ORIENTED_EDGE ( 'NONE', *, *, #16998, .T. ) ; -#14844 = ORIENTED_EDGE ( 'NONE', *, *, #7361, .F. ) ; -#14845 = DIRECTION ( 'NONE', ( -0.0006039748319386907495, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#14846 = CARTESIAN_POINT ( 'NONE', ( -35.57981409087999936, 192.4624458391000132, 104.0002278041999944 ) ) ; -#14847 = ORIENTED_EDGE ( 'NONE', *, *, #13441, .T. ) ; -#14848 = CARTESIAN_POINT ( 'NONE', ( -26.00107461933026443, 120.7512200989553151, 87.53535867504626822 ) ) ; -#14849 = ORIENTED_EDGE ( 'NONE', *, *, #23364, .F. ) ; -#14850 = DIRECTION ( 'NONE', ( -0.9999998268368034404, -0.0001323825955363455871, 0.0005734119039304815891 ) ) ; -#14851 = CARTESIAN_POINT ( 'NONE', ( 15.50176591790000025, 128.0783593493999888, 92.29169035091000239 ) ) ; -#14852 = ORIENTED_EDGE ( 'NONE', *, *, #15207, .F. ) ; -#14853 = CIRCLE ( 'NONE', #36408, 4.500000000071178619 ) ; -#14854 = FACE_OUTER_BOUND ( 'NONE', #30905, .T. ) ; -#14855 = CARTESIAN_POINT ( 'NONE', ( 3.806357625657792010, 174.7432254729364161, 102.7945264273639054 ) ) ; -#14856 = CARTESIAN_POINT ( 'NONE', ( -3.804637439536749266, 167.8806383395850048, 101.2168609214313193 ) ) ; -#14857 = EDGE_LOOP ( 'NONE', ( #5573, #40222, #9737, #39093, #24844, #7900, #40053, #25226, #28581, #10739, #19095, #9597, #31974 ) ) ; -#14858 = CARTESIAN_POINT ( 'NONE', ( -45.18925545272470856, 80.56898504508372127, 280.9798118546170258 ) ) ; -#14859 = CARTESIAN_POINT ( 'NONE', ( 41.02702155346852209, 188.5398332461408870, 107.5358668361008228 ) ) ; -#14860 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748612543, 179.1800746285557580, 103.5747911657685734 ) ) ; -#14861 = ADVANCED_FACE ( 'NONE', ( #2949 ), #1727, .T. ) ; -#14862 = VERTEX_POINT ( 'NONE', #15040 ) ; -#14863 = CARTESIAN_POINT ( 'NONE', ( 24.84150023435487142, 115.7113441437079899, 90.25278119554212708 ) ) ; -#14864 = ORIENTED_EDGE ( 'NONE', *, *, #17835, .F. ) ; -#14865 = FACE_OUTER_BOUND ( 'NONE', #34929, .T. ) ; -#14866 = CARTESIAN_POINT ( 'NONE', ( -35.45487758071271855, 209.7096534091000137, 76.07991848633032816 ) ) ; -#14867 = CARTESIAN_POINT ( 'NONE', ( -14.42530050483258286, 182.6237780248500258, 101.9947080626078559 ) ) ; -#14868 = EDGE_CURVE ( 'NONE', #4358, #1663, #18282, .T. ) ; -#14869 = CARTESIAN_POINT ( 'NONE', ( -35.43925701461602529, 191.9759150222000130, 101.9428517634920155 ) ) ; -#14870 = ORIENTED_EDGE ( 'NONE', *, *, #8255, .T. ) ; -#14871 = EDGE_CURVE ( 'NONE', #34014, #3655, #18037, .T. ) ; -#14872 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#14873 = CARTESIAN_POINT ( 'NONE', ( -6.045835231059395021, 134.9182589738620095, 90.80491324842614631 ) ) ; -#14874 = ADVANCED_FACE ( 'NONE', ( #28126 ), #8715, .F. ) ; -#14875 = CARTESIAN_POINT ( 'NONE', ( 38.08852185710932048, 146.1696274809962119, 280.9295141638872906 ) ) ; -#14876 = CARTESIAN_POINT ( 'NONE', ( -16.27844647523966159, 151.6576545058942997, 160.4643156198225427 ) ) ; -#14877 = AXIS2_PLACEMENT_3D ( 'NONE', #27449, #15731, #24768 ) ; -#14878 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319370571820 ) ) ; -#14879 = CARTESIAN_POINT ( 'NONE', ( 31.03325069022026383, 177.6068007423234008, 100.6379405975941097 ) ) ; -#14880 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; -#14881 = CARTESIAN_POINT ( 'NONE', ( 21.94280614663047047, 115.3059885538493177, 90.25453193413594022 ) ) ; -#14882 = EDGE_LOOP ( 'NONE', ( #37727, #22936, #19480, #26601 ) ) ; -#14883 = VERTEX_POINT ( 'NONE', #27934 ) ; -#14884 = CARTESIAN_POINT ( 'NONE', ( -2.935493006219376255, 190.8915656532114724, 106.8042233182557652 ) ) ; -#14885 = PLANE ( 'NONE', #6588 ) ; -#14886 = ORIENTED_EDGE ( 'NONE', *, *, #8263, .F. ) ; -#14887 = CARTESIAN_POINT ( 'NONE', ( -20.49853057565002601, 184.3993303303604705, 104.8029991440840973 ) ) ; -#14888 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921577410, 0.2249510932971590937 ) ) ; -#14889 = EDGE_LOOP ( 'NONE', ( #1607, #23367, #17522, #37102 ) ) ; -#14890 = DIRECTION ( 'NONE', ( -0.0005884949950231212505, 0.2249510543438350829, -0.9743698870671434475 ) ) ; -#14891 = CARTESIAN_POINT ( 'NONE', ( -5.668214785696392255, 130.7937963942969475, 90.04674115371072673 ) ) ; -#14892 = ORIENTED_EDGE ( 'NONE', *, *, #22210, .T. ) ; -#14893 = CARTESIAN_POINT ( 'NONE', ( -43.65360665174738841, 185.3905100451317765, 107.6115822775834374 ) ) ; -#14894 = CARTESIAN_POINT ( 'NONE', ( 75.24056455973224899, 196.4820008462166641, 189.1802437148639058 ) ) ; -#14895 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 2.710505431213761687E-20, -0.0006039748319346910192 ) ) ; -#14896 = CARTESIAN_POINT ( 'NONE', ( -1.458415330484564842, 144.9404864492794047, 129.0359332385724258 ) ) ; -#14897 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749387275, 132.8602140592439866, 90.82839891339261840 ) ) ; -#14898 = EDGE_LOOP ( 'NONE', ( #5460, #1077, #19635, #6055, #16790 ) ) ; -#14899 = CARTESIAN_POINT ( 'NONE', ( 39.73982121083000152, 119.6329988433000011, 87.90935942237000233 ) ) ; -#14900 = CARTESIAN_POINT ( 'NONE', ( -6.031620047117566052, 177.7903949882438042, 100.7027583919079063 ) ) ; -#14901 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; -#14902 = ADVANCED_FACE ( 'NONE', ( #3353 ), #18679, .T. ) ; -#14903 = EDGE_CURVE ( 'NONE', #27587, #29108, #2768, .T. ) ; -#14904 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#14905 = EDGE_CURVE ( 'NONE', #16249, #18466, #14161, .T. ) ; -#14906 = ORIENTED_EDGE ( 'NONE', *, *, #39270, .T. ) ; -#14907 = DIRECTION ( 'NONE', ( -0.0005884949961193429967, 0.2249510543439072197, -0.9743698870671261281 ) ) ; -#14908 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #7434, #4570 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14909 = CARTESIAN_POINT ( 'NONE', ( 22.34608376466076507, 115.6781728360633679, 89.75450174034121176 ) ) ; -#14910 = CARTESIAN_POINT ( 'NONE', ( 1.226896413245818884, 139.0230654261391692, 177.9317107752453921 ) ) ; -#14911 = DIRECTION ( 'NONE', ( 0.6087611434179127645, 0.7731004625452339019, 0.1781166614240815016 ) ) ; -#14912 = CARTESIAN_POINT ( 'NONE', ( -21.17604533225664554, 114.6186307098221846, 152.8157487814333422 ) ) ; -#14913 = EDGE_CURVE ( 'NONE', #37711, #25532, #19352, .T. ) ; -#14914 = CARTESIAN_POINT ( 'NONE', ( -12.63633097960429197, 127.9084167607413320, 92.27263726944957511 ) ) ; -#14915 = CARTESIAN_POINT ( 'NONE', ( 21.46568501808666696, 116.4032067661892569, 184.4826706400311025 ) ) ; -#14916 = CARTESIAN_POINT ( 'NONE', ( -25.66870877867046374, 209.7112358038351090, 73.41525054140304007 ) ) ; -#14917 = CARTESIAN_POINT ( 'NONE', ( 33.97342776401706743, 128.5679624385472266, 291.5380248361651638 ) ) ; -#14918 = EDGE_CURVE ( 'NONE', #28359, #36719, #21484, .T. ) ; -#14919 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319697021, 89.39970233729044935, 291.5295797804315612 ) ) ; -#14920 = CARTESIAN_POINT ( 'NONE', ( -6.035970131895957103, 136.6793194835712484, 94.29038707408911080 ) ) ; -#14921 = CARTESIAN_POINT ( 'NONE', ( 18.08289561727003658, 152.6324032069051384, 184.7487331658680887 ) ) ; -#14922 = CARTESIAN_POINT ( 'NONE', ( -27.01791081220863333, 113.9384843682444739, 176.2313260275029734 ) ) ; -#14923 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971547084 ) ) ; -#14925 = VERTEX_POINT ( 'NONE', #3152 ) ; -#14924 = CARTESIAN_POINT ( 'NONE', ( 37.28138085964135229, 124.9697182170792331, 93.49058584749309375 ) ) ; -#14926 = ORIENTED_EDGE ( 'NONE', *, *, #35704, .T. ) ; -#14927 = VERTEX_POINT ( 'NONE', #692 ) ; -#14929 = AXIS2_PLACEMENT_3D ( 'NONE', #19439, #4502, #3897 ) ; -#14928 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941776877568, 160.8896114957608177, 98.33667293300580070 ) ) ; -#14930 = ORIENTED_EDGE ( 'NONE', *, *, #1929, .F. ) ; -#14931 = LINE ( 'NONE', #14739, #10498 ) ; -#14932 = AXIS2_PLACEMENT_3D ( 'NONE', #31852, #19551, #12833 ) ; -#14933 = DIRECTION ( 'NONE', ( 0.5988974202702760374, -0.8008257488327958917, 0.000000000000000000 ) ) ; -#14934 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #40386, #24885, #31203, #22214 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.002537838772308321188, 0.007867325901353338855 ), - .UNSPECIFIED. ) ; -#14935 = CARTESIAN_POINT ( 'NONE', ( -19.99800679399352532, 151.2849267590962654, 97.67087031631508864 ) ) ; -#14936 = CONICAL_SURFACE ( 'NONE', #36553, 2.502994258127966720, 0.7853981633568209997 ) ; -#14937 = CONICAL_SURFACE ( 'NONE', #40368, 2.503080545183768546, 0.7853981633889626224 ) ; -#14938 = VERTEX_POINT ( 'NONE', #35220 ) ; -#14939 = CARTESIAN_POINT ( 'NONE', ( -5.662686464640452222, 188.3429660633563287, 103.1387990589197869 ) ) ; -#14940 = DIRECTION ( 'NONE', ( -0.0004161288024618653870, 0.8480480897819120401, -0.5299191110481576983 ) ) ; -#14941 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.271205363195980628E-14, -0.9999998176071845934 ) ) ; -#14942 = CARTESIAN_POINT ( 'NONE', ( 16.00176529486913424, 184.2900636920902002, 105.2688851223920778 ) ) ; -#14943 = ORIENTED_EDGE ( 'NONE', *, *, #27103, .T. ) ; -#14944 = CARTESIAN_POINT ( 'NONE', ( 17.25787011369294177, 152.4458873259683287, 182.8835471660145231 ) ) ; -#14945 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16968, #29468, #1443, #29668 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0001462318381979060247, 0.004088694087170433554 ), - .UNSPECIFIED. ) ; -#14946 = CARTESIAN_POINT ( 'NONE', ( 26.71688048470999988, 176.9326579885999990, 103.3072462416999997 ) ) ; -#14947 = CYLINDRICAL_SURFACE ( 'NONE', #7786, 16.50000000000000000 ) ; -#14948 = CARTESIAN_POINT ( 'NONE', ( -4.606085391967113196, 188.1124318115141989, 103.0848823474960625 ) ) ; -#14949 = CARTESIAN_POINT ( 'NONE', ( -22.62605270318119466, 214.0903621265957213, 76.07221691162195043 ) ) ; -#14950 = VERTEX_POINT ( 'NONE', #31794 ) ; -#14951 = CARTESIAN_POINT ( 'NONE', ( -27.81649859982000095, 186.9854473794999876, 103.4908046625999987 ) ) ; -#14952 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24676, #27944, #34045, #40374 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( -3.279828533275069060E-07, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#14953 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; -#14954 = CARTESIAN_POINT ( 'NONE', ( 37.71190864537933862, 212.3970730851055748, 73.53572712575454773 ) ) ; -#14955 = ORIENTED_EDGE ( 'NONE', *, *, #2214, .F. ) ; -#14956 = EDGE_CURVE ( 'NONE', #31137, #26517, #1462, .T. ) ; -#14957 = VERTEX_POINT ( 'NONE', #28517 ) ; -#14958 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#14959 = ADVANCED_FACE ( 'NONE', ( #10322 ), #22388, .T. ) ; -#14960 = ORIENTED_EDGE ( 'NONE', *, *, #7300, .T. ) ; -#14961 = VECTOR ( 'NONE', #7933, 1000.000000000000227 ) ; -#14962 = VECTOR ( 'NONE', #30449, 999.9999999999998863 ) ; -#14963 = VERTEX_POINT ( 'NONE', #38311 ) ; -#14964 = VECTOR ( 'NONE', #26037, 1000.000000000000000 ) ; -#14965 = ORIENTED_EDGE ( 'NONE', *, *, #4506, .F. ) ; -#14966 = CARTESIAN_POINT ( 'NONE', ( 23.36190162741788967, 177.7945445883550519, 100.6858769593398080 ) ) ; -#14967 = CONICAL_SURFACE ( 'NONE', #10390, 6.499999999957617014, 0.7853981634197665374 ) ; -#14968 = DIRECTION ( 'NONE', ( 0.7856007465113979960, 0.6187337610642678065, 0.000000000000000000 ) ) ; -#14969 = CARTESIAN_POINT ( 'NONE', ( 14.93318671104674777, 124.4798289405424612, 171.6828735292820625 ) ) ; -#14970 = ORIENTED_EDGE ( 'NONE', *, *, #17462, .T. ) ; -#14971 = CARTESIAN_POINT ( 'NONE', ( -30.44899543503618489, 184.9287465216532098, 105.4443919424699487 ) ) ; -#14972 = ORIENTED_EDGE ( 'NONE', *, *, #8310, .T. ) ; -#14973 = CARTESIAN_POINT ( 'NONE', ( 26.12685208517629931, 121.2579486302669949, 90.71245394277049456 ) ) ; -#14974 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#14976 = CARTESIAN_POINT ( 'NONE', ( 38.20283421333017060, 112.8208469135682037, 151.2502482518302145 ) ) ; -#14975 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319384230599 ) ) ; -#14977 = ORIENTED_EDGE ( 'NONE', *, *, #29558, .T. ) ; -#14978 = ADVANCED_FACE ( 'NONE', ( #29120 ), #1092, .T. ) ; -#14979 = DIRECTION ( 'NONE', ( 0.6087613186456907188, -0.7729176985478710682, -0.1789074850089337476 ) ) ; -#14980 = ORIENTED_EDGE ( 'NONE', *, *, #17243, .T. ) ; -#14981 = ORIENTED_EDGE ( 'NONE', *, *, #537, .T. ) ; -#14982 = CARTESIAN_POINT ( 'NONE', ( -28.53030869656295110, 124.6043131503039803, 91.51623810099293621 ) ) ; -#14983 = AXIS2_PLACEMENT_3D ( 'NONE', #5881, #30834, #17928 ) ; -#14984 = CARTESIAN_POINT ( 'NONE', ( 13.47462245814947934, 158.2310456470601423, 98.74105996008697161 ) ) ; -#14985 = CARTESIAN_POINT ( 'NONE', ( 45.36193107847550010, 123.6517040319592695, 91.25168146711183681 ) ) ; -#14986 = CARTESIAN_POINT ( 'NONE', ( 30.96384560852109047, 128.5897405105000360, 89.32150042245991983 ) ) ; -#14987 = CARTESIAN_POINT ( 'NONE', ( -15.49852918818087844, 160.1761146135337697, 99.20761364607615462 ) ) ; -#14988 = VERTEX_POINT ( 'NONE', #19690 ) ; -#14989 = AXIS2_PLACEMENT_3D ( 'NONE', #8262, #38514, #38708 ) ; -#14990 = EDGE_LOOP ( 'NONE', ( #35997, #25697, #1686, #28195, #3694, #32672 ) ) ; -#14991 = CIRCLE ( 'NONE', #13035, 5.999999999829195296 ) ; -#14992 = LINE ( 'NONE', #14194, #24675 ) ; -#14993 = VECTOR ( 'NONE', #32751, 1000.000000000000114 ) ; -#14994 = CARTESIAN_POINT ( 'NONE', ( 14.50494660459214202, 188.1403489822673407, 103.0797849509411606 ) ) ; -#14995 = ORIENTED_EDGE ( 'NONE', *, *, #3892, .F. ) ; -#14996 = CARTESIAN_POINT ( 'NONE', ( 35.80006985119368323, 209.7096538286036775, 75.78341165758600084 ) ) ; -#14997 = EDGE_CURVE ( 'NONE', #12942, #33829, #16095, .T. ) ; -#14998 = CARTESIAN_POINT ( 'NONE', ( 1.191689505327423015, 188.4327942350174396, 106.2411708578321736 ) ) ; -#14999 = EDGE_CURVE ( 'NONE', #28821, #29586, #38498, .T. ) ; -#15000 = CARTESIAN_POINT ( 'NONE', ( -20.51961669426007973, 208.8045157407349848, 73.66040143448114463 ) ) ; -#15001 = CARTESIAN_POINT ( 'NONE', ( -37.83635444431042316, 190.3639788717852923, 106.7036751988638912 ) ) ; -#15002 = CARTESIAN_POINT ( 'NONE', ( 20.50147081616042755, 137.9496117178372003, 94.05447709939286938 ) ) ; -#15003 = CARTESIAN_POINT ( 'NONE', ( 23.36337295639098599, 174.7961192000784649, 102.5594366671658833 ) ) ; -#15004 = ORIENTED_EDGE ( 'NONE', *, *, #1903, .T. ) ; -#15005 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319364164186 ) ) ; -#15006 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32464, #34699, #7299, #32268, #15905, #28794, #774, #25944, #32072, #13061, #25746, #13260, #25542, #28401 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 0.000000000000000000, 0.2499727892209989422, 0.4999454735151304119, 0.6249318156621461728, 0.7499181578092619649, 0.8124113288828697099, 0.8749044999562777258, 0.9373976710298355108, 0.9686442565666094628, 0.9842675493349863913, 0.9999740798740125447, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15007 = PLANE ( 'NONE', #16002 ) ; -#15008 = LINE ( 'NONE', #30340, #39783 ) ; -#15009 = AXIS2_PLACEMENT_3D ( 'NONE', #27240, #11885, #11267 ) ; -#15010 = AXIS2_PLACEMENT_3D ( 'NONE', #1703, #26657, #11306 ) ; -#15011 = ORIENTED_EDGE ( 'NONE', *, *, #17500, .T. ) ; -#15012 = CIRCLE ( 'NONE', #18899, 2.500000000000003997 ) ; -#15013 = VECTOR ( 'NONE', #25946, 1000.000000000000114 ) ; -#15014 = CARTESIAN_POINT ( 'NONE', ( 16.04677293489484668, 121.3099732125007364, 177.4328244646404187 ) ) ; -#15015 = ORIENTED_EDGE ( 'NONE', *, *, #14594, .T. ) ; -#15016 = CIRCLE ( 'NONE', #20887, 7.500000000039277914 ) ; -#15018 = CARTESIAN_POINT ( 'NONE', ( 36.11364262193256280, 191.5260145455536929, 103.8483746271915322 ) ) ; -#15017 = CARTESIAN_POINT ( 'NONE', ( 58.66975477332916711, 28.73766266558741478, 151.7693572141883749 ) ) ; -#15019 = EDGE_LOOP ( 'NONE', ( #13645, #428, #10104, #6375 ) ) ; -#15020 = ORIENTED_EDGE ( 'NONE', *, *, #13617, .F. ) ; -#15021 = EDGE_CURVE ( 'NONE', #40336, #23375, #30741, .T. ) ; -#15022 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6676, #19553, #38559, #4208, #22447, #32244, #10576, #23046, #9771, #19144, #3604 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998985256, 0.3749999999998269717, 0.4374999999997786215, 0.4687499999997544742, 0.4999999999997302713, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15023 = ORIENTED_EDGE ( 'NONE', *, *, #32765, .T. ) ; -#15024 = CARTESIAN_POINT ( 'NONE', ( -30.17967539261260868, 185.9478675171641271, 102.6005988726028590 ) ) ; -#15025 = CARTESIAN_POINT ( 'NONE', ( 36.04593084803799741, 218.5902260770999987, 76.03673379060180082 ) ) ; -#15026 = DIRECTION ( 'NONE', ( -3.965082230941001926E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; -#15027 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498896523, 179.0675991014397255, 104.0619761092555535 ) ) ; -#15028 = ORIENTED_EDGE ( 'NONE', *, *, #32127, .F. ) ; -#15029 = ORIENTED_EDGE ( 'NONE', *, *, #12133, .F. ) ; -#15030 = CARTESIAN_POINT ( 'NONE', ( -35.95473150033171095, 205.5673820438934172, 76.32193034924722497 ) ) ; -#15031 = VERTEX_POINT ( 'NONE', #34615 ) ; -#15032 = ORIENTED_EDGE ( 'NONE', *, *, #8213, .T. ) ; -#15033 = CARTESIAN_POINT ( 'NONE', ( 25.50832794966548889, 194.2771770616000140, 102.8828691709000083 ) ) ; -#15034 = FACE_OUTER_BOUND ( 'NONE', #39806, .T. ) ; -#15035 = CARTESIAN_POINT ( 'NONE', ( 23.49456796478292731, 134.9226066419677750, 90.78806929407819837 ) ) ; -#15036 = LINE ( 'NONE', #6218, #13121 ) ; -#15037 = ORIENTED_EDGE ( 'NONE', *, *, #31344, .F. ) ; -#15038 = EDGE_CURVE ( 'NONE', #25693, #33874, #24614, .T. ) ; -#15039 = VERTEX_POINT ( 'NONE', #19090 ) ; -#15040 = CARTESIAN_POINT ( 'NONE', ( 6.042240099596939196, 177.1173855813495948, 103.6190021212635770 ) ) ; -#15041 = CARTESIAN_POINT ( 'NONE', ( -36.32345314786999779, 191.9373732646000121, 104.5577068233999967 ) ) ; -#15042 = VERTEX_POINT ( 'NONE', #31585 ) ; -#15043 = CARTESIAN_POINT ( 'NONE', ( -26.09494683763999845, 122.9286295258000052, 88.39116117343999690 ) ) ; -#15044 = VECTOR ( 'NONE', #17936, 999.9999999999998863 ) ; -#15045 = EDGE_CURVE ( 'NONE', #15381, #10264, #3545, .T. ) ; -#15046 = ORIENTED_EDGE ( 'NONE', *, *, #26914, .T. ) ; -#15047 = CARTESIAN_POINT ( 'NONE', ( 22.78222448783905563, 147.4012051316053373, 96.74832440318435545 ) ) ; -#15048 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; -#15049 = VECTOR ( 'NONE', #5420, 1000.000000000000000 ) ; -#15050 = ORIENTED_EDGE ( 'NONE', *, *, #11114, .T. ) ; -#15051 = AXIS2_PLACEMENT_3D ( 'NONE', #3383, #18713, #18513 ) ; -#15052 = AXIS2_PLACEMENT_3D ( 'NONE', #9473, #15598, #21953 ) ; -#15053 = ADVANCED_FACE ( 'NONE', ( #6819 ), #30466, .T. ) ; -#15054 = FACE_OUTER_BOUND ( 'NONE', #11763, .T. ) ; -#15055 = EDGE_CURVE ( 'NONE', #11228, #2503, #452, .T. ) ; -#15056 = CARTESIAN_POINT ( 'NONE', ( 14.42549689688723902, 176.7813770855786970, 100.6284578791999849 ) ) ; -#15057 = EDGE_CURVE ( 'NONE', #27737, #14771, #37036, .T. ) ; -#15058 = CARTESIAN_POINT ( 'NONE', ( -19.36170877788639189, 125.9457204061172604, 176.2201754958151980 ) ) ; -#15059 = EDGE_CURVE ( 'NONE', #3485, #16249, #31687, .T. ) ; -#15060 = CARTESIAN_POINT ( 'NONE', ( 5.666638401079358900, 185.7962301796234783, 103.0570926492003423 ) ) ; -#15061 = LINE ( 'NONE', #34437, #5156 ) ; -#15062 = VERTEX_POINT ( 'NONE', #33762 ) ; -#15063 = CARTESIAN_POINT ( 'NONE', ( 23.00089693216080988, 115.1133509736824152, 90.25389292129368357 ) ) ; -#15064 = EDGE_LOOP ( 'NONE', ( #32281, #32194, #27485, #29146 ) ) ; -#15065 = ORIENTED_EDGE ( 'NONE', *, *, #32612, .T. ) ; -#15066 = CARTESIAN_POINT ( 'NONE', ( -39.67088391192145735, 107.0888282672084699, 184.9170418304496195 ) ) ; -#15067 = CARTESIAN_POINT ( 'NONE', ( -38.20994760263000245, 118.4557571329000041, 87.83717842695000400 ) ) ; -#15068 = CARTESIAN_POINT ( 'NONE', ( 38.73196185082999676, 118.4320966457000139, 89.50377527013000645 ) ) ; -#15069 = CARTESIAN_POINT ( 'NONE', ( -20.51882342812400850, 211.4177743922000730, 75.57082808996456436 ) ) ; -#15070 = CARTESIAN_POINT ( 'NONE', ( 6.033445973870449563, 135.2348759297800029, 91.30213210094883891 ) ) ; -#15071 = ORIENTED_EDGE ( 'NONE', *, *, #18846, .F. ) ; -#15072 = CARTESIAN_POINT ( 'NONE', ( 16.55946513390808406, 121.8573583107191780, 177.5776958584335148 ) ) ; -#15073 = AXIS2_PLACEMENT_3D ( 'NONE', #8098, #11363, #36514 ) ; -#15074 = EDGE_CURVE ( 'NONE', #19918, #15284, #23272, .T. ) ; -#15075 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319356122658 ) ) ; -#15076 = ORIENTED_EDGE ( 'NONE', *, *, #8257, .F. ) ; -#15077 = CARTESIAN_POINT ( 'NONE', ( 23.68479074153999875, 130.4250414353013241, 90.26276162061896002 ) ) ; -#15078 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36989, #8580, #18150, #8986, #16105, #12434, #12851, #557, #37383, #25328 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000945355, 0.3750000000001261768, 0.4375000000001419975, 0.5000000000001577627, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15079 = CARTESIAN_POINT ( 'NONE', ( 22.10845038464975332, 154.3881759508926734, 95.28288806961444379 ) ) ; -#15080 = CARTESIAN_POINT ( 'NONE', ( -28.70758035546699460, 163.1500623791996816, 99.90218165579484833 ) ) ; -#15081 = CARTESIAN_POINT ( 'NONE', ( -36.79864679810778227, 165.0248183764149701, 194.7126685882008985 ) ) ; -#15082 = DIRECTION ( 'NONE', ( -0.7856245185210576354, -0.6187035767623751958, 0.000000000000000000 ) ) ; -#15083 = CARTESIAN_POINT ( 'NONE', ( -1.208995885426419781, 135.1225269230298238, 180.6332618066155931 ) ) ; -#15084 = EDGE_LOOP ( 'NONE', ( #10816, #27491, #18224, #18371 ) ) ; -#15085 = ORIENTED_EDGE ( 'NONE', *, *, #29534, .T. ) ; -#15086 = CARTESIAN_POINT ( 'NONE', ( 1.240445527565428030, 189.1176099620038826, 105.7708271182180653 ) ) ; -#15087 = DIRECTION ( 'NONE', ( -0.5968393679911998539, -0.8023607473050168304, 0.000000000000000000 ) ) ; -#15088 = EDGE_CURVE ( 'NONE', #8503, #39173, #10880, .T. ) ; -#15089 = VERTEX_POINT ( 'NONE', #37636 ) ; -#15090 = LINE ( 'NONE', #31430, #10185 ) ; -#15091 = VERTEX_POINT ( 'NONE', #40096 ) ; -#15092 = CARTESIAN_POINT ( 'NONE', ( -38.99718989648000189, 120.0910792986999951, 87.40634461756999940 ) ) ; -#15093 = EDGE_CURVE ( 'NONE', #22, #24364, #24886, .T. ) ; -#15094 = CARTESIAN_POINT ( 'NONE', ( -5.668456030792887290, 130.7409932062415976, 90.07973636940788253 ) ) ; -#15095 = EDGE_LOOP ( 'NONE', ( #14706, #996, #14501 ) ) ; -#15096 = DIRECTION ( 'NONE', ( 0.0005667561018013857546, 0.5299192634445675232, 0.8480479072657912676 ) ) ; -#15097 = DIRECTION ( 'NONE', ( -0.0005734119072324083549, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#15098 = CARTESIAN_POINT ( 'NONE', ( -38.11718854129877343, 118.8155790694493561, 90.29079743518840928 ) ) ; -#15099 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #6798, #34794 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15100 = CARTESIAN_POINT ( 'NONE', ( 13.47343164508975377, 158.6809479346725595, 96.79232023565108989 ) ) ; -#15101 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988409597765, 161.7142231050778207, 96.98759364909003011 ) ) ; -#15102 = ORIENTED_EDGE ( 'NONE', *, *, #20051, .F. ) ; -#15103 = ADVANCED_FACE ( 'NONE', ( #22111 ), #34542, .F. ) ; -#15104 = ORIENTED_EDGE ( 'NONE', *, *, #21242, .F. ) ; -#15105 = CARTESIAN_POINT ( 'NONE', ( -20.68769432855515333, 105.5805168951702342, 87.28027914095393669 ) ) ; -#15106 = VECTOR ( 'NONE', #38571, 1000.000000000000114 ) ; -#15107 = CARTESIAN_POINT ( 'NONE', ( -12.63633098392225662, 174.6781851931449410, 103.0702648796800673 ) ) ; -#15108 = CARTESIAN_POINT ( 'NONE', ( 37.51815168729829963, 191.4396200122112077, 104.3353197794647826 ) ) ; -#15109 = CIRCLE ( 'NONE', #25562, 2.499999999988871124 ) ; -#15110 = CIRCLE ( 'NONE', #13778, 2.499999999999997335 ) ; -#15111 = CARTESIAN_POINT ( 'NONE', ( -15.94527957999837575, 152.8243907355866611, 181.6127031347539003 ) ) ; -#15112 = ORIENTED_EDGE ( 'NONE', *, *, #36359, .T. ) ; -#15113 = ORIENTED_EDGE ( 'NONE', *, *, #39774, .T. ) ; -#15114 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; -#15115 = CARTESIAN_POINT ( 'NONE', ( 12.31198009898977297, 134.9205818654068025, 90.79431936396761671 ) ) ; -#15116 = CARTESIAN_POINT ( 'NONE', ( -3.668404233967317740, 183.5617789224675676, 104.5994755554405486 ) ) ; -#15117 = LINE ( 'NONE', #12048, #11189 ) ; -#15118 = FACE_OUTER_BOUND ( 'NONE', #30760, .T. ) ; -#15119 = CARTESIAN_POINT ( 'NONE', ( -36.36397650069000065, 191.9049264267000012, 104.5553411748999935 ) ) ; -#15120 = CARTESIAN_POINT ( 'NONE', ( 14.94976271106517807, 136.0909262678420077, 93.97082019938331143 ) ) ; -#15121 = CARTESIAN_POINT ( 'NONE', ( -30.84019928186018689, 183.3517191563202005, 102.0016297752730168 ) ) ; -#15122 = CARTESIAN_POINT ( 'NONE', ( 7.997218435461875607, 131.0225853275861141, 89.89707245289747561 ) ) ; -#15123 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35359, #7365, #4297, #4501 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15124 = CARTESIAN_POINT ( 'NONE', ( -25.77483565525809084, 209.7107308647096033, 73.30925164553990214 ) ) ; -#15125 = CARTESIAN_POINT ( 'NONE', ( -0.02845919973435177830, 93.66652340833722690, 291.5585611238757906 ) ) ; -#15126 = CARTESIAN_POINT ( 'NONE', ( 38.12236789434999906, 118.6347812900000065, 87.56703225248999445 ) ) ; -#15127 = APPROVAL_STATUS ( 'not_yet_approved' ) ; -#15128 = CARTESIAN_POINT ( 'NONE', ( 4.214178076569004894, 182.1297273395886975, 101.6983387179820397 ) ) ; -#15129 = DIRECTION ( 'NONE', ( -0.0005884949961176016596, 0.2249510543439068588, -0.9743698870671261281 ) ) ; -#15130 = FACE_OUTER_BOUND ( 'NONE', #32814, .T. ) ; -#15131 = CYLINDRICAL_SURFACE ( 'NONE', #5158, 2.250000000000011102 ) ; -#15133 = ORIENTED_EDGE ( 'NONE', *, *, #31800, .F. ) ; -#15132 = CARTESIAN_POINT ( 'NONE', ( 36.46428275574999844, 191.4173107530999971, 106.4736958616000067 ) ) ; -#15134 = ORIENTED_EDGE ( 'NONE', *, *, #40094, .T. ) ; -#15135 = ORIENTED_EDGE ( 'NONE', *, *, #29907, .T. ) ; -#15136 = CYLINDRICAL_SURFACE ( 'NONE', #4919, 6.000000000000011546 ) ; -#15137 = VECTOR ( 'NONE', #30243, 1000.000000000000227 ) ; -#15138 = ORIENTED_EDGE ( 'NONE', *, *, #35872, .F. ) ; -#15139 = CARTESIAN_POINT ( 'NONE', ( 24.53499378586817414, 109.6131156702000027, 90.25296631807577796 ) ) ; -#15140 = ADVANCED_FACE ( 'NONE', ( #9242 ), #37511, .F. ) ; -#15141 = EDGE_CURVE ( 'NONE', #38935, #4337, #10033, .T. ) ; -#15142 = DIRECTION ( 'NONE', ( 0.0005884936524312223746, -0.2249510543440256249, 0.9743698870679101676 ) ) ; -#15143 = FACE_OUTER_BOUND ( 'NONE', #2638, .T. ) ; -#15144 = ADVANCED_FACE ( 'NONE', ( #9845 ), #23184, .F. ) ; -#15145 = EDGE_CURVE ( 'NONE', #4337, #27040, #2248, .T. ) ; -#15146 = ORIENTED_EDGE ( 'NONE', *, *, #15228, .F. ) ; -#15147 = CARTESIAN_POINT ( 'NONE', ( 14.01595022200380924, 135.4465979594034764, 93.65157854464966647 ) ) ; -#15148 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#15149 = CARTESIAN_POINT ( 'NONE', ( -13.35978900763059762, 130.9435614395062260, 89.89169326634505808 ) ) ; -#15150 = VERTEX_POINT ( 'NONE', #14919 ) ; -#15151 = EDGE_CURVE ( 'NONE', #27940, #34917, #22913, .T. ) ; -#15152 = CARTESIAN_POINT ( 'NONE', ( -42.54327191201071656, 120.9996688098205340, 92.62994261980294652 ) ) ; -#15153 = CARTESIAN_POINT ( 'NONE', ( 23.36439212065845794, 176.8044416301941055, 103.1046897219861904 ) ) ; -#15154 = CARTESIAN_POINT ( 'NONE', ( 37.06791829841335328, 117.4340048322533079, 90.24539674539980183 ) ) ; -#15155 = DIRECTION ( 'NONE', ( -0.0005884949961218734161, 0.2249510543439056931, -0.9743698870671265722 ) ) ; -#15156 = EDGE_CURVE ( 'NONE', #36682, #38732, #8174, .T. ) ; -#15157 = ORIENTED_EDGE ( 'NONE', *, *, #28165, .T. ) ; -#15158 = CARTESIAN_POINT ( 'NONE', ( -27.61276218341999922, 188.2939806148000059, 103.0017547080000071 ) ) ; -#15159 = CARTESIAN_POINT ( 'NONE', ( 1.315675836357660389, 189.1541845523380232, 103.7399269907329966 ) ) ; -#15160 = CARTESIAN_POINT ( 'NONE', ( 23.68617299094906059, 127.9139236766033179, 92.24878420086326969 ) ) ; -#15161 = VERTEX_POINT ( 'NONE', #33505 ) ; -#15162 = EDGE_LOOP ( 'NONE', ( #30602, #19530 ) ) ; -#15163 = CONICAL_SURFACE ( 'NONE', #4684, 2.503115222802204443, 0.7853981633873898804 ) ; -#15164 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; -#15165 = ORIENTED_EDGE ( 'NONE', *, *, #1410, .T. ) ; -#15166 = AXIS2_PLACEMENT_3D ( 'NONE', #1160, #34685, #3818 ) ; -#15167 = ADVANCED_FACE ( 'NONE', ( #39235 ), #39035, .F. ) ; -#15168 = CIRCLE ( 'NONE', #37339, 6.000000251127745265 ) ; -#15169 = CARTESIAN_POINT ( 'NONE', ( -17.26174088632014403, 121.9765816702171009, 174.4814081256518534 ) ) ; -#15170 = CARTESIAN_POINT ( 'NONE', ( -37.98654602637000011, 191.4670132987999978, 104.1597717548000190 ) ) ; -#15171 = CARTESIAN_POINT ( 'NONE', ( -20.01830659250219213, 205.5538814942069052, 75.24804808645014020 ) ) ; -#15172 = CARTESIAN_POINT ( 'NONE', ( -37.18901461366416328, 191.0654016131968262, 106.3408188258918727 ) ) ; -#15173 = ORIENTED_EDGE ( 'NONE', *, *, #2954, .T. ) ; -#15174 = CARTESIAN_POINT ( 'NONE', ( -21.44693882331385026, 135.7861819143374760, 91.01458761472625270 ) ) ; -#15175 = CARTESIAN_POINT ( 'NONE', ( -25.50129497783076715, 118.5814613607333285, 87.78316531807180922 ) ) ; -#15176 = CARTESIAN_POINT ( 'NONE', ( -1.914441492903718123, 189.6526805815070986, 105.9269172079772829 ) ) ; -#15177 = ORIENTED_EDGE ( 'NONE', *, *, #22986, .F. ) ; -#15178 = FACE_BOUND ( 'NONE', #28753, .T. ) ; -#15179 = CARTESIAN_POINT ( 'NONE', ( -35.85878617516480205, 191.6073043381418870, 103.9089155225263283 ) ) ; -#15181 = CARTESIAN_POINT ( 'NONE', ( -32.65040898612480191, 153.0051697192221241, 291.5764532040477093 ) ) ; -#15180 = CARTESIAN_POINT ( 'NONE', ( -23.00157826576616671, 118.1131156702000169, 87.27825658246501916 ) ) ; -#15182 = EDGE_LOOP ( 'NONE', ( #24150, #27740, #3268, #3865 ) ) ; -#15183 = EDGE_LOOP ( 'NONE', ( #19233, #23201, #19199, #25202, #35961 ) ) ; -#15184 = EDGE_CURVE ( 'NONE', #27979, #26904, #32708, .T. ) ; -#15185 = AXIS2_PLACEMENT_3D ( 'NONE', #28171, #8957, #12405 ) ; -#15186 = EDGE_CURVE ( 'NONE', #13948, #35226, #38972, .T. ) ; -#15187 = VERTEX_POINT ( 'NONE', #15518 ) ; -#15189 = VECTOR ( 'NONE', #6564, 1000.000000000000000 ) ; -#15188 = FACE_OUTER_BOUND ( 'NONE', #27600, .T. ) ; -#15190 = AXIS2_PLACEMENT_3D ( 'NONE', #29949, #39538, #8487 ) ; -#15191 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265228896, -0.1368326740407719011 ) ) ; -#15192 = CARTESIAN_POINT ( 'NONE', ( 29.66018523879016300, 130.7316300977390711, 89.81678206544971488 ) ) ; -#15193 = CARTESIAN_POINT ( 'NONE', ( -12.63917946761317879, 135.0411934724452010, 91.00683831463108220 ) ) ; -#15194 = ORIENTED_EDGE ( 'NONE', *, *, #20847, .T. ) ; -#15195 = EDGE_CURVE ( 'NONE', #9411, #38443, #30666, .T. ) ; -#15196 = EDGE_LOOP ( 'NONE', ( #18703, #10326, #9049, #12453, #23267, #29104, #5030, #11136, #14078, #34649, #2375, #27475 ) ) ; -#15197 = CARTESIAN_POINT ( 'NONE', ( 35.56284489036890051, 193.8169247291054376, 102.6814306727405750 ) ) ; -#15198 = CARTESIAN_POINT ( 'NONE', ( 13.76537810311827847, 124.4276589313617905, 178.6661833187116883 ) ) ; -#15199 = ADVANCED_FACE ( 'NONE', ( #37195 ), #6105, .T. ) ; -#15200 = ORIENTED_EDGE ( 'NONE', *, *, #14592, .T. ) ; -#15201 = CARTESIAN_POINT ( 'NONE', ( -36.06506250534999936, 191.3439698402999909, 106.7337090868000047 ) ) ; -#15202 = FACE_OUTER_BOUND ( 'NONE', #34447, .T. ) ; -#15203 = CARTESIAN_POINT ( 'NONE', ( 3.199984518777000631, 190.8630714974999876, 106.9328794001999938 ) ) ; -#15204 = EDGE_LOOP ( 'NONE', ( #39323, #17827, #30012, #22529 ) ) ; -#15205 = CARTESIAN_POINT ( 'NONE', ( 0.5641564930821999502, 188.3875164193000273, 106.2241891016000039 ) ) ; -#15206 = CARTESIAN_POINT ( 'NONE', ( 5.667442478653145876, 130.8359915337342727, 90.01481240614560875 ) ) ; -#15207 = EDGE_CURVE ( 'NONE', #31175, #36214, #15316, .T. ) ; -#15208 = CARTESIAN_POINT ( 'NONE', ( -46.35684242861079696, 110.7105035214231776, 151.9824889214679615 ) ) ; -#15209 = FACE_OUTER_BOUND ( 'NONE', #2996, .T. ) ; -#15210 = VECTOR ( 'NONE', #32555, 1000.000000000000114 ) ; -#15211 = ORIENTED_EDGE ( 'NONE', *, *, #20092, .F. ) ; -#15212 = VECTOR ( 'NONE', #24033, 1000.000000000000227 ) ; -#15213 = CARTESIAN_POINT ( 'NONE', ( -36.09769066460763298, 187.5602729729505711, 106.0553394373776115 ) ) ; -#15214 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391913256 ) ) ; -#15215 = CIRCLE ( 'NONE', #32175, 5.999999999651004501 ) ; -#15216 = ORIENTED_EDGE ( 'NONE', *, *, #35532, .T. ) ; -#15217 = CARTESIAN_POINT ( 'NONE', ( 30.17614589098232258, 126.7625099796061932, 88.90012650384656467 ) ) ; -#15218 = VERTEX_POINT ( 'NONE', #9389 ) ; -#15220 = CARTESIAN_POINT ( 'NONE', ( -44.88822238842725199, 179.5780855356435950, 137.0595526267623825 ) ) ; -#15219 = CARTESIAN_POINT ( 'NONE', ( -39.68697719330157270, 104.2905048274910058, 197.1740080326743794 ) ) ; -#15221 = ORIENTED_EDGE ( 'NONE', *, *, #37488, .T. ) ; -#15222 = ORIENTED_EDGE ( 'NONE', *, *, #170, .F. ) ; -#15223 = ORIENTED_EDGE ( 'NONE', *, *, #20245, .F. ) ; -#15224 = CARTESIAN_POINT ( 'NONE', ( 3.146407946422999924, 209.5134149454999886, 76.20363659513000698 ) ) ; -#15225 = CARTESIAN_POINT ( 'NONE', ( 2.564210731195382120, 191.0000001071945235, 106.3128016873806274 ) ) ; -#15226 = DIRECTION ( 'NONE', ( -2.530387804365254516E-14, -0.9743700557921585181, -0.2249510932971561239 ) ) ; -#15227 = DIRECTION ( 'NONE', ( -0.0005884949961254435855, 0.2249510543439056098, -0.9743698870671265722 ) ) ; -#15228 = EDGE_CURVE ( 'NONE', #31532, #8723, #6495, .T. ) ; -#15229 = VERTEX_POINT ( 'NONE', #33910 ) ; -#15230 = EDGE_CURVE ( 'NONE', #15773, #8079, #24540, .T. ) ; -#15231 = VERTEX_POINT ( 'NONE', #24744 ) ; -#15232 = ORIENTED_EDGE ( 'NONE', *, *, #13249, .F. ) ; -#15233 = VERTEX_POINT ( 'NONE', #28007 ) ; -#15234 = DIRECTION ( 'NONE', ( 0.0004270283471111629785, -0.7071067811866028618, 0.7071066522432896129 ) ) ; -#15235 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.110223024625155594E-14, -1.000000000000000000 ) ) ; -#15236 = CARTESIAN_POINT ( 'NONE', ( 8.046776635720599202, 151.4387294071806593, 94.61044745561473235 ) ) ; -#15237 = LINE ( 'NONE', #34419, #35879 ) ; -#15238 = AXIS2_PLACEMENT_3D ( 'NONE', #14718, #26581, #5083 ) ; -#15239 = ORIENTED_EDGE ( 'NONE', *, *, #33775, .F. ) ; -#15240 = ORIENTED_EDGE ( 'NONE', *, *, #38927, .T. ) ; -#15241 = CYLINDRICAL_SURFACE ( 'NONE', #12831, 10.00000000000000533 ) ; -#15242 = ADVANCED_FACE ( 'NONE', ( #176 ), #6943, .F. ) ; -#15243 = CYLINDRICAL_SURFACE ( 'NONE', #2200, 2.000000000000011546 ) ; -#15244 = DIRECTION ( 'NONE', ( 0.0005884981308560151671, -0.2249510543434312670, 0.9743698870653425548 ) ) ; -#15245 = AXIS2_PLACEMENT_3D ( 'NONE', #3993, #25908, #10559 ) ; -#15246 = VERTEX_POINT ( 'NONE', #21260 ) ; -#15247 = CARTESIAN_POINT ( 'NONE', ( -20.50037936456179821, 118.1134456052949560, 87.78011095654957785 ) ) ; -#15248 = ORIENTED_EDGE ( 'NONE', *, *, #22302, .F. ) ; -#15249 = VECTOR ( 'NONE', #39960, 1000.000000000000000 ) ; -#15250 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971571509 ) ) ; -#15251 = CARTESIAN_POINT ( 'NONE', ( -40.85601813336936061, 189.7480745836568303, 106.8731605699205574 ) ) ; -#15252 = VERTEX_POINT ( 'NONE', #5910 ) ; -#15253 = CARTESIAN_POINT ( 'NONE', ( -36.48898135731426606, 115.4643415116839975, 89.74914836252970929 ) ) ; -#15254 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20636, #4274, #20217, #35949 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15255 = CARTESIAN_POINT ( 'NONE', ( 46.37626369660664949, 72.18299133667814260, 291.5305338340516528 ) ) ; -#15256 = CARTESIAN_POINT ( 'NONE', ( -32.68154407215684643, 153.2594451684146293, 291.5782827689202463 ) ) ; -#15257 = CARTESIAN_POINT ( 'NONE', ( -37.54908091477015120, 212.5463744629944074, 73.41451618045002192 ) ) ; -#15258 = CARTESIAN_POINT ( 'NONE', ( -13.50000077688951450, 188.3420892684051751, 103.1432776901117307 ) ) ; -#15259 = ORIENTED_EDGE ( 'NONE', *, *, #3394, .F. ) ; -#15260 = CARTESIAN_POINT ( 'NONE', ( 21.98718844691312668, 129.2990422925554981, 92.22748880099159408 ) ) ; -#15261 = CARTESIAN_POINT ( 'NONE', ( -25.90158191252999842, 191.3557575943999893, 103.9673941423999963 ) ) ; -#15262 = DIRECTION ( 'NONE', ( -0.0006039748319382906789, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#15263 = FACE_OUTER_BOUND ( 'NONE', #6166, .T. ) ; -#15264 = DIRECTION ( 'NONE', ( -0.7075227810178683630, 0.1590644155802670434, -0.6885564799178420792 ) ) ; -#15265 = ORIENTED_EDGE ( 'NONE', *, *, #18131, .F. ) ; -#15266 = AXIS2_PLACEMENT_3D ( 'NONE', #14519, #33307, #27209 ) ; -#15267 = CARTESIAN_POINT ( 'NONE', ( 9.995029200524999879, 159.1892556871999886, 28.07991271570000080 ) ) ; -#15268 = ORIENTED_EDGE ( 'NONE', *, *, #37880, .T. ) ; -#15270 = ADVANCED_FACE ( 'NONE', ( #34305 ), #6299, .T. ) ; -#15269 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25281, #13001, #22611, #25484, #32011, #13594, #13202, #16644, #37935, #3971, #16444 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998275824, 0.3749999999997819522, 0.4374999999998048228, 0.4687499999997975508, 0.4999999999997902789, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15271 = CIRCLE ( 'NONE', #31587, 5.499999999543050855 ) ; -#15272 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#15273 = EDGE_CURVE ( 'NONE', #7173, #2217, #10240, .T. ) ; -#15274 = AXIS2_PLACEMENT_3D ( 'NONE', #19992, #31894, #13875 ) ; -#15275 = ORIENTED_EDGE ( 'NONE', *, *, #25439, .T. ) ; -#15276 = LINE ( 'NONE', #14876, #32306 ) ; -#15277 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555133 ) ) ; -#15278 = CARTESIAN_POINT ( 'NONE', ( -36.26459936063917411, 164.9566154569169782, 193.1834482597365366 ) ) ; -#15279 = DIRECTION ( 'NONE', ( -0.0003759422414365064615, 0.7826081567317987320, -0.6225145232717768096 ) ) ; -#15280 = EDGE_CURVE ( 'NONE', #16409, #4989, #40240, .T. ) ; -#15281 = DIRECTION ( 'NONE', ( -0.7933533411653052037, 0.5930537057989929695, 0.1373964268091736607 ) ) ; -#15282 = EDGE_CURVE ( 'NONE', #10977, #19860, #24381, .T. ) ; -#15283 = LINE ( 'NONE', #27970, #16058 ) ; -#15284 = VERTEX_POINT ( 'NONE', #37586 ) ; -#15285 = ADVANCED_FACE ( 'NONE', ( #34492 ), #27423, .T. ) ; -#15286 = CARTESIAN_POINT ( 'NONE', ( -20.50037936456179821, 118.1134456052949560, 87.78011095654957785 ) ) ; -#15287 = CARTESIAN_POINT ( 'NONE', ( -25.98970595316612631, 191.9759150222000130, 106.9371460002143692 ) ) ; -#15288 = VERTEX_POINT ( 'NONE', #27815 ) ; -#15289 = CARTESIAN_POINT ( 'NONE', ( 19.98170452206136005, 205.5539062507874917, 75.22380842103150655 ) ) ; -#15290 = ORIENTED_EDGE ( 'NONE', *, *, #15628, .T. ) ; -#15291 = CARTESIAN_POINT ( 'NONE', ( -26.00831778363330571, 205.1071295951813340, 76.12055741644476825 ) ) ; -#15292 = CARTESIAN_POINT ( 'NONE', ( -3.535851989103623971, 143.5328828484186943, 95.87118806634899215 ) ) ; -#15293 = ORIENTED_EDGE ( 'NONE', *, *, #14301, .T. ) ; -#15294 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; -#15295 = VECTOR ( 'NONE', #37874, 1000.000000000000227 ) ; -#15296 = AXIS2_PLACEMENT_3D ( 'NONE', #23874, #39593, #30408 ) ; -#15297 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 82.27946979429611929, 297.5967072516832559 ) ) ; -#15298 = CARTESIAN_POINT ( 'NONE', ( -26.12594029382999850, 191.4284810197000013, 107.0434483078000056 ) ) ; -#15299 = VECTOR ( 'NONE', #17574, 1000.000000000000227 ) ; -#15300 = CARTESIAN_POINT ( 'NONE', ( -24.01451938906670946, 115.2897724545006071, 90.28228900716538874 ) ) ; -#15301 = CARTESIAN_POINT ( 'NONE', ( 3.166264962546063710, 126.6495829448442407, 88.89036871524665173 ) ) ; -#15302 = ORIENTED_EDGE ( 'NONE', *, *, #22796, .F. ) ; -#15303 = CARTESIAN_POINT ( 'NONE', ( -41.93243227727202793, 132.0857236358559135, 291.5838700735885709 ) ) ; -#15304 = VECTOR ( 'NONE', #18241, 1000.000000000000000 ) ; -#15305 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989940797, 0.1373964268091564245 ) ) ; -#15306 = CARTESIAN_POINT ( 'NONE', ( 30.07038801303579234, 134.2481741983066854, 93.70730552177415973 ) ) ; -#15307 = CARTESIAN_POINT ( 'NONE', ( -46.23837296033245536, 124.7988103812620579, 91.22973473997339511 ) ) ; -#15308 = ORIENTED_EDGE ( 'NONE', *, *, #6673, .F. ) ; -#15309 = FACE_OUTER_BOUND ( 'NONE', #5948, .T. ) ; -#15310 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825947466614054, 0.0005734119017560097235 ) ) ; -#15311 = CARTESIAN_POINT ( 'NONE', ( 22.99138912207082441, 214.0899462551063266, 73.04463992848049259 ) ) ; -#15312 = CARTESIAN_POINT ( 'NONE', ( -27.14319524275719786, 187.2717417431980209, 105.4684560175520005 ) ) ; -#15313 = CIRCLE ( 'NONE', #36198, 5.499999999997797318 ) ; -#15314 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#15315 = ADVANCED_FACE ( 'NONE', ( #36788 ), #8791, .T. ) ; -#15316 = LINE ( 'NONE', #18557, #4315 ) ; -#15317 = AXIS2_PLACEMENT_3D ( 'NONE', #19797, #38810, #39226 ) ; -#15318 = AXIS2_PLACEMENT_3D ( 'NONE', #28869, #14953, #11476 ) ; -#15319 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971538202 ) ) ; -#15320 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700558022311276, -0.2249510932535267183 ) ) ; -#15321 = DIRECTION ( 'NONE', ( -0.6185863125140933505, -0.7857168535612664151, 0.000000000000000000 ) ) ; -#15322 = CARTESIAN_POINT ( 'NONE', ( 37.68865679123659618, 190.9605833865500415, 106.2965747328459969 ) ) ; -#15323 = AXIS2_PLACEMENT_3D ( 'NONE', #39645, #36174, #30465 ) ; -#15324 = ADVANCED_FACE ( 'NONE', ( #26683 ), #3039, .T. ) ; -#15325 = ADVANCED_FACE ( 'NONE', ( #22470 ), #25945, .F. ) ; -#15326 = ORIENTED_EDGE ( 'NONE', *, *, #14023, .T. ) ; -#15327 = CARTESIAN_POINT ( 'NONE', ( 36.64645721461000250, 191.6442232212000079, 106.2387314096999944 ) ) ; -#15328 = ORIENTED_EDGE ( 'NONE', *, *, #33032, .T. ) ; -#15329 = ORIENTED_EDGE ( 'NONE', *, *, #11343, .F. ) ; -#15330 = EDGE_CURVE ( 'NONE', #14524, #35793, #37782, .T. ) ; -#15331 = CARTESIAN_POINT ( 'NONE', ( -4.804068707279816053, 135.2091091625680406, 90.87130529227184184 ) ) ; -#15332 = ADVANCED_FACE ( 'NONE', ( #771 ), #3703, .T. ) ; -#15333 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971557076 ) ) ; -#15334 = DIRECTION ( 'NONE', ( -0.7933533411653069800, 0.5930537057989943017, 0.1373964268091564522 ) ) ; -#15335 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178582671909E-05, -0.0002331579774919533509 ) ) ; -#15336 = ORIENTED_EDGE ( 'NONE', *, *, #7917, .F. ) ; -#15337 = CARTESIAN_POINT ( 'NONE', ( 40.87847416758199870, 217.7719116157724670, 73.36714790239413730 ) ) ; -#15338 = CARTESIAN_POINT ( 'NONE', ( -28.70875734540877389, 163.5999644878620245, 97.95344188170561495 ) ) ; -#15339 = LINE ( 'NONE', #2680, #11193 ) ; -#15340 = FACE_OUTER_BOUND ( 'NONE', #19920, .T. ) ; -#15341 = ORIENTED_EDGE ( 'NONE', *, *, #19374, .F. ) ; -#15342 = LINE ( 'NONE', #8814, #16664 ) ; -#15343 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15564, #27264, #24397, #33962 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15344 = CARTESIAN_POINT ( 'NONE', ( 23.37116632637657077, 177.1196686977561399, 103.6090577849978445 ) ) ; -#15345 = CARTESIAN_POINT ( 'NONE', ( 0.5626164669235433902, 188.9999987160578598, 103.6843922204118940 ) ) ; -#15346 = CARTESIAN_POINT ( 'NONE', ( -43.30038974941377461, 190.4174923657541285, 106.7193308803196601 ) ) ; -#15347 = CARTESIAN_POINT ( 'NONE', ( -21.17491851070888131, 213.4894134887179575, 76.07132462503170700 ) ) ; -#15348 = AXIS2_PLACEMENT_3D ( 'NONE', #23658, #36104, #33043 ) ; -#15349 = ORIENTED_EDGE ( 'NONE', *, *, #21375, .T. ) ; -#15350 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825936697426862, 0.0005734119020020883800 ) ) ; -#15351 = CARTESIAN_POINT ( 'NONE', ( 1.767930770475999891, 189.4068743987000119, 103.8090290509999960 ) ) ; -#15352 = AXIS2_PLACEMENT_3D ( 'NONE', #40432, #13046, #35085 ) ; -#15353 = CIRCLE ( 'NONE', #6835, 1.749999999975493381 ) ; -#15354 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; -#15355 = CIRCLE ( 'NONE', #36233, 2.000000002746800565 ) ; -#15356 = EDGE_LOOP ( 'NONE', ( #2726, #1672, #20467, #8798 ) ) ; -#15357 = CARTESIAN_POINT ( 'NONE', ( 23.72254622402000024, 115.9590670144843330, 152.9217693939943388 ) ) ; -#15358 = VERTEX_POINT ( 'NONE', #16306 ) ; -#15359 = CARTESIAN_POINT ( 'NONE', ( -16.56450047176163309, 122.2697573860770319, 175.5880185216135203 ) ) ; -#15360 = EDGE_CURVE ( 'NONE', #32435, #18851, #19380, .T. ) ; -#15361 = DIRECTION ( 'NONE', ( 1.227022876780779975E-15, 0.9743700557917523986, 0.2249510932989154111 ) ) ; -#15362 = EDGE_CURVE ( 'NONE', #33884, #20941, #17041, .T. ) ; -#15363 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#15364 = CARTESIAN_POINT ( 'NONE', ( -35.93226012891999943, 192.4368824471000039, 104.9893856757999941 ) ) ; -#15365 = LINE ( 'NONE', #5130, #30015 ) ; -#15366 = CYLINDRICAL_SURFACE ( 'NONE', #27890, 2.000000000000011546 ) ; -#15367 = EDGE_CURVE ( 'NONE', #21152, #26196, #38194, .T. ) ; -#15368 = CARTESIAN_POINT ( 'NONE', ( -25.50131619893729962, 118.3473562840666773, 87.78314412258384891 ) ) ; -#15369 = DIRECTION ( 'NONE', ( -0.6087614810001786836, 0.7729390313185912076, 0.1788147452386050495 ) ) ; -#15370 = ORIENTED_EDGE ( 'NONE', *, *, #32934, .T. ) ; -#15371 = EDGE_CURVE ( 'NONE', #28855, #29199, #19460, .T. ) ; -#15372 = DIRECTION ( 'NONE', ( -0.0006039748319389028194, -1.385776189666588672E-14, -0.9999998176071847045 ) ) ; -#15373 = CARTESIAN_POINT ( 'NONE', ( 3.062676760987444347, 191.1124749746885811, 103.7728652716954514 ) ) ; -#15374 = DIRECTION ( 'NONE', ( 0.7933530821293330870, 0.5932640870757638352, 0.1364866662427067223 ) ) ; -#15376 = CARTESIAN_POINT ( 'NONE', ( 16.22208376845709310, 122.1533376337188628, 174.2257921326907422 ) ) ; -#15375 = CARTESIAN_POINT ( 'NONE', ( -25.50129508846853099, 118.1132512059233335, 87.78307593003776788 ) ) ; -#15377 = ORIENTED_EDGE ( 'NONE', *, *, #11530, .T. ) ; -#15378 = EDGE_CURVE ( 'NONE', #24997, #24826, #8060, .T. ) ; -#15379 = AXIS2_PLACEMENT_3D ( 'NONE', #10470, #16567, #29063 ) ; -#15380 = AXIS2_PLACEMENT_3D ( 'NONE', #14603, #1299, #26270 ) ; -#15381 = VERTEX_POINT ( 'NONE', #39136 ) ; -#15382 = CONICAL_SURFACE ( 'NONE', #22566, 47.99999999995237232, 0.7853981633972918486 ) ; -#15383 = CIRCLE ( 'NONE', #38227, 1.999999999955081931 ) ; -#15384 = EDGE_LOOP ( 'NONE', ( #37929, #26311, #26813, #30714 ) ) ; -#15385 = CARTESIAN_POINT ( 'NONE', ( 25.49934386937603392, 120.6644425437606287, 88.00825483662825377 ) ) ; -#15386 = CARTESIAN_POINT ( 'NONE', ( 13.47241245321180259, 158.0311791718573886, 98.86596480645644647 ) ) ; -#15387 = CARTESIAN_POINT ( 'NONE', ( -25.74963657374999926, 201.9934155195000187, 90.49394230229999891 ) ) ; -#15388 = DIRECTION ( 'NONE', ( 0.0005884949671858177161, -0.2249510543353067105, 0.9743698870691290814 ) ) ; -#15389 = LINE ( 'NONE', #37063, #38654 ) ; -#15390 = ORIENTED_EDGE ( 'NONE', *, *, #19791, .F. ) ; -#15391 = ORIENTED_EDGE ( 'NONE', *, *, #28657, .T. ) ; -#15392 = CARTESIAN_POINT ( 'NONE', ( 37.78687090636931600, 218.5902260770998282, 61.03567957051413373 ) ) ; -#15393 = PLANE ( 'NONE', #37334 ) ; -#15394 = ORIENTED_EDGE ( 'NONE', *, *, #13197, .T. ) ; -#15395 = CARTESIAN_POINT ( 'NONE', ( -36.51612232699000060, 191.1898310933999880, 106.5271947874000062 ) ) ; -#15396 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319389474885 ) ) ; -#15397 = CARTESIAN_POINT ( 'NONE', ( 15.95613733389899025, 121.8961617987971238, 174.4891947115541484 ) ) ; -#15398 = CONICAL_SURFACE ( 'NONE', #29849, 2.249999999963673503, 0.7853981633778843729 ) ; -#15399 = ORIENTED_EDGE ( 'NONE', *, *, #37158, .F. ) ; -#15400 = CARTESIAN_POINT ( 'NONE', ( 2.951980948709000074, 190.0921062097999936, 106.6158610948999979 ) ) ; -#15401 = AXIS2_PLACEMENT_3D ( 'NONE', #30920, #32, #12702 ) ; -#15402 = CARTESIAN_POINT ( 'NONE', ( 5.667875642759740984, 130.6721462434133230, 90.11719410458975688 ) ) ; -#15403 = AXIS2_PLACEMENT_3D ( 'NONE', #14869, #27151, #23866 ) ; -#15404 = LINE ( 'NONE', #15208, #12782 ) ; -#15405 = CARTESIAN_POINT ( 'NONE', ( -34.95487766943185193, 220.4002260771000294, 76.07961650006694754 ) ) ; -#15406 = CARTESIAN_POINT ( 'NONE', ( 3.535080169976978492, 144.6901993477816006, 93.05515119550676673 ) ) ; -#15407 = ADVANCED_FACE ( 'NONE', ( #1514 ), #8306, .F. ) ; -#15408 = AXIS2_PLACEMENT_3D ( 'NONE', #36803, #5921, #15334 ) ; -#15409 = EDGE_CURVE ( 'NONE', #37526, #16610, #1905, .T. ) ; -#15410 = EDGE_LOOP ( 'NONE', ( #39217, #21716, #37313, #16142 ) ) ; -#15411 = ADVANCED_FACE ( 'NONE', ( #36057 ), #20525, .T. ) ; -#15412 = EDGE_CURVE ( 'NONE', #20537, #33399, #30502, .T. ) ; -#15413 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999904787, 179.7376864901910949, 101.1595092801111377 ) ) ; -#15414 = CARTESIAN_POINT ( 'NONE', ( -20.41767204683837633, 127.1614620270025426, 91.67148453719821077 ) ) ; -#15415 = ORIENTED_EDGE ( 'NONE', *, *, #29519, .F. ) ; -#15416 = ADVANCED_FACE ( 'NONE', ( #26479 ), #2144, .T. ) ; -#15417 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3779, #16253, #35041, #7051 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15418 = CARTESIAN_POINT ( 'NONE', ( -5.669412827410644340, 187.7434695915656562, 103.5134950631828588 ) ) ; -#15419 = EDGE_LOOP ( 'NONE', ( #11559, #31376, #1444, #26570, #26908 ) ) ; -#15421 = DIRECTION ( 'NONE', ( -1.249000902695084964E-14, 0.9743700557921582961, 0.2249510932971567345 ) ) ; -#15420 = CARTESIAN_POINT ( 'NONE', ( 1.447658031000570666, 152.0519508845351595, 130.6788418773748219 ) ) ; -#15422 = ORIENTED_EDGE ( 'NONE', *, *, #37797, .T. ) ; -#15423 = EDGE_CURVE ( 'NONE', #25840, #8707, #37965, .T. ) ; -#15424 = EDGE_LOOP ( 'NONE', ( #18489, #38959, #10547, #710 ) ) ; -#15425 = CARTESIAN_POINT ( 'NONE', ( 25.49226348177107582, 205.5673819639667954, 76.28481786455526503 ) ) ; -#15426 = ORIENTED_EDGE ( 'NONE', *, *, #10299, .T. ) ; -#15427 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825916136676223, 0.0005734119024715054200 ) ) ; -#15428 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#15429 = ORIENTED_EDGE ( 'NONE', *, *, #13782, .T. ) ; -#15430 = AXIS2_PLACEMENT_3D ( 'NONE', #36591, #2052, #5502 ) ; -#15431 = ORIENTED_EDGE ( 'NONE', *, *, #27, .T. ) ; -#15432 = CIRCLE ( 'NONE', #20647, 2.499999999987245314 ) ; -#15433 = ORIENTED_EDGE ( 'NONE', *, *, #13023, .F. ) ; -#15434 = FACE_OUTER_BOUND ( 'NONE', #33649, .T. ) ; -#15435 = CARTESIAN_POINT ( 'NONE', ( 30.44899542203640408, 126.4319227165660635, 91.90255272003975051 ) ) ; -#15436 = CARTESIAN_POINT ( 'NONE', ( 13.50222385217858267, 187.3269060524752661, 105.5005337516834629 ) ) ; -#15437 = LINE ( 'NONE', #27931, #14371 ) ; -#15438 = VECTOR ( 'NONE', #25552, 1000.000000000000000 ) ; -#15439 = ORIENTED_EDGE ( 'NONE', *, *, #8357, .T. ) ; -#15440 = VERTEX_POINT ( 'NONE', #15219 ) ; -#15441 = CARTESIAN_POINT ( 'NONE', ( -5.669971430217174202, 123.9176819113750554, 91.14983607065533988 ) ) ; -#15442 = CIRCLE ( 'NONE', #20656, 47.49999999999543832 ) ; -#15443 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#15444 = DIRECTION ( 'NONE', ( -0.0004225984971752187952, 0.2247404086396479206, -0.9744185805571413672 ) ) ; -#15445 = CARTESIAN_POINT ( 'NONE', ( -28.44201500224999890, 125.3783906434000102, 88.78702912938001646 ) ) ; -#15446 = ORIENTED_EDGE ( 'NONE', *, *, #27956, .T. ) ; -#15447 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825822545, 158.2317141435470376, 98.73576230545255328 ) ) ; -#15448 = CARTESIAN_POINT ( 'NONE', ( -5.668571547462038396, 124.2905521228788785, 90.91684019217574075 ) ) ; -#15449 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#15450 = ORIENTED_EDGE ( 'NONE', *, *, #20147, .F. ) ; -#15451 = CARTESIAN_POINT ( 'NONE', ( 13.53825347476000118, 113.1227133813000023, 152.4718672074000381 ) ) ; -#15452 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930881478 ) ) ; -#15453 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -6.071530832037190021E-16, -0.0006039748319384735838 ) ) ; -#15454 = DIRECTION ( 'NONE', ( 0.5989082241854611910, -0.8008175873178838833, -0.0003617255600150170222 ) ) ; -#15455 = AXIS2_PLACEMENT_3D ( 'NONE', #33707, #5713, #2663 ) ; -#15456 = ORIENTED_EDGE ( 'NONE', *, *, #34677, .F. ) ; -#15457 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; -#15458 = EDGE_LOOP ( 'NONE', ( #27130, #19119, #38694, #9644 ) ) ; -#15459 = EDGE_CURVE ( 'NONE', #20244, #8209, #5808, .T. ) ; -#15460 = CARTESIAN_POINT ( 'NONE', ( 35.27885543649455258, 77.14301703111104302, 291.5372363905759130 ) ) ; -#15461 = AXIS2_PLACEMENT_3D ( 'NONE', #2357, #39749, #22531 ) ; -#15462 = LINE ( 'NONE', #5652, #5528 ) ; -#15463 = AXIS2_PLACEMENT_3D ( 'NONE', #4688, #4890, #7959 ) ; -#15464 = CARTESIAN_POINT ( 'NONE', ( 25.82535974979346705, 209.7094246239551012, 75.87624978972131373 ) ) ; -#15465 = CARTESIAN_POINT ( 'NONE', ( -35.81474217949671868, 108.6541353822862703, 168.9015064287443977 ) ) ; -#15466 = CARTESIAN_POINT ( 'NONE', ( 92.50187971282166188, 221.8453154663451699, 201.2060978135920379 ) ) ; -#15467 = ORIENTED_EDGE ( 'NONE', *, *, #26244, .F. ) ; -#15468 = AXIS2_PLACEMENT_3D ( 'NONE', #3842, #3439, #28412 ) ; -#15469 = CARTESIAN_POINT ( 'NONE', ( -38.01808904093999786, 118.9131641596000009, 90.45269863391999365 ) ) ; -#15470 = VERTEX_POINT ( 'NONE', #17654 ) ; -#15471 = CARTESIAN_POINT ( 'NONE', ( -5.668107805537519361, 126.1261160540004767, 91.85696217430825072 ) ) ; -#15472 = FACE_OUTER_BOUND ( 'NONE', #6660, .T. ) ; -#15473 = CARTESIAN_POINT ( 'NONE', ( 42.83487131658635860, 120.7910107177264081, 92.64688251868899727 ) ) ; -#15474 = CARTESIAN_POINT ( 'NONE', ( -22.50072399476195528, 158.3009599602069954, 96.21317557253242114 ) ) ; -#15475 = CARTESIAN_POINT ( 'NONE', ( 17.27193883265227825, 122.1565372283859290, 173.7595026853086324 ) ) ; -#15476 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6283, #18950, #18738, #31448, #31235, #12842, #3215 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 4 ), - ( 0.000000000000000000, 0.0002542678779985293731, 0.0005089035069198654618 ), - .UNSPECIFIED. ) ; -#15477 = CARTESIAN_POINT ( 'NONE', ( -37.09480771575991298, 117.6307073562036578, 90.29018917355014651 ) ) ; -#15478 = ORIENTED_EDGE ( 'NONE', *, *, #33140, .F. ) ; -#15479 = CARTESIAN_POINT ( 'NONE', ( -19.70055405364098533, 149.1723619494412389, 182.9474843209757751 ) ) ; -#15480 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971578725 ) ) ; -#15481 = EDGE_CURVE ( 'NONE', #11452, #25074, #14822, .T. ) ; -#15482 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#15483 = ORIENTED_EDGE ( 'NONE', *, *, #33577, .T. ) ; -#15484 = DIRECTION ( 'NONE', ( 0.0005884949961259295249, -0.2249510543438812127, 0.9743698870671321233 ) ) ; -#15485 = FACE_OUTER_BOUND ( 'NONE', #39577, .T. ) ; -#15486 = AXIS2_PLACEMENT_3D ( 'NONE', #13077, #16512, #26159 ) ; -#15487 = ORIENTED_EDGE ( 'NONE', *, *, #27905, .T. ) ; -#15488 = FACE_OUTER_BOUND ( 'NONE', #17124, .T. ) ; -#15489 = AXIS2_PLACEMENT_3D ( 'NONE', #19069, #15608, #15803 ) ; -#15490 = CARTESIAN_POINT ( 'NONE', ( -20.00111603559079398, 118.1131148921541438, 87.27965578728156970 ) ) ; -#15491 = CARTESIAN_POINT ( 'NONE', ( -3.738963458913685756, 143.5821509023425904, 95.67443424898375781 ) ) ; -#15492 = DIRECTION ( 'NONE', ( 0.6087614115774879764, 0.7729348350621345620, 0.1788331191967953704 ) ) ; -#15493 = ORIENTED_EDGE ( 'NONE', *, *, #6525, .F. ) ; -#15494 = CARTESIAN_POINT ( 'NONE', ( 37.96340688161021149, 191.0388337556233864, 103.7347927322450261 ) ) ; -#15495 = CARTESIAN_POINT ( 'NONE', ( 19.46094516130095542, 125.6747539604571813, 178.4426934156100231 ) ) ; -#15496 = CARTESIAN_POINT ( 'NONE', ( 16.19205324837119164, 122.0564273762022793, 174.6239568424747404 ) ) ; -#15497 = FACE_OUTER_BOUND ( 'NONE', #3095, .T. ) ; -#15498 = DIRECTION ( 'NONE', ( 1.982541115402070435E-15, 0.9743700557921585181, 0.2249510932971559851 ) ) ; -#15499 = ORIENTED_EDGE ( 'NONE', *, *, #11385, .T. ) ; -#15500 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555965 ) ) ; -#15501 = DIRECTION ( 'NONE', ( 0.6772915400549810450, 0.7357147339627989613, 0.000000000000000000 ) ) ; -#15502 = CARTESIAN_POINT ( 'NONE', ( 21.32710341636608220, 124.0031502495809121, 174.3449744221197761 ) ) ; -#15503 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27856, #34153, #6945, #19205, #25183, #34532, #22105, #3673, #16536, #34345 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15504 = CARTESIAN_POINT ( 'NONE', ( 76.10689632611000377, 156.0201458301999935, 97.16650080654000021 ) ) ; -#15505 = VERTEX_POINT ( 'NONE', #18264 ) ; -#15506 = EDGE_CURVE ( 'NONE', #31792, #22006, #36382, .T. ) ; -#15507 = ORIENTED_EDGE ( 'NONE', *, *, #27633, .T. ) ; -#15508 = CARTESIAN_POINT ( 'NONE', ( 30.44722912908971679, 185.6116624766144696, 102.4863628258041501 ) ) ; -#15509 = ADVANCED_FACE ( 'NONE', ( #39733 ), #18720, .F. ) ; -#15510 = CARTESIAN_POINT ( 'NONE', ( -41.91025164549390780, 121.8985265256900590, 90.89963868520955259 ) ) ; -#15511 = CARTESIAN_POINT ( 'NONE', ( 24.42207296340776779, 213.7301733865842266, 73.04375376229047845 ) ) ; -#15512 = CARTESIAN_POINT ( 'NONE', ( -36.05664063452000079, 191.5958398806000389, 104.0134324235999941 ) ) ; -#15513 = ORIENTED_EDGE ( 'NONE', *, *, #5968, .F. ) ; -#15514 = CARTESIAN_POINT ( 'NONE', ( -25.54062333385549621, 190.4808759212580185, 106.2083752500079896 ) ) ; -#15515 = EDGE_CURVE ( 'NONE', #5601, #14392, #17445, .T. ) ; -#15516 = AXIS2_PLACEMENT_3D ( 'NONE', #37050, #31877, #40302 ) ; -#15517 = CARTESIAN_POINT ( 'NONE', ( -19.70070278794882057, 149.4222755489676047, 181.8632635963006408 ) ) ; -#15518 = CARTESIAN_POINT ( 'NONE', ( -20.49970533410106910, 151.8550384231813553, 95.23695349207935124 ) ) ; -#15519 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -1.676366911644155200E-18, -0.0006039748319336982153 ) ) ; -#15520 = CARTESIAN_POINT ( 'NONE', ( 37.42082352723856076, 132.6200669550715929, 336.9739440566017379 ) ) ; -#15521 = CARTESIAN_POINT ( 'NONE', ( 38.08026479933000275, 190.5116989059000048, 106.5670812404000003 ) ) ; -#15522 = CARTESIAN_POINT ( 'NONE', ( 36.18932080103540017, 192.0081794014270145, 104.3591424689070095 ) ) ; -#15524 = ORIENTED_EDGE ( 'NONE', *, *, #34590, .T. ) ; -#15523 = CARTESIAN_POINT ( 'NONE', ( 36.65916486431000010, 191.2456250189000002, 106.4454339660999977 ) ) ; -#15525 = ORIENTED_EDGE ( 'NONE', *, *, #39994, .T. ) ; -#15526 = CARTESIAN_POINT ( 'NONE', ( 6.065957172925149798, 165.2216646702348726, 152.9217693117704755 ) ) ; -#15527 = EDGE_CURVE ( 'NONE', #24364, #11960, #40144, .T. ) ; -#15528 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4460, #1198, #26365, #31899, #7527, #35513 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.003386932291534215222, 0.5016934661457671529, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15529 = CARTESIAN_POINT ( 'NONE', ( -20.24433135671547745, 184.9057498690842749, 102.6049128384596543 ) ) ; -#15530 = CARTESIAN_POINT ( 'NONE', ( 41.04524146633079340, 217.7719116456999870, 73.53371387620883581 ) ) ; -#15531 = ORIENTED_EDGE ( 'NONE', *, *, #1987, .T. ) ; -#15532 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#15533 = DIRECTION ( 'NONE', ( 0.6088835872828582962, 0.7728434907583781044, 0.1788119568987562025 ) ) ; -#15534 = CARTESIAN_POINT ( 'NONE', ( -12.63633279611098637, 174.6788778987209696, 103.0672644427368141 ) ) ; -#15535 = DIRECTION ( 'NONE', ( -7.677760455955688654E-18, 1.000000000000000000, -1.271205131337280331E-14 ) ) ; -#15536 = VERTEX_POINT ( 'NONE', #33808 ) ; -#15537 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9687, #12534, #4694, #3932 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15538 = CARTESIAN_POINT ( 'NONE', ( -21.70206945121835673, 129.8649430144931216, 89.98981461717227148 ) ) ; -#15539 = CARTESIAN_POINT ( 'NONE', ( 25.50051830703121780, 120.2145355607603534, 89.95699753438390189 ) ) ; -#15540 = CARTESIAN_POINT ( 'NONE', ( 5.669237377567532654, 130.1643386382168330, 92.52843164004643484 ) ) ; -#15541 = CARTESIAN_POINT ( 'NONE', ( -13.36381811942701781, 134.9949716747269974, 90.82703762294032401 ) ) ; -#15542 = AXIS2_PLACEMENT_3D ( 'NONE', #17856, #30570, #21376 ) ; -#15543 = CARTESIAN_POINT ( 'NONE', ( -14.16977588484152939, 129.7240516297933368, 90.12378855087145268 ) ) ; -#15544 = ORIENTED_EDGE ( 'NONE', *, *, #10895, .F. ) ; -#15545 = EDGE_CURVE ( 'NONE', #7877, #14237, #21906, .T. ) ; -#15546 = DIRECTION ( 'NONE', ( -0.0004161288024513937829, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#15547 = CARTESIAN_POINT ( 'NONE', ( 1.804326061463000119, 188.9338856921999934, 103.2700435273000039 ) ) ; -#15548 = CARTESIAN_POINT ( 'NONE', ( -19.83814135548826840, 313.4886687833925407, 132.0394724468755214 ) ) ; -#15549 = EDGE_CURVE ( 'NONE', #32574, #19175, #12861, .T. ) ; -#15550 = VERTEX_POINT ( 'NONE', #24018 ) ; -#15551 = FACE_OUTER_BOUND ( 'NONE', #23093, .T. ) ; -#15552 = ORIENTED_EDGE ( 'NONE', *, *, #15481, .T. ) ; -#15553 = ADVANCED_FACE ( 'NONE', ( #33401 ), #9589, .F. ) ; -#15554 = ADVANCED_FACE ( 'NONE', ( #5397 ), #2545, .T. ) ; -#15555 = CARTESIAN_POINT ( 'NONE', ( 14.89305397814877452, 176.0596799000455803, 100.6326092481401133 ) ) ; -#15556 = EDGE_CURVE ( 'NONE', #27328, #26238, #40437, .T. ) ; -#15557 = CARTESIAN_POINT ( 'NONE', ( 28.46511207850870662, 181.6173849770507900, 104.1311689187607215 ) ) ; -#15558 = DIRECTION ( 'NONE', ( 0.0005884933334877639251, -0.2249510526608011762, 0.9743698874567060519 ) ) ; -#15559 = CARTESIAN_POINT ( 'NONE', ( 39.17918664236205473, 77.03152903297159071, 290.9156096052041676 ) ) ; -#15560 = DIRECTION ( 'NONE', ( -0.6087611434179115433, 0.7728348325624404547, 0.1792657018023851023 ) ) ; -#15561 = CARTESIAN_POINT ( 'NONE', ( -1.458415330454428505, 152.0517121853154379, 130.6798743964100993 ) ) ; -#15562 = DIRECTION ( 'NONE', ( 0.0005884949961244385300, -0.2249510543439064425, 0.9743698870671262391 ) ) ; -#15563 = ORIENTED_EDGE ( 'NONE', *, *, #39396, .T. ) ; -#15564 = CARTESIAN_POINT ( 'NONE', ( -21.44693681792356443, 182.5559435529752363, 101.8122371725110611 ) ) ; -#15565 = CARTESIAN_POINT ( 'NONE', ( -0.02993291085645299193, 92.27946995574508549, 297.5585631083172302 ) ) ; -#15566 = CIRCLE ( 'NONE', #18179, 2.499999999890851754 ) ; -#15568 = CARTESIAN_POINT ( 'NONE', ( 16.22228026661851175, 122.1117483434376538, 174.4064439747764652 ) ) ; -#15567 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#15569 = ADVANCED_FACE ( 'NONE', ( #12247 ), #3067, .T. ) ; -#15570 = ORIENTED_EDGE ( 'NONE', *, *, #24149, .F. ) ; -#15571 = EDGE_LOOP ( 'NONE', ( #29715, #30506, #33609 ) ) ; -#15572 = LINE ( 'NONE', #31131, #2832 ) ; -#15573 = CARTESIAN_POINT ( 'NONE', ( -2.437379602191326988, 196.1181861119999894, 103.6812116302992877 ) ) ; -#15574 = CARTESIAN_POINT ( 'NONE', ( -20.50069624036807880, 196.1175417876341385, 103.6936179443737842 ) ) ; -#15575 = CARTESIAN_POINT ( 'NONE', ( 30.94196180770107674, 128.9721955471032402, 89.40981035832403734 ) ) ; -#15576 = CARTESIAN_POINT ( 'NONE', ( -12.63986498321543372, 135.0215617510153834, 90.97542152242847635 ) ) ; -#15577 = ORIENTED_EDGE ( 'NONE', *, *, #8766, .T. ) ; -#15578 = CARTESIAN_POINT ( 'NONE', ( 16.57480312883150120, 122.4809640191215152, 174.7222864645349887 ) ) ; -#15579 = EDGE_CURVE ( 'NONE', #29855, #37711, #37189, .T. ) ; -#15580 = EDGE_LOOP ( 'NONE', ( #17172, #19422, #11930, #2093 ) ) ; -#15581 = LINE ( 'NONE', #18632, #25976 ) ; -#15582 = CARTESIAN_POINT ( 'NONE', ( 44.86764334808821530, 186.7951585210016390, 105.8297977827117506 ) ) ; -#15583 = VERTEX_POINT ( 'NONE', #18960 ) ; -#15584 = CONICAL_SURFACE ( 'NONE', #18832, 55.00273826250365516, 0.7853981633972993981 ) ; -#15585 = ADVANCED_FACE ( 'NONE', ( #21251 ), #7832, .F. ) ; -#15586 = DIRECTION ( 'NONE', ( 0.0002393071041605206672, 0.2255699564796173062, -0.9742269435125952004 ) ) ; -#15587 = CARTESIAN_POINT ( 'NONE', ( 1.149713694548329279, 188.6824523264095603, 103.2130056182572702 ) ) ; -#15588 = CARTESIAN_POINT ( 'NONE', ( -26.00862899788921823, 205.2974736693811622, 75.67203179090084575 ) ) ; -#15589 = CARTESIAN_POINT ( 'NONE', ( -8.473620765651141085, 161.4179317431856475, 97.43745832156695030 ) ) ; -#15590 = EDGE_CURVE ( 'NONE', #4758, #33189, #14584, .T. ) ; -#15591 = CIRCLE ( 'NONE', #22786, 5.500000000093046459 ) ; -#15592 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #15105, #2826 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15593 = ORIENTED_EDGE ( 'NONE', *, *, #26137, .F. ) ; -#15594 = CARTESIAN_POINT ( 'NONE', ( 3.056793808240038324, 190.5188190123237177, 106.7271838340357561 ) ) ; -#15595 = ORIENTED_EDGE ( 'NONE', *, *, #26685, .F. ) ; -#15596 = EDGE_CURVE ( 'NONE', #24048, #17766, #1760, .T. ) ; -#15597 = PLANE ( 'NONE', #13421 ) ; -#15598 = DIRECTION ( 'NONE', ( -0.7933533416835752972, 0.5930537051408127924, 0.1373964266575312121 ) ) ; -#15599 = CARTESIAN_POINT ( 'NONE', ( -26.13120584929999879, 120.3817185810000154, 90.67887808736001887 ) ) ; -#15600 = VERTEX_POINT ( 'NONE', #3546 ) ; -#15601 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26704, #33206, #1533, #5201 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0007245802958363142723, 0.001812217952646025948 ), - .UNSPECIFIED. ) ; -#15602 = CARTESIAN_POINT ( 'NONE', ( -1.458415330486092287, 152.0517121852905973, 130.6798743963483673 ) ) ; -#15603 = CARTESIAN_POINT ( 'NONE', ( 77.77238909525101462, 192.2324461921776617, 194.3567101486201238 ) ) ; -#15604 = VERTEX_POINT ( 'NONE', #9308 ) ; -#15605 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; -#15606 = VERTEX_POINT ( 'NONE', #18680 ) ; -#15608 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; -#15607 = CARTESIAN_POINT ( 'NONE', ( 36.16444667182974371, 192.0609968746609013, 104.3828606498395573 ) ) ; -#15609 = VERTEX_POINT ( 'NONE', #40164 ) ; -#15610 = AXIS2_PLACEMENT_3D ( 'NONE', #16475, #10370, #6467 ) ; -#15611 = DIRECTION ( 'NONE', ( 0.0005884951729871207987, -0.2249510544218079611, 0.9743698870490344888 ) ) ; -#15612 = EDGE_LOOP ( 'NONE', ( #35410, #4492, #4242, #9497, #25012, #17431, #36658, #24684 ) ) ; -#15613 = CARTESIAN_POINT ( 'NONE', ( 3.078223283673000132, 209.7348231832999943, 76.19194169975999387 ) ) ; -#15614 = AXIS2_PLACEMENT_3D ( 'NONE', #16436, #28928, #10335 ) ; -#15615 = AXIS2_PLACEMENT_3D ( 'NONE', #12747, #25238, #31562 ) ; -#15616 = CARTESIAN_POINT ( 'NONE', ( 20.25014673412999855, 123.8560256903000010, 88.49168292467001606 ) ) ; -#15617 = ORIENTED_EDGE ( 'NONE', *, *, #35326, .F. ) ; -#15618 = AXIS2_PLACEMENT_3D ( 'NONE', #14774, #30712, #14968 ) ; -#15619 = ORIENTED_EDGE ( 'NONE', *, *, #10280, .T. ) ; -#15620 = DIRECTION ( 'NONE', ( 0.0006039748319395907457, 1.314021223879979801E-14, 0.9999998176071847045 ) ) ; -#15621 = CARTESIAN_POINT ( 'NONE', ( 30.18434728222111829, 126.7045899472522308, 91.62356130930872666 ) ) ; -#15622 = CARTESIAN_POINT ( 'NONE', ( 13.50544439768758664, 187.6165333045301509, 105.9640318452364056 ) ) ; -#15623 = CARTESIAN_POINT ( 'NONE', ( 22.81270356676756350, 135.0716824376671923, 90.82289798865961927 ) ) ; -#15624 = CARTESIAN_POINT ( 'NONE', ( 36.07403909944999754, 192.3900100081999938, 104.3752709241999952 ) ) ; -#15625 = ORIENTED_EDGE ( 'NONE', *, *, #5427, .F. ) ; -#15626 = EDGE_CURVE ( 'NONE', #35766, #9326, #5677, .T. ) ; -#15627 = EDGE_LOOP ( 'NONE', ( #17926, #26751, #21961, #35768 ) ) ; -#15628 = EDGE_CURVE ( 'NONE', #8486, #36684, #12367, .T. ) ; -#15629 = VERTEX_POINT ( 'NONE', #34224 ) ; -#15630 = CARTESIAN_POINT ( 'NONE', ( 14.55129770294257341, 129.4786662571763998, 92.61555079168689986 ) ) ; -#15631 = ADVANCED_FACE ( 'NONE', ( #3354 ), #24666, .F. ) ; -#15632 = CARTESIAN_POINT ( 'NONE', ( 20.33495833690937005, 173.9218102917841691, 102.5304087197118434 ) ) ; -#15633 = CARTESIAN_POINT ( 'NONE', ( -3.668404236601097601, 185.3449489774860979, 105.0111528754605530 ) ) ; -#15634 = EDGE_CURVE ( 'NONE', #9657, #25568, #38963, .T. ) ; -#15635 = CARTESIAN_POINT ( 'NONE', ( -3.589080272436853125, 149.3464402607426962, 130.0539584787920830 ) ) ; -#15636 = ORIENTED_EDGE ( 'NONE', *, *, #9718, .T. ) ; -#15637 = LINE ( 'NONE', #28133, #31734 ) ; -#15638 = CARTESIAN_POINT ( 'NONE', ( -40.67088416478974011, 188.1990424077830255, 107.8411755427910776 ) ) ; -#15639 = EDGE_LOOP ( 'NONE', ( #34210, #38729, #9134, #20405 ) ) ; -#15640 = EDGE_CURVE ( 'NONE', #9595, #12555, #36035, .T. ) ; -#15641 = DIRECTION ( 'NONE', ( 0.0005884949961218503226, -0.2249510543439091348, 0.9743698870671257950 ) ) ; -#15642 = CARTESIAN_POINT ( 'NONE', ( -35.96311564216326673, 218.5902260770998282, 61.08022271437000938 ) ) ; -#15643 = EDGE_CURVE ( 'NONE', #1723, #30329, #21990, .T. ) ; -#15644 = CARTESIAN_POINT ( 'NONE', ( -37.40113477844868584, 212.8449769292228950, 73.08109343054711360 ) ) ; -#15645 = CARTESIAN_POINT ( 'NONE', ( 28.46284161542680025, 187.5721379928345129, 102.9401731420402939 ) ) ; -#15646 = ORIENTED_EDGE ( 'NONE', *, *, #35308, .F. ) ; -#15647 = PLANE ( 'NONE', #24310 ) ; -#15648 = ORIENTED_EDGE ( 'NONE', *, *, #27017, .F. ) ; -#15649 = CARTESIAN_POINT ( 'NONE', ( 41.76074418039778635, 76.52721947789308388, 288.1972846910081216 ) ) ; -#15650 = DIRECTION ( 'NONE', ( 0.7933533411653073131, 0.5931840316265226676, 0.1368326740407721509 ) ) ; -#15651 = AXIS2_PLACEMENT_3D ( 'NONE', #32309, #23309, #20016 ) ; -#15652 = CARTESIAN_POINT ( 'NONE', ( 37.90468641847999720, 118.3397859469999958, 90.10467778014999851 ) ) ; -#15653 = EDGE_CURVE ( 'NONE', #35446, #8079, #19092, .T. ) ; -#15654 = EDGE_LOOP ( 'NONE', ( #1705, #10448, #7736, #20031 ) ) ; -#15655 = CYLINDRICAL_SURFACE ( 'NONE', #29149, 4.999999999999990230 ) ; -#15656 = ORIENTED_EDGE ( 'NONE', *, *, #1354, .T. ) ; -#15657 = CARTESIAN_POINT ( 'NONE', ( 45.13396388906383550, 144.4285190563504386, 288.0543464848796020 ) ) ; -#15658 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #10365, #23228 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15659 = ORIENTED_EDGE ( 'NONE', *, *, #38163, .F. ) ; -#15660 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749389406, 179.6299767372367171, 101.6260513916640633 ) ) ; -#15661 = CARTESIAN_POINT ( 'NONE', ( -32.45585619719672366, 153.0051697192221241, 291.5781464590990026 ) ) ; -#15662 = DIRECTION ( 'NONE', ( 3.331154357219597397E-10, 0.9743700558672070411, 0.2249510929720852648 ) ) ; -#15663 = CARTESIAN_POINT ( 'NONE', ( -35.74514700973497128, 114.7698281653908481, 90.28937401230335524 ) ) ; -#15664 = ORIENTED_EDGE ( 'NONE', *, *, #23080, .T. ) ; -#15665 = ORIENTED_EDGE ( 'NONE', *, *, #28130, .T. ) ; -#15667 = AXIS2_PLACEMENT_3D ( 'NONE', #10423, #25566, #19995 ) ; -#15666 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#15668 = DIRECTION ( 'NONE', ( 0.6087614883550946931, -0.7730004026499607273, -0.1785492307423602321 ) ) ; -#15669 = AXIS2_PLACEMENT_3D ( 'NONE', #21817, #6063, #15277 ) ; -#15670 = ORIENTED_EDGE ( 'NONE', *, *, #22104, .F. ) ; -#15671 = CARTESIAN_POINT ( 'NONE', ( 19.98065423330452717, 207.8023024357342194, 73.39927846491143271 ) ) ; -#15672 = AXIS2_PLACEMENT_3D ( 'NONE', #34974, #37878, #25632 ) ; -#15673 = EDGE_CURVE ( 'NONE', #27579, #37550, #7243, .T. ) ; -#15674 = DIRECTION ( 'NONE', ( 0.7066905234128858515, 0.1590644159615968445, -0.6894106292284863935 ) ) ; -#15675 = ADVANCED_FACE ( 'NONE', ( #28319 ), #25260, .T. ) ; -#15676 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19628, #32126, #1024, #13514 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999992928140459814 ), - .UNSPECIFIED. ) ; -#15677 = ORIENTED_EDGE ( 'NONE', *, *, #35868, .F. ) ; -#15678 = CYLINDRICAL_SURFACE ( 'NONE', #37251, 2.000000000000011546 ) ; -#15679 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 92.27946979429643193, 322.5967026918627312 ) ) ; -#15680 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#15681 = ORIENTED_EDGE ( 'NONE', *, *, #10532, .F. ) ; -#15682 = CARTESIAN_POINT ( 'NONE', ( 28.21200539798000051, 125.5548472498000052, 89.13590720598000416 ) ) ; -#15683 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36124, #24083, #29602, #7711 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15684 = CARTESIAN_POINT ( 'NONE', ( -18.11101809600965140, 126.4107873866457368, 175.0113113579019739 ) ) ; -#15685 = CARTESIAN_POINT ( 'NONE', ( 17.27264158547648165, 121.9609240029174941, 174.6061468887760668 ) ) ; -#15686 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #40445, #24945, #16502, #1174 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.391724131716651547, 1.570796326794897446 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973295471489360686, 0.9973295471489360686, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#15687 = CARTESIAN_POINT ( 'NONE', ( -19.99994197501026250, 125.2902815941508408, 88.59048179173321103 ) ) ; -#15688 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319412346130 ) ) ; -#15689 = ORIENTED_EDGE ( 'NONE', *, *, #14530, .F. ) ; -#15690 = CARTESIAN_POINT ( 'NONE', ( -28.46004690425293404, 130.8179028617305732, 90.04286148709125825 ) ) ; -#15691 = FACE_OUTER_BOUND ( 'NONE', #30538, .T. ) ; -#15692 = CARTESIAN_POINT ( 'NONE', ( 36.75303272014377143, 191.6324003026956859, 104.3442794745380127 ) ) ; -#15693 = FACE_OUTER_BOUND ( 'NONE', #35427, .T. ) ; -#15694 = VERTEX_POINT ( 'NONE', #16026 ) ; -#15695 = CARTESIAN_POINT ( 'NONE', ( 38.56339867466881799, 119.0882710927012482, 90.25372335301064197 ) ) ; -#15696 = CARTESIAN_POINT ( 'NONE', ( 12.31576967456374838, 135.2953866561074676, 91.39403622019926843 ) ) ; -#15697 = CARTESIAN_POINT ( 'NONE', ( -19.44522556511200406, 148.1576261194917947, 181.5778736950635732 ) ) ; -#15698 = EDGE_CURVE ( 'NONE', #18185, #8486, #25463, .T. ) ; -#15699 = AXIS2_PLACEMENT_3D ( 'NONE', #25808, #15769, #10268 ) ; -#15700 = CARTESIAN_POINT ( 'NONE', ( -25.50061241622579544, 190.9799426753714613, 106.3218592287567077 ) ) ; -#15701 = EDGE_LOOP ( 'NONE', ( #31493, #21833, #17170, #2337 ) ) ; -#15702 = VECTOR ( 'NONE', #29754, 1000.000000000000114 ) ; -#15703 = FACE_OUTER_BOUND ( 'NONE', #59, .T. ) ; -#15704 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15435, #2363, #15621, #40352 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 5.340901054339369348E-08, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15705 = CIRCLE ( 'NONE', #39223, 2.000000001784958847 ) ; -#15706 = CARTESIAN_POINT ( 'NONE', ( -12.63886188339458094, 181.8545105071091257, 101.8741920870010347 ) ) ; -#15707 = DIRECTION ( 'NONE', ( 0.0004161288024487149904, -0.8480480898035930304, 0.5299191110134608973 ) ) ; -#15708 = ORIENTED_EDGE ( 'NONE', *, *, #20637, .F. ) ; -#15709 = LINE ( 'NONE', #12063, #34808 ) ; -#15710 = DIRECTION ( 'NONE', ( 0.0005884948869652768940, -0.2249510543002911367, 0.9743698870772616871 ) ) ; -#15711 = CARTESIAN_POINT ( 'NONE', ( 20.20768266840917704, 127.3886079643583571, 89.26371417184604695 ) ) ; -#15712 = CARTESIAN_POINT ( 'NONE', ( 36.36654477671010000, 191.7216060454559852, 106.4021762953440060 ) ) ; -#15713 = CARTESIAN_POINT ( 'NONE', ( 36.50285708549999697, 190.9865300476000129, 106.6685476356000066 ) ) ; -#15714 = EDGE_LOOP ( 'NONE', ( #35980, #19627, #14828, #35128 ) ) ; -#15715 = VERTEX_POINT ( 'NONE', #18283 ) ; -#15716 = ORIENTED_EDGE ( 'NONE', *, *, #34366, .T. ) ; -#15717 = CARTESIAN_POINT ( 'NONE', ( -3.841346491554074039, 136.1850729056500313, 91.09604285724341821 ) ) ; -#15718 = PLANE ( 'NONE', #38577 ) ; -#15719 = DIRECTION ( 'NONE', ( 0.0005884949961229807118, -0.2249510543439059429, 0.9743698870671263501 ) ) ; -#15720 = CARTESIAN_POINT ( 'NONE', ( 62.08695490598599775, 78.64495961329345164, 282.5210433287024898 ) ) ; -#15721 = EDGE_CURVE ( 'NONE', #5067, #25046, #26583, .T. ) ; -#15722 = EDGE_CURVE ( 'NONE', #10701, #29247, #18480, .T. ) ; -#15723 = EDGE_LOOP ( 'NONE', ( #5396, #24257, #34181, #20682 ) ) ; -#15724 = CARTESIAN_POINT ( 'NONE', ( -26.00148896606084037, 118.3501043404999962, 87.28357517440494462 ) ) ; -#15725 = VECTOR ( 'NONE', #7352, 1000.000000000000114 ) ; -#15726 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749387985, 132.8602140592423382, 90.82839891339965277 ) ) ; -#15727 = DIRECTION ( 'NONE', ( 7.930164461882003851E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; -#15728 = CARTESIAN_POINT ( 'NONE', ( -3.668404236352207359, 128.0226348367964988, 91.77725148510558029 ) ) ; -#15729 = VERTEX_POINT ( 'NONE', #27935 ) ; -#15730 = CARTESIAN_POINT ( 'NONE', ( -12.63780403360421545, 175.2412555344319856, 100.6313397257130617 ) ) ; -#15731 = DIRECTION ( 'NONE', ( -0.0005884949961263758909, 0.2249510543439055821, -0.9743698870671265722 ) ) ; -#15732 = ADVANCED_FACE ( 'NONE', ( #38695 ), #13377, .F. ) ; -#15733 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#15734 = CARTESIAN_POINT ( 'NONE', ( -15.83323561231152965, 184.9252659090778081, 102.5268986338905250 ) ) ; -#15735 = ORIENTED_EDGE ( 'NONE', *, *, #3561, .T. ) ; -#15736 = CARTESIAN_POINT ( 'NONE', ( 12.64071154648716799, 176.8676401789000749, 103.2142495390799866 ) ) ; -#15737 = CARTESIAN_POINT ( 'NONE', ( 2.549741881329860238, 190.9970219424760103, 104.2732579596220006 ) ) ; -#15738 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#15739 = ORIENTED_EDGE ( 'NONE', *, *, #20794, .T. ) ; -#15740 = ORIENTED_EDGE ( 'NONE', *, *, #25079, .F. ) ; -#15741 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930882562 ) ) ; -#15742 = ORIENTED_EDGE ( 'NONE', *, *, #18995, .T. ) ; -#15743 = CARTESIAN_POINT ( 'NONE', ( -40.78982053831894916, 220.4002260996649056, 73.41647350591635757 ) ) ; -#15744 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749096068, 179.1800746284886259, 103.5747911658217078 ) ) ; -#15745 = CARTESIAN_POINT ( 'NONE', ( 22.78191781013921968, 158.2317512751428126, 98.73560149028561739 ) ) ; -#15746 = CIRCLE ( 'NONE', #12481, 5.499999999997804423 ) ; -#15747 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2534, #12146, #39724, #24426 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.001265839647099397444 ), - .UNSPECIFIED. ) ; -#15748 = CARTESIAN_POINT ( 'NONE', ( 44.90072207509915359, 127.0650837324493523, 92.04000096660296037 ) ) ; -#15749 = VECTOR ( 'NONE', #6627, 1000.000000000000114 ) ; -#15750 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#15751 = CIRCLE ( 'NONE', #21649, 22.00000000001092815 ) ; -#15752 = DIRECTION ( 'NONE', ( 0.0005884949961232824453, -0.2249510543439075805, 0.9743698870671260170 ) ) ; -#15753 = CARTESIAN_POINT ( 'NONE', ( 44.05265128906093963, 113.3760414474945009, 85.80123528811637357 ) ) ; -#15754 = ORIENTED_EDGE ( 'NONE', *, *, #17414, .F. ) ; -#15755 = EDGE_CURVE ( 'NONE', #35358, #23147, #27274, .T. ) ; -#15756 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#15757 = CARTESIAN_POINT ( 'NONE', ( 25.50011543809205250, 118.8155664120999973, 94.25238413803072035 ) ) ; -#15758 = ORIENTED_EDGE ( 'NONE', *, *, #3750, .F. ) ; -#15759 = EDGE_LOOP ( 'NONE', ( #12697, #1, #17060, #38420 ) ) ; -#15760 = ADVANCED_FACE ( 'NONE', ( #3952 ), #23182, .F. ) ; -#15761 = ORIENTED_EDGE ( 'NONE', *, *, #7124, .F. ) ; -#15762 = CARTESIAN_POINT ( 'NONE', ( -20.33307505328456699, 118.8155084438010931, 87.61342193665612399 ) ) ; -#15763 = ADVANCED_FACE ( 'NONE', ( #886 ), #34814, .T. ) ; -#15764 = EDGE_CURVE ( 'NONE', #20447, #21013, #25273, .T. ) ; -#15765 = ORIENTED_EDGE ( 'NONE', *, *, #24427, .T. ) ; -#15766 = ADVANCED_FACE ( 'NONE', ( #1288 ), #31806, .F. ) ; -#15767 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971545696 ) ) ; -#15768 = CARTESIAN_POINT ( 'NONE', ( 38.86900528589750081, 119.2001525857115922, 87.69880077671245999 ) ) ; -#15769 = DIRECTION ( 'NONE', ( 0.0005884949961217107858, -0.2249510543439044441, 0.9743698870671267942 ) ) ; -#15770 = CARTESIAN_POINT ( 'NONE', ( 12.63580143090830887, 130.5208300941526147, 90.20832784594151121 ) ) ; -#15771 = LINE ( 'NONE', #34374, #39981 ) ; -#15772 = VERTEX_POINT ( 'NONE', #16425 ) ; -#15773 = VERTEX_POINT ( 'NONE', #22790 ) ; -#15774 = FACE_OUTER_BOUND ( 'NONE', #1889, .T. ) ; -#15775 = CIRCLE ( 'NONE', #27563, 2.249999999963659292 ) ; -#15776 = CARTESIAN_POINT ( 'NONE', ( 31.91041242450083004, 174.4868366864082532, 100.4302623719975571 ) ) ; -#15777 = CARTESIAN_POINT ( 'NONE', ( 15.95613733389899025, 121.8961617987971238, 174.4891947115541484 ) ) ; -#15778 = CONICAL_SURFACE ( 'NONE', #11212, 3.000000000033072212, 0.7853981634062642270 ) ; -#15779 = EDGE_LOOP ( 'NONE', ( #38437, #2382, #29744, #6367 ) ) ; -#15780 = FACE_OUTER_BOUND ( 'NONE', #32646, .T. ) ; -#15781 = AXIS2_PLACEMENT_3D ( 'NONE', #32261, #13845, #16700 ) ; -#15782 = CARTESIAN_POINT ( 'NONE', ( 2.621083284465321572, 189.6939337031247135, 103.4456358662860112 ) ) ; -#15783 = CARTESIAN_POINT ( 'NONE', ( -26.00146729410618107, 120.3902237924994836, 87.46289810595230563 ) ) ; -#15784 = VERTEX_POINT ( 'NONE', #19495 ) ; -#15785 = CARTESIAN_POINT ( 'NONE', ( -15.10713178427481651, 176.3794795624077096, 100.3824614381103828 ) ) ; -#15786 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251387457, 179.1753088543557624, 103.5954339978685965 ) ) ; -#15787 = ORIENTED_EDGE ( 'NONE', *, *, #6435, .T. ) ; -#15788 = ADVANCED_FACE ( 'NONE', ( #26457 ), #3754, .T. ) ; -#15789 = CARTESIAN_POINT ( 'NONE', ( -35.95668941153999754, 206.4002260771000010, 73.08022102180001411 ) ) ; -#15790 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36523, #24277, #34240, #36720 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15791 = CARTESIAN_POINT ( 'NONE', ( -35.95496198192999771, 218.5902260770999987, 74.58022025207000638 ) ) ; -#15792 = CARTESIAN_POINT ( 'NONE', ( 14.54953207236175139, 130.1535194663153447, 89.69244121379192336 ) ) ; -#15793 = ORIENTED_EDGE ( 'NONE', *, *, #23868, .T. ) ; -#15794 = CARTESIAN_POINT ( 'NONE', ( 2.444755512867411440, 189.2322982050264670, 106.4180782769317659 ) ) ; -#15795 = CARTESIAN_POINT ( 'NONE', ( -13.46754865746872376, 158.0276785376866826, 98.88143215986140433 ) ) ; -#15796 = CYLINDRICAL_SURFACE ( 'NONE', #14353, 4.999999999999990230 ) ; -#15797 = ORIENTED_EDGE ( 'NONE', *, *, #12578, .F. ) ; -#15798 = EDGE_CURVE ( 'NONE', #8915, #36967, #16774, .T. ) ; -#15799 = CARTESIAN_POINT ( 'NONE', ( 17.97063383950253623, 126.0060190202803625, 174.3181455802166795 ) ) ; -#15800 = CARTESIAN_POINT ( 'NONE', ( 41.44446280484381617, 121.0638739319363140, 90.65659975668269510 ) ) ; -#15801 = CIRCLE ( 'NONE', #30828, 2.000000000000011546 ) ; -#15803 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319411731388 ) ) ; -#15802 = CARTESIAN_POINT ( 'NONE', ( 36.40558664052492333, 191.8188463803718093, 104.3612499972096117 ) ) ; -#15804 = ORIENTED_EDGE ( 'NONE', *, *, #19025, .T. ) ; -#15805 = CIRCLE ( 'NONE', #30188, 2.499999999978018028 ) ; -#15806 = EDGE_CURVE ( 'NONE', #17411, #14103, #5042, .T. ) ; -#15807 = CARTESIAN_POINT ( 'NONE', ( 25.49092517336361041, 207.5918372323820904, 74.04845020794621746 ) ) ; -#15808 = AXIS2_PLACEMENT_3D ( 'NONE', #23167, #29912, #2106 ) ; -#15809 = EDGE_LOOP ( 'NONE', ( #24135, #29763, #27278, #25895 ) ) ; -#15810 = CARTESIAN_POINT ( 'NONE', ( 3.785823397764000564, 140.1660989325999935, 94.83286549423999645 ) ) ; -#15811 = EDGE_CURVE ( 'NONE', #18436, #34191, #27295, .T. ) ; -#15812 = CARTESIAN_POINT ( 'NONE', ( -22.49823186950551346, 173.8370468426015805, 102.8821234254057089 ) ) ; -#15813 = CARTESIAN_POINT ( 'NONE', ( 39.69446386203616584, 161.8153251821185563, 196.1471770628630793 ) ) ; -#15814 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; -#15815 = EDGE_LOOP ( 'NONE', ( #39036, #39967, #25381, #20199 ) ) ; -#15816 = EDGE_CURVE ( 'NONE', #37208, #21067, #2840, .T. ) ; -#15817 = VERTEX_POINT ( 'NONE', #22987 ) ; -#15818 = EDGE_CURVE ( 'NONE', #24578, #37440, #37054, .T. ) ; -#15819 = CARTESIAN_POINT ( 'NONE', ( 13.53487526333000091, 140.5899962463843167, 152.9217693939943388 ) ) ; -#15820 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 77.27946979429643193, 322.5967026918629017 ) ) ; -#15821 = CARTESIAN_POINT ( 'NONE', ( 23.08601424118414513, 134.9925771438349784, 90.80447001643439364 ) ) ; -#15822 = ORIENTED_EDGE ( 'NONE', *, *, #19408, .F. ) ; -#15823 = ORIENTED_EDGE ( 'NONE', *, *, #1302, .F. ) ; -#15824 = VERTEX_POINT ( 'NONE', #39107 ) ; -#15825 = CARTESIAN_POINT ( 'NONE', ( 34.29411924272742596, 218.5902260770999987, 73.03779129371588397 ) ) ; -#15826 = CARTESIAN_POINT ( 'NONE', ( 20.08486655242547414, 128.0648441155641990, 89.20688914988019746 ) ) ; -#15827 = CARTESIAN_POINT ( 'NONE', ( -28.35189984747000125, 125.4776471425000040, 88.98101198637000664 ) ) ; -#15828 = ORIENTED_EDGE ( 'NONE', *, *, #22113, .T. ) ; -#15829 = CARTESIAN_POINT ( 'NONE', ( 20.50039165879256942, 118.8156470718432729, 87.75541749211321019 ) ) ; -#15830 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#15831 = ORIENTED_EDGE ( 'NONE', *, *, #1026, .F. ) ; -#15832 = VECTOR ( 'NONE', #4133, 1000.000000000000114 ) ; -#15833 = CARTESIAN_POINT ( 'NONE', ( -36.99951977468094100, 116.5506918669546792, 89.73453862280433668 ) ) ; -#15834 = FACE_OUTER_BOUND ( 'NONE', #12546, .T. ) ; -#15835 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#15836 = VECTOR ( 'NONE', #35191, 1000.000000000000000 ) ; -#15837 = CARTESIAN_POINT ( 'NONE', ( 38.97204648811698036, 118.8228816124465368, 89.67376701884533929 ) ) ; -#15838 = CARTESIAN_POINT ( 'NONE', ( -3.169906973602109712, 126.7999172216492099, 88.92891361563410157 ) ) ; -#15839 = ORIENTED_EDGE ( 'NONE', *, *, #39532, .F. ) ; -#15840 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 1.376043959293782775E-15, -0.0006039748319377434820 ) ) ; -#15841 = VERTEX_POINT ( 'NONE', #32968 ) ; -#15842 = CARTESIAN_POINT ( 'NONE', ( 34.09746542872949249, 82.01624178880980764, 290.5639394685908314 ) ) ; -#15843 = CARTESIAN_POINT ( 'NONE', ( -38.01656497497999965, 118.6347820250999945, 87.61306182308000245 ) ) ; -#15844 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #2993, #15475, #40403, #18923 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.701183077854123038, 1.701264852836251729 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999994427375416, 0.9999999994427375416, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#15845 = CARTESIAN_POINT ( 'NONE', ( 29.05352371370200615, 110.6131156702000027, 87.25023669171606855 ) ) ; -#15846 = VERTEX_POINT ( 'NONE', #2322 ) ; -#15847 = FACE_OUTER_BOUND ( 'NONE', #29961, .T. ) ; -#15848 = ADVANCED_FACE ( 'NONE', ( #33579 ), #11722, .T. ) ; -#15849 = VERTEX_POINT ( 'NONE', #8033 ) ; -#15850 = EDGE_CURVE ( 'NONE', #21171, #35987, #11116, .T. ) ; -#15852 = EDGE_CURVE ( 'NONE', #39810, #36343, #39710, .T. ) ; -#15851 = CARTESIAN_POINT ( 'NONE', ( 25.18497250179792601, 116.8542503881588175, 89.75272387405183849 ) ) ; -#15853 = CARTESIAN_POINT ( 'NONE', ( 35.80546160733999983, 201.9934155195000187, 90.45676456543999677 ) ) ; -#15854 = EDGE_CURVE ( 'NONE', #25751, #2067, #10924, .T. ) ; -#15855 = EDGE_LOOP ( 'NONE', ( #22771, #16854, #34072, #13338 ) ) ; -#15856 = CARTESIAN_POINT ( 'NONE', ( -12.63810009328765815, 175.3544237672228121, 100.1411543447596983 ) ) ; -#15857 = CARTESIAN_POINT ( 'NONE', ( 28.70699186922535873, 163.1576631238072821, 99.86925946332931403 ) ) ; -#15858 = DIRECTION ( 'NONE', ( -5.551115123437337795E-15, 0.9743700557921585181, 0.2249510932971564292 ) ) ; -#15859 = CARTESIAN_POINT ( 'NONE', ( -39.70379676582250283, 165.1621345740199160, 181.9116255470079579 ) ) ; -#15860 = CARTESIAN_POINT ( 'NONE', ( -20.45296611704877776, 159.3209472110458762, 96.44741428446211273 ) ) ; -#15861 = AXIS2_PLACEMENT_3D ( 'NONE', #31177, #15620, #24455 ) ; -#15862 = CARTESIAN_POINT ( 'NONE', ( -12.59983791313500667, 115.9590670279657445, 152.9217693160060776 ) ) ; -#15863 = ORIENTED_EDGE ( 'NONE', *, *, #4734, .F. ) ; -#15864 = CARTESIAN_POINT ( 'NONE', ( -35.69245307692643365, 114.5537190934489189, 90.28934218648832655 ) ) ; -#15865 = ORIENTED_EDGE ( 'NONE', *, *, #7499, .F. ) ; -#15866 = ORIENTED_EDGE ( 'NONE', *, *, #37885, .F. ) ; -#15867 = EDGE_CURVE ( 'NONE', #9058, #35255, #14992, .T. ) ; -#15868 = CARTESIAN_POINT ( 'NONE', ( 30.09291612729013110, 103.6131156702000027, 152.4718672073996117 ) ) ; -#15869 = CARTESIAN_POINT ( 'NONE', ( 15.99970520780110483, 160.7332544674666508, 96.75156078672274873 ) ) ; -#15870 = ORIENTED_EDGE ( 'NONE', *, *, #25447, .F. ) ; -#15871 = CARTESIAN_POINT ( 'NONE', ( -14.89118547255141500, 175.5309352547254775, 102.9232378619308861 ) ) ; -#15872 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#15873 = ORIENTED_EDGE ( 'NONE', *, *, #13790, .F. ) ; -#15874 = CARTESIAN_POINT ( 'NONE', ( 23.31716640680999930, 201.2278123622999999, 28.07991271570000080 ) ) ; -#15875 = EDGE_CURVE ( 'NONE', #30846, #734, #11515, .T. ) ; -#15876 = CARTESIAN_POINT ( 'NONE', ( 77.76885812527426367, 193.5821525182410880, 188.5104908262173637 ) ) ; -#15877 = VERTEX_POINT ( 'NONE', #17428 ) ; -#15878 = CARTESIAN_POINT ( 'NONE', ( 28.11271033718000112, 125.4906462842000110, 89.12114495753000654 ) ) ; -#15879 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 164.9087802455859162, 182.8989377884010139 ) ) ; -#15880 = CARTESIAN_POINT ( 'NONE', ( 15.83512664620924326, 151.3287663793590809, 97.48834744810477559 ) ) ; -#15881 = CARTESIAN_POINT ( 'NONE', ( 30.07127365770511318, 176.8230753548089638, 103.1292432202702969 ) ) ; -#15882 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; -#15883 = EDGE_LOOP ( 'NONE', ( #28056, #22562, #6974, #3711 ) ) ; -#15884 = CARTESIAN_POINT ( 'NONE', ( 16.56026951762423494, 122.5141854615031178, 174.6306262266012084 ) ) ; -#15885 = LINE ( 'NONE', #28378, #29060 ) ; -#15886 = AXIS2_PLACEMENT_3D ( 'NONE', #8738, #9894, #22366 ) ; -#15887 = CARTESIAN_POINT ( 'NONE', ( 36.42433494591709575, 191.8057322581022390, 104.3592985921623750 ) ) ; -#15888 = CARTESIAN_POINT ( 'NONE', ( 12.63777575465211456, 130.2256679117907368, 92.62110684792574489 ) ) ; -#15889 = EDGE_LOOP ( 'NONE', ( #31986, #36304, #3330, #6353, #30883 ) ) ; -#15890 = VECTOR ( 'NONE', #37654, 1000.000000000000000 ) ; -#15891 = CARTESIAN_POINT ( 'NONE', ( 39.53379105069361543, 120.3902222971681368, 87.42331650858173475 ) ) ; -#15892 = CARTESIAN_POINT ( 'NONE', ( 19.32342759816472011, 148.9592218696507189, 180.9802330199531184 ) ) ; -#15893 = CARTESIAN_POINT ( 'NONE', ( -3.334876874488374998, 183.4854709603033598, 104.9237563252875844 ) ) ; -#15894 = AXIS2_PLACEMENT_3D ( 'NONE', #9660, #24817, #31536 ) ; -#15895 = CARTESIAN_POINT ( 'NONE', ( 43.53560975226982777, 121.3918131887250524, 90.46069063649885322 ) ) ; -#15896 = CARTESIAN_POINT ( 'NONE', ( -25.67411157019000001, 190.9010507822000022, 106.4782221023999966 ) ) ; -#15897 = ORIENTED_EDGE ( 'NONE', *, *, #3514, .F. ) ; -#15898 = EDGE_CURVE ( 'NONE', #10734, #32124, #1381, .T. ) ; -#15899 = ADVANCED_FACE ( 'NONE', ( #20921 ), #18087, .F. ) ; -#15900 = EDGE_CURVE ( 'NONE', #40361, #25177, #33125, .T. ) ; -#15901 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2233, #23293, #36569, #20620 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15902 = CARTESIAN_POINT ( 'NONE', ( -12.63924462906329005, 181.8109532889671698, 101.8044862477469081 ) ) ; -#15903 = CARTESIAN_POINT ( 'NONE', ( 0.06400980323497000579, 188.6937622364000049, 105.9808922080000002 ) ) ; -#15904 = CARTESIAN_POINT ( 'NONE', ( -2.770634212112902617, 196.4250215355508828, 103.8116555233700353 ) ) ; -#15905 = CARTESIAN_POINT ( 'NONE', ( -25.99372727560586682, 191.7362033397953383, 103.9228720321462447 ) ) ; -#15906 = EDGE_CURVE ( 'NONE', #8808, #19860, #28741, .T. ) ; -#15907 = DIRECTION ( 'NONE', ( -0.0005734119072288677843, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#15908 = CARTESIAN_POINT ( 'NONE', ( 36.36531231111000295, 191.8368571526999915, 104.3615859421999943 ) ) ; -#15909 = CARTESIAN_POINT ( 'NONE', ( 36.51615922305000339, 190.9752249994000124, 106.6662851373999956 ) ) ; -#15910 = VERTEX_POINT ( 'NONE', #21122 ) ; -#15911 = EDGE_CURVE ( 'NONE', #5671, #23621, #23384, .T. ) ; -#15912 = CARTESIAN_POINT ( 'NONE', ( -3.538821847849364488, 137.0364201774141577, 91.29240918044028774 ) ) ; -#15913 = VECTOR ( 'NONE', #2585, 999.9999999999998863 ) ; -#15914 = CARTESIAN_POINT ( 'NONE', ( -20.05040618438584943, 184.9463469738533661, 102.4150248276820179 ) ) ; -#15915 = VECTOR ( 'NONE', #38581, 1000.000000000000114 ) ; -#15916 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971556521 ) ) ; -#15917 = EDGE_LOOP ( 'NONE', ( #27061, #30121, #31333, #20648, #12703, #20192, #15975, #21193, #10001, #32225, #20736, #22613 ) ) ; -#15918 = CARTESIAN_POINT ( 'NONE', ( -14.78424370841450042, 128.6742020487672278, 91.93439134535178425 ) ) ; -#15919 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #13494, #30037, #25980, #16931 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 2.906772358712197857, 4.712388980384624837 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7462717963450520298, 0.7462717963450520298, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#15920 = CIRCLE ( 'NONE', #23763, 1.999999998088923370 ) ; -#15921 = ORIENTED_EDGE ( 'NONE', *, *, #39700, .F. ) ; -#15922 = DIRECTION ( 'NONE', ( 0.0005884949961247345172, -0.2249510543439062205, 0.9743698870671264611 ) ) ; -#15923 = CARTESIAN_POINT ( 'NONE', ( -3.169881662145332513, 128.5839160399947332, 89.34077473205128683 ) ) ; -#15924 = EDGE_LOOP ( 'NONE', ( #20190, #9314, #827, #1858 ) ) ; -#15925 = CARTESIAN_POINT ( 'NONE', ( 32.37225756566472512, 173.7344409119733086, 102.8220398834807980 ) ) ; -#15926 = CARTESIAN_POINT ( 'NONE', ( 23.38532237667366331, 214.0898681195277788, 76.04433488945258546 ) ) ; -#15927 = CARTESIAN_POINT ( 'NONE', ( 38.22623376675434059, 118.8155667128057615, 90.24469678293085906 ) ) ; -#15928 = CARTESIAN_POINT ( 'NONE', ( 13.50130427968899305, 124.2930898811154918, 90.90584795535438900 ) ) ; -#15929 = ORIENTED_EDGE ( 'NONE', *, *, #4359, .F. ) ; -#15930 = PLANE ( 'NONE', #14805 ) ; -#15931 = CARTESIAN_POINT ( 'NONE', ( 2.552808849906440081, 190.8272003400429924, 104.2221943813569851 ) ) ; -#15932 = LINE ( 'NONE', #15548, #7090 ) ; -#15933 = ORIENTED_EDGE ( 'NONE', *, *, #2308, .F. ) ; -#15934 = CYLINDRICAL_SURFACE ( 'NONE', #16575, 2.500000000000003997 ) ; -#15935 = VERTEX_POINT ( 'NONE', #33168 ) ; -#15936 = AXIS2_PLACEMENT_3D ( 'NONE', #39430, #26189, #10845 ) ; -#15937 = CARTESIAN_POINT ( 'NONE', ( 22.11776639833565028, 135.5859592220768945, 93.50780862338704935 ) ) ; -#15938 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10226, #35115, #993, #13486, #35324, #32489, #14289, #26975, #17122, #27186 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999997623568, 0.3749999999996778133, 0.4374999999997005729, 0.4999999999997233324, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#15939 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118071, 102.4385832782338071, 173.5892250900641045 ) ) ; -#15940 = AXIS2_PLACEMENT_3D ( 'NONE', #32300, #23100, #26776 ) ; -#15941 = AXIS2_PLACEMENT_3D ( 'NONE', #4009, #31439, #16086 ) ; -#15942 = LINE ( 'NONE', #6345, #1887 ) ; -#15943 = ADVANCED_FACE ( 'NONE', ( #26867 ), #23339, .T. ) ; -#15944 = CARTESIAN_POINT ( 'NONE', ( -14.31750948537055201, 182.2834106990709984, 101.7450119985854826 ) ) ; -#15945 = CIRCLE ( 'NONE', #19845, 1.749999999975493381 ) ; -#15946 = ADVANCED_FACE ( 'NONE', ( #17632 ), #32781, .F. ) ; -#15947 = CARTESIAN_POINT ( 'NONE', ( 1.226479719036516425, 136.3602109141136793, 175.2633797041700063 ) ) ; -#15948 = DIRECTION ( 'NONE', ( 0.6087614810001747978, -0.7729390313185978689, -0.1788147452385885350 ) ) ; -#15949 = LINE ( 'NONE', #19617, #364 ) ; -#15950 = CARTESIAN_POINT ( 'NONE', ( -36.34630485966000890, 190.6271491411999932, 106.9111579357000039 ) ) ; -#15951 = ORIENTED_EDGE ( 'NONE', *, *, #8780, .F. ) ; -#15952 = LINE ( 'NONE', #37242, #34190 ) ; -#15953 = CARTESIAN_POINT ( 'NONE', ( 19.71701219870257304, 124.6133069866743455, 177.2811646003819135 ) ) ; -#15954 = FACE_OUTER_BOUND ( 'NONE', #8215, .T. ) ; -#15955 = EDGE_CURVE ( 'NONE', #25569, #11781, #30122, .T. ) ; -#15956 = FACE_OUTER_BOUND ( 'NONE', #7751, .T. ) ; -#15957 = EDGE_LOOP ( 'NONE', ( #38083, #9398, #35849, #8714, #8407, #11847, #18069, #21225, #14474, #16371, #18455 ) ) ; -#15958 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #28827, #3863, #19195, #1206 ), - ( #3661, #34925, #16739, #10233 ), - ( #601, #13684, #38017, #29023 ), - ( #6733, #32104, #13291, #28628 ), - ( #1002, #406, #12896, #22704 ), - ( #38419, #25370, #16342, #35123 ), - ( #22301, #7137, #10430, #34730 ), - ( #37820, #4058, #10632, #16530 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.06155209981437000100, 0.000000000000000000, 0.3333252697642999918, 0.6666627199550000382, 1.000000000000000000, 1.082818155623000100 ), - ( 3.677872018049000041E-08, 1.000452713559000006 ), - .UNSPECIFIED. ) ; -#15959 = EDGE_LOOP ( 'NONE', ( #25478, #26213, #27659, #5967 ) ) ; -#15960 = CARTESIAN_POINT ( 'NONE', ( -43.95866919468323886, 185.6592565981171390, 107.3047072462908460 ) ) ; -#15961 = CARTESIAN_POINT ( 'NONE', ( 22.25124494035251388, 115.1832291781610564, 87.25434509765634061 ) ) ; -#15962 = CARTESIAN_POINT ( 'NONE', ( -6.037441369385219581, 175.2421293076922382, 100.6275549983384394 ) ) ; -#15963 = CARTESIAN_POINT ( 'NONE', ( -33.70586835455132046, 218.5902260770999987, 73.07886158226766327 ) ) ; -#15964 = ORIENTED_EDGE ( 'NONE', *, *, #19855, .T. ) ; -#15966 = EDGE_LOOP ( 'NONE', ( #952, #11342, #32459, #30495, #24437, #27927, #35004 ) ) ; -#15965 = CC_DESIGN_APPROVAL ( #25220, ( #26440 ) ) ; -#15967 = AXIS2_PLACEMENT_3D ( 'NONE', #36323, #20994, #4628 ) ; -#15968 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 77.27946979429631824, 312.5857197240631535 ) ) ; -#15969 = EDGE_CURVE ( 'NONE', #16187, #25826, #36453, .T. ) ; -#15970 = CARTESIAN_POINT ( 'NONE', ( 12.31470871943427348, 134.6455694126359219, 93.46769794297644296 ) ) ; -#15971 = CARTESIAN_POINT ( 'NONE', ( 0.04593741417267090121, 271.9029643395999187, 76.05847688452558941 ) ) ; -#15972 = LINE ( 'NONE', #3698, #33325 ) ; -#15973 = AXIS2_PLACEMENT_3D ( 'NONE', #30395, #24685, #20782 ) ; -#15974 = DIRECTION ( 'NONE', ( -0.0005884956407902205500, 0.2249510534665960237, -0.9743698872692800883 ) ) ; -#15975 = ORIENTED_EDGE ( 'NONE', *, *, #38563, .T. ) ; -#15976 = DIRECTION ( 'NONE', ( 3.885780586188055465E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#15977 = EDGE_LOOP ( 'NONE', ( #3581, #29864 ) ) ; -#15978 = ORIENTED_EDGE ( 'NONE', *, *, #33775, .T. ) ; -#15979 = CARTESIAN_POINT ( 'NONE', ( -23.65441916643283804, 115.6781806121213236, 89.78203721638622881 ) ) ; -#15980 = CONICAL_SURFACE ( 'NONE', #1620, 2.503080714863939793, 0.7853981633931875761 ) ; -#15981 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#15982 = DIRECTION ( 'NONE', ( 0.7933533411653069800, 0.5931840316265230006, 0.1368326740407719011 ) ) ; -#15983 = EDGE_LOOP ( 'NONE', ( #23220, #25773, #31233, #29651, #5421 ) ) ; -#15984 = CARTESIAN_POINT ( 'NONE', ( -2.941972109285600379, 190.8911159914279949, 103.7220337298560082 ) ) ; -#15985 = CARTESIAN_POINT ( 'NONE', ( 1.988498828323496115, 189.0590404400041393, 103.2994412454972633 ) ) ; -#15986 = CARTESIAN_POINT ( 'NONE', ( 38.51366257970000362, 191.2261826337999935, 104.0342813249999949 ) ) ; -#15987 = CARTESIAN_POINT ( 'NONE', ( -8.191411996002011975, 161.3204080351630978, 97.07267131671726190 ) ) ; -#15988 = ADVANCED_FACE ( 'NONE', ( #33377 ), #25303, .T. ) ; -#15989 = ORIENTED_EDGE ( 'NONE', *, *, #28293, .F. ) ; -#15990 = DIRECTION ( 'NONE', ( -4.163336342515006295E-15, 0.9743700557921587402, 0.2249510932971554300 ) ) ; -#15991 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#15992 = ORIENTED_EDGE ( 'NONE', *, *, #28452, .T. ) ; -#15993 = FACE_OUTER_BOUND ( 'NONE', #13737, .T. ) ; -#15994 = CARTESIAN_POINT ( 'NONE', ( 36.14465427956680088, 191.5051434224318712, 103.8435392573484961 ) ) ; -#15995 = CARTESIAN_POINT ( 'NONE', ( -26.13596305067000003, 119.9704139356000070, 90.58392378377000398 ) ) ; -#15996 = ORIENTED_EDGE ( 'NONE', *, *, #3839, .T. ) ; -#15997 = EDGE_CURVE ( 'NONE', #19279, #10234, #9647, .T. ) ; -#15998 = CARTESIAN_POINT ( 'NONE', ( 2.804985645282946471, 189.7674754617468409, 106.5414161346845816 ) ) ; -#15999 = ADVANCED_FACE ( 'NONE', ( #15774 ), #39922, .T. ) ; -#16000 = FACE_OUTER_BOUND ( 'NONE', #30097, .T. ) ; -#16001 = CARTESIAN_POINT ( 'NONE', ( 35.04524255441999259, 226.4002260770880355, 73.53733772517182388 ) ) ; -#16002 = AXIS2_PLACEMENT_3D ( 'NONE', #36880, #27512, #39937 ) ; -#16003 = AXIS2_PLACEMENT_3D ( 'NONE', #28192, #5695, #37570 ) ; -#16004 = ORIENTED_EDGE ( 'NONE', *, *, #29295, .T. ) ; -#16005 = CIRCLE ( 'NONE', #23286, 2.000000000000011546 ) ; -#16006 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989941907, -0.1373964268091565077 ) ) ; -#16007 = DIRECTION ( 'NONE', ( -0.0006039748319387576447, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#16008 = VECTOR ( 'NONE', #33922, 1000.000000000000000 ) ; -#16010 = FACE_OUTER_BOUND ( 'NONE', #19447, .T. ) ; -#16009 = CARTESIAN_POINT ( 'NONE', ( -20.49846059232846684, 118.8155328640159070, 89.78014971369738362 ) ) ; -#16011 = ORIENTED_EDGE ( 'NONE', *, *, #24549, .F. ) ; -#16012 = CARTESIAN_POINT ( 'NONE', ( 38.90297999749881797, 118.7655883057561965, 89.66942185881842420 ) ) ; -#16013 = VERTEX_POINT ( 'NONE', #2729 ) ; -#16014 = PLANE ( 'NONE', #29740 ) ; -#16015 = LINE ( 'NONE', #84, #15832 ) ; -#16016 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18090, #6383, #36517, #29790 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16017 = PLANE ( 'NONE', #37773 ) ; -#16018 = ORIENTED_EDGE ( 'NONE', *, *, #38660, .T. ) ; -#16019 = VERTEX_POINT ( 'NONE', #37264 ) ; -#16020 = CARTESIAN_POINT ( 'NONE', ( 22.78111302661506343, 158.5316860073367593, 97.43644165524102618 ) ) ; -#16021 = CARTESIAN_POINT ( 'NONE', ( 22.63655809249918605, 181.7690946929418487, 101.6039534401006392 ) ) ; -#16022 = CARTESIAN_POINT ( 'NONE', ( 35.56356469037133650, 192.3002554099812471, 103.8734939767707885 ) ) ; -#16023 = ORIENTED_EDGE ( 'NONE', *, *, #15590, .T. ) ; -#16024 = ORIENTED_EDGE ( 'NONE', *, *, #33674, .T. ) ; -#16025 = DIRECTION ( 'NONE', ( -0.7933310414247657372, -0.5931044597393388962, -0.1373060761554398823 ) ) ; -#16026 = CARTESIAN_POINT ( 'NONE', ( -42.86867325711791921, 121.2310159755540155, 90.74611056646313045 ) ) ; -#16027 = FACE_OUTER_BOUND ( 'NONE', #31584, .T. ) ; -#16028 = AXIS2_PLACEMENT_3D ( 'NONE', #2395, #21203, #17292 ) ; -#16029 = VERTEX_POINT ( 'NONE', #18829 ) ; -#16030 = VERTEX_POINT ( 'NONE', #9261 ) ; -#16031 = CARTESIAN_POINT ( 'NONE', ( 1.752039179668178903, 151.6655327357930219, 130.5892088565730091 ) ) ; -#16032 = ORIENTED_EDGE ( 'NONE', *, *, #34590, .F. ) ; -#16033 = VECTOR ( 'NONE', #17580, 1000.000000000000114 ) ; -#16034 = VECTOR ( 'NONE', #37165, 1000.000000000000000 ) ; -#16035 = AXIS2_PLACEMENT_3D ( 'NONE', #3057, #3253, #3447 ) ; -#16036 = ORIENTED_EDGE ( 'NONE', *, *, #27793, .T. ) ; -#16037 = CARTESIAN_POINT ( 'NONE', ( -15.99998595512920652, 185.9065961375156348, 102.5825112407314634 ) ) ; -#16038 = ORIENTED_EDGE ( 'NONE', *, *, #9085, .T. ) ; -#16039 = CARTESIAN_POINT ( 'NONE', ( -31.86340836050871417, 157.9239924182404877, 186.3985076549964788 ) ) ; -#16040 = EDGE_CURVE ( 'NONE', #28366, #37711, #16804, .T. ) ; -#16041 = CARTESIAN_POINT ( 'NONE', ( -2.554995790067999817, 191.0434702462999894, 106.4538185388999949 ) ) ; -#16042 = CARTESIAN_POINT ( 'NONE', ( 37.33701730692213516, 104.0256123824346446, 184.2143347311343859 ) ) ; -#16043 = VERTEX_POINT ( 'NONE', #40118 ) ; -#16044 = DIRECTION ( 'NONE', ( -0.0006039748319377451083, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#16046 = EDGE_CURVE ( 'NONE', #11449, #5782, #12129, .T. ) ; -#16045 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#16047 = EDGE_CURVE ( 'NONE', #37167, #7673, #9661, .T. ) ; -#16048 = LINE ( 'NONE', #910, #11427 ) ; -#16049 = CARTESIAN_POINT ( 'NONE', ( 19.46059643144436535, 126.3442427331793141, 175.5385488862945635 ) ) ; -#16050 = EDGE_CURVE ( 'NONE', #6998, #19028, #31837, .T. ) ; -#16051 = EDGE_CURVE ( 'NONE', #23911, #18328, #33773, .T. ) ; -#16052 = CARTESIAN_POINT ( 'NONE', ( 35.88952463556218930, 77.14301703112145958, 291.5368675616688279 ) ) ; -#16053 = VERTEX_POINT ( 'NONE', #24615 ) ; -#16054 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#16055 = ORIENTED_EDGE ( 'NONE', *, *, #38180, .F. ) ; -#16056 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28226, #18382, #21282, #9609 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16057 = CARTESIAN_POINT ( 'NONE', ( 22.68638433482282935, 158.3069331428809221, 96.18725556137884780 ) ) ; -#16058 = VECTOR ( 'NONE', #18715, 1000.000000000000000 ) ; -#16059 = AXIS2_PLACEMENT_3D ( 'NONE', #915, #26280, #10733 ) ; -#16060 = CARTESIAN_POINT ( 'NONE', ( -37.60586764323186060, 218.5902260770999987, 73.08121708413273154 ) ) ; -#16061 = ORIENTED_EDGE ( 'NONE', *, *, #18182, .T. ) ; -#16062 = CYLINDRICAL_SURFACE ( 'NONE', #11238, 30.00000000000001066 ) ; -#16063 = ORIENTED_EDGE ( 'NONE', *, *, #36774, .T. ) ; -#16065 = AXIS2_PLACEMENT_3D ( 'NONE', #15812, #19277, #9492 ) ; -#16064 = LINE ( 'NONE', #32021, #31032 ) ; -#16066 = CARTESIAN_POINT ( 'NONE', ( -26.06164500446789134, 121.6777288763670128, 87.76017847578864917 ) ) ; -#16067 = VECTOR ( 'NONE', #23999, 1000.000000000000000 ) ; -#16068 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16069 = VERTEX_POINT ( 'NONE', #34179 ) ; -#16070 = CARTESIAN_POINT ( 'NONE', ( 26.00081424259415641, 120.1020648120652510, 90.44388058125247198 ) ) ; -#16071 = ORIENTED_EDGE ( 'NONE', *, *, #30527, .T. ) ; -#16072 = ORIENTED_EDGE ( 'NONE', *, *, #21373, .F. ) ; -#16073 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250909262, 179.1753088544093657, 103.5954339977318739 ) ) ; -#16074 = ADVANCED_FACE ( 'NONE', ( #2908 ), #6376, .T. ) ; -#16075 = CYLINDRICAL_SURFACE ( 'NONE', #32632, 8.000000000000007105 ) ; -#16076 = ORIENTED_EDGE ( 'NONE', *, *, #15722, .F. ) ; -#16077 = CARTESIAN_POINT ( 'NONE', ( -25.50845318152657981, 205.7388967348897495, 75.91153402304078668 ) ) ; -#16078 = ORIENTED_EDGE ( 'NONE', *, *, #34002, .T. ) ; -#16079 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -0.000000000000000000, 0.0006039748319387908213 ) ) ; -#16080 = DIRECTION ( 'NONE', ( 0.0005884949961241158715, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16081 = DIRECTION ( 'NONE', ( 0.7075337269410153507, -2.187927502986928824E-15, 0.7066795774896545979 ) ) ; -#16082 = ORIENTED_EDGE ( 'NONE', *, *, #18430, .F. ) ; -#16083 = CARTESIAN_POINT ( 'NONE', ( 27.93899438949999947, 125.0366658260000037, 88.67409159612999758 ) ) ; -#16084 = ADVANCED_FACE ( 'NONE', ( #22137 ), #11605, .F. ) ; -#16085 = AXIS2_PLACEMENT_3D ( 'NONE', #15753, #15562, #21522 ) ; -#16086 = DIRECTION ( 'NONE', ( -7.115269692215706960E-15, 0.9743043966640313469, 0.2252353050503801690 ) ) ; -#16087 = CARTESIAN_POINT ( 'NONE', ( -20.00007258987272252, 169.9137872412887873, 98.89276590963629587 ) ) ; -#16088 = CARTESIAN_POINT ( 'NONE', ( 2.544461030880475594, 209.0000001909309901, 73.61327617014224245 ) ) ; -#16089 = CARTESIAN_POINT ( 'NONE', ( 20.49589212329804155, 159.2510479451992467, 96.40654468016703049 ) ) ; -#16090 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #23397, #22999, #7433, #19894 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.0004791655021827933257, 1.570796326795345532 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8048507809858619355, 0.8048507809858619355, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#16091 = VECTOR ( 'NONE', #8992, 1000.000000000000000 ) ; -#16092 = ORIENTED_EDGE ( 'NONE', *, *, #20062, .T. ) ; -#16093 = CARTESIAN_POINT ( 'NONE', ( 20.00171108015191024, 119.7153632178993377, 90.35824133875276232 ) ) ; -#16094 = EDGE_CURVE ( 'NONE', #36696, #21313, #10639, .T. ) ; -#16095 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25865, #19290, #28714, #13182 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16096 = DIRECTION ( 'NONE', ( 0.0005884949961209496759, -0.2249510543439030841, 0.9743698870671270162 ) ) ; -#16097 = CARTESIAN_POINT ( 'NONE', ( 25.49226348177107582, 205.5673819639667954, 76.28481786455526503 ) ) ; -#16098 = AXIS2_PLACEMENT_3D ( 'NONE', #1670, #13736, #1458 ) ; -#16099 = EDGE_CURVE ( 'NONE', #31534, #27880, #38991, .T. ) ; -#16100 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490314253413, 156.2427122711482070, 96.23754757943429183 ) ) ; -#16101 = CARTESIAN_POINT ( 'NONE', ( 38.47940687698435624, 119.0232181275810603, 90.24981979719966318 ) ) ; -#16102 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7512, #38995, #4443, #16897 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0008238168743097512266, 0.002797249353616942501 ), - .UNSPECIFIED. ) ; -#16103 = CARTESIAN_POINT ( 'NONE', ( -25.84447102352329750, 211.0902258593999932, 75.91014019561482939 ) ) ; -#16104 = LINE ( 'NONE', #31865, #35939 ) ; -#16105 = CARTESIAN_POINT ( 'NONE', ( 12.63850902179698998, 181.2597007827056643, 104.3624407909059784 ) ) ; -#16106 = ADVANCED_FACE ( 'NONE', ( #27888 ), #30936, .F. ) ; -#16107 = CARTESIAN_POINT ( 'NONE', ( -25.50638302354030174, 190.9262359218180052, 106.3111740386750057 ) ) ; -#16108 = VERTEX_POINT ( 'NONE', #28272 ) ; -#16109 = CARTESIAN_POINT ( 'NONE', ( -15.99974174651862313, 174.5231975350379514, 99.95452847233616467 ) ) ; -#16110 = CARTESIAN_POINT ( 'NONE', ( -16.17928014215196342, 122.0409702652264770, 178.1070844152368409 ) ) ; -#16111 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265226676, -0.1368326740407719011 ) ) ; -#16112 = CARTESIAN_POINT ( 'NONE', ( 2.545655555827734950, 209.1852808049790156, 75.59112338335545189 ) ) ; -#16113 = LINE ( 'NONE', #1173, #19150 ) ; -#16114 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38671, #35194, #19859, #35798 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 3.356945441522706129E-06, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16115 = CARTESIAN_POINT ( 'NONE', ( -13.46995280217765156, 158.2275496627099756, 98.75652669741377565 ) ) ; -#16116 = VECTOR ( 'NONE', #40235, 1000.000000000000000 ) ; -#16117 = CARTESIAN_POINT ( 'NONE', ( -8.622914549094021552, 190.8510648561669996, 106.7984846684352931 ) ) ; -#16118 = CARTESIAN_POINT ( 'NONE', ( 36.06383348468500571, 192.3733900160179928, 104.3179881943819822 ) ) ; -#16119 = VECTOR ( 'NONE', #4450, 1000.000000000000000 ) ; -#16120 = CARTESIAN_POINT ( 'NONE', ( -39.73142568412256992, 175.7232364642230777, 136.1664758066176830 ) ) ; -#16121 = ORIENTED_EDGE ( 'NONE', *, *, #22339, .T. ) ; -#16122 = FACE_OUTER_BOUND ( 'NONE', #37753, .T. ) ; -#16123 = PLANE ( 'NONE', #728 ) ; -#16124 = VECTOR ( 'NONE', #20296, 1000.000000000000114 ) ; -#16125 = CARTESIAN_POINT ( 'NONE', ( -35.93657501960694134, 192.7057386088000044, 106.3835760624021702 ) ) ; -#16126 = VERTEX_POINT ( 'NONE', #15197 ) ; -#16127 = CARTESIAN_POINT ( 'NONE', ( 19.99579756797234253, 191.9758059840616227, 101.9094256439181407 ) ) ; -#16128 = ORIENTED_EDGE ( 'NONE', *, *, #5210, .F. ) ; -#16129 = FACE_OUTER_BOUND ( 'NONE', #10433, .T. ) ; -#16130 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#16131 = CARTESIAN_POINT ( 'NONE', ( -36.31535185967262436, 190.8511613781771530, 106.8152324789805903 ) ) ; -#16132 = CARTESIAN_POINT ( 'NONE', ( -36.39991929748588717, 191.7382947397175599, 104.3966283125774623 ) ) ; -#16133 = EDGE_CURVE ( 'NONE', #6360, #33655, #15581, .T. ) ; -#16134 = CARTESIAN_POINT ( 'NONE', ( 17.27264158547648165, 121.9609240029174941, 174.6061468887760668 ) ) ; -#16135 = EDGE_CURVE ( 'NONE', #2293, #29235, #8336, .T. ) ; -#16137 = EDGE_CURVE ( 'NONE', #16794, #34336, #13599, .T. ) ; -#16136 = CARTESIAN_POINT ( 'NONE', ( 13.47462245814947934, 158.2310456470601423, 98.74105996008697161 ) ) ; -#16138 = CARTESIAN_POINT ( 'NONE', ( 13.81050778898542220, 149.9387330909817422, 180.4582364612731453 ) ) ; -#16139 = ADVANCED_FACE ( 'NONE', ( #7179 ), #32531, .F. ) ; -#16140 = CARTESIAN_POINT ( 'NONE', ( -30.06788429262541484, 177.0224639546494245, 103.4955571594761921 ) ) ; -#16141 = CARTESIAN_POINT ( 'NONE', ( -13.47112979352495543, 158.6774517721759139, 96.80778692315055878 ) ) ; -#16142 = ORIENTED_EDGE ( 'NONE', *, *, #10916, .F. ) ; -#16143 = ORIENTED_EDGE ( 'NONE', *, *, #21842, .F. ) ; -#16144 = LINE ( 'NONE', #596, #19994 ) ; -#16145 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971551802 ) ) ; -#16146 = EDGE_CURVE ( 'NONE', #11146, #9209, #37001, .T. ) ; -#16147 = AXIS2_PLACEMENT_3D ( 'NONE', #239, #37066, #24412 ) ; -#16148 = CARTESIAN_POINT ( 'NONE', ( -22.78280640698083559, 157.8259455793779864, 99.01153522024156928 ) ) ; -#16149 = EDGE_LOOP ( 'NONE', ( #17281, #28062, #9496, #25422 ) ) ; -#16150 = CYLINDRICAL_SURFACE ( 'NONE', #34208, 22.50000000000000000 ) ; -#16151 = VERTEX_POINT ( 'NONE', #34960 ) ; -#16152 = CIRCLE ( 'NONE', #27914, 40.00000000000073186 ) ; -#16153 = ADVANCED_FACE ( 'NONE', ( #842 ), #35167, .T. ) ; -#16154 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32926, #32735, #35986, #17584, #23745, #17378, #35773, #2274, #30085, #24162 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 7.859448383017418837E-15, 0.0004322186000195859384, 0.0008644372000313124953, 0.001296655800043038835, 0.001728874400054765392 ), - .UNSPECIFIED. ) ; -#16155 = CARTESIAN_POINT ( 'NONE', ( 19.99993950111425889, 196.1317665718410410, 104.7318359668413450 ) ) ; -#16156 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 166.8945455544008780, 183.3579980745095952 ) ) ; -#16157 = CARTESIAN_POINT ( 'NONE', ( 35.56356469037133650, 192.3002554099812471, 103.8734939767707885 ) ) ; -#16158 = FACE_OUTER_BOUND ( 'NONE', #13867, .T. ) ; -#16159 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 177.2126930573676304, 102.0942813187813982 ) ) ; -#16160 = EDGE_CURVE ( 'NONE', #13020, #12345, #35696, .T. ) ; -#16161 = CARTESIAN_POINT ( 'NONE', ( 20.48171464736319436, 206.1150451720382364, 75.33802399314664910 ) ) ; -#16162 = CARTESIAN_POINT ( 'NONE', ( 38.13598105415000106, 118.9081287641000131, 90.39876254777999520 ) ) ; -#16163 = ORIENTED_EDGE ( 'NONE', *, *, #34057, .T. ) ; -#16164 = CARTESIAN_POINT ( 'NONE', ( -28.53208073851174476, 125.2791694434640135, 88.59312828080875590 ) ) ; -#16165 = CARTESIAN_POINT ( 'NONE', ( 19.71680892478428859, 124.9569912405921883, 175.7901266015387023 ) ) ; -#16166 = CARTESIAN_POINT ( 'NONE', ( -45.16400980236513618, 70.91888486856629470, 322.7789803297500839 ) ) ; -#16167 = LINE ( 'NONE', #24599, #2981 ) ; -#16168 = ORIENTED_EDGE ( 'NONE', *, *, #18303, .T. ) ; -#16169 = EDGE_LOOP ( 'NONE', ( #24264, #17999, #14757, #14647 ) ) ; -#16170 = DIRECTION ( 'NONE', ( 0.0005884949961248158324, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16171 = AXIS2_PLACEMENT_3D ( 'NONE', #29014, #18992, #38412 ) ; -#16172 = CARTESIAN_POINT ( 'NONE', ( -30.05261220888372975, 126.8329673478291397, 91.51853052256073795 ) ) ; -#16173 = EDGE_LOOP ( 'NONE', ( #32067, #7131, #20492, #18659, #38634, #19688 ) ) ; -#16174 = ORIENTED_EDGE ( 'NONE', *, *, #25267, .T. ) ; -#16175 = CARTESIAN_POINT ( 'NONE', ( 35.55352078495887724, 112.9281706801280194, 87.24630913759760631 ) ) ; -#16176 = CARTESIAN_POINT ( 'NONE', ( -38.61757737722999906, 118.8204316123000126, 89.90765668362000440 ) ) ; -#16177 = FACE_OUTER_BOUND ( 'NONE', #18353, .T. ) ; -#16178 = FACE_OUTER_BOUND ( 'NONE', #33433, .T. ) ; -#16179 = ORIENTED_EDGE ( 'NONE', *, *, #36454, .T. ) ; -#16180 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319388799427 ) ) ; -#16181 = ORIENTED_EDGE ( 'NONE', *, *, #895, .F. ) ; -#16182 = EDGE_CURVE ( 'NONE', #36222, #38924, #31945, .T. ) ; -#16183 = CARTESIAN_POINT ( 'NONE', ( -25.43497462449660063, 117.4586649291000526, 89.78312114523609466 ) ) ; -#16184 = EDGE_CURVE ( 'NONE', #17805, #10259, #25412, .T. ) ; -#16185 = CARTESIAN_POINT ( 'NONE', ( -20.07947113715306386, 184.2548677810397635, 102.2036388924518207 ) ) ; -#16186 = CARTESIAN_POINT ( 'NONE', ( -22.63655565215235299, 130.9412805326379612, 89.89676961200316896 ) ) ; -#16187 = VERTEX_POINT ( 'NONE', #3907 ) ; -#16188 = CARTESIAN_POINT ( 'NONE', ( -2.771763471025999959, 190.8679547378000336, 103.8875947975000003 ) ) ; -#16189 = CARTESIAN_POINT ( 'NONE', ( 2.549069100720744441, 189.5938708632902774, 103.4225780300034643 ) ) ; -#16190 = DIRECTION ( 'NONE', ( -0.6087906217132950104, 0.7729786229956039367, 0.1785441886642067377 ) ) ; -#16191 = ORIENTED_EDGE ( 'NONE', *, *, #36359, .F. ) ; -#16192 = CARTESIAN_POINT ( 'NONE', ( 20.39650128425949305, 118.1111548655870536, 87.65155641249134533 ) ) ; -#16193 = LINE ( 'NONE', #25025, #34356 ) ; -#16194 = ORIENTED_EDGE ( 'NONE', *, *, #12359, .F. ) ; -#16195 = DIRECTION ( 'NONE', ( 0.7856246208753498994, 0.6187034467937467808, 0.000000000000000000 ) ) ; -#16196 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971545696 ) ) ; -#16197 = CARTESIAN_POINT ( 'NONE', ( -27.74595536588000400, 123.8455685898999974, 91.47954628734001403 ) ) ; -#16198 = CIRCLE ( 'NONE', #9038, 2.749999999927935423 ) ; -#16199 = VERTEX_POINT ( 'NONE', #38452 ) ; -#16200 = DIRECTION ( 'NONE', ( 0.0005884949672441799938, -0.2249510543775923299, 0.9743698870593667793 ) ) ; -#16201 = CARTESIAN_POINT ( 'NONE', ( -16.78807852584197491, 121.7176299279596208, 177.2134147146401233 ) ) ; -#16202 = CARTESIAN_POINT ( 'NONE', ( -19.99827944177191341, 118.8155627782461181, 90.27982142893266371 ) ) ; -#16203 = CARTESIAN_POINT ( 'NONE', ( -3.488613621442726576, 125.5688127946150985, 88.64487260003835445 ) ) ; -#16204 = EDGE_CURVE ( 'NONE', #37821, #26262, #14853, .T. ) ; -#16205 = VERTEX_POINT ( 'NONE', #443 ) ; -#16206 = CARTESIAN_POINT ( 'NONE', ( 26.00310484108860010, 120.1790658327160060, 90.46504372733748767 ) ) ; -#16207 = CARTESIAN_POINT ( 'NONE', ( 16.55946513390808406, 121.8573583107191780, 177.5776958584335148 ) ) ; -#16208 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16210 = CARTESIAN_POINT ( 'NONE', ( -13.49845036060215975, 187.8662283970866724, 103.4406284738125095 ) ) ; -#16209 = CARTESIAN_POINT ( 'NONE', ( -28.25571780481785567, 186.4543157461568228, 105.2821206686522686 ) ) ; -#16211 = DIRECTION ( 'NONE', ( -0.0005959779364584452156, -0.1621899515575390416, -0.9867593751386719569 ) ) ; -#16212 = ORIENTED_EDGE ( 'NONE', *, *, #3720, .F. ) ; -#16213 = CARTESIAN_POINT ( 'NONE', ( -30.04735478916544977, 185.8115295537965892, 102.7400937164344725 ) ) ; -#16214 = CARTESIAN_POINT ( 'NONE', ( -31.91217790952610756, 137.5486857473001407, 93.99357256101205849 ) ) ; -#16215 = FACE_OUTER_BOUND ( 'NONE', #25090, .T. ) ; -#16216 = CARTESIAN_POINT ( 'NONE', ( 28.64682496188636307, 225.5077044860236981, 75.54120257392457916 ) ) ; -#16217 = ORIENTED_EDGE ( 'NONE', *, *, #34449, .F. ) ; -#16218 = ORIENTED_EDGE ( 'NONE', *, *, #14624, .T. ) ; -#16219 = CARTESIAN_POINT ( 'NONE', ( 2.463364856792551905, 209.5677208948551993, 75.55701285043443249 ) ) ; -#16220 = AXIS2_PLACEMENT_3D ( 'NONE', #12312, #25007, #15191 ) ; -#16221 = CARTESIAN_POINT ( 'NONE', ( -46.70670256065962889, 123.1338644119410617, 91.82415844558849471 ) ) ; -#16222 = DIRECTION ( 'NONE', ( 0.6087611434178770153, 0.7731004625452604362, 0.1781166614240885793 ) ) ; -#16223 = CARTESIAN_POINT ( 'NONE', ( 35.98964030471999820, 192.0251590663000343, 104.2273425422000059 ) ) ; -#16224 = EDGE_LOOP ( 'NONE', ( #25598, #24977, #28242, #31855 ) ) ; -#16225 = EDGE_LOOP ( 'NONE', ( #16572, #22028, #27112, #25198 ) ) ; -#16226 = AXIS2_PLACEMENT_3D ( 'NONE', #26981, #5482, #23701 ) ; -#16227 = ORIENTED_EDGE ( 'NONE', *, *, #22104, .T. ) ; -#16228 = CARTESIAN_POINT ( 'NONE', ( 77.76885812527426367, 193.5821525182410880, 188.5104908262173637 ) ) ; -#16229 = EDGE_CURVE ( 'NONE', #21313, #11228, #12934, .T. ) ; -#16230 = CARTESIAN_POINT ( 'NONE', ( -23.36114798465503029, 134.5341053823447339, 93.55485419817190973 ) ) ; -#16231 = EDGE_CURVE ( 'NONE', #38615, #267, #29066, .T. ) ; -#16232 = FACE_OUTER_BOUND ( 'NONE', #40314, .T. ) ; -#16233 = ORIENTED_EDGE ( 'NONE', *, *, #8058, .F. ) ; -#16234 = ORIENTED_EDGE ( 'NONE', *, *, #9689, .T. ) ; -#16235 = LINE ( 'NONE', #13186, #21958 ) ; -#16236 = ORIENTED_EDGE ( 'NONE', *, *, #33627, .T. ) ; -#16237 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490291018744, 156.2427122711393395, 96.23754757947276062 ) ) ; -#16238 = ORIENTED_EDGE ( 'NONE', *, *, #21573, .T. ) ; -#16239 = CARTESIAN_POINT ( 'NONE', ( -13.82477833516488275, 124.3657273933217056, 88.37336118349627156 ) ) ; -#16240 = CARTESIAN_POINT ( 'NONE', ( -3.002001848952000174, 190.1395903318000080, 106.7780402845999959 ) ) ; -#16241 = LINE ( 'NONE', #38133, #29343 ) ; -#16242 = ORIENTED_EDGE ( 'NONE', *, *, #39861, .F. ) ; -#16243 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#16244 = CARTESIAN_POINT ( 'NONE', ( 13.49999902183750322, 160.7426630972690020, 96.75207176916120488 ) ) ; -#16245 = CARTESIAN_POINT ( 'NONE', ( 20.99968489185805964, 213.3366701443009106, 73.04582079892783497 ) ) ; -#16246 = FACE_OUTER_BOUND ( 'NONE', #37411, .T. ) ; -#16247 = AXIS2_PLACEMENT_3D ( 'NONE', #5928, #27832, #16130 ) ; -#16248 = CARTESIAN_POINT ( 'NONE', ( 30.44899456515794256, 126.4319216541827728, 91.90255247881687239 ) ) ; -#16249 = VERTEX_POINT ( 'NONE', #1241 ) ; -#16250 = CARTESIAN_POINT ( 'NONE', ( -46.39364199823201318, 124.7770151420462525, 91.05374585112593877 ) ) ; -#16251 = VECTOR ( 'NONE', #29935, 1000.000000000000227 ) ; -#16252 = VECTOR ( 'NONE', #21916, 1000.000000000000114 ) ; -#16253 = CARTESIAN_POINT ( 'NONE', ( -15.66646869924428032, 126.7256369811235714, 89.26140537028169319 ) ) ; -#16254 = CONICAL_SURFACE ( 'NONE', #8436, 4.999999999930198946, 0.7853981634432324332 ) ; -#16255 = DIRECTION ( 'NONE', ( 0.9999998268367997767, 0.0001323825946806684044, -0.0005734119104333256422 ) ) ; -#16256 = ORIENTED_EDGE ( 'NONE', *, *, #35730, .F. ) ; -#16257 = ORIENTED_EDGE ( 'NONE', *, *, #23630, .T. ) ; -#16258 = CARTESIAN_POINT ( 'NONE', ( 11.75690610893360422, 158.5518943791668676, 96.25041046018972679 ) ) ; -#16259 = EDGE_CURVE ( 'NONE', #12706, #27940, #34765, .T. ) ; -#16260 = CARTESIAN_POINT ( 'NONE', ( -38.38649509150999961, 190.6638049979000016, 106.5166526994999998 ) ) ; -#16261 = FACE_OUTER_BOUND ( 'NONE', #7364, .T. ) ; -#16262 = FACE_OUTER_BOUND ( 'NONE', #17116, .T. ) ; -#16263 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319356112900 ) ) ; -#16264 = VERTEX_POINT ( 'NONE', #25813 ) ; -#16265 = ORIENTED_EDGE ( 'NONE', *, *, #16359, .F. ) ; -#16266 = EDGE_LOOP ( 'NONE', ( #16461, #33026, #14970, #15, #8301, #36722, #33514, #6570, #32938 ) ) ; -#16267 = CARTESIAN_POINT ( 'NONE', ( -20.00006118649763209, 147.3680339623835209, 93.68765596609371471 ) ) ; -#16268 = EDGE_CURVE ( 'NONE', #11987, #22385, #21868, .T. ) ; -#16269 = CARTESIAN_POINT ( 'NONE', ( 36.05352243695642755, 118.8155670042997087, 87.24600886789973231 ) ) ; -#16270 = EDGE_LOOP ( 'NONE', ( #745, #21803, #24231, #15394, #19722 ) ) ; -#16271 = ORIENTED_EDGE ( 'NONE', *, *, #5847, .F. ) ; -#16272 = CARTESIAN_POINT ( 'NONE', ( 40.13009284222664519, 84.66001446739429070, 280.9279456820921723 ) ) ; -#16273 = EDGE_CURVE ( 'NONE', #30422, #39309, #4098, .T. ) ; -#16274 = CARTESIAN_POINT ( 'NONE', ( -38.57146445400000090, 119.0360826316999976, 90.16028290594999817 ) ) ; -#16275 = EDGE_CURVE ( 'NONE', #2569, #16955, #26214, .T. ) ; -#16276 = ORIENTED_EDGE ( 'NONE', *, *, #1179, .T. ) ; -#16277 = CARTESIAN_POINT ( 'NONE', ( 2.943104451508621544, 209.7096517725655644, 76.05672380837390278 ) ) ; -#16278 = EDGE_CURVE ( 'NONE', #6308, #17976, #33581, .T. ) ; -#16279 = AXIS2_PLACEMENT_3D ( 'NONE', #24051, #2377, #30791 ) ; -#16280 = ADVANCED_FACE ( 'NONE', ( #8617 ), #24038, .T. ) ; -#16281 = DIRECTION ( 'NONE', ( -0.7933533419755064431, 0.5930537050706157221, 0.1373964252748610115 ) ) ; -#16282 = VERTEX_POINT ( 'NONE', #39458 ) ; -#16283 = CARTESIAN_POINT ( 'NONE', ( 28.18055532800000051, 125.5349220596000066, 89.13115644789000669 ) ) ; -#16284 = AXIS2_PLACEMENT_3D ( 'NONE', #17545, #27199, #26990 ) ; -#16285 = CARTESIAN_POINT ( 'NONE', ( 25.02112415033897364, 129.9425189845125601, 92.71631651849574496 ) ) ; -#16286 = CARTESIAN_POINT ( 'NONE', ( 94.49328988966108511, 77.27448630901744764, 291.5014723559426670 ) ) ; -#16287 = CARTESIAN_POINT ( 'NONE', ( 23.68617301077875581, 136.6832543673160956, 94.27334322351919127 ) ) ; -#16288 = CIRCLE ( 'NONE', #29993, 4.500000000039500847 ) ; -#16289 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#16290 = ORIENTED_EDGE ( 'NONE', *, *, #9829, .T. ) ; -#16291 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 77.27946979429628982, 310.0857197240630967 ) ) ; -#16292 = CARTESIAN_POINT ( 'NONE', ( 1.086103810833373817, 189.0697198636973724, 103.7041996269950772 ) ) ; -#16293 = CARTESIAN_POINT ( 'NONE', ( -38.57146895724624613, 191.0388322217830250, 103.7810094805231387 ) ) ; -#16294 = CARTESIAN_POINT ( 'NONE', ( 12.63723266175987270, 130.1298785553014739, 92.46781221652395288 ) ) ; -#16295 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16296 = FACE_OUTER_BOUND ( 'NONE', #441, .T. ) ; -#16297 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319391458975 ) ) ; -#16298 = ADVANCED_FACE ( 'NONE', ( #39058 ), #23532, .T. ) ; -#16299 = CARTESIAN_POINT ( 'NONE', ( 45.36643772877659586, 116.4348306700458124, 122.4284095016645608 ) ) ; -#16300 = ORIENTED_EDGE ( 'NONE', *, *, #32495, .F. ) ; -#16301 = CARTESIAN_POINT ( 'NONE', ( 17.99794026751194309, 132.4103114830704442, 92.77714071222307268 ) ) ; -#16302 = CARTESIAN_POINT ( 'NONE', ( -19.44522627092439038, 148.1589718280038710, 181.5720362247187438 ) ) ; -#16303 = ORIENTED_EDGE ( 'NONE', *, *, #18563, .F. ) ; -#16304 = CARTESIAN_POINT ( 'NONE', ( -43.65360665174738841, 185.3905100451317765, 107.6115822775834374 ) ) ; -#16305 = VECTOR ( 'NONE', #19729, 1000.000000000000227 ) ; -#16306 = CARTESIAN_POINT ( 'NONE', ( -38.20405560931869360, 218.5902260770999987, 76.08157892187939808 ) ) ; -#16307 = CARTESIAN_POINT ( 'NONE', ( 20.81480888314487387, 116.8538579756977924, 87.75498164167572668 ) ) ; -#16308 = PLANE ( 'NONE', #19206 ) ; -#16309 = EDGE_CURVE ( 'NONE', #39281, #20371, #39017, .T. ) ; -#16310 = AXIS2_PLACEMENT_3D ( 'NONE', #7710, #29601, #20173 ) ; -#16311 = FACE_OUTER_BOUND ( 'NONE', #357, .T. ) ; -#16312 = CARTESIAN_POINT ( 'NONE', ( 36.06507820818748655, 192.5954166247090313, 106.3788509914820111 ) ) ; -#16313 = CONICAL_SURFACE ( 'NONE', #21565, 6.499999999924747307, 0.7853981633862021638 ) ; -#16314 = CARTESIAN_POINT ( 'NONE', ( 36.14095822016396653, 114.4249042674252763, 87.72551690086099541 ) ) ; -#16315 = CONICAL_SURFACE ( 'NONE', #39171, 2.500000339008657146, 0.7853981633778087668 ) ; -#16316 = CARTESIAN_POINT ( 'NONE', ( 35.43506417528000441, 192.9711071536000020, 106.9376191850000026 ) ) ; -#16317 = ORIENTED_EDGE ( 'NONE', *, *, #16853, .F. ) ; -#16318 = CARTESIAN_POINT ( 'NONE', ( 20.50028285398298777, 191.4126458000098978, 104.3447517631808097 ) ) ; -#16319 = EDGE_CURVE ( 'NONE', #14084, #28366, #39261, .T. ) ; -#16320 = DIRECTION ( 'NONE', ( 0.4303597330247870278, 0.7060138277436147636, -0.5624366410767025481 ) ) ; -#16321 = EDGE_CURVE ( 'NONE', #39083, #30155, #11438, .T. ) ; -#16322 = CARTESIAN_POINT ( 'NONE', ( 20.49369975149401668, 199.8820069588898320, 94.80039694518488602 ) ) ; -#16323 = ORIENTED_EDGE ( 'NONE', *, *, #39623, .T. ) ; -#16324 = CARTESIAN_POINT ( 'NONE', ( 24.86285456769096669, 182.2983400162870851, 101.7247947455283992 ) ) ; -#16325 = ADVANCED_FACE ( 'NONE', ( #36410 ), #28593, .T. ) ; -#16326 = VERTEX_POINT ( 'NONE', #23341 ) ; -#16327 = ADVANCED_FACE ( 'NONE', ( #36194 ), #10961, .F. ) ; -#16328 = CARTESIAN_POINT ( 'NONE', ( -5.663464557155529988, 131.0206703453534374, 89.90489628355439322 ) ) ; -#16329 = DIRECTION ( 'NONE', ( -0.7066905234128858515, -0.1590644159615968445, 0.6894106292284863935 ) ) ; -#16330 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023854076 ) ) ; -#16331 = CARTESIAN_POINT ( 'NONE', ( -23.35716082638948521, 130.0938126195854636, 92.43835990256307866 ) ) ; -#16332 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384538513 ) ) ; -#16333 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14659, #38759, #20777, #23857 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16334 = CARTESIAN_POINT ( 'NONE', ( -20.02002437005085511, 209.7095682957761085, 73.07054393135327075 ) ) ; -#16335 = ORIENTED_EDGE ( 'NONE', *, *, #29824, .T. ) ; -#16336 = CARTESIAN_POINT ( 'NONE', ( 39.76816811907257687, 175.4177889136913109, 159.9692080044317493 ) ) ; -#16337 = CONICAL_SURFACE ( 'NONE', #35907, 2.499999999965141662, 0.7853981634008656565 ) ; -#16338 = CARTESIAN_POINT ( 'NONE', ( -3.837388691982094091, 176.5591841211374629, 100.4171401915558306 ) ) ; -#16339 = CARTESIAN_POINT ( 'NONE', ( 5.668111417580466771, 183.4499515673966812, 105.0842738006407018 ) ) ; -#16340 = VECTOR ( 'NONE', #17457, 1000.000000000000000 ) ; -#16341 = AXIS2_PLACEMENT_3D ( 'NONE', #33289, #5487, #26779 ) ; -#16342 = CARTESIAN_POINT ( 'NONE', ( -36.29868172540000160, 191.6823464439000020, 104.2736944691999952 ) ) ; -#16343 = ORIENTED_EDGE ( 'NONE', *, *, #30497, .T. ) ; -#16344 = DIRECTION ( 'NONE', ( -0.1305262373691799260, -0.9659798014921964215, -0.2232620085624539286 ) ) ; -#16345 = ORIENTED_EDGE ( 'NONE', *, *, #26864, .T. ) ; -#16346 = CARTESIAN_POINT ( 'NONE', ( 3.847675889067868393, 147.9886445650915618, 129.7371189396918680 ) ) ; -#16347 = PLANE ( 'NONE', #9716 ) ; -#16348 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18859, #28497, #6596, #16209 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16349 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319417801836 ) ) ; -#16350 = CARTESIAN_POINT ( 'NONE', ( -37.29638110713771226, 178.8156383198445667, 136.8789424484697008 ) ) ; -#16351 = CARTESIAN_POINT ( 'NONE', ( 20.48073942642239942, 207.7074378936182768, 74.00492349107967982 ) ) ; -#16352 = CARTESIAN_POINT ( 'NONE', ( 38.50820439054000133, 118.5727785117999957, 89.80762991176000298 ) ) ; -#16353 = ORIENTED_EDGE ( 'NONE', *, *, #1089, .T. ) ; -#16354 = EDGE_CURVE ( 'NONE', #26865, #12152, #20669, .T. ) ; -#16355 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16356 = EDGE_CURVE ( 'NONE', #7827, #38615, #23954, .T. ) ; -#16357 = CARTESIAN_POINT ( 'NONE', ( -36.44242984183888723, 191.5061647249781061, 106.4038886115175728 ) ) ; -#16358 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 181.0156285263394125, 104.5149534146526236 ) ) ; -#16359 = EDGE_CURVE ( 'NONE', #26011, #16791, #35727, .T. ) ; -#16360 = CARTESIAN_POINT ( 'NONE', ( -20.50046838666520799, 193.8411600273693978, 103.5994668550054314 ) ) ; -#16361 = ORIENTED_EDGE ( 'NONE', *, *, #37118, .F. ) ; -#16362 = VERTEX_POINT ( 'NONE', #17582 ) ; -#16363 = VECTOR ( 'NONE', #1919, 1000.000000000000000 ) ; -#16364 = VECTOR ( 'NONE', #6548, 1000.000000000000227 ) ; -#16365 = ORIENTED_EDGE ( 'NONE', *, *, #14147, .T. ) ; -#16366 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555133 ) ) ; -#16367 = ADVANCED_FACE ( 'NONE', ( #29673 ), #29905, .F. ) ; -#16368 = CONICAL_SURFACE ( 'NONE', #37947, 6.000000401320364496, 0.7853981634158426761 ) ; -#16369 = VECTOR ( 'NONE', #30397, 1000.000000000000000 ) ; -#16370 = FACE_OUTER_BOUND ( 'NONE', #37428, .T. ) ; -#16371 = ORIENTED_EDGE ( 'NONE', *, *, #27813, .T. ) ; -#16372 = DIRECTION ( 'NONE', ( 0.7066903926851649809, 0.000000000000000000, -0.7075229246367126246 ) ) ; -#16373 = ADVANCED_FACE ( 'NONE', ( #30083 ), #38857, .F. ) ; -#16374 = CARTESIAN_POINT ( 'NONE', ( 34.28687154474416587, 218.5902260770998282, 61.03779348242591141 ) ) ; -#16375 = CARTESIAN_POINT ( 'NONE', ( 2.561557524529688212, 191.9759150222000130, 101.9199002238063372 ) ) ; -#16376 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#16377 = VERTEX_POINT ( 'NONE', #5739 ) ; -#16378 = CARTESIAN_POINT ( 'NONE', ( 16.57435211472781589, 122.8698034444475695, 173.0361124685911989 ) ) ; -#16379 = EDGE_LOOP ( 'NONE', ( #6565, #14247, #26650, #1526 ) ) ; -#16380 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498900431, 179.0675991014231556, 104.0619761093272899 ) ) ; -#16381 = CARTESIAN_POINT ( 'NONE', ( -21.68370027014267620, 130.4236040016583047, 89.77667904513492658 ) ) ; -#16382 = ADVANCED_FACE ( 'NONE', ( #8817 ), #18391, .T. ) ; -#16383 = EDGE_LOOP ( 'NONE', ( #7192, #158, #25146, #38537 ) ) ; -#16384 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250904998, 132.4055461762928019, 92.79778151953361487 ) ) ; -#16385 = PLANE ( 'NONE', #15318 ) ; -#16386 = CARTESIAN_POINT ( 'NONE', ( -20.49970532888763941, 191.4139234226054498, 104.3698659823340478 ) ) ; -#16387 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#16388 = VERTEX_POINT ( 'NONE', #36814 ) ; -#16389 = CIRCLE ( 'NONE', #19657, 47.50000000000088107 ) ; -#16390 = DIRECTION ( 'NONE', ( -0.6319268263561552690, -0.7750280550608716901, 0.000000000000000000 ) ) ; -#16391 = FACE_OUTER_BOUND ( 'NONE', #29228, .T. ) ; -#16392 = EDGE_LOOP ( 'NONE', ( #29256, #38089, #15173, #2266 ) ) ; -#16393 = AXIS2_PLACEMENT_3D ( 'NONE', #13586, #4766, #19891 ) ; -#16394 = VECTOR ( 'NONE', #9694, 999.9999999999997726 ) ; -#16395 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#16396 = CARTESIAN_POINT ( 'NONE', ( -25.65884129073699782, 194.1237596081920742, 102.8486509400222388 ) ) ; -#16397 = DIRECTION ( 'NONE', ( -0.7933533411653074241, -0.5931840316265230006, -0.1368326740407701525 ) ) ; -#16398 = EDGE_LOOP ( 'NONE', ( #20228, #4014, #26800, #21326 ) ) ; -#16399 = VECTOR ( 'NONE', #27841, 1000.000000000000114 ) ; -#16400 = DIRECTION ( 'NONE', ( 0.0005884949961242350253, -0.2249510543439066923, 0.9743698870671262391 ) ) ; -#16401 = LINE ( 'NONE', #6592, #28705 ) ; -#16402 = ORIENTED_EDGE ( 'NONE', *, *, #24485, .F. ) ; -#16403 = CARTESIAN_POINT ( 'NONE', ( 25.67102090886999832, 120.3907441056999943, 90.16869597336001618 ) ) ; -#16404 = EDGE_CURVE ( 'NONE', #34206, #5155, #18946, .T. ) ; -#16405 = CARTESIAN_POINT ( 'NONE', ( -15.67958464821357722, 153.2035578972894996, 95.03222041879267579 ) ) ; -#16406 = EDGE_CURVE ( 'NONE', #29855, #5612, #39872, .T. ) ; -#16408 = CARTESIAN_POINT ( 'NONE', ( 97.89458707257233527, 73.08085066759555559, 291.4994180576736085 ) ) ; -#16407 = LINE ( 'NONE', #7402, #23728 ) ; -#16409 = VERTEX_POINT ( 'NONE', #9614 ) ; -#16410 = CARTESIAN_POINT ( 'NONE', ( -29.91503390656419370, 185.6751918267468682, 102.8795885021705061 ) ) ; -#16411 = EDGE_CURVE ( 'NONE', #7887, #32617, #21692, .T. ) ; -#16412 = CARTESIAN_POINT ( 'NONE', ( -40.96777089817398121, 130.0214998612392208, 92.77440595303380633 ) ) ; -#16413 = EDGE_LOOP ( 'NONE', ( #17499, #31807, #5572, #28406 ) ) ; -#16414 = VECTOR ( 'NONE', #33985, 1000.000000000000114 ) ; -#16415 = ORIENTED_EDGE ( 'NONE', *, *, #13068, .T. ) ; -#16416 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#16417 = EDGE_CURVE ( 'NONE', #21067, #29513, #30490, .T. ) ; -#16418 = CARTESIAN_POINT ( 'NONE', ( 1.214432203236400998, 156.8167772888575655, 100.9862065159453124 ) ) ; -#16419 = LINE ( 'NONE', #10318, #37670 ) ; -#16420 = CARTESIAN_POINT ( 'NONE', ( 15.99970520780110483, 160.7332544674666508, 96.75156078672274873 ) ) ; -#16421 = ORIENTED_EDGE ( 'NONE', *, *, #15481, .F. ) ; -#16422 = ORIENTED_EDGE ( 'NONE', *, *, #37885, .T. ) ; -#16423 = ORIENTED_EDGE ( 'NONE', *, *, #1794, .F. ) ; -#16424 = CARTESIAN_POINT ( 'NONE', ( -42.83388826220544132, 121.9349074780233195, 87.82968285981074530 ) ) ; -#16425 = CARTESIAN_POINT ( 'NONE', ( 33.79411933395220302, 218.5902260770999987, 73.03809328116246036 ) ) ; -#16426 = FACE_OUTER_BOUND ( 'NONE', #5417, .T. ) ; -#16427 = EDGE_CURVE ( 'NONE', #43, #8699, #1876, .T. ) ; -#16428 = ORIENTED_EDGE ( 'NONE', *, *, #26911, .T. ) ; -#16429 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12231, #31229, #9565, #27596, #34280, #21230 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16430 = CARTESIAN_POINT ( 'NONE', ( 75.24056455973224899, 196.4820008462166641, 189.1802437148639058 ) ) ; -#16431 = ORIENTED_EDGE ( 'NONE', *, *, #28303, .T. ) ; -#16432 = DIRECTION ( 'NONE', ( -0.7933533416835752972, 0.5930537051408127924, 0.1373964266575312121 ) ) ; -#16433 = ORIENTED_EDGE ( 'NONE', *, *, #29730, .T. ) ; -#16434 = CARTESIAN_POINT ( 'NONE', ( -38.09104460848572415, 163.5977002183961986, 197.9766423606148180 ) ) ; -#16435 = CARTESIAN_POINT ( 'NONE', ( -3.067671275023999833, 190.9450925682999980, 106.9545067451000193 ) ) ; -#16436 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251386036, 132.4055461763500432, 92.79778151959344257 ) ) ; -#16437 = ORIENTED_EDGE ( 'NONE', *, *, #7424, .F. ) ; -#16438 = CARTESIAN_POINT ( 'NONE', ( 2.462157221798171314, 209.5677243469951634, 73.55701709285500556 ) ) ; -#16439 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22654, #23241, #13243, #16876, #4016, #35677 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16440 = CARTESIAN_POINT ( 'NONE', ( -24.26035614307613741, 115.9286812804331532, 87.78225227416257326 ) ) ; -#16441 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13496, #1210, #35526, #13689 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16442 = CIRCLE ( 'NONE', #38649, 6.000000000000007994 ) ; -#16443 = CARTESIAN_POINT ( 'NONE', ( 20.25283899970633783, 212.3189532007872344, 73.04627187513231945 ) ) ; -#16444 = CARTESIAN_POINT ( 'NONE', ( 13.50130427969020275, 124.2930898829833524, 90.90584795771297877 ) ) ; -#16445 = CONICAL_SURFACE ( 'NONE', #4719, 2.502994021815846182, 0.7853981633807167739 ) ; -#16446 = AXIS2_PLACEMENT_3D ( 'NONE', #30405, #33247, #17504 ) ; -#16447 = DIRECTION ( 'NONE', ( -0.9914446600486714889, 0.1270322995874082761, 0.03000468167652007440 ) ) ; -#16448 = VERTEX_POINT ( 'NONE', #17988 ) ; -#16449 = CARTESIAN_POINT ( 'NONE', ( 33.59566074061859098, 83.36374835074464329, 285.7734289287842557 ) ) ; -#16450 = ADVANCED_FACE ( 'NONE', ( #24366 ), #17468, .F. ) ; -#16451 = ADVANCED_FACE ( 'NONE', ( #40070 ), #29258, .F. ) ; -#16452 = CARTESIAN_POINT ( 'NONE', ( -36.47994717572999690, 115.7898166395000175, 89.87704453466000132 ) ) ; -#16453 = ORIENTED_EDGE ( 'NONE', *, *, #15997, .F. ) ; -#16454 = VERTEX_POINT ( 'NONE', #37219 ) ; -#16455 = CARTESIAN_POINT ( 'NONE', ( 37.59407280179000566, 112.0479120775361821, 151.0714151308390854 ) ) ; -#16456 = PLANE ( 'NONE', #31358 ) ; -#16457 = CARTESIAN_POINT ( 'NONE', ( 75.33446582941786573, 196.6730905574605970, 189.2244420380926329 ) ) ; -#16458 = EDGE_CURVE ( 'NONE', #23325, #8503, #18433, .T. ) ; -#16459 = ORIENTED_EDGE ( 'NONE', *, *, #9414, .T. ) ; -#16460 = FACE_BOUND ( 'NONE', #15196, .T. ) ; -#16461 = ORIENTED_EDGE ( 'NONE', *, *, #9642, .T. ) ; -#16462 = ORIENTED_EDGE ( 'NONE', *, *, #30793, .T. ) ; -#16463 = CARTESIAN_POINT ( 'NONE', ( 20.16681565195775150, 118.8156056749160001, 87.42222852412939460 ) ) ; -#16464 = DIRECTION ( 'NONE', ( -0.7933532970003733809, -0.5930762008556731413, -0.1372995488602876957 ) ) ; -#16465 = CARTESIAN_POINT ( 'NONE', ( -23.36190347369393194, 128.5832235793138523, 89.34972834851440382 ) ) ; -#16466 = VERTEX_POINT ( 'NONE', #15539 ) ; -#16467 = PLANE ( 'NONE', #12803 ) ; -#16468 = CARTESIAN_POINT ( 'NONE', ( 35.50063842825999672, 114.5394629846999948, 87.10535886572000663 ) ) ; -#16469 = CARTESIAN_POINT ( 'NONE', ( -38.52752199465000160, 119.2961657191000171, 90.46788514962000249 ) ) ; -#16470 = CARTESIAN_POINT ( 'NONE', ( -29.20104124294445214, 148.3921741051831873, 97.00850424916733061 ) ) ; -#16471 = VECTOR ( 'NONE', #34910, 1000.000000000000227 ) ; -#16472 = ADVANCED_FACE ( 'NONE', ( #2480 ), #3254, .T. ) ; -#16473 = VECTOR ( 'NONE', #30865, 1000.000000000000114 ) ; -#16474 = CARTESIAN_POINT ( 'NONE', ( -38.90591266646470103, 169.4072598844840627, 182.8931904839043625 ) ) ; -#16475 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749388340, 132.8602140592406045, 90.82839891340712768 ) ) ; -#16476 = CARTESIAN_POINT ( 'NONE', ( 21.23862774292054212, 136.3779700007411009, 91.12542899279699782 ) ) ; -#16477 = ORIENTED_EDGE ( 'NONE', *, *, #31340, .F. ) ; -#16478 = CARTESIAN_POINT ( 'NONE', ( 28.52619946403000029, 125.2833734473000078, 88.56110222834999490 ) ) ; -#16479 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700560425838653, -0.2249510922124452195 ) ) ; -#16480 = LINE ( 'NONE', #4206, #11665 ) ; -#16481 = CARTESIAN_POINT ( 'NONE', ( -35.62325547678683080, 209.7096871504523676, 73.24668633324121458 ) ) ; -#16482 = CARTESIAN_POINT ( 'NONE', ( -2.437027990547441014, 191.0000000396348128, 104.2633722229568605 ) ) ; -#16483 = ORIENTED_EDGE ( 'NONE', *, *, #22800, .T. ) ; -#16484 = DIRECTION ( 'NONE', ( -0.9999998176071912548, 1.116701431525940521E-11, 0.0006039748207718291517 ) ) ; -#16485 = CARTESIAN_POINT ( 'NONE', ( 0.7008280748616902978, 189.0047931960354219, 103.6853728373111920 ) ) ; -#16486 = CARTESIAN_POINT ( 'NONE', ( -0.7674275430754152749, 188.3856493364897347, 106.2245540265581241 ) ) ; -#16487 = EDGE_CURVE ( 'NONE', #4779, #24868, #39443, .T. ) ; -#16488 = CARTESIAN_POINT ( 'NONE', ( -16.56460962585015295, 151.5351474169435733, 184.4312778327909541 ) ) ; -#16489 = CARTESIAN_POINT ( 'NONE', ( -25.61308381689000058, 191.8269069694999871, 104.3105675431999941 ) ) ; -#16490 = DIRECTION ( 'NONE', ( -0.0001408415334274825802, 0.2249510912533641271, -0.9743700460849477052 ) ) ; -#16491 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16492 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16493 = VERTEX_POINT ( 'NONE', #4250 ) ; -#16494 = EDGE_CURVE ( 'NONE', #19286, #12627, #32159, .T. ) ; -#16495 = EDGE_CURVE ( 'NONE', #32173, #34620, #10013, .T. ) ; -#16496 = ADVANCED_FACE ( 'NONE', ( #12887 ), #13083, .F. ) ; -#16497 = LINE ( 'NONE', #4437, #3043 ) ; -#16498 = CIRCLE ( 'NONE', #12601, 51.90509898881904149 ) ; -#16499 = CARTESIAN_POINT ( 'NONE', ( -43.85192579621110553, 185.5794629365180413, 107.4090340691420664 ) ) ; -#16500 = ORIENTED_EDGE ( 'NONE', *, *, #5141, .F. ) ; -#16501 = LINE ( 'NONE', #19967, #14616 ) ; -#16502 = CARTESIAN_POINT ( 'NONE', ( -37.45249394195251824, 145.6179928404688724, 281.5041015744685637 ) ) ; -#16503 = CYLINDRICAL_SURFACE ( 'NONE', #26118, 2.000000000000014655 ) ; -#16504 = CARTESIAN_POINT ( 'NONE', ( 36.06383963597500752, 192.3117859303959847, 104.3281134044120080 ) ) ; -#16505 = CARTESIAN_POINT ( 'NONE', ( -13.46391575659845685, 154.4039982810205629, 95.30803284751881677 ) ) ; -#16506 = CARTESIAN_POINT ( 'NONE', ( 35.43188809533000239, 192.9169409211000072, 106.9485261150999946 ) ) ; -#16507 = ORIENTED_EDGE ( 'NONE', *, *, #10800, .T. ) ; -#16508 = CARTESIAN_POINT ( 'NONE', ( -2.913189425919000097, 209.5191065594000008, 76.06629948724000201 ) ) ; -#16509 = CARTESIAN_POINT ( 'NONE', ( -32.57214901757254211, 137.3507445002516079, 91.38251427481793598 ) ) ; -#16510 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; -#16511 = ORIENTED_EDGE ( 'NONE', *, *, #4660, .T. ) ; -#16512 = DIRECTION ( 'NONE', ( -0.0005884949961261437632, 0.2249510543439059151, -0.9743698870671263501 ) ) ; -#16513 = ORIENTED_EDGE ( 'NONE', *, *, #14871, .F. ) ; -#16514 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971580668 ) ) ; -#16515 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; -#16516 = CARTESIAN_POINT ( 'NONE', ( -36.81620286734185044, 191.5634815702392473, 104.3852644490423103 ) ) ; -#16517 = FACE_OUTER_BOUND ( 'NONE', #4385, .T. ) ; -#16518 = VECTOR ( 'NONE', #5149, 999.9999999999998863 ) ; -#16519 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14986, #18425, #15575, #36855, #30732, #6171, #37456, #8864, #21934, #39706, #5780, #2724, #15192, #30932, #3102, #28073, #22335, #34955, #25206, #35160 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999998899769, 0.1874999999998245848, 0.2187499999997803424, 0.2343749999997683797, 0.2499999999997563893, 0.4999999999998131495, 0.6249999999998484546, 0.6874999999998605560, 0.7187499999998683275, 0.7343749999998769873, 0.7499999999998856470, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16520 = CARTESIAN_POINT ( 'NONE', ( -35.98817295377529746, 191.5260130662397273, 103.8919236801626340 ) ) ; -#16521 = CARTESIAN_POINT ( 'NONE', ( 21.85768935794949996, 135.9059676768250711, 91.18714493273058963 ) ) ; -#16522 = ORIENTED_EDGE ( 'NONE', *, *, #5054, .F. ) ; -#16523 = EDGE_LOOP ( 'NONE', ( #37223, #27122, #18072, #13349 ) ) ; -#16524 = CARTESIAN_POINT ( 'NONE', ( 15.10764778216198323, 128.9370057249701063, 92.49016256005407399 ) ) ; -#16525 = VECTOR ( 'NONE', #4403, 999.9999999999998863 ) ; -#16526 = DIRECTION ( 'NONE', ( -0.7066903833891088338, -9.361005956066117864E-05, 0.7075229277292088836 ) ) ; -#16527 = CARTESIAN_POINT ( 'NONE', ( -18.61117187107760884, 125.1353300184083253, 178.8218272577300354 ) ) ; -#16528 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8591, #30464, #2458, #30250, #5715, #14116, #1626, #11443 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 4 ), - ( 1.040834085586084103E-17, 0.0002767357485092747566, 0.0005534714970185391049, 0.001106942994037067802 ), - .UNSPECIFIED. ) ; -#16529 = EDGE_CURVE ( 'NONE', #15062, #19831, #25783, .T. ) ; -#16530 = CARTESIAN_POINT ( 'NONE', ( -36.29419933191000069, 191.9582539845000042, 104.5583661083999942 ) ) ; -#16531 = ORIENTED_EDGE ( 'NONE', *, *, #34361, .T. ) ; -#16532 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#16533 = CARTESIAN_POINT ( 'NONE', ( 3.664993456856746601, 130.0812534783833030, 89.68233120885354026 ) ) ; -#16534 = EDGE_CURVE ( 'NONE', #19888, #20336, #22293, .T. ) ; -#16535 = CARTESIAN_POINT ( 'NONE', ( -20.89286847790088331, 136.3261294211067138, 91.13890976780785991 ) ) ; -#16536 = CARTESIAN_POINT ( 'NONE', ( 25.49176550122653850, 211.4176093050745067, 75.54327414409580399 ) ) ; -#16537 = EDGE_CURVE ( 'NONE', #36684, #1422, #40383, .T. ) ; -#16538 = EDGE_CURVE ( 'NONE', #9013, #29879, #2478, .T. ) ; -#16539 = DIRECTION ( 'NONE', ( 0.0005884949961195158185, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16540 = EDGE_CURVE ( 'NONE', #9057, #23733, #792, .T. ) ; -#16541 = FACE_OUTER_BOUND ( 'NONE', #32181, .T. ) ; -#16542 = CARTESIAN_POINT ( 'NONE', ( -2.836031461634000106, 208.9827885628999979, 73.23448830942000143 ) ) ; -#16543 = CARTESIAN_POINT ( 'NONE', ( 38.14662459809999717, 118.9171916317999944, 90.39768274928999858 ) ) ; -#16544 = VECTOR ( 'NONE', #34579, 1000.000000000000227 ) ; -#16545 = AXIS2_PLACEMENT_3D ( 'NONE', #16892, #10595, #1370 ) ; -#16546 = VERTEX_POINT ( 'NONE', #3449 ) ; -#16547 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#16548 = CARTESIAN_POINT ( 'NONE', ( 20.50176505208000322, 183.2870761629000071, 105.0346093865999961 ) ) ; -#16549 = DIRECTION ( 'NONE', ( 0.0004161288024805896127, -0.8480480897555470188, 0.5299191110903505031 ) ) ; -#16550 = AXIS2_PLACEMENT_3D ( 'NONE', #12108, #15372, #40098 ) ; -#16551 = CARTESIAN_POINT ( 'NONE', ( 44.73086057231283519, 108.4360122525000492, 169.8450455613742349 ) ) ; -#16552 = ORIENTED_EDGE ( 'NONE', *, *, #34489, .F. ) ; -#16553 = ORIENTED_EDGE ( 'NONE', *, *, #12885, .T. ) ; -#16554 = EDGE_LOOP ( 'NONE', ( #15032, #11045, #16092, #17659 ) ) ; -#16555 = LINE ( 'NONE', #4292, #39192 ) ; -#16556 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700562169599344, -0.2249510914571397902 ) ) ; -#16557 = CARTESIAN_POINT ( 'NONE', ( 5.667647268250993520, 124.2920528419670632, 90.91033987003989125 ) ) ; -#16558 = ORIENTED_EDGE ( 'NONE', *, *, #21797, .T. ) ; -#16559 = ORIENTED_EDGE ( 'NONE', *, *, #27304, .F. ) ; -#16560 = CARTESIAN_POINT ( 'NONE', ( 15.99999411728631671, 174.5114300543024513, 99.93239967722463746 ) ) ; -#16561 = CARTESIAN_POINT ( 'NONE', ( 12.31023268411626148, 134.2457138696073855, 93.71750156584897695 ) ) ; -#16562 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950931402, 137.3532831589782575, 178.0585834213011083 ) ) ; -#16563 = CARTESIAN_POINT ( 'NONE', ( -38.01370974153999782, 119.1992765896000037, 87.30104918352000709 ) ) ; -#16564 = CARTESIAN_POINT ( 'NONE', ( 12.63604222480166150, 130.6208451921540075, 90.14583135183596596 ) ) ; -#16565 = DIRECTION ( 'NONE', ( 0.0006039748319393677253, 3.488873499045632102E-19, 0.9999998176071845934 ) ) ; -#16566 = VERTEX_POINT ( 'NONE', #25763 ) ; -#16567 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#16568 = ORIENTED_EDGE ( 'NONE', *, *, #12054, .T. ) ; -#16569 = CARTESIAN_POINT ( 'NONE', ( 35.09291703857000044, 220.4002260771000010, 152.4718672074000381 ) ) ; -#16570 = CARTESIAN_POINT ( 'NONE', ( -26.00831778364999636, 205.1071295952009166, 76.12055741644040552 ) ) ; -#16571 = DIRECTION ( 'NONE', ( 0.0004161288024549962073, 0.5299192578740949955, 0.8480479980348919478 ) ) ; -#16572 = ORIENTED_EDGE ( 'NONE', *, *, #11701, .F. ) ; -#16573 = CARTESIAN_POINT ( 'NONE', ( 20.14888587518330354, 205.2606208450517329, 76.15744753280239365 ) ) ; -#16574 = CARTESIAN_POINT ( 'NONE', ( -8.048542123008331828, 160.5967930229313367, 99.81338747665230926 ) ) ; -#16575 = AXIS2_PLACEMENT_3D ( 'NONE', #6340, #22304, #9834 ) ; -#16576 = CIRCLE ( 'NONE', #39433, 6.500001098231858343 ) ; -#16577 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825829930067965, 0.0005734119044644985386 ) ) ; -#16578 = EDGE_CURVE ( 'NONE', #7841, #10482, #28618, .T. ) ; -#16579 = CONICAL_SURFACE ( 'NONE', #24483, 2.503093623396721146, 0.7853981633639495197 ) ; -#16580 = VERTEX_POINT ( 'NONE', #29225 ) ; -#16581 = CARTESIAN_POINT ( 'NONE', ( -25.50873731069575712, 209.2199388313156021, 75.57458662847975006 ) ) ; -#16582 = CARTESIAN_POINT ( 'NONE', ( 2.941278393888057341, 209.7096877029368613, 73.05672770647804271 ) ) ; -#16583 = ORIENTED_EDGE ( 'NONE', *, *, #27494, .T. ) ; -#16584 = EDGE_CURVE ( 'NONE', #15877, #31407, #28421, .T. ) ; -#16585 = FACE_OUTER_BOUND ( 'NONE', #25592, .T. ) ; -#16586 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28565, #38357, #29170, #13816, #1142, #35661, #26106, #25912, #16077, #6871 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16587 = ADVANCED_FACE ( 'NONE', ( #16517 ), #22725, .F. ) ; -#16588 = ORIENTED_EDGE ( 'NONE', *, *, #37749, .F. ) ; -#16589 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25018, #31341, #16573, #9466 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16590 = CARTESIAN_POINT ( 'NONE', ( 1.825277717689219870, 188.7045273156206520, 106.2966068932076240 ) ) ; -#16591 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18265, #27710, #22372, #24643, #9691, #34599, #30762, #2750, #6403, #18860 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.0004307675617671707360, 0.0008615351235343414720, 0.001292302685301512100, 0.001723070247068682944 ), - .UNSPECIFIED. ) ; -#16592 = CARTESIAN_POINT ( 'NONE', ( 28.25950385170297352, 125.5846682600628412, 89.14251585184922533 ) ) ; -#16593 = CARTESIAN_POINT ( 'NONE', ( -8.048542123480551425, 150.7617452742509556, 97.54278737913534769 ) ) ; -#16594 = EDGE_CURVE ( 'NONE', #36682, #34607, #7328, .T. ) ; -#16595 = VERTEX_POINT ( 'NONE', #396 ) ; -#16596 = VERTEX_POINT ( 'NONE', #20823 ) ; -#16597 = CARTESIAN_POINT ( 'NONE', ( 25.50429067071999967, 120.4343480257000039, 90.00774254085000337 ) ) ; -#16598 = LINE ( 'NONE', #19670, #22146 ) ; -#16599 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4044, #10409, #29001, #19776 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16601 = DIRECTION ( 'NONE', ( -0.0004270746993304995942, -0.7071067811865993091, -0.7071066522152992251 ) ) ; -#16600 = CARTESIAN_POINT ( 'NONE', ( -76.10777906862098519, 155.6625685549207105, 98.71533786495776042 ) ) ; -#16602 = FACE_OUTER_BOUND ( 'NONE', #31451, .T. ) ; -#16603 = CIRCLE ( 'NONE', #4203, 1.999999999983348431 ) ; -#16604 = AXIS2_PLACEMENT_3D ( 'NONE', #25367, #9022, #21505 ) ; -#16605 = ORIENTED_EDGE ( 'NONE', *, *, #36878, .T. ) ; -#16606 = CARTESIAN_POINT ( 'NONE', ( -35.44629553207012407, 109.6131156415000021, 90.28919351360151779 ) ) ; -#16607 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621345620, 0.1788331191967953704 ) ) ; -#16609 = ORIENTED_EDGE ( 'NONE', *, *, #9641, .T. ) ; -#16608 = VECTOR ( 'NONE', #36479, 1000.000000000000114 ) ; -#16610 = VERTEX_POINT ( 'NONE', #35718 ) ; -#16611 = CARTESIAN_POINT ( 'NONE', ( 2.623277854660710062, 209.6150308759818870, 75.72358690466917608 ) ) ; -#16612 = FACE_OUTER_BOUND ( 'NONE', #6020, .T. ) ; -#16613 = CARTESIAN_POINT ( 'NONE', ( -45.21698515504639460, 124.3314463512707846, 91.71916011353340537 ) ) ; -#16614 = LINE ( 'NONE', #10319, #26142 ) ; -#16615 = CARTESIAN_POINT ( 'NONE', ( 36.07326204741000453, 192.3427678687999958, 104.3838198541999986 ) ) ; -#16616 = ORIENTED_EDGE ( 'NONE', *, *, #5992, .F. ) ; -#16617 = VERTEX_POINT ( 'NONE', #33276 ) ; -#16618 = CARTESIAN_POINT ( 'NONE', ( -42.87041437821633139, 121.8978841230586170, 87.86525719409469559 ) ) ; -#16619 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498903273, 179.0675991014140607, 104.0619761093665971 ) ) ; -#16620 = LINE ( 'NONE', #3953, #2028 ) ; -#16621 = EDGE_LOOP ( 'NONE', ( #29357, #35243, #4747, #22785 ) ) ; -#16622 = ORIENTED_EDGE ( 'NONE', *, *, #27848, .T. ) ; -#16623 = PRODUCT ( 'MID360+\X2\76f8673a652f67b6\X0\6.24', 'MID360+\X2\76f8673a652f67b6\X0\6.24', '', ( #27422 ) ) ; -#16624 = FACE_OUTER_BOUND ( 'NONE', #30582, .T. ) ; -#16625 = ORIENTED_EDGE ( 'NONE', *, *, #9789, .F. ) ; -#16626 = EDGE_CURVE ( 'NONE', #13079, #29758, #5074, .T. ) ; -#16627 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5828, #39962, #20965, #5621 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16628 = EDGE_CURVE ( 'NONE', #37091, #23190, #7213, .T. ) ; -#16629 = VERTEX_POINT ( 'NONE', #11219 ) ; -#16630 = DIRECTION ( 'NONE', ( -0.0005884949961271457829, 0.2249510543439062482, -0.9743698870671264611 ) ) ; -#16631 = ORIENTED_EDGE ( 'NONE', *, *, #30279, .F. ) ; -#16632 = CARTESIAN_POINT ( 'NONE', ( -30.07200330635009067, 135.2897752519686776, 91.41834187752364471 ) ) ; -#16633 = AXIS2_PLACEMENT_3D ( 'NONE', #40382, #12385, #24883 ) ; -#16634 = CARTESIAN_POINT ( 'NONE', ( -0.3574740697902000219, 188.5380013795999901, 106.1066132219000053 ) ) ; -#16635 = CIRCLE ( 'NONE', #3586, 2.500000000031143088 ) ; -#16636 = AXIS2_PLACEMENT_3D ( 'NONE', #28776, #10183, #35079 ) ; -#16637 = LINE ( 'NONE', #39122, #27461 ) ; -#16638 = DIRECTION ( 'NONE', ( 0.6087614115774527823, 0.7729348350621608743, 0.1788331191968013101 ) ) ; -#16639 = EDGE_CURVE ( 'NONE', #21867, #1663, #26283, .T. ) ; -#16640 = ORIENTED_EDGE ( 'NONE', *, *, #3394, .T. ) ; -#16641 = AXIS2_PLACEMENT_3D ( 'NONE', #29105, #24141, #36594 ) ; -#16642 = FACE_OUTER_BOUND ( 'NONE', #30344, .T. ) ; -#16643 = CARTESIAN_POINT ( 'NONE', ( 17.33255171641533110, 121.2645175805946138, 177.4250592562015925 ) ) ; -#16644 = CARTESIAN_POINT ( 'NONE', ( 13.50019245297331949, 123.9864599348986616, 91.09745217655513727 ) ) ; -#16645 = EDGE_CURVE ( 'NONE', #27296, #38321, #2023, .T. ) ; -#16646 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825918840956979, 0.0005734119024144099241 ) ) ; -#16647 = ORIENTED_EDGE ( 'NONE', *, *, #33477, .F. ) ; -#16648 = CARTESIAN_POINT ( 'NONE', ( 23.65482006811145155, 115.6781945452533904, 89.75368254526981104 ) ) ; -#16649 = CARTESIAN_POINT ( 'NONE', ( -37.54611826410999953, 117.6150725292000061, 89.85907085683001583 ) ) ; -#16650 = EDGE_LOOP ( 'NONE', ( #15493, #31323, #342, #23998, #14789, #2675, #16840, #28340, #136, #23977, #17516 ) ) ; -#16651 = CARTESIAN_POINT ( 'NONE', ( -39.76913700811847718, 108.4405668372959468, 169.8253437122761795 ) ) ; -#16652 = ORIENTED_EDGE ( 'NONE', *, *, #12890, .T. ) ; -#16653 = CARTESIAN_POINT ( 'NONE', ( 12.93166457001120229, 158.3132409016616862, 96.19460342880938697 ) ) ; -#16654 = CARTESIAN_POINT ( 'NONE', ( 26.00081427186901095, 120.1020675870059762, 90.44387584870027297 ) ) ; -#16655 = CARTESIAN_POINT ( 'NONE', ( 2.730741220598960517, 190.9310047356335360, 106.4668625363826493 ) ) ; -#16656 = EDGE_LOOP ( 'NONE', ( #27976, #37872, #6961, #8267 ) ) ; -#16657 = ORIENTED_EDGE ( 'NONE', *, *, #12098, .T. ) ; -#16658 = FACE_BOUND ( 'NONE', #15917, .T. ) ; -#16659 = EDGE_LOOP ( 'NONE', ( #28363, #25461, #20325, #22795, #6827, #7579, #10161, #33354, #39179, #24971, #6745, #4741, #32749, #11692 ) ) ; -#16660 = CIRCLE ( 'NONE', #34293, 58.90509898902387675 ) ; -#16661 = ORIENTED_EDGE ( 'NONE', *, *, #10674, .T. ) ; -#16662 = VERTEX_POINT ( 'NONE', #1396 ) ; -#16663 = CARTESIAN_POINT ( 'NONE', ( -6.036394940235839002, 177.4973813401495875, 100.8859267458554854 ) ) ; -#16664 = VECTOR ( 'NONE', #36406, 1000.000000000000114 ) ; -#16665 = FACE_OUTER_BOUND ( 'NONE', #38317, .T. ) ; -#16666 = AXIS2_PLACEMENT_3D ( 'NONE', #24830, #9274, #34193 ) ; -#16667 = CIRCLE ( 'NONE', #39522, 48.00000000000002132 ) ; -#16668 = VERTEX_POINT ( 'NONE', #14288 ) ; -#16669 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#16670 = VECTOR ( 'NONE', #21398, 1000.000000000000114 ) ; -#16671 = CARTESIAN_POINT ( 'NONE', ( -6.036405711825560516, 134.8430548831865963, 93.35330002338830013 ) ) ; -#16672 = CARTESIAN_POINT ( 'NONE', ( 36.23883791301999935, 191.5582779153000104, 103.9620754990999956 ) ) ; -#16673 = LINE ( 'NONE', #19345, #21599 ) ; -#16674 = ORIENTED_EDGE ( 'NONE', *, *, #25214, .F. ) ; -#16675 = PLANE ( 'NONE', #22598 ) ; -#16676 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#16677 = FACE_OUTER_BOUND ( 'NONE', #33525, .T. ) ; -#16678 = ORIENTED_EDGE ( 'NONE', *, *, #37016, .F. ) ; -#16679 = LINE ( 'NONE', #33787, #25582 ) ; -#16680 = PLANE ( 'NONE', #34209 ) ; -#16681 = CARTESIAN_POINT ( 'NONE', ( 23.32645555946442073, 115.6131185450060030, 87.75350244859328086 ) ) ; -#16682 = EDGE_CURVE ( 'NONE', #39827, #9576, #37496, .T. ) ; -#16683 = EDGE_CURVE ( 'NONE', #13511, #16043, #19878, .T. ) ; -#16684 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455648501747, -31.54510897440487938, 136.4474729010642875 ) ) ; -#16685 = CARTESIAN_POINT ( 'NONE', ( -11.79202345736525892, 125.7774812735008254, 176.8918472601677365 ) ) ; -#16686 = ORIENTED_EDGE ( 'NONE', *, *, #1317, .T. ) ; -#16687 = CARTESIAN_POINT ( 'NONE', ( -42.38963504733576571, 73.00513959036860001, 297.5841473069626772 ) ) ; -#16688 = CARTESIAN_POINT ( 'NONE', ( -35.44810745648619132, 109.6131156741000154, 87.28919406056773767 ) ) ; -#16689 = CARTESIAN_POINT ( 'NONE', ( 36.40838257471642692, 191.8167960244688288, 104.3619212928119140 ) ) ; -#16690 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29589, #20165, #1779, #2193, #26734, #27149 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16691 = CARTESIAN_POINT ( 'NONE', ( 12.64033828019901939, 130.2859757627005877, 92.71761759901836797 ) ) ; -#16692 = CARTESIAN_POINT ( 'NONE', ( -25.35636387728000329, 191.7351922414000001, 104.5598766893999993 ) ) ; -#16693 = CONICAL_SURFACE ( 'NONE', #24556, 2.502999999887194349, 0.7853981633984101762 ) ; -#16694 = DIRECTION ( 'NONE', ( -0.1305262373691798983, 0.9659583596717404852, 0.2233547598295697878 ) ) ; -#16695 = CARTESIAN_POINT ( 'NONE', ( 21.00010498221761779, 176.2223731533329953, 100.4954345433673240 ) ) ; -#16696 = CARTESIAN_POINT ( 'NONE', ( 39.00044143696274546, 135.4860176042719786, 291.5349886458730566 ) ) ; -#16697 = CARTESIAN_POINT ( 'NONE', ( 26.71555981742730168, 123.8732672728377793, 90.80094690554606984 ) ) ; -#16698 = EDGE_LOOP ( 'NONE', ( #40054, #37536, #1713, #7627, #13823 ) ) ; -#16699 = VECTOR ( 'NONE', #25399, 1000.000000000000114 ) ; -#16700 = DIRECTION ( 'NONE', ( -0.5987319967475925875, -0.8009494341533932582, 0.000000000000000000 ) ) ; -#16701 = AXIS2_PLACEMENT_3D ( 'NONE', #16384, #12724, #651 ) ; -#16702 = CARTESIAN_POINT ( 'NONE', ( -15.87117416798851366, 146.8921292067080628, 179.7466459197605957 ) ) ; -#16703 = EDGE_CURVE ( 'NONE', #21152, #39877, #13876, .T. ) ; -#16704 = EDGE_LOOP ( 'NONE', ( #8285, #29475, #5924, #15664 ) ) ; -#16705 = LINE ( 'NONE', #10398, #15915 ) ; -#16706 = LINE ( 'NONE', #4229, #35507 ) ; -#16707 = CARTESIAN_POINT ( 'NONE', ( -76.10807331609903770, 155.7904255491852723, 98.23170401357633352 ) ) ; -#16708 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319401643971 ) ) ; -#16709 = CARTESIAN_POINT ( 'NONE', ( 16.55837427060546219, 127.1115566547025821, 154.7760191776372380 ) ) ; -#16710 = DIRECTION ( 'NONE', ( 0.0005884949961156549746, -0.2249510543439098842, 0.9743698870671255730 ) ) ; -#16711 = ORIENTED_EDGE ( 'NONE', *, *, #14172, .T. ) ; -#16712 = ORIENTED_EDGE ( 'NONE', *, *, #4545, .F. ) ; -#16713 = LINE ( 'NONE', #26550, #4090 ) ; -#16714 = CARTESIAN_POINT ( 'NONE', ( -2.850522251479513436, 209.7115537078749128, 76.06022745297526910 ) ) ; -#16715 = CARTESIAN_POINT ( 'NONE', ( 36.57174901144423274, 117.0762946090158607, 87.24569587203919241 ) ) ; -#16716 = LINE ( 'NONE', #38404, #15438 ) ; -#16717 = ORIENTED_EDGE ( 'NONE', *, *, #30225, .F. ) ; -#16718 = CARTESIAN_POINT ( 'NONE', ( 13.81047920904208226, 125.0581942443353114, 174.4028524411866954 ) ) ; -#16719 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927823695848, 0.0005734119022063523946 ) ) ; -#16720 = AXIS2_PLACEMENT_3D ( 'NONE', #19582, #25750, #28996 ) ; -#16721 = EDGE_LOOP ( 'NONE', ( #26602, #37447, #29893, #1564, #3493, #27843, #39102, #27913, #35542, #6491 ) ) ; -#16722 = VECTOR ( 'NONE', #28343, 1000.000000000000000 ) ; -#16723 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #235, #5781, #5976, #18231 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16724 = CARTESIAN_POINT ( 'NONE', ( -3.336611124200936640, 129.4601111755350189, 89.54315797652932929 ) ) ; -#16725 = ORIENTED_EDGE ( 'NONE', *, *, #38382, .F. ) ; -#16726 = CARTESIAN_POINT ( 'NONE', ( 36.43042111832376406, 191.6595748262901395, 106.3773235261021597 ) ) ; -#16727 = AXIS2_PLACEMENT_3D ( 'NONE', #22484, #18981, #37800 ) ; -#16728 = CARTESIAN_POINT ( 'NONE', ( -29.94810855088000423, 104.1131156701966916, 87.28587219915669948 ) ) ; -#16729 = AXIS2_PLACEMENT_3D ( 'NONE', #7945, #29229, #23291 ) ; -#16730 = ADVANCED_FACE ( 'NONE', ( #26565 ), #14228, .F. ) ; -#16731 = EDGE_CURVE ( 'NONE', #26863, #8041, #23693, .T. ) ; -#16732 = FACE_OUTER_BOUND ( 'NONE', #31390, .T. ) ; -#16733 = FACE_OUTER_BOUND ( 'NONE', #10412, .T. ) ; -#16734 = ORIENTED_EDGE ( 'NONE', *, *, #22302, .T. ) ; -#16735 = ORIENTED_EDGE ( 'NONE', *, *, #34133, .T. ) ; -#16736 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16737 = FACE_OUTER_BOUND ( 'NONE', #1305, .T. ) ; -#16738 = CARTESIAN_POINT ( 'NONE', ( 44.05294553655904366, 113.2635659203072578, 86.28842023171608844 ) ) ; -#16739 = CARTESIAN_POINT ( 'NONE', ( -37.92200784295000204, 191.3253432445999920, 104.2385424362999942 ) ) ; -#16740 = ORIENTED_EDGE ( 'NONE', *, *, #30703, .F. ) ; -#16741 = CARTESIAN_POINT ( 'NONE', ( 23.36018451437981369, 181.9417229093960771, 101.9854922266229664 ) ) ; -#16742 = LINE ( 'NONE', #7953, #26062 ) ; -#16743 = DIRECTION ( 'NONE', ( 0.7066905299392122197, 0.1591580245907027458, -0.6893890179736117396 ) ) ; -#16744 = AXIS2_PLACEMENT_3D ( 'NONE', #18604, #2886, #25188 ) ; -#16745 = CARTESIAN_POINT ( 'NONE', ( -18.59070810293174603, 148.9276284220111393, 180.2165354988448200 ) ) ; -#16746 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27050, #28738, #19711, #19515, #4379, #38715 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( -0.002794158215913641278, -0.0009957982206659000447, 0.0008025617745818411884 ), - .UNSPECIFIED. ) ; -#16747 = CONICAL_SURFACE ( 'NONE', #22008, 2.500000000044046544, 0.7853981634220001951 ) ; -#16748 = DIRECTION ( 'NONE', ( -0.0005884949961221202890, 0.2249510543439054433, -0.9743698870671265722 ) ) ; -#16749 = DIRECTION ( 'NONE', ( 0.0005884949961252946161, -0.2249510543439068866, 0.9743698870671261281 ) ) ; -#16750 = ADVANCED_FACE ( 'NONE', ( #36362 ), #4668, .T. ) ; -#16751 = CARTESIAN_POINT ( 'NONE', ( -3.090309791701999931, 208.8048984618000077, 73.00436043185000301 ) ) ; -#16752 = CARTESIAN_POINT ( 'NONE', ( 38.22486551803000765, 118.9813135233000025, 90.39832425324000553 ) ) ; -#16753 = ORIENTED_EDGE ( 'NONE', *, *, #2171, .T. ) ; -#16754 = VECTOR ( 'NONE', #36239, 1000.000000000000000 ) ; -#16755 = FACE_OUTER_BOUND ( 'NONE', #9707, .T. ) ; -#16756 = CARTESIAN_POINT ( 'NONE', ( -36.00791524158660195, 192.2004950762134854, 106.4370239608170010 ) ) ; -#16757 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319381693566 ) ) ; -#16758 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927787594355, 0.0005734119022079395582 ) ) ; -#16759 = ORIENTED_EDGE ( 'NONE', *, *, #5662, .T. ) ; -#16760 = EDGE_LOOP ( 'NONE', ( #17872, #23048, #16168, #34569 ) ) ; -#16761 = ORIENTED_EDGE ( 'NONE', *, *, #31507, .T. ) ; -#16762 = CARTESIAN_POINT ( 'NONE', ( -26.00869527696544381, 209.3199455192979315, 76.07456294362603444 ) ) ; -#16763 = EDGE_CURVE ( 'NONE', #27517, #15784, #26974, .T. ) ; -#16764 = CARTESIAN_POINT ( 'NONE', ( -42.83272783108322557, 107.4558756614410697, 150.2543767220365680 ) ) ; -#16765 = LINE ( 'NONE', #26607, #14819 ) ; -#16766 = ORIENTED_EDGE ( 'NONE', *, *, #22096, .T. ) ; -#16767 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -3.519737326604822600E-16, 0.0006039748319386522603 ) ) ; -#16768 = ADVANCED_FACE ( 'NONE', ( #39009 ), #20753, .T. ) ; -#16769 = CARTESIAN_POINT ( 'NONE', ( 20.00175897098971589, 118.8155681873422651, 90.25573236258343002 ) ) ; -#16770 = CARTESIAN_POINT ( 'NONE', ( -38.69784441830000077, 119.3720474567000025, 87.61528327729999432 ) ) ; -#16771 = FACE_OUTER_BOUND ( 'NONE', #7160, .T. ) ; -#16772 = VERTEX_POINT ( 'NONE', #17530 ) ; -#16773 = FACE_OUTER_BOUND ( 'NONE', #21341, .T. ) ; -#16774 = CIRCLE ( 'NONE', #12249, 2.000000002639695573 ) ; -#16775 = ORIENTED_EDGE ( 'NONE', *, *, #19168, .F. ) ; -#16776 = CARTESIAN_POINT ( 'NONE', ( 6.026693642215255053, 134.9199437178238838, 90.79804054718465522 ) ) ; -#16777 = CARTESIAN_POINT ( 'NONE', ( -45.26910127184291355, 115.3600147242497655, 130.2183997636157358 ) ) ; -#16778 = EDGE_CURVE ( 'NONE', #15784, #33558, #11023, .T. ) ; -#16779 = EDGE_CURVE ( 'NONE', #27307, #15773, #10622, .T. ) ; -#16780 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#16781 = AXIS2_PLACEMENT_3D ( 'NONE', #21365, #36681, #30560 ) ; -#16782 = CARTESIAN_POINT ( 'NONE', ( 46.20495712151593182, 125.4530955044509994, 88.75919419801047638 ) ) ; -#16783 = ADVANCED_FACE ( 'NONE', ( #7526 ), #32485, .F. ) ; -#16784 = ORIENTED_EDGE ( 'NONE', *, *, #15057, .F. ) ; -#16785 = CARTESIAN_POINT ( 'NONE', ( -1.677606480948000023, 188.9082371776000002, 103.2668395941000057 ) ) ; -#16786 = EDGE_CURVE ( 'NONE', #36559, #36424, #23308, .T. ) ; -#16787 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971551247 ) ) ; -#16788 = CARTESIAN_POINT ( 'NONE', ( 2.942644232360999812, 190.8797677718000045, 106.6729900079999993 ) ) ; -#16789 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19091, #15632, #28127, #7021 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16790 = ORIENTED_EDGE ( 'NONE', *, *, #12874, .T. ) ; -#16791 = VERTEX_POINT ( 'NONE', #24106 ) ; -#16792 = LINE ( 'NONE', #39275, #22480 ) ; -#16793 = CARTESIAN_POINT ( 'NONE', ( 19.98232544185748694, 209.7096131673859816, 76.04619115725449774 ) ) ; -#16794 = VERTEX_POINT ( 'NONE', #40217 ) ; -#16795 = EDGE_LOOP ( 'NONE', ( #13548, #19645, #35248, #26630 ) ) ; -#16796 = CARTESIAN_POINT ( 'NONE', ( -25.50111726777775090, 120.6553742016506874, 88.03695713991920968 ) ) ; -#16797 = EDGE_LOOP ( 'NONE', ( #2523, #13271, #2551, #37720 ) ) ; -#16798 = CARTESIAN_POINT ( 'NONE', ( -26.55624928970721399, 189.5398351624320128, 103.4276817862043885 ) ) ; -#16799 = CARTESIAN_POINT ( 'NONE', ( 8.708260088791295317, 196.5784692043456516, 103.8697732926175235 ) ) ; -#16800 = DIRECTION ( 'NONE', ( -0.0005734119072319287039, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#16801 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27290, #33992, #2530, #15000, #20722, #39931, #8877, #11317, #21350, #23798, #2738, #36254, #5170, #17639, #25772, #35331, #13492, #23098, #7537, #25575 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000420219, 0.1875000000000630329, 0.2187500000000735523, 0.2343750000000709710, 0.2500000000000683897, 0.5000000000000383027, 0.6250000000000253131, 0.6875000000000132117, 0.7187500000000069944, 0.7343750000000068834, 0.7500000000000066613, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16802 = ORIENTED_EDGE ( 'NONE', *, *, #26909, .T. ) ; -#16803 = CARTESIAN_POINT ( 'NONE', ( 25.66683533177824472, 120.1550886336836328, 90.09407280630837533 ) ) ; -#16804 = CIRCLE ( 'NONE', #20043, 2.499999999997815525 ) ; -#16805 = AXIS2_PLACEMENT_3D ( 'NONE', #17205, #27266, #18014 ) ; -#16807 = DIRECTION ( 'NONE', ( -0.9999998268367383814, -0.0001323827281007119180, 0.0005734119867657175469 ) ) ; -#16806 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16808 = LINE ( 'NONE', #3936, #2707 ) ; -#16809 = ORIENTED_EDGE ( 'NONE', *, *, #15527, .T. ) ; -#16810 = CARTESIAN_POINT ( 'NONE', ( -17.26178222639411430, 121.7713432978476220, 175.3684242141576703 ) ) ; -#16811 = CARTESIAN_POINT ( 'NONE', ( -27.19659902433550158, 110.6131156702000027, 89.78421081230766276 ) ) ; -#16812 = ORIENTED_EDGE ( 'NONE', *, *, #11253, .F. ) ; -#16813 = EDGE_LOOP ( 'NONE', ( #20550, #18354, #4026, #27437, #33406, #27549 ) ) ; -#16814 = CARTESIAN_POINT ( 'NONE', ( -37.02440097146959630, 118.0188495538648965, 87.29014610246385075 ) ) ; -#16815 = EDGE_CURVE ( 'NONE', #11960, #27919, #39364, .T. ) ; -#16816 = CARTESIAN_POINT ( 'NONE', ( -46.09612443885006883, 125.3278102177660429, 91.69387951472775455 ) ) ; -#16817 = DIRECTION ( 'NONE', ( -0.6983012566254244158, 0.000000000000000000, -0.7158039920225042207 ) ) ; -#16818 = EDGE_CURVE ( 'NONE', #16617, #19286, #33479, .T. ) ; -#16819 = ORIENTED_EDGE ( 'NONE', *, *, #2979, .T. ) ; -#16820 = EDGE_LOOP ( 'NONE', ( #8305, #12383, #24010, #10937 ) ) ; -#16821 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#16822 = CARTESIAN_POINT ( 'NONE', ( 22.50176647125079654, 173.8430425847558354, 102.8561530174562222 ) ) ; -#16823 = EDGE_CURVE ( 'NONE', #40349, #23375, #9709, .T. ) ; -#16824 = ORIENTED_EDGE ( 'NONE', *, *, #26589, .F. ) ; -#16825 = CARTESIAN_POINT ( 'NONE', ( -35.43127413710199392, 192.7876450715299939, 106.8815844585819974 ) ) ; -#16826 = AXIS2_PLACEMENT_3D ( 'NONE', #5112, #4508, #10873 ) ; -#16827 = LINE ( 'NONE', #29327, #30776 ) ; -#16828 = ORIENTED_EDGE ( 'NONE', *, *, #5291, .T. ) ; -#16829 = CARTESIAN_POINT ( 'NONE', ( 39.04990644688274415, 118.8856079855554668, 89.67794042206942606 ) ) ; -#16830 = AXIS2_PLACEMENT_3D ( 'NONE', #38535, #7453, #4389 ) ; -#16831 = CARTESIAN_POINT ( 'NONE', ( -44.77033340054011745, 105.5798858094823771, 174.2946625126398033 ) ) ; -#16832 = CARTESIAN_POINT ( 'NONE', ( -14.22265864990228401, 129.0629248693782074, 176.7848948385215806 ) ) ; -#16833 = CARTESIAN_POINT ( 'NONE', ( -35.45484958737997516, 205.1071295952006324, 76.12626288494027449 ) ) ; -#16834 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8057, #35636, #8269, #14000 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16835 = VERTEX_POINT ( 'NONE', #9167 ) ; -#16836 = DIRECTION ( 'NONE', ( -0.3756662126443757188, -0.7425674685094612038, 0.5544983781661413369 ) ) ; -#16837 = CARTESIAN_POINT ( 'NONE', ( 22.73844078587000084, 180.7017300104000128, 28.07991271570000080 ) ) ; -#16838 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#16839 = CARTESIAN_POINT ( 'NONE', ( -20.01839880255527149, 211.0884570636477520, 76.07059838194729195 ) ) ; -#16840 = ORIENTED_EDGE ( 'NONE', *, *, #2537, .T. ) ; -#16841 = CARTESIAN_POINT ( 'NONE', ( 32.08976031478660929, 77.14301703112181485, 318.8298887698903741 ) ) ; -#16842 = CARTESIAN_POINT ( 'NONE', ( -36.08315564226000305, 112.4034012541000038, 89.65458067341999993 ) ) ; -#16843 = EDGE_LOOP ( 'NONE', ( #11732, #13513, #36262, #16032 ) ) ; -#16844 = ORIENTED_EDGE ( 'NONE', *, *, #28476, .F. ) ; -#16845 = ADVANCED_FACE ( 'NONE', ( #24316 ), #18733, .T. ) ; -#16846 = CARTESIAN_POINT ( 'NONE', ( -30.11038580418999899, 151.9652147204000130, 28.07991271570000080 ) ) ; -#16847 = ADVANCED_FACE ( 'NONE', ( #24922 ), #36758, .F. ) ; -#16848 = AXIS2_PLACEMENT_3D ( 'NONE', #23145, #7589, #22949 ) ; -#16849 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16850 = ADVANCED_FACE ( 'NONE', ( #27597 ), #34550, .F. ) ; -#16851 = CARTESIAN_POINT ( 'NONE', ( -56.27298699561663398, 71.65331048429315786, 282.5958934331605406 ) ) ; -#16852 = ORIENTED_EDGE ( 'NONE', *, *, #24941, .T. ) ; -#16853 = EDGE_CURVE ( 'NONE', #29958, #9058, #34281, .T. ) ; -#16854 = ORIENTED_EDGE ( 'NONE', *, *, #36939, .T. ) ; -#16855 = DIRECTION ( 'NONE', ( 0.0005884949961212385073, -0.2249510543439022514, 0.9743698870671273493 ) ) ; -#16856 = VECTOR ( 'NONE', #3940, 1000.000000000000227 ) ; -#16857 = EDGE_LOOP ( 'NONE', ( #5313, #4924, #22974 ) ) ; -#16858 = ORIENTED_EDGE ( 'NONE', *, *, #10435, .T. ) ; -#16859 = CARTESIAN_POINT ( 'NONE', ( 1.918799663737837724, 189.5286487069128327, 105.8885755798531250 ) ) ; -#16860 = DIRECTION ( 'NONE', ( 0.0002393071182785538528, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#16861 = ORIENTED_EDGE ( 'NONE', *, *, #12326, .T. ) ; -#16862 = CARTESIAN_POINT ( 'NONE', ( 37.23485478980474994, 185.6815848316524011, 105.5773190055030142 ) ) ; -#16863 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 2.782262518445068689E-15, -0.0006039748319343033085 ) ) ; -#16864 = CARTESIAN_POINT ( 'NONE', ( 38.27239922564999830, 118.3969922751000041, 87.79417198072999895 ) ) ; -#16865 = CARTESIAN_POINT ( 'NONE', ( 36.33552280992999783, 191.7504287502000011, 104.2396449161000049 ) ) ; -#16866 = CARTESIAN_POINT ( 'NONE', ( 41.98377182996610202, 80.72020747014904885, 291.5331867890723743 ) ) ; -#16867 = ADVANCED_FACE ( 'NONE', ( #37759 ), #6675, .T. ) ; -#16868 = VERTEX_POINT ( 'NONE', #19143 ) ; -#16869 = CARTESIAN_POINT ( 'NONE', ( -23.35875116767058302, 176.9906340971583063, 103.4393502540127088 ) ) ; -#16870 = ORIENTED_EDGE ( 'NONE', *, *, #40140, .T. ) ; -#16871 = CARTESIAN_POINT ( 'NONE', ( -22.49823373578437113, 151.2926910092157868, 97.67409313451828723 ) ) ; -#16872 = CARTESIAN_POINT ( 'NONE', ( -35.95638742416511491, 209.7096535813600156, 73.58022093100927918 ) ) ; -#16873 = CARTESIAN_POINT ( 'NONE', ( 45.16919206690911892, 186.2581417638802463, 106.4094479429941060 ) ) ; -#16874 = VERTEX_POINT ( 'NONE', #9770 ) ; -#16875 = EDGE_CURVE ( 'NONE', #33874, #32027, #5104, .T. ) ; -#16876 = CARTESIAN_POINT ( 'NONE', ( -21.97178402990095236, 135.2954952222275153, 90.90161795910944420 ) ) ; -#16877 = AXIS2_PLACEMENT_3D ( 'NONE', #7980, #10866, #20241 ) ; -#16878 = CARTESIAN_POINT ( 'NONE', ( 0.8484015457715478048, 189.0205269402587760, 103.6908266210117660 ) ) ; -#16879 = CARTESIAN_POINT ( 'NONE', ( -15.99823486132897266, 118.9409032897876841, 90.20116722531848552 ) ) ; -#16880 = AXIS2_PLACEMENT_3D ( 'NONE', #30233, #27192, #29838 ) ; -#16881 = PLANE ( 'NONE', #37337 ) ; -#16882 = EDGE_LOOP ( 'NONE', ( #30781, #37962, #35383, #12734, #28830, #26947 ) ) ; -#16883 = CARTESIAN_POINT ( 'NONE', ( -26.12831152884999852, 191.8782704244000001, 103.7981124760000000 ) ) ; -#16884 = FACE_OUTER_BOUND ( 'NONE', #18275, .T. ) ; -#16885 = VECTOR ( 'NONE', #32406, 1000.000000000000114 ) ; -#16886 = CARTESIAN_POINT ( 'NONE', ( 38.15045221970718359, 118.4868570840783377, 87.66883015867043127 ) ) ; -#16887 = DIRECTION ( 'NONE', ( 0.0006039748319381496242, 1.231904546584163304E-14, 0.9999998176071845934 ) ) ; -#16888 = DIRECTION ( 'NONE', ( -0.6773442687123943928, -0.7356661890031861439, 0.000000000000000000 ) ) ; -#16889 = ORIENTED_EDGE ( 'NONE', *, *, #3084, .T. ) ; -#16890 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15644, #40377, #15257, #18690 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16891 = CARTESIAN_POINT ( 'NONE', ( 2.879966871558743868, 207.7152227517433403, 77.21019060626942121 ) ) ; -#16892 = CARTESIAN_POINT ( 'NONE', ( -76.10807331611901816, 155.7750440820818199, 98.22815292147127764 ) ) ; -#16893 = DIRECTION ( 'NONE', ( 0.9914448496618609719, 0.1271951731318045342, 0.02930013670514376375 ) ) ; -#16894 = CARTESIAN_POINT ( 'NONE', ( 36.45662811238000245, 191.0198550572999920, 106.6760028587000022 ) ) ; -#16895 = CARTESIAN_POINT ( 'NONE', ( 36.06506602550999929, 192.5926268146000098, 106.3586798020999993 ) ) ; -#16896 = EDGE_CURVE ( 'NONE', #31339, #11449, #8171, .T. ) ; -#16897 = CARTESIAN_POINT ( 'NONE', ( -16.15354643030308424, 152.0177870148501427, 180.9315030652959422 ) ) ; -#16898 = ADVANCED_FACE ( 'NONE', ( #28970 ), #7278, .F. ) ; -#16899 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825822545, 158.2317141435470376, 98.73576230545255328 ) ) ; -#16900 = ORIENTED_EDGE ( 'NONE', *, *, #10530, .T. ) ; -#16901 = CARTESIAN_POINT ( 'NONE', ( -5.669507493902576023, 181.2998697191823680, 104.3463240144063633 ) ) ; -#16903 = AXIS2_PLACEMENT_3D ( 'NONE', #17315, #29826, #29421 ) ; -#16902 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#16904 = CARTESIAN_POINT ( 'NONE', ( 35.55163102684422682, 113.4589874760156647, 87.24631199773988044 ) ) ; -#16905 = ADVANCED_FACE ( 'NONE', ( #25317 ), #37112, .F. ) ; -#16906 = AXIS2_PLACEMENT_3D ( 'NONE', #25684, #28534, #34633 ) ; -#16907 = LINE ( 'NONE', #24034, #13483 ) ; -#16908 = VERTEX_POINT ( 'NONE', #35274 ) ; -#16909 = PLANE ( 'NONE', #35031 ) ; -#16910 = CARTESIAN_POINT ( 'NONE', ( -45.39636767568900666, 130.6771924050837868, 92.41530714614147257 ) ) ; -#16911 = AXIS2_PLACEMENT_3D ( 'NONE', #8888, #18254, #30757 ) ; -#16912 = VERTEX_POINT ( 'NONE', #25517 ) ; -#16913 = ADVANCED_FACE ( 'NONE', ( #3603 ), #10177, .T. ) ; -#16914 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927790412197, -0.0005734119022076163575 ) ) ; -#16915 = CARTESIAN_POINT ( 'NONE', ( 23.77969838655435453, 115.1895133759981036, 87.25342195007469570 ) ) ; -#16916 = ORIENTED_EDGE ( 'NONE', *, *, #5442, .T. ) ; -#16917 = CARTESIAN_POINT ( 'NONE', ( 36.41030898367129964, 191.6852911315839663, 106.3796197328945965 ) ) ; -#16918 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19467, #3327, #25233, #25637, #25834, #16590, #37680, #15794, #28883, #9679, #15998, #25431, #38280, #2094, #13950, #4735, #8221, #17194, #1885, #29697 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), - ( 1.873882562120391099E-11, 0.0004916302229572380202, 0.0009832604271756500113, 0.001966520835612442335, 0.002458151039830843050, 0.002949781244049243332, 0.003441411448267643180, 0.003687226550376838767, 0.003810134101431441548, 0.003933041652486044329 ), - .UNSPECIFIED. ) ; -#16919 = CARTESIAN_POINT ( 'NONE', ( -35.44810745648619132, 109.6131156741000154, 87.28919406056773767 ) ) ; -#16920 = PLANE ( 'NONE', #5871 ) ; -#16921 = CARTESIAN_POINT ( 'NONE', ( 15.66686184794137127, 174.4404117407328840, 100.2583057336249368 ) ) ; -#16922 = ORIENTED_EDGE ( 'NONE', *, *, #28727, .F. ) ; -#16923 = EDGE_CURVE ( 'NONE', #4793, #38952, #33501, .T. ) ; -#16924 = CARTESIAN_POINT ( 'NONE', ( -13.49852954173680430, 158.2273469405900812, 98.75649715832007303 ) ) ; -#16925 = CARTESIAN_POINT ( 'NONE', ( -3.683314158571560082, 176.1742929228452113, 100.3281879834612909 ) ) ; -#16926 = CARTESIAN_POINT ( 'NONE', ( 20.94827535171210897, 136.6018947531004244, 91.17730147031002730 ) ) ; -#16927 = CARTESIAN_POINT ( 'NONE', ( 48.05258722404280292, 141.3314364184359420, 335.5134981609783154 ) ) ; -#16928 = ORIENTED_EDGE ( 'NONE', *, *, #12936, .F. ) ; -#16929 = ORIENTED_EDGE ( 'NONE', *, *, #9777, .F. ) ; -#16930 = ORIENTED_EDGE ( 'NONE', *, *, #21006, .F. ) ; -#16931 = CARTESIAN_POINT ( 'NONE', ( -21.69612205307337760, 152.4962460410746417, 197.7980205213018507 ) ) ; -#16932 = AXIS2_PLACEMENT_3D ( 'NONE', #12372, #5636, #18288 ) ; -#16933 = VECTOR ( 'NONE', #34807, 1000.000000000000114 ) ; -#16934 = CARTESIAN_POINT ( 'NONE', ( 38.22927031300470446, 118.1319447778811735, 89.66605183978815319 ) ) ; -#16935 = LINE ( 'NONE', #1009, #5824 ) ; -#16936 = CONICAL_SURFACE ( 'NONE', #27460, 2.499999999973934628, 0.7853981633778842619 ) ; -#16937 = AXIS2_PLACEMENT_3D ( 'NONE', #37401, #180, #18760 ) ; -#16938 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1457, #11275, #4728, #29284 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16939 = CIRCLE ( 'NONE', #3239, 9.000000000000008882 ) ; -#16940 = CARTESIAN_POINT ( 'NONE', ( 13.85658554640870932, 150.4134353348987929, 179.9607612626138007 ) ) ; -#16941 = CARTESIAN_POINT ( 'NONE', ( 25.41600307607999909, 190.8124423181000111, 106.1157579006000020 ) ) ; -#16942 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3409, #37173, #5886, #6474 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.003918820842042696796, 0.004627366295791773831 ), - .UNSPECIFIED. ) ; -#16943 = CARTESIAN_POINT ( 'NONE', ( -6.036122723735069862, 176.7409673271154702, 103.0261968760796378 ) ) ; -#16944 = CARTESIAN_POINT ( 'NONE', ( 38.30887535778000341, 118.7291051865999947, 90.10309265731001460 ) ) ; -#16945 = ORIENTED_EDGE ( 'NONE', *, *, #22437, .T. ) ; -#16946 = CARTESIAN_POINT ( 'NONE', ( 42.53291556922801675, 121.0577657085915035, 91.31834487752931295 ) ) ; -#16947 = CARTESIAN_POINT ( 'NONE', ( -28.26185612672702518, 125.5768230428473373, 89.17483656727264929 ) ) ; -#16948 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391911088 ) ) ; -#16949 = EDGE_CURVE ( 'NONE', #17966, #27038, #32243, .T. ) ; -#16950 = EDGE_CURVE ( 'NONE', #36191, #11452, #16480, .T. ) ; -#16951 = CARTESIAN_POINT ( 'NONE', ( -20.50065345750364898, 194.0643729098902384, 103.3282459304506773 ) ) ; -#16952 = VERTEX_POINT ( 'NONE', #35074 ) ; -#16953 = VERTEX_POINT ( 'NONE', #9972 ) ; -#16954 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #21675, #27820, #3041, #36999, #37402, #9800, #22274, #8999, #30869, #12648 ), - ( #12066, #37788, #21474, #31465, #34496, #34114, #25143, #18974, #15322, #18165 ), - ( #5718, #24544, #37590, #9591, #30671, #6109, #18565, #3237, #21865, #2667 ), - ( #12449, #22069, #3430, #33916, #28403, #9393, #376, #18368, #5914, #27621 ), - ( #40246, #12259, #181, #15908, #34312, #12863, #24749, #15712, #37201, #9197 ), - ( #31068, #6304, #15522, #28011, #40448, #24948, #18761, #31259, #776, #10797 ), - ( #6911, #38584, #38775, #4442, #7302, #35491, #13850, #7107, #22474, #10401 ), - ( #19767, #16504, #34897, #3832, #19382, #28993, #16895, #34701, #37992, #16312 ), - ( #19578, #16118, #31876, #10598, #28796, #22872, #23067, #569, #25947, #22677 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 4 ), - ( 4, 3, 3, 4 ), - ( 7.328236918486999764E-07, 0.2500013691263999749, 0.5000009923943999901, 0.6250008040283000499, 0.7500006156623000297, 0.8750004272963000096, 0.9999999999973999687 ), - ( 0.07073812993396939863, 0.07915448979703999799, 0.9207904761041000308, 0.9292068359671706856 ), - .UNSPECIFIED. ) ; -#16955 = VERTEX_POINT ( 'NONE', #22446 ) ; -#16956 = CARTESIAN_POINT ( 'NONE', ( -13.49987458194983425, 124.7394176591053423, 88.97259030931672896 ) ) ; -#16957 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34894, #9995, #10202, #16307, #19163, #565, #13060, #23063, #25541, #35488 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16958 = DIRECTION ( 'NONE', ( 0.0005884949961251158311, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#16959 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -0.000000000000000000, 0.0006039748319387908213 ) ) ; -#16960 = ORIENTED_EDGE ( 'NONE', *, *, #19991, .F. ) ; -#16961 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999905853, 179.7376864902958005, 101.1595092800906457 ) ) ; -#16962 = AXIS2_PLACEMENT_3D ( 'NONE', #27325, #24253, #14020 ) ; -#16963 = CARTESIAN_POINT ( 'NONE', ( -35.33451947138878069, 160.3133637736180219, 188.0241402224691569 ) ) ; -#16964 = CARTESIAN_POINT ( 'NONE', ( 44.88493990080282714, 186.3882837704542510, 107.4179575081553253 ) ) ; -#16965 = CARTESIAN_POINT ( 'NONE', ( -39.60525137617000269, 120.0401714335000207, 87.73240259396999363 ) ) ; -#16966 = CARTESIAN_POINT ( 'NONE', ( -26.01186646957073378, 210.6300580106999973, 73.07250685818237912 ) ) ; -#16967 = EDGE_LOOP ( 'NONE', ( #39253, #23884, #33969, #28917, #18325, #11727, #30874, #26358, #27570 ) ) ; -#16968 = CARTESIAN_POINT ( 'NONE', ( -37.31440426593247395, 172.2715631620466468, 165.0215178663606252 ) ) ; -#16969 = CIRCLE ( 'NONE', #16310, 2.499999999420936092 ) ; -#16970 = VERTEX_POINT ( 'NONE', #7080 ) ; -#16971 = CARTESIAN_POINT ( 'NONE', ( -46.25461004409986288, 125.6172549309450801, 93.81340741558051377 ) ) ; -#16972 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566790 ) ) ; -#16973 = CARTESIAN_POINT ( 'NONE', ( 43.07948244848589070, 114.2049668346823239, 142.4505081202680401 ) ) ; -#16974 = ORIENTED_EDGE ( 'NONE', *, *, #33366, .F. ) ; -#16975 = EDGE_CURVE ( 'NONE', #27038, #20569, #25117, .T. ) ; -#16976 = CARTESIAN_POINT ( 'NONE', ( -1.066424343056000090, 188.6647002756000120, 103.2102455249000030 ) ) ; -#16977 = DIRECTION ( 'NONE', ( 0.1782590667764302472, 0.3529010024509862120, -0.9185230468426391903 ) ) ; -#16978 = CARTESIAN_POINT ( 'NONE', ( 3.199984448537000592, 190.8479886215000079, 106.9296817209000068 ) ) ; -#16979 = ORIENTED_EDGE ( 'NONE', *, *, #3523, .F. ) ; -#16980 = CARTESIAN_POINT ( 'NONE', ( -24.54100696812323790, 121.5315340049588855, 173.9846402519010269 ) ) ; -#16981 = CARTESIAN_POINT ( 'NONE', ( 37.28972155214677997, 111.6142886700882713, 151.1857112732826636 ) ) ; -#16982 = EDGE_LOOP ( 'NONE', ( #4500, #2190, #3006, #32471, #8342, #10536 ) ) ; -#16983 = EDGE_CURVE ( 'NONE', #37750, #29048, #6703, .T. ) ; -#16984 = ORIENTED_EDGE ( 'NONE', *, *, #33448, .F. ) ; -#16985 = CARTESIAN_POINT ( 'NONE', ( -45.30255556275930928, 123.8777291761282129, 93.38906572069882372 ) ) ; -#16986 = ORIENTED_EDGE ( 'NONE', *, *, #32882, .T. ) ; -#16987 = CARTESIAN_POINT ( 'NONE', ( -28.34546150099999906, 186.5535928724000030, 105.4761456043000010 ) ) ; -#16988 = CARTESIAN_POINT ( 'NONE', ( -8.331143224077584009, 150.6641467966076391, 97.17832424337015595 ) ) ; -#16989 = AXIS2_PLACEMENT_3D ( 'NONE', #5429, #26718, #39570 ) ; -#16990 = EDGE_CURVE ( 'NONE', #1667, #28306, #6473, .T. ) ; -#16991 = CIRCLE ( 'NONE', #24871, 6.000000000067867489 ) ; -#16992 = CARTESIAN_POINT ( 'NONE', ( -5.670703162332638492, 181.9020850521579575, 101.9448554198169745 ) ) ; -#16993 = ORIENTED_EDGE ( 'NONE', *, *, #2845, .T. ) ; -#16994 = CARTESIAN_POINT ( 'NONE', ( 25.66721973961999836, 120.1770533424000007, 90.11923128508999525 ) ) ; -#16995 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28632, #18792, #15743, #12685 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#16996 = VECTOR ( 'NONE', #25710, 1000.000000000000000 ) ; -#16997 = DIRECTION ( 'NONE', ( 0.7933532411131102302, 0.5932638852154231701, 0.1364866195435442964 ) ) ; -#16998 = EDGE_CURVE ( 'NONE', #22653, #33715, #12301, .T. ) ; -#16999 = EDGE_CURVE ( 'NONE', #37463, #31691, #20120, .T. ) ; -#17001 = CARTESIAN_POINT ( 'NONE', ( -12.92992625491334735, 154.3966043506143251, 95.30599622086934630 ) ) ; -#17000 = CARTESIAN_POINT ( 'NONE', ( 25.49186599382388962, 210.6299066825333171, 75.54315863433498635 ) ) ; -#17002 = EDGE_CURVE ( 'NONE', #26903, #12880, #38367, .T. ) ; -#17003 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#17004 = ORIENTED_EDGE ( 'NONE', *, *, #29398, .F. ) ; -#17005 = CARTESIAN_POINT ( 'NONE', ( 25.91302100389999907, 181.8795946532999892, 101.8840615430000014 ) ) ; -#17006 = CARTESIAN_POINT ( 'NONE', ( 5.696483686681999892, 174.3879284816999871, 152.4718672074000381 ) ) ; -#17007 = EDGE_LOOP ( 'NONE', ( #38451, #25615, #6868, #30195 ) ) ; -#17008 = CARTESIAN_POINT ( 'NONE', ( 38.90081508490000317, 118.9029124540000026, 89.81098821378002128 ) ) ; -#17009 = CARTESIAN_POINT ( 'NONE', ( 75.31277094998291943, 196.2503230467754349, 191.1794474674156277 ) ) ; -#17010 = CARTESIAN_POINT ( 'NONE', ( 5.669394968218998798, 187.4866721514941048, 105.7623639025581213 ) ) ; -#17011 = DIRECTION ( 'NONE', ( 0.0004161288024376838296, -0.8480480898185422944, 0.5299191109895370344 ) ) ; -#17012 = ORIENTED_EDGE ( 'NONE', *, *, #39868, .F. ) ; -#17013 = ORIENTED_EDGE ( 'NONE', *, *, #25005, .F. ) ; -#17014 = CARTESIAN_POINT ( 'NONE', ( -23.36112933754671062, 134.4863425043212715, 93.58469975075284708 ) ) ; -#17015 = AXIS2_PLACEMENT_3D ( 'NONE', #8099, #13632, #14446 ) ; -#17016 = ORIENTED_EDGE ( 'NONE', *, *, #29462, .T. ) ; -#17017 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 77.27946979429628982, 310.0857197240630967 ) ) ; -#17018 = VECTOR ( 'NONE', #3755, 1000.000000000000000 ) ; -#17019 = ORIENTED_EDGE ( 'NONE', *, *, #21905, .F. ) ; -#17020 = CARTESIAN_POINT ( 'NONE', ( -12.63318022686153697, 177.7898047555129040, 100.7065638408787436 ) ) ; -#17021 = AXIS2_PLACEMENT_3D ( 'NONE', #35917, #17308, #15482 ) ; -#17022 = VECTOR ( 'NONE', #34909, 1000.000000000000114 ) ; -#17023 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825939415874888, 0.0005734119019403442589 ) ) ; -#17024 = ORIENTED_EDGE ( 'NONE', *, *, #4530, .F. ) ; -#17025 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; -#17026 = FACE_OUTER_BOUND ( 'NONE', #6002, .T. ) ; -#17027 = DIRECTION ( 'NONE', ( -0.0004161288024528938308, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#17028 = CARTESIAN_POINT ( 'NONE', ( 42.42192200091505327, 180.1607944338011862, 148.5017479457221441 ) ) ; -#17029 = EDGE_CURVE ( 'NONE', #24015, #14526, #26928, .T. ) ; -#17030 = ORIENTED_EDGE ( 'NONE', *, *, #32667, .T. ) ; -#17031 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#17032 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 6.705467647123323749E-18, 0.0006039748319385910029 ) ) ; -#17033 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22128, #13124, #34756, #9451 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.001817041690626580372, 0.003004561830990456345 ), - .UNSPECIFIED. ) ; -#17034 = CARTESIAN_POINT ( 'NONE', ( -29.44951657505878728, 160.9899919687744330, 187.1078845272746776 ) ) ; -#17035 = EDGE_CURVE ( 'NONE', #16388, #10860, #17144, .T. ) ; -#17036 = VERTEX_POINT ( 'NONE', #17483 ) ; -#17037 = EDGE_CURVE ( 'NONE', #34614, #15536, #14041, .T. ) ; -#17038 = CARTESIAN_POINT ( 'NONE', ( -76.10807331609906612, 155.7904255491920367, 98.23170401354687442 ) ) ; -#17039 = VECTOR ( 'NONE', #12464, 1000.000000000000114 ) ; -#17040 = ADVANCED_FACE ( 'NONE', ( #4811 ), #32440, .F. ) ; -#17042 = CARTESIAN_POINT ( 'NONE', ( -37.74902905047999724, 117.4606082276000052, 89.56629544742000348 ) ) ; -#17041 = LINE ( 'NONE', #25743, #6973 ) ; -#17043 = EDGE_CURVE ( 'NONE', #25569, #11123, #10992, .T. ) ; -#17044 = ORIENTED_EDGE ( 'NONE', *, *, #28931, .T. ) ; -#17045 = CARTESIAN_POINT ( 'NONE', ( -22.54486751829999847, 202.1123865979000129, 28.07991271570000080 ) ) ; -#17046 = ADVANCED_FACE ( 'NONE', ( #36307 ), #29786, .F. ) ; -#17047 = VECTOR ( 'NONE', #25032, 1000.000000000000000 ) ; -#17048 = ORIENTED_EDGE ( 'NONE', *, *, #22806, .T. ) ; -#17049 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17050 = CARTESIAN_POINT ( 'NONE', ( 37.24531140497809645, 191.0903604573513519, 106.2990387539292385 ) ) ; -#17051 = CARTESIAN_POINT ( 'NONE', ( -38.81604098509072998, 106.1964408357682856, 169.3067908620723472 ) ) ; -#17052 = FACE_OUTER_BOUND ( 'NONE', #31425, .T. ) ; -#17053 = ORIENTED_EDGE ( 'NONE', *, *, #29313, .T. ) ; -#17054 = ORIENTED_EDGE ( 'NONE', *, *, #28298, .F. ) ; -#17055 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606773498981405, 136.6775772631814618, 180.9814965275718919 ) ) ; -#17056 = ORIENTED_EDGE ( 'NONE', *, *, #12194, .F. ) ; -#17057 = VERTEX_POINT ( 'NONE', #39167 ) ; -#17058 = CARTESIAN_POINT ( 'NONE', ( 77.66065009075275327, 193.3992594998515244, 188.4681838635439419 ) ) ; -#17059 = CARTESIAN_POINT ( 'NONE', ( 2.838525112095999781, 209.4270098178000126, 73.22775551082000334 ) ) ; -#17060 = ORIENTED_EDGE ( 'NONE', *, *, #9188, .T. ) ; -#17061 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17062 = PLANE ( 'NONE', #36809 ) ; -#17063 = CARTESIAN_POINT ( 'NONE', ( -33.42986125250909168, 142.5729643372171722, 280.9723740511064989 ) ) ; -#17064 = CARTESIAN_POINT ( 'NONE', ( 37.75543887471000204, 191.1265769391000049, 103.8768853900000124 ) ) ; -#17065 = PLANE ( 'NONE', #29431 ) ; -#17066 = ORIENTED_EDGE ( 'NONE', *, *, #1269, .T. ) ; -#17067 = CARTESIAN_POINT ( 'NONE', ( 28.69329030557365101, 225.5077044868852170, 152.4737688808613711 ) ) ; -#17068 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971573729 ) ) ; -#17069 = ORIENTED_EDGE ( 'NONE', *, *, #25927, .T. ) ; -#17070 = FACE_OUTER_BOUND ( 'NONE', #27754, .T. ) ; -#17071 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825963514080415, 0.0005734119013848138109 ) ) ; -#17072 = AXIS2_PLACEMENT_3D ( 'NONE', #26015, #16571, #1243 ) ; -#17073 = CARTESIAN_POINT ( 'NONE', ( -14.29753829223670003, 176.6356860434633802, 100.7832211550218346 ) ) ; -#17074 = CARTESIAN_POINT ( 'NONE', ( -19.70071604027683065, 149.4445624503525778, 181.7665744593643637 ) ) ; -#17075 = VERTEX_POINT ( 'NONE', #10974 ) ; -#17076 = AXIS2_PLACEMENT_3D ( 'NONE', #16100, #19152, #22854 ) ; -#17077 = CARTESIAN_POINT ( 'NONE', ( 45.03701848846946376, 181.3762064645945600, 101.6707694279998293 ) ) ; -#17078 = AXIS2_PLACEMENT_3D ( 'NONE', #35692, #7706, #16111 ) ; -#17079 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567900 ) ) ; -#17080 = CARTESIAN_POINT ( 'NONE', ( -14.29593191187739087, 209.7096839136990809, 76.06713901443235670 ) ) ; -#17081 = EDGE_CURVE ( 'NONE', #8531, #24276, #30630, .T. ) ; -#17082 = EDGE_CURVE ( 'NONE', #5645, #40029, #12951, .T. ) ; -#17083 = ORIENTED_EDGE ( 'NONE', *, *, #30795, .T. ) ; -#17084 = CARTESIAN_POINT ( 'NONE', ( 37.28123020134204779, 185.8375337558694866, 106.4638125528461501 ) ) ; -#17085 = EDGE_LOOP ( 'NONE', ( #5939, #31621, #32806, #11896 ) ) ; -#17086 = EDGE_CURVE ( 'NONE', #32727, #20686, #7685, .T. ) ; -#17087 = CARTESIAN_POINT ( 'NONE', ( -26.13221451157999908, 191.7053700682999988, 103.7821650485000049 ) ) ; -#17088 = DIRECTION ( 'NONE', ( -0.0005884949961245386019, 0.2249510543439047772, -0.9743698870671267942 ) ) ; -#17089 = CARTESIAN_POINT ( 'NONE', ( 37.78115515336936880, 118.8155650090541968, 87.24496173037786662 ) ) ; -#17090 = EDGE_CURVE ( 'NONE', #921, #24745, #7056, .T. ) ; -#17091 = CARTESIAN_POINT ( 'NONE', ( 15.94070757266567995, 152.8237909711254190, 181.6389010276846818 ) ) ; -#17092 = LINE ( 'NONE', #35901, #28450 ) ; -#17093 = ORIENTED_EDGE ( 'NONE', *, *, #32442, .F. ) ; -#17094 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#17095 = ADVANCED_FACE ( 'NONE', ( #20559 ), #14442, .T. ) ; -#17096 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 4.622231866529367416E-33, -0.0006039748319394906738 ) ) ; -#17097 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749898865, 181.8223093628335221, 102.1321913515297126 ) ) ; -#17098 = CARTESIAN_POINT ( 'NONE', ( -2.955788759824745426, 209.1883112457904019, 73.08018916681729138 ) ) ; -#17099 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901141, 134.9773540767009763, 93.88293913757796361 ) ) ; -#17100 = CARTESIAN_POINT ( 'NONE', ( 32.44146722115601023, 176.1285443563099022, 100.2958076299900938 ) ) ; -#17101 = LINE ( 'NONE', #29409, #2162 ) ; -#17102 = CARTESIAN_POINT ( 'NONE', ( -5.666943510250832539, 130.1499721591725347, 92.51434240712107737 ) ) ; -#17103 = VECTOR ( 'NONE', #37026, 1000.000000000000114 ) ; -#17104 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498900431, 132.2978364233248953, 93.26432363101957890 ) ) ; -#17105 = ORIENTED_EDGE ( 'NONE', *, *, #37283, .T. ) ; -#17106 = VECTOR ( 'NONE', #25275, 999.9999999999998863 ) ; -#17107 = EDGE_CURVE ( 'NONE', #3220, #36851, #33028, .T. ) ; -#17108 = LINE ( 'NONE', #29607, #172 ) ; -#17109 = VECTOR ( 'NONE', #38529, 1000.000000000000114 ) ; -#17110 = CARTESIAN_POINT ( 'NONE', ( 17.18127995227040117, 121.6259304897876774, 177.7629839600756156 ) ) ; -#17111 = CARTESIAN_POINT ( 'NONE', ( 0.05451946023377000211, 104.1131156706999974, 90.26775191081999594 ) ) ; -#17112 = DIRECTION ( 'NONE', ( 0.0004161288024603425708, -0.8480480897887666680, 0.5299191110371879176 ) ) ; -#17113 = ORIENTED_EDGE ( 'NONE', *, *, #20320, .F. ) ; -#17114 = CARTESIAN_POINT ( 'NONE', ( 26.00894335418652048, 191.9759150222000130, 103.9057414310139080 ) ) ; -#17115 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564847 ) ) ; -#17116 = EDGE_LOOP ( 'NONE', ( #36207, #18274, #2412, #10060 ) ) ; -#17117 = LINE ( 'NONE', #35923, #14961 ) ; -#17118 = ORIENTED_EDGE ( 'NONE', *, *, #37738, .T. ) ; -#17119 = LINE ( 'NONE', #36356, #13798 ) ; -#17120 = DIRECTION ( 'NONE', ( -0.0005884949961191883894, 0.2249510543439073307, -0.9743698870671261281 ) ) ; -#17121 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#17122 = CARTESIAN_POINT ( 'NONE', ( -12.63510598152721975, 130.9323451246731338, 89.96358487428598494 ) ) ; -#17123 = LINE ( 'NONE', #23092, #8654 ) ; -#17124 = EDGE_LOOP ( 'NONE', ( #4302, #25641, #16323, #33110, #21378, #7907, #20884, #4705 ) ) ; -#17125 = PLANE ( 'NONE', #1653 ) ; -#17126 = CARTESIAN_POINT ( 'NONE', ( 12.63703436142900216, 181.9093167050804709, 101.9420519965222240 ) ) ; -#17127 = CIRCLE ( 'NONE', #34129, 2.000000001304274910 ) ; -#17128 = CARTESIAN_POINT ( 'NONE', ( 37.42082352723856076, 132.6200669550715929, 336.9739440566017379 ) ) ; -#17129 = EDGE_CURVE ( 'NONE', #26262, #6484, #2310, .T. ) ; -#17131 = ORIENTED_EDGE ( 'NONE', *, *, #16584, .T. ) ; -#17130 = EDGE_CURVE ( 'NONE', #30603, #16668, #10353, .T. ) ; -#17132 = CARTESIAN_POINT ( 'NONE', ( 17.02597799957154834, 152.4294734933178290, 182.1650376563844702 ) ) ; -#17133 = ADVANCED_FACE ( 'NONE', ( #29575 ), #21457, .F. ) ; -#17134 = ORIENTED_EDGE ( 'NONE', *, *, #37539, .T. ) ; -#17135 = AXIS2_PLACEMENT_3D ( 'NONE', #37156, #36958, #9350 ) ; -#17136 = CARTESIAN_POINT ( 'NONE', ( 42.83487131658636571, 120.7910107177263797, 92.64688251868901148 ) ) ; -#17137 = EDGE_CURVE ( 'NONE', #24276, #629, #7648, .T. ) ; -#17138 = CARTESIAN_POINT ( 'NONE', ( 37.39185766581847759, 191.0442970149452151, 103.7363911818666509 ) ) ; -#17139 = CARTESIAN_POINT ( 'NONE', ( 16.16729401867695515, 152.0078996042194603, 180.9416867539977716 ) ) ; -#17140 = CONICAL_SURFACE ( 'NONE', #31527, 2.502999398265778108, 0.7853981633749954616 ) ; -#17141 = FACE_OUTER_BOUND ( 'NONE', #32158, .T. ) ; -#17142 = EDGE_CURVE ( 'NONE', #36832, #28131, #16198, .T. ) ; -#17143 = CARTESIAN_POINT ( 'NONE', ( 18.58912714118548237, 148.0271172827300177, 184.1229846802908128 ) ) ; -#17144 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #19944, #35884, #26119, #7889 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.1325196467246753107, 1.704150287259436958 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8045411634788308675, 0.8045411634788308675, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#17145 = CARTESIAN_POINT ( 'NONE', ( 25.49183423580130636, 211.0903769678246817, 75.54322026927223988 ) ) ; -#17146 = EDGE_CURVE ( 'NONE', #28366, #29855, #20839, .T. ) ; -#17147 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8971, #21446, #40215, #37168 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17148 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; -#17149 = CARTESIAN_POINT ( 'NONE', ( 20.48049177332755733, 208.4149586973334181, 73.73637375758902124 ) ) ; -#17150 = CARTESIAN_POINT ( 'NONE', ( 26.55314565214595035, 123.1309328123378606, 88.06389908587492243 ) ) ; -#17151 = ORIENTED_EDGE ( 'NONE', *, *, #29307, .F. ) ; -#17152 = DIRECTION ( 'NONE', ( 0.9999998160276427628, 6.024061281570464090E-07, -0.0006065841390484965311 ) ) ; -#17153 = LINE ( 'NONE', #17960, #4851 ) ; -#17154 = CARTESIAN_POINT ( 'NONE', ( -25.26021706816886692, 117.1739734221355889, 170.8214860574283591 ) ) ; -#17155 = FACE_OUTER_BOUND ( 'NONE', #8363, .T. ) ; -#17156 = EDGE_CURVE ( 'NONE', #25599, #20440, #37468, .T. ) ; -#17157 = ORIENTED_EDGE ( 'NONE', *, *, #10299, .F. ) ; -#17158 = EDGE_LOOP ( 'NONE', ( #28316, #28110, #13806, #25776 ) ) ; -#17159 = ORIENTED_EDGE ( 'NONE', *, *, #38303, .F. ) ; -#17160 = CARTESIAN_POINT ( 'NONE', ( 36.04796026473877646, 209.7096538831000032, 78.03673292964222696 ) ) ; -#17161 = CIRCLE ( 'NONE', #21781, 58.90509898151368873 ) ; -#17162 = CARTESIAN_POINT ( 'NONE', ( 22.31312662366504540, 116.2335386298891393, 182.3227435278615474 ) ) ; -#17163 = CARTESIAN_POINT ( 'NONE', ( -0.4543644820471367529, 208.9999999999988916, 75.55877896301241492 ) ) ; -#17164 = VERTEX_POINT ( 'NONE', #19049 ) ; -#17165 = AXIS2_PLACEMENT_3D ( 'NONE', #26905, #8080, #4598 ) ; -#17166 = ORIENTED_EDGE ( 'NONE', *, *, #19723, .F. ) ; -#17167 = CARTESIAN_POINT ( 'NONE', ( -13.83106602394250650, 188.3420923983079547, 103.1434753385557741 ) ) ; -#17168 = VECTOR ( 'NONE', #14632, 1000.000000000000000 ) ; -#17169 = CARTESIAN_POINT ( 'NONE', ( -35.83070930321999725, 112.8598257618999980, 87.67250422460000436 ) ) ; -#17170 = ORIENTED_EDGE ( 'NONE', *, *, #88, .F. ) ; -#17171 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17172 = ORIENTED_EDGE ( 'NONE', *, *, #17830, .T. ) ; -#17173 = DIRECTION ( 'NONE', ( -0.0006039748319380815363, -1.388651635424563573E-14, -0.9999998176071845934 ) ) ; -#17174 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319383098692 ) ) ; -#17175 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15024, #16213, #16410, #34409 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17176 = CARTESIAN_POINT ( 'NONE', ( 0.04442747709263908384, 271.9029643395999756, 73.55847734050897202 ) ) ; -#17177 = CARTESIAN_POINT ( 'NONE', ( 12.31706371121084231, 136.7942246724338702, 93.79267811176558212 ) ) ; -#17178 = ORIENTED_EDGE ( 'NONE', *, *, #28476, .T. ) ; -#17179 = CARTESIAN_POINT ( 'NONE', ( -19.99998967951139051, 191.8246488541593919, 103.9335226341060263 ) ) ; -#17180 = CARTESIAN_POINT ( 'NONE', ( -8.331143220612540645, 160.8442841037902724, 99.52859455750945017 ) ) ; -#17181 = CARTESIAN_POINT ( 'NONE', ( 28.53094770716555217, 124.6122665164779164, 91.48361085109841895 ) ) ; -#17182 = EDGE_CURVE ( 'NONE', #16030, #7007, #9627, .T. ) ; -#17183 = EDGE_LOOP ( 'NONE', ( #30369, #33269, #29093, #3218 ) ) ; -#17184 = CARTESIAN_POINT ( 'NONE', ( -2.390862647930000140, 209.5043720128000189, 75.55992074799000591 ) ) ; -#17185 = CARTESIAN_POINT ( 'NONE', ( -24.86160776171564990, 213.4882199952567419, 76.07240447855350851 ) ) ; -#17186 = ADVANCED_FACE ( 'NONE', ( #21946 ), #6381, .T. ) ; -#17187 = ORIENTED_EDGE ( 'NONE', *, *, #1536, .F. ) ; -#17188 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33193, #33410, #39543, #1945, #30158, #8490, #1737, #17050, #4995, #23414, #26898, #11143, #29549, #38939, #1522 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998973599, 0.3749999999998370748, 0.4374999999998115952, 0.4687499999997922773, 0.4843749999997982725, 0.4999999999998042677, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17189 = VERTEX_POINT ( 'NONE', #37073 ) ; -#17190 = VECTOR ( 'NONE', #19378, 1000.000000000000114 ) ; -#17191 = ORIENTED_EDGE ( 'NONE', *, *, #34859, .T. ) ; -#17192 = CARTESIAN_POINT ( 'NONE', ( 44.69319351362821635, 71.37631305377094293, 322.8294081051816420 ) ) ; -#17193 = ORIENTED_EDGE ( 'NONE', *, *, #9520, .T. ) ; -#17194 = CARTESIAN_POINT ( 'NONE', ( 3.063265537705500918, 190.7705380642428565, 106.7728354309631840 ) ) ; -#17195 = VECTOR ( 'NONE', #33162, 1000.000000000000114 ) ; -#17196 = LINE ( 'NONE', #7603, #2982 ) ; -#17197 = FACE_OUTER_BOUND ( 'NONE', #19783, .T. ) ; -#17198 = AXIS2_PLACEMENT_3D ( 'NONE', #22241, #28365, #34667 ) ; -#17199 = ORIENTED_EDGE ( 'NONE', *, *, #13565, .T. ) ; -#17200 = CARTESIAN_POINT ( 'NONE', ( -23.01844285970464909, 211.0902260919000355, 76.07552203529617429 ) ) ; -#17201 = VERTEX_POINT ( 'NONE', #3314 ) ; -#17202 = CARTESIAN_POINT ( 'NONE', ( 27.30158521878999878, 124.4440410757000137, 90.93222334034000198 ) ) ; -#17203 = PLANE ( 'NONE', #20850 ) ; -#17205 = CARTESIAN_POINT ( 'NONE', ( 5.666342389540173663, 185.9093800082626160, 102.5669869859405026 ) ) ; -#17204 = DIRECTION ( 'NONE', ( -0.0005884952009901332510, 0.2249510543175750887, -0.9743698870730815864 ) ) ; -#17206 = ORIENTED_EDGE ( 'NONE', *, *, #35841, .T. ) ; -#17207 = EDGE_CURVE ( 'NONE', #33874, #8706, #9468, .T. ) ; -#17208 = CYLINDRICAL_SURFACE ( 'NONE', #28243, 2.000000000000000000 ) ; -#17209 = EDGE_LOOP ( 'NONE', ( #32512, #12500, #7115, #34578, #27822, #10603, #23936, #16477 ) ) ; -#17210 = CARTESIAN_POINT ( 'NONE', ( -36.17271632336002085, 191.9052612783726772, 104.4154311915522015 ) ) ; -#17211 = ORIENTED_EDGE ( 'NONE', *, *, #22899, .F. ) ; -#17212 = DIRECTION ( 'NONE', ( -0.0005884949671858177161, 0.2249510543353067105, -0.9743698870691290814 ) ) ; -#17213 = LINE ( 'NONE', #8027, #18646 ) ; -#17214 = DIRECTION ( 'NONE', ( 0.6087614115774561130, 0.7729348350580500515, 0.1788331192145569681 ) ) ; -#17215 = DIRECTION ( 'NONE', ( 0.0002393071041605207214, 0.2255699564796172785, -0.9742269435125953114 ) ) ; -#17216 = CARTESIAN_POINT ( 'NONE', ( 36.11983317218000167, 191.5127010687999984, 103.8373663176000008 ) ) ; -#17217 = VECTOR ( 'NONE', #40081, 1000.000000000000000 ) ; -#17218 = ORIENTED_EDGE ( 'NONE', *, *, #38173, .F. ) ; -#17219 = VERTEX_POINT ( 'NONE', #21551 ) ; -#17220 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #28559, #526, #25501, #9957 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.570796326794893449, 1.750577995572639267 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973083591495172096, 0.9973083591495172096, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#17221 = DIRECTION ( 'NONE', ( -0.5988681445390194868, 0.8008476418498040594, 0.000000000000000000 ) ) ; -#17222 = ORIENTED_EDGE ( 'NONE', *, *, #1224, .F. ) ; -#17223 = AXIS2_PLACEMENT_3D ( 'NONE', #32329, #29266, #13718 ) ; -#17224 = CARTESIAN_POINT ( 'NONE', ( -35.46848709283599987, 192.2361886390060306, 106.9493674620740080 ) ) ; -#17225 = VERTEX_POINT ( 'NONE', #15783 ) ; -#17226 = ADVANCED_FACE ( 'NONE', ( #22352 ), #12941, .T. ) ; -#17227 = CARTESIAN_POINT ( 'NONE', ( 3.069762736230476907, 190.8498496381319569, 106.7968308444213648 ) ) ; -#17228 = EDGE_CURVE ( 'NONE', #34253, #16448, #17417, .T. ) ; -#17229 = ORIENTED_EDGE ( 'NONE', *, *, #19003, .F. ) ; -#17230 = FACE_OUTER_BOUND ( 'NONE', #10296, .T. ) ; -#17231 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772234801672, 136.6775772631780796, 180.9814965275865575 ) ) ; -#17232 = CARTESIAN_POINT ( 'NONE', ( 9.583319590155999990, 124.5551187389999939, 88.65952379800000926 ) ) ; -#17233 = LINE ( 'NONE', #7642, #13033 ) ; -#17234 = ORIENTED_EDGE ( 'NONE', *, *, #13296, .F. ) ; -#17235 = CARTESIAN_POINT ( 'NONE', ( -15.94446068766880487, 121.2107412334159591, 177.4020268254936923 ) ) ; -#17236 = LINE ( 'NONE', #26679, #2562 ) ; -#17237 = AXIS2_PLACEMENT_3D ( 'NONE', #2285, #21508, #33948 ) ; -#17238 = VECTOR ( 'NONE', #35120, 1000.000000000000000 ) ; -#17239 = EDGE_LOOP ( 'NONE', ( #14839, #23696, #15076 ) ) ; -#17240 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#17241 = DIRECTION ( 'NONE', ( 0.0005884949907373547388, -0.2249510543438368870, 0.9743698870671455570 ) ) ; -#17242 = ORIENTED_EDGE ( 'NONE', *, *, #37892, .F. ) ; -#17243 = EDGE_CURVE ( 'NONE', #20872, #17425, #31543, .T. ) ; -#17244 = CARTESIAN_POINT ( 'NONE', ( -6.028075236889769428, 177.1156665047246008, 103.6258451396837899 ) ) ; -#17245 = ORIENTED_EDGE ( 'NONE', *, *, #22614, .T. ) ; -#17246 = CARTESIAN_POINT ( 'NONE', ( 91.24547840862865655, 222.8067606030032550, 201.4280517774668624 ) ) ; -#17247 = CARTESIAN_POINT ( 'NONE', ( -20.33310178517772826, 127.6671047516186377, 89.48154071701799239 ) ) ; -#17248 = LINE ( 'NONE', #16851, #10995 ) ; -#17249 = ORIENTED_EDGE ( 'NONE', *, *, #27108, .T. ) ; -#17250 = ORIENTED_EDGE ( 'NONE', *, *, #8596, .T. ) ; -#17251 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265228896, -0.1368326740407719011 ) ) ; -#17252 = ORIENTED_EDGE ( 'NONE', *, *, #39501, .F. ) ; -#17253 = EDGE_LOOP ( 'NONE', ( #1181, #40154, #27958, #3739 ) ) ; -#17254 = ORIENTED_EDGE ( 'NONE', *, *, #26823, .F. ) ; -#17255 = CARTESIAN_POINT ( 'NONE', ( 20.00182604067493131, 190.8514159882993511, 106.7812686061269716 ) ) ; -#17256 = CARTESIAN_POINT ( 'NONE', ( 28.64561701362920942, 225.5077044868850180, 73.54120293868254521 ) ) ; -#17257 = CARTESIAN_POINT ( 'NONE', ( -2.851222922393109815, 209.7096616640929199, 76.06022722140575354 ) ) ; -#17258 = ORIENTED_EDGE ( 'NONE', *, *, #10743, .F. ) ; -#17259 = EDGE_CURVE ( 'NONE', #13129, #14154, #30944, .T. ) ; -#17260 = ORIENTED_EDGE ( 'NONE', *, *, #11684, .F. ) ; -#17261 = CARTESIAN_POINT ( 'NONE', ( 18.98780079260364317, 148.3242069017240681, 184.1917624428014904 ) ) ; -#17262 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#17263 = CARTESIAN_POINT ( 'NONE', ( -35.71142153204999659, 191.5606522780000205, 103.7690409172000017 ) ) ; -#17264 = CARTESIAN_POINT ( 'NONE', ( 36.61401666729999960, 191.8263800043999936, 104.5069429764999995 ) ) ; -#17265 = CARTESIAN_POINT ( 'NONE', ( -25.66782949977000428, 120.7016921406000023, 87.87645205366999335 ) ) ; -#17266 = AXIS2_PLACEMENT_3D ( 'NONE', #17290, #10987, #11186 ) ; -#17267 = ADVANCED_FACE ( 'NONE', ( #30742 ), #2736, .T. ) ; -#17268 = LINE ( 'NONE', #1970, #29099 ) ; -#17269 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921576300, -0.2249510932971598709 ) ) ; -#17270 = VERTEX_POINT ( 'NONE', #15397 ) ; -#17271 = VECTOR ( 'NONE', #27147, 1000.000000000000000 ) ; -#17272 = VECTOR ( 'NONE', #24521, 1000.000000000000114 ) ; -#17273 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17809, #18217, #30304, #8018 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17274 = DIRECTION ( 'NONE', ( -0.0005884949961246157971, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#17275 = DIRECTION ( 'NONE', ( -0.0006039748319382907873, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#17276 = VECTOR ( 'NONE', #35645, 1000.000000000000000 ) ; -#17277 = ADVANCED_FACE ( 'NONE', ( #6186 ), #13050, .F. ) ; -#17278 = CARTESIAN_POINT ( 'NONE', ( 20.50038014672672304, 194.9390793442601364, 105.3094855762004727 ) ) ; -#17279 = ADVANCED_FACE ( 'NONE', ( #7187 ), #34480, .F. ) ; -#17280 = FACE_OUTER_BOUND ( 'NONE', #30193, .T. ) ; -#17281 = ORIENTED_EDGE ( 'NONE', *, *, #22437, .F. ) ; -#17282 = CARTESIAN_POINT ( 'NONE', ( 20.00001350029910085, 189.3408603011638718, 103.3536401978308419 ) ) ; -#17283 = ADVANCED_FACE ( 'NONE', ( #25622 ), #653, .T. ) ; -#17284 = CARTESIAN_POINT ( 'NONE', ( 2.560074644014078693, 190.8728800184543104, 104.2237589072057773 ) ) ; -#17285 = CARTESIAN_POINT ( 'NONE', ( 32.50505481319044065, 136.7246762262726918, 91.19866780689935126 ) ) ; -#17286 = ORIENTED_EDGE ( 'NONE', *, *, #39255, .T. ) ; -#17287 = CARTESIAN_POINT ( 'NONE', ( 20.48008986686174282, 210.6299648728911222, 73.54684484258879706 ) ) ; -#17288 = ORIENTED_EDGE ( 'NONE', *, *, #23113, .F. ) ; -#17289 = CARTESIAN_POINT ( 'NONE', ( -25.61801701081000360, 191.6082135239000195, 104.2857596666000006 ) ) ; -#17290 = CARTESIAN_POINT ( 'NONE', ( 5.668111471659128320, 185.2331518488130655, 105.4960524095502734 ) ) ; -#17291 = CARTESIAN_POINT ( 'NONE', ( -25.45534549256436918, 211.7447000708251608, 73.57353581660497355 ) ) ; -#17292 = DIRECTION ( 'NONE', ( 1.804112415037046094E-14, 0.9743700557921584071, 0.2249510932971567900 ) ) ; -#17293 = ORIENTED_EDGE ( 'NONE', *, *, #28500, .F. ) ; -#17294 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#17295 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265227786, 0.1368326740407719844 ) ) ; -#17296 = EDGE_CURVE ( 'NONE', #24799, #39067, #20017, .T. ) ; -#17297 = VECTOR ( 'NONE', #24157, 1000.000000000000114 ) ; -#17298 = AXIS2_PLACEMENT_3D ( 'NONE', #10724, #36462, #14394 ) ; -#17299 = CARTESIAN_POINT ( 'NONE', ( -35.94008004079000074, 192.5552285418999929, 104.9676488416999973 ) ) ; -#17301 = CARTESIAN_POINT ( 'NONE', ( -16.88747875106462715, 122.0414632028714124, 175.0198840672369442 ) ) ; -#17300 = CIRCLE ( 'NONE', #24624, 2.249999999984611421 ) ; -#17302 = DIRECTION ( 'NONE', ( -0.0005884949961260158274, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#17303 = DIRECTION ( 'NONE', ( 0.0002265441438622214161, -0.9034129951719994667, 0.4287713946056891934 ) ) ; -#17304 = CARTESIAN_POINT ( 'NONE', ( -5.664830602385754865, 130.2917189741279458, 92.74118313415932846 ) ) ; -#17305 = CARTESIAN_POINT ( 'NONE', ( -38.39791937170240743, 118.8574915090185726, 87.72183780368946771 ) ) ; -#17306 = ORIENTED_EDGE ( 'NONE', *, *, #40206, .F. ) ; -#17307 = CARTESIAN_POINT ( 'NONE', ( 3.647052574382751544, 144.1925529306576266, 93.05594058926581624 ) ) ; -#17308 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; -#17309 = EDGE_CURVE ( 'NONE', #18814, #33719, #23389, .T. ) ; -#17310 = ORIENTED_EDGE ( 'NONE', *, *, #2081, .T. ) ; -#17311 = CARTESIAN_POINT ( 'NONE', ( 5.665019113453634958, 181.9430578531224967, 102.0015240401697554 ) ) ; -#17312 = VERTEX_POINT ( 'NONE', #28673 ) ; -#17313 = EDGE_CURVE ( 'NONE', #18192, #33506, #29604, .T. ) ; -#17314 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082099409, 3.782957827463197881E-12, 297.5876476292049801 ) ) ; -#17315 = CARTESIAN_POINT ( 'NONE', ( -61.84220049570050293, 78.72323700374754196, 282.5958934331605406 ) ) ; -#17316 = FACE_OUTER_BOUND ( 'NONE', #20679, .T. ) ; -#17317 = ORIENTED_EDGE ( 'NONE', *, *, #11912, .F. ) ; -#17318 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#17319 = ADVANCED_FACE ( 'NONE', ( #3914 ), #10073, .T. ) ; -#17320 = AXIS2_PLACEMENT_3D ( 'NONE', #23472, #4850, #27382 ) ; -#17321 = CARTESIAN_POINT ( 'NONE', ( 20.50029382537679723, 138.3995138256450446, 92.10573732898133414 ) ) ; -#17322 = CARTESIAN_POINT ( 'NONE', ( 3.064505435595261229, 190.8915653482034998, 106.8005998850467222 ) ) ; -#17323 = CONICAL_SURFACE ( 'NONE', #29123, 6.499999999885919699, 0.7853981633843651888 ) ; -#17324 = CARTESIAN_POINT ( 'NONE', ( 29.37618521805934080, 109.9008702326019886, 185.6692766672719017 ) ) ; -#17325 = CARTESIAN_POINT ( 'NONE', ( 30.01965015980229978, 186.1545558735057853, 102.6119579121506433 ) ) ; -#17326 = EDGE_CURVE ( 'NONE', #26196, #29062, #22550, .T. ) ; -#17327 = VERTEX_POINT ( 'NONE', #35178 ) ; -#17328 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421897730, 184.2914807614346273, 105.2707223254774931 ) ) ; -#17329 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#17330 = AXIS2_PLACEMENT_3D ( 'NONE', #13640, #6893, #35286 ) ; -#17331 = CARTESIAN_POINT ( 'NONE', ( 8.471855298021594649, 160.9702727382075125, 99.37648202509593887 ) ) ; -#17332 = CARTESIAN_POINT ( 'NONE', ( -28.47344760044883216, 181.6851202344923308, 101.6154648382260035 ) ) ; -#17333 = AXIS2_PLACEMENT_3D ( 'NONE', #33024, #5016, #17479 ) ; -#17334 = ORIENTED_EDGE ( 'NONE', *, *, #33070, .F. ) ; -#17335 = CARTESIAN_POINT ( 'NONE', ( 23.35635955975471134, 181.6919812636757285, 101.5857449861623110 ) ) ; -#17336 = CARTESIAN_POINT ( 'NONE', ( -43.60275574284717237, 120.4180340293254972, 91.53716516524805513 ) ) ; -#17337 = CARTESIAN_POINT ( 'NONE', ( 6.034635603964243700, 134.5587005980779622, 93.52506117850155931 ) ) ; -#17338 = FACE_OUTER_BOUND ( 'NONE', #35535, .T. ) ; -#17339 = CARTESIAN_POINT ( 'NONE', ( 31.91158940776717046, 137.5571349200599798, 93.95697525044668907 ) ) ; -#17340 = CARTESIAN_POINT ( 'NONE', ( -15.49970618479461137, 184.8500655517521807, 102.8514372352811108 ) ) ; -#17341 = CARTESIAN_POINT ( 'NONE', ( 20.50147089296921266, 119.8278772667796090, 89.87074392140300461 ) ) ; -#17342 = CARTESIAN_POINT ( 'NONE', ( 23.68587876377409529, 136.7957297058827351, 93.78615909692494768 ) ) ; -#17343 = CARTESIAN_POINT ( 'NONE', ( 28.13101631667413471, 125.0359381400565582, 88.50275130584401495 ) ) ; -#17344 = ORIENTED_EDGE ( 'NONE', *, *, #27154, .T. ) ; -#17345 = FACE_OUTER_BOUND ( 'NONE', #18717, .T. ) ; -#17346 = CARTESIAN_POINT ( 'NONE', ( 26.00076108762728211, 119.7153706401760758, 90.35460073770548206 ) ) ; -#17347 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15425, #21368, #37294, #27920, #5814, #15807, #12346, #9292, #12543, #9489 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17348 = CARTESIAN_POINT ( 'NONE', ( -91.29662383756267729, 223.8160270898476085, 197.5110405146249946 ) ) ; -#17349 = CARTESIAN_POINT ( 'NONE', ( 26.03550245107076933, 190.8511564191358900, 106.7775725292634945 ) ) ; -#17350 = CONICAL_SURFACE ( 'NONE', #19982, 2.499999999930474281, 0.7853981634269987522 ) ; -#17351 = CARTESIAN_POINT ( 'NONE', ( -38.34602178450000309, 118.5791799481999931, 89.90303731784000263 ) ) ; -#17352 = AXIS2_PLACEMENT_3D ( 'NONE', #18209, #30713, #2706 ) ; -#17353 = ORIENTED_EDGE ( 'NONE', *, *, #7492, .F. ) ; -#17354 = ORIENTED_EDGE ( 'NONE', *, *, #21206, .F. ) ; -#17355 = ORIENTED_EDGE ( 'NONE', *, *, #558, .T. ) ; -#17356 = CARTESIAN_POINT ( 'NONE', ( -23.35851273695973873, 177.6602557452652036, 100.7926513040667658 ) ) ; -#17357 = EDGE_CURVE ( 'NONE', #34643, #9107, #20054, .T. ) ; -#17358 = VECTOR ( 'NONE', #10317, 1000.000000000000114 ) ; -#17359 = EDGE_CURVE ( 'NONE', #14963, #29005, #20790, .T. ) ; -#17360 = CARTESIAN_POINT ( 'NONE', ( 26.32033074026975328, 114.4659742150060282, 176.3663696116665278 ) ) ; -#17361 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #3036, #12445 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17362 = DIRECTION ( 'NONE', ( -0.0005884949961254158299, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#17363 = EDGE_CURVE ( 'NONE', #21843, #29784, #34009, .T. ) ; -#17364 = AXIS2_PLACEMENT_3D ( 'NONE', #24371, #11682, #2872 ) ; -#17365 = EDGE_CURVE ( 'NONE', #10264, #6338, #31753, .T. ) ; -#17366 = ORIENTED_EDGE ( 'NONE', *, *, #9414, .F. ) ; -#17367 = FACE_BOUND ( 'NONE', #39977, .T. ) ; -#17368 = CARTESIAN_POINT ( 'NONE', ( -37.56657168646712108, 112.0458133426950695, 151.1389157892933781 ) ) ; -#17369 = CARTESIAN_POINT ( 'NONE', ( -36.09521837964000213, 112.8619364219999994, 87.93783553672000153 ) ) ; -#17370 = ORIENTED_EDGE ( 'NONE', *, *, #34490, .T. ) ; -#17371 = EDGE_CURVE ( 'NONE', #38213, #16794, #32078, .T. ) ; -#17372 = CARTESIAN_POINT ( 'NONE', ( -31.74259674813110266, 153.0051697192226641, 334.9416436895348284 ) ) ; -#17373 = ORIENTED_EDGE ( 'NONE', *, *, #34426, .F. ) ; -#17374 = DIRECTION ( 'NONE', ( -0.0005884949961236305826, 0.2249510543439055266, -0.9743698870671265722 ) ) ; -#17375 = CARTESIAN_POINT ( 'NONE', ( 20.33743256209849903, 184.3692938640446073, 104.9398584957469751 ) ) ; -#17376 = LINE ( 'NONE', #14755, #2586 ) ; -#17377 = CARTESIAN_POINT ( 'NONE', ( -3.255230332982838704, 186.5475403829457548, 102.7227827455729852 ) ) ; -#17378 = CARTESIAN_POINT ( 'NONE', ( -19.31467031021941949, 148.4018994673661780, 183.4532939704609760 ) ) ; -#17379 = EDGE_LOOP ( 'NONE', ( #11424, #29437, #25894, #27378 ) ) ; -#17380 = EDGE_CURVE ( 'NONE', #29108, #39755, #33857, .T. ) ; -#17381 = VERTEX_POINT ( 'NONE', #26625 ) ; -#17382 = CARTESIAN_POINT ( 'NONE', ( -2.470687046066000647, 189.8752689345000135, 103.6418612018999994 ) ) ; -#17383 = CARTESIAN_POINT ( 'NONE', ( 1.159933842655000102, 188.9561970069999859, 103.5493244023000017 ) ) ; -#17384 = DIRECTION ( 'NONE', ( 0.0006039748319371906473, -0.000000000000000000, 0.9999998176071844824 ) ) ; -#17385 = CARTESIAN_POINT ( 'NONE', ( 26.90851097252234325, 123.0590747987910589, 91.12600760642735054 ) ) ; -#17386 = VECTOR ( 'NONE', #20639, 1000.000000000000114 ) ; -#17387 = ORIENTED_EDGE ( 'NONE', *, *, #3840, .F. ) ; -#17388 = CARTESIAN_POINT ( 'NONE', ( 31.91041241775748105, 138.0070370287062644, 92.00823547631698318 ) ) ; -#17389 = VECTOR ( 'NONE', #521, 999.9999999999998863 ) ; -#17390 = ORIENTED_EDGE ( 'NONE', *, *, #25068, .T. ) ; -#17391 = ORIENTED_EDGE ( 'NONE', *, *, #13399, .T. ) ; -#17392 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #6092, #37571, #31046, #161 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.442085121493781097, 1.442120204651619719 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999998974310467, 0.9999999998974310467, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#17393 = AXIS2_PLACEMENT_3D ( 'NONE', #14310, #29852, #7747 ) ; -#17394 = EDGE_CURVE ( 'NONE', #8036, #20595, #6443, .T. ) ; -#17395 = AXIS2_PLACEMENT_3D ( 'NONE', #28678, #6384, #18843 ) ; -#17396 = ORIENTED_EDGE ( 'NONE', *, *, #17657, .F. ) ; -#17397 = DIRECTION ( 'NONE', ( 0.0005884965786932929224, -0.2255194605963585786, 0.9742384854665229188 ) ) ; -#17398 = ORIENTED_EDGE ( 'NONE', *, *, #10528, .F. ) ; -#17399 = CONICAL_SURFACE ( 'NONE', #36922, 2.503156890187742345, 0.7853981634156100844 ) ; -#17400 = CARTESIAN_POINT ( 'NONE', ( -27.84411046026790615, 187.9073204487185933, 103.0515638343963190 ) ) ; -#17401 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385318054 ) ) ; -#17402 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858958, 190.9636369981938913, 106.3296296870415887 ) ) ; -#17403 = CARTESIAN_POINT ( 'NONE', ( 22.50216366289214065, 153.7345681062837457, 98.21065990825610470 ) ) ; -#17404 = ORIENTED_EDGE ( 'NONE', *, *, #24059, .T. ) ; -#17405 = FACE_OUTER_BOUND ( 'NONE', #23971, .T. ) ; -#17406 = EDGE_LOOP ( 'NONE', ( #13219, #31765, #11573, #12316 ) ) ; -#17407 = CARTESIAN_POINT ( 'NONE', ( 26.06239804790540049, 120.9051242772579968, 90.63100925411518460 ) ) ; -#17408 = CARTESIAN_POINT ( 'NONE', ( -23.34599098040433063, 213.5902373340899487, 75.57257973203529389 ) ) ; -#17410 = CARTESIAN_POINT ( 'NONE', ( -42.64607636366788057, 189.6955224779507034, 106.3355408767127130 ) ) ; -#17409 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17411 = VERTEX_POINT ( 'NONE', #14954 ) ; -#17412 = EDGE_LOOP ( 'NONE', ( #35922, #38034, #957 ) ) ; -#17413 = AXIS2_PLACEMENT_3D ( 'NONE', #13979, #7628, #19291 ) ; -#17414 = EDGE_CURVE ( 'NONE', #16580, #10957, #6132, .T. ) ; -#17415 = EDGE_CURVE ( 'NONE', #19816, #35304, #30038, .T. ) ; -#17416 = CIRCLE ( 'NONE', #5607, 4.999999999999990230 ) ; -#17417 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #58, #454, #18438, #18638 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17418 = AXIS2_PLACEMENT_3D ( 'NONE', #12539, #12962, #15421 ) ; -#17419 = VERTEX_POINT ( 'NONE', #29686 ) ; -#17420 = CARTESIAN_POINT ( 'NONE', ( 38.71212993358000176, 119.3468886729999952, 90.42738107078000098 ) ) ; -#17421 = CARTESIAN_POINT ( 'NONE', ( -35.64769754903084475, 114.8291202300115117, 87.28931460809403120 ) ) ; -#17422 = DIRECTION ( 'NONE', ( -0.0002267487151011638629, -0.6230052038431761474, -0.7822176580526309930 ) ) ; -#17423 = CARTESIAN_POINT ( 'NONE', ( -21.44517147737999707, 135.1113278520462586, 93.93769420648519031 ) ) ; -#17424 = FACE_OUTER_BOUND ( 'NONE', #24139, .T. ) ; -#17425 = VERTEX_POINT ( 'NONE', #39065 ) ; -#17426 = EDGE_LOOP ( 'NONE', ( #16437, #9896, #36624, #27033 ) ) ; -#17427 = VERTEX_POINT ( 'NONE', #11076 ) ; -#17428 = CARTESIAN_POINT ( 'NONE', ( -37.20408499829227367, 178.1325612192622430, 136.7211859319445466 ) ) ; -#17429 = CARTESIAN_POINT ( 'NONE', ( 26.51446272604999876, 123.3842700242000063, 88.29346878733001347 ) ) ; -#17430 = ORIENTED_EDGE ( 'NONE', *, *, #20375, .T. ) ; -#17431 = ORIENTED_EDGE ( 'NONE', *, *, #11530, .F. ) ; -#17432 = DIRECTION ( 'NONE', ( -6.245004513516517373E-15, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#17433 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17434 = EDGE_LOOP ( 'NONE', ( #23653, #15439, #12002, #39375 ) ) ; -#17435 = CARTESIAN_POINT ( 'NONE', ( 39.30807791769741044, 119.0864935850325992, 89.70193021882299433 ) ) ; -#17436 = EDGE_CURVE ( 'NONE', #31729, #2793, #35992, .T. ) ; -#17437 = CARTESIAN_POINT ( 'NONE', ( 21.29537473037836293, 122.9345409059655196, 152.1198303650941170 ) ) ; -#17438 = CARTESIAN_POINT ( 'NONE', ( 20.45288617049414270, 153.3893259209510234, 95.05328524723617534 ) ) ; -#17439 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17440 = ORIENTED_EDGE ( 'NONE', *, *, #20606, .F. ) ; -#17441 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.271205363195980628E-14, -0.9999998176071845934 ) ) ; -#17442 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#17443 = VECTOR ( 'NONE', #33, 1000.000000000000114 ) ; -#17444 = FACE_OUTER_BOUND ( 'NONE', #7409, .T. ) ; -#17445 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30761, #11749, #37089, #8483 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17446 = EDGE_LOOP ( 'NONE', ( #18268, #26668, #2163, #31102 ) ) ; -#17447 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999894129, 179.7376864901495992, 101.1595092802908198 ) ) ; -#17448 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13563, #35000, #38100, #28903 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17450 = LINE ( 'NONE', #14823, #21363 ) ; -#17449 = CARTESIAN_POINT ( 'NONE', ( 13.48868993473300826, 135.2035988320031095, 90.85898476414814695 ) ) ; -#17451 = ORIENTED_EDGE ( 'NONE', *, *, #2632, .T. ) ; -#17452 = ORIENTED_EDGE ( 'NONE', *, *, #22384, .F. ) ; -#17453 = CARTESIAN_POINT ( 'NONE', ( -37.28640831843555503, 117.9292370818984352, 123.9370462788764087 ) ) ; -#17454 = CARTESIAN_POINT ( 'NONE', ( 38.60142841442970507, 118.4926359200404846, 89.66235211310707598 ) ) ; -#17455 = ORIENTED_EDGE ( 'NONE', *, *, #1784, .F. ) ; -#17456 = CARTESIAN_POINT ( 'NONE', ( 2.579967698511000052, 209.6022726829999954, 75.67849517673001003 ) ) ; -#17457 = DIRECTION ( 'NONE', ( -0.7933535325932937754, 0.5931614258681804364, 0.1369295263402624530 ) ) ; -#17458 = APPLICATION_CONTEXT ( 'configuration controlled 3d designs of mechanical parts and assemblies' ) ; -#17459 = DIRECTION ( 'NONE', ( -0.7857167650892391553, 0.6185862428610305885, 0.0004745532376930882562 ) ) ; -#17460 = EDGE_CURVE ( 'NONE', #13095, #33101, #30550, .T. ) ; -#17461 = ORIENTED_EDGE ( 'NONE', *, *, #34539, .F. ) ; -#17462 = EDGE_CURVE ( 'NONE', #10098, #22830, #259, .T. ) ; -#17463 = ORIENTED_EDGE ( 'NONE', *, *, #17740, .F. ) ; -#17464 = CARTESIAN_POINT ( 'NONE', ( 10.03449820175319118, 168.3857740907195364, 99.03493333412644972 ) ) ; -#17465 = ORIENTED_EDGE ( 'NONE', *, *, #23015, .T. ) ; -#17466 = VERTEX_POINT ( 'NONE', #11273 ) ; -#17467 = DIRECTION ( 'NONE', ( 0.0005884949961234757585, -0.2249510543439061094, 0.9743698870671263501 ) ) ; -#17468 = CONICAL_SURFACE ( 'NONE', #33798, 2.503080714863939793, 0.7853981633931875761 ) ; -#17469 = CARTESIAN_POINT ( 'NONE', ( -1.762796036306197633, 151.6652447677196847, 130.5904578367407396 ) ) ; -#17470 = CARTESIAN_POINT ( 'NONE', ( -18.98879854313464577, 125.4558735758789538, 175.9382205149915706 ) ) ; -#17471 = CARTESIAN_POINT ( 'NONE', ( -35.82451515115999996, 192.4421462047999967, 104.2777259915000059 ) ) ; -#17472 = DIRECTION ( 'NONE', ( -0.5605692862037908730, 0.2602880237709958022, 0.7861375325261872327 ) ) ; -#17473 = ORIENTED_EDGE ( 'NONE', *, *, #12252, .F. ) ; -#17474 = CARTESIAN_POINT ( 'NONE', ( -26.00065299636052529, 120.7346046267106203, 87.52068782721254081 ) ) ; -#17475 = VECTOR ( 'NONE', #17459, 1000.000000000000227 ) ; -#17476 = CARTESIAN_POINT ( 'NONE', ( -31.84898476996059813, 157.9423125112969331, 186.4027463543498584 ) ) ; -#17477 = ORIENTED_EDGE ( 'NONE', *, *, #17137, .T. ) ; -#17478 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; -#17479 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971575949 ) ) ; -#17480 = CARTESIAN_POINT ( 'NONE', ( -23.35829001585551978, 177.0054919146453756, 103.4631273769316806 ) ) ; -#17481 = VERTEX_POINT ( 'NONE', #11892 ) ; -#17482 = CARTESIAN_POINT ( 'NONE', ( 37.78115515336936880, 118.8155650090541968, 87.24496173037786662 ) ) ; -#17483 = CARTESIAN_POINT ( 'NONE', ( 14.78600926606004862, 175.8977815190944796, 100.7663474239818839 ) ) ; -#17484 = CARTESIAN_POINT ( 'NONE', ( 20.50072654596022304, 194.3039055573108840, 105.7669459458108037 ) ) ; -#17485 = CARTESIAN_POINT ( 'NONE', ( 44.87321850267542800, 186.3681360267014782, 107.6486605579196123 ) ) ; -#17486 = ORIENTED_EDGE ( 'NONE', *, *, #3678, .F. ) ; -#17487 = CARTESIAN_POINT ( 'NONE', ( -19.40198027091592081, 124.9165765156423760, 177.8474014814652264 ) ) ; -#17488 = EDGE_CURVE ( 'NONE', #17201, #16019, #22729, .T. ) ; -#17489 = FACE_OUTER_BOUND ( 'NONE', #34554, .T. ) ; -#17490 = CARTESIAN_POINT ( 'NONE', ( 20.25161797161999999, 123.2936480544000091, 90.92760764233000259 ) ) ; -#17491 = EDGE_LOOP ( 'NONE', ( #6870, #21520, #26822, #38946 ) ) ; -#17492 = CARTESIAN_POINT ( 'NONE', ( 59.75594728261907562, 246.2738964432155342, 199.3192736266051668 ) ) ; -#17493 = ORIENTED_EDGE ( 'NONE', *, *, #29300, .F. ) ; -#17494 = CARTESIAN_POINT ( 'NONE', ( 13.50029502672948389, 174.4049036335025562, 100.4224658841498297 ) ) ; -#17495 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#17496 = FACE_OUTER_BOUND ( 'NONE', #35644, .T. ) ; -#17497 = CARTESIAN_POINT ( 'NONE', ( -20.01777344647963730, 205.1071326358727163, 76.11698016271346035 ) ) ; -#17498 = CARTESIAN_POINT ( 'NONE', ( -28.26067782467530520, 125.1269179218217857, 91.12357580992288320 ) ) ; -#17499 = ORIENTED_EDGE ( 'NONE', *, *, #13568, .F. ) ; -#17500 = EDGE_CURVE ( 'NONE', #6589, #7826, #13457, .T. ) ; -#17501 = VECTOR ( 'NONE', #13436, 1000.000000000000000 ) ; -#17502 = CARTESIAN_POINT ( 'NONE', ( -30.69659838596064461, 110.6131156702000027, 89.78632472421946886 ) ) ; -#17503 = ADVANCED_FACE ( 'NONE', ( #21300 ), #8828, .T. ) ; -#17504 = DIRECTION ( 'NONE', ( -0.0006039748319387582953, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#17505 = CARTESIAN_POINT ( 'NONE', ( 12.63245678305150044, 181.0156363297572000, 104.5149566212380989 ) ) ; -#17506 = CARTESIAN_POINT ( 'NONE', ( -17.08814518252571091, 121.9278384327233624, 175.1946533361529532 ) ) ; -#17507 = CARTESIAN_POINT ( 'NONE', ( 22.34217513307632785, 154.4094372266218613, 95.28765545888695954 ) ) ; -#17508 = CARTESIAN_POINT ( 'NONE', ( 23.36219596639283225, 175.2460213084726206, 100.6106968941989663 ) ) ; -#17509 = DIRECTION ( 'NONE', ( 0.0006039748319392990953, 2.305558552177526877E-15, 0.9999998176071847045 ) ) ; -#17510 = EDGE_CURVE ( 'NONE', #22903, #19279, #20158, .T. ) ; -#17511 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#17512 = EDGE_CURVE ( 'NONE', #19373, #28309, #9227, .T. ) ; -#17513 = FACE_OUTER_BOUND ( 'NONE', #31217, .T. ) ; -#17514 = ORIENTED_EDGE ( 'NONE', *, *, #30095, .F. ) ; -#17515 = EDGE_CURVE ( 'NONE', #288, #18050, #28429, .T. ) ; -#17516 = ORIENTED_EDGE ( 'NONE', *, *, #4353, .T. ) ; -#17517 = CARTESIAN_POINT ( 'NONE', ( 3.417962904437000127, 184.3981819701000120, 105.0448705359000030 ) ) ; -#17518 = EDGE_CURVE ( 'NONE', #7059, #2798, #13, .T. ) ; -#17519 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#17520 = ORIENTED_EDGE ( 'NONE', *, *, #38163, .T. ) ; -#17521 = CARTESIAN_POINT ( 'NONE', ( 2.564210731195382120, 191.0000001071945235, 106.3128016873806274 ) ) ; -#17522 = ORIENTED_EDGE ( 'NONE', *, *, #38927, .F. ) ; -#17523 = AXIS2_PLACEMENT_3D ( 'NONE', #11259, #36403, #14536 ) ; -#17524 = DIRECTION ( 'NONE', ( -0.0005884949961243157984, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#17525 = CARTESIAN_POINT ( 'NONE', ( 36.05539628129138663, 119.7153741857807745, 90.34852886392080507 ) ) ; -#17526 = VERTEX_POINT ( 'NONE', #37624 ) ; -#17527 = CARTESIAN_POINT ( 'NONE', ( -42.33056243206983282, 103.5691829158648716, 168.6985699702358090 ) ) ; -#17528 = CONICAL_SURFACE ( 'NONE', #25420, 2.503022984658444638, 0.7853981634305220449 ) ; -#17529 = CARTESIAN_POINT ( 'NONE', ( 20.33353033788438680, 138.4388794944718200, 91.94387688982007489 ) ) ; -#17530 = CARTESIAN_POINT ( 'NONE', ( -45.38224234400345125, 124.4312361121064896, 88.40754498314288412 ) ) ; -#17531 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319387907129 ) ) ; -#17532 = VECTOR ( 'NONE', #18795, 1000.000000000000227 ) ; -#17533 = CARTESIAN_POINT ( 'NONE', ( -22.78329764787637046, 154.4034317766920310, 95.31352365236099899 ) ) ; -#17534 = ORIENTED_EDGE ( 'NONE', *, *, #39528, .F. ) ; -#17535 = ORIENTED_EDGE ( 'NONE', *, *, #17371, .T. ) ; -#17536 = CARTESIAN_POINT ( 'NONE', ( 39.93170777403999949, 119.7458890212000142, 87.93590199493999648 ) ) ; -#17537 = EDGE_CURVE ( 'NONE', #22589, #13086, #12977, .T. ) ; -#17538 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17539 = EDGE_LOOP ( 'NONE', ( #35823, #23086, #28470, #8801 ) ) ; -#17540 = CARTESIAN_POINT ( 'NONE', ( -25.07217336826253273, 181.6855096711613839, 101.6134976257350644 ) ) ; -#17541 = ORIENTED_EDGE ( 'NONE', *, *, #25161, .T. ) ; -#17542 = DIRECTION ( 'NONE', ( -0.6087613505914957202, 0.7729391287514063569, 0.1788147680451337707 ) ) ; -#17543 = PLANE ( 'NONE', #10164 ) ; -#17544 = FACE_OUTER_BOUND ( 'NONE', #29011, .T. ) ; -#17545 = CARTESIAN_POINT ( 'NONE', ( 3.416491666947000017, 184.9605596060000039, 102.6089458181999987 ) ) ; -#17546 = CARTESIAN_POINT ( 'NONE', ( 14.74285125918311756, 136.4206760581051867, 93.70497248843004456 ) ) ; -#17547 = ADVANCED_FACE ( 'NONE', ( #24775 ), #18838, .F. ) ; -#17548 = CARTESIAN_POINT ( 'NONE', ( 44.30515803278058229, 188.2843354219114929, 106.1739411498338939 ) ) ; -#17549 = CARTESIAN_POINT ( 'NONE', ( 6.037042346762936162, 176.9423404431283871, 103.3389806385386294 ) ) ; -#17550 = VECTOR ( 'NONE', #986, 1000.000000000000000 ) ; -#17551 = EDGE_CURVE ( 'NONE', #40142, #31711, #27847, .T. ) ; -#17552 = CARTESIAN_POINT ( 'NONE', ( 38.31600023055000293, 118.4557739757999997, 87.79094888852999645 ) ) ; -#17553 = CARTESIAN_POINT ( 'NONE', ( 20.48050040959321549, 208.3867791706507546, 73.74492918753165327 ) ) ; -#17554 = CARTESIAN_POINT ( 'NONE', ( 38.62452218546999916, 119.2816704622000117, 90.41603517917999966 ) ) ; -#17555 = ORIENTED_EDGE ( 'NONE', *, *, #25896, .T. ) ; -#17556 = EDGE_CURVE ( 'NONE', #32811, #13604, #27647, .T. ) ; -#17557 = DIRECTION ( 'NONE', ( -1.734723476052543855E-15, 0.9743700557921586292, 0.2249510932971556243 ) ) ; -#17558 = CARTESIAN_POINT ( 'NONE', ( -20.49954538792513148, 118.3474577000311143, 87.78002983709943408 ) ) ; -#17559 = FACE_OUTER_BOUND ( 'NONE', #26870, .T. ) ; -#17560 = CARTESIAN_POINT ( 'NONE', ( -20.15539790843522283, 117.1470949619612583, 87.27995764731555539 ) ) ; -#17561 = VECTOR ( 'NONE', #40245, 1000.000000000000114 ) ; -#17562 = EDGE_CURVE ( 'NONE', #32051, #31339, #12678, .T. ) ; -#17563 = AXIS2_PLACEMENT_3D ( 'NONE', #2881, #39481, #33552 ) ; -#17564 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 108.4362817545589905, 169.8438797714867405 ) ) ; -#17565 = ORIENTED_EDGE ( 'NONE', *, *, #14071, .F. ) ; -#17566 = ORIENTED_EDGE ( 'NONE', *, *, #7046, .F. ) ; -#17567 = EDGE_CURVE ( 'NONE', #13870, #24015, #37850, .T. ) ; -#17568 = CARTESIAN_POINT ( 'NONE', ( -2.852240684793061476, 190.4446136019508344, 103.6222497587798870 ) ) ; -#17569 = ORIENTED_EDGE ( 'NONE', *, *, #19327, .T. ) ; -#17570 = CARTESIAN_POINT ( 'NONE', ( 30.06438278973887535, 134.2480451416175811, 93.70732421818068758 ) ) ; -#17571 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6370, #18822, #25205, #31326 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17572 = DIRECTION ( 'NONE', ( -0.0005884949961296528920, 0.2249510543439046939, -0.9743698870671267942 ) ) ; -#17573 = ORIENTED_EDGE ( 'NONE', *, *, #38301, .F. ) ; -#17574 = DIRECTION ( 'NONE', ( -0.0004161288024723274501, 0.8480480897761999426, -0.5299191110572988306 ) ) ; -#17575 = CARTESIAN_POINT ( 'NONE', ( -37.04044279746617008, 161.2612793056356963, 189.7402396365586696 ) ) ; -#17576 = CARTESIAN_POINT ( 'NONE', ( -25.60336619595795327, 134.9156435395334199, 90.81609673312185294 ) ) ; -#17577 = FACE_OUTER_BOUND ( 'NONE', #34090, .T. ) ; -#17578 = CARTESIAN_POINT ( 'NONE', ( -37.78603381399999961, 118.7643818931999959, 87.39034903127999598 ) ) ; -#17579 = VERTEX_POINT ( 'NONE', #9023 ) ; -#17580 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#17581 = DIRECTION ( 'NONE', ( -0.0005884941996571894972, 0.2249510543439501575, -0.9743698870675971957 ) ) ; -#17582 = CARTESIAN_POINT ( 'NONE', ( 20.50147081773584290, 151.4111479308915023, 97.16231817868397513 ) ) ; -#17583 = CARTESIAN_POINT ( 'NONE', ( 39.72066837979766518, 175.7297623423441166, 136.1382466769391897 ) ) ; -#17584 = CARTESIAN_POINT ( 'NONE', ( -19.42613131718963260, 148.7783707801748392, 183.2662285685778443 ) ) ; -#17585 = ORIENTED_EDGE ( 'NONE', *, *, #23125, .T. ) ; -#17586 = ORIENTED_EDGE ( 'NONE', *, *, #38338, .T. ) ; -#17587 = VECTOR ( 'NONE', #7473, 1000.000000000000227 ) ; -#17588 = CARTESIAN_POINT ( 'NONE', ( -19.33043961327094706, 148.7913001523307912, 183.3364864566283359 ) ) ; -#17589 = CARTESIAN_POINT ( 'NONE', ( 39.01469539726659264, 120.0482035829021328, 87.34466845720035622 ) ) ; -#17590 = CARTESIAN_POINT ( 'NONE', ( -36.24924816598951338, 190.9038461227203243, 106.8273557833577456 ) ) ; -#17591 = VECTOR ( 'NONE', #40130, 1000.000000000000227 ) ; -#17592 = AXIS2_PLACEMENT_3D ( 'NONE', #29527, #14395, #26469 ) ; -#17593 = ORIENTED_EDGE ( 'NONE', *, *, #8961, .F. ) ; -#17594 = CARTESIAN_POINT ( 'NONE', ( -22.49999922076347758, 151.9675441756866690, 94.75098345857672655 ) ) ; -#17595 = ORIENTED_EDGE ( 'NONE', *, *, #5668, .F. ) ; -#17596 = CARTESIAN_POINT ( 'NONE', ( 25.49065798218091672, 210.6301881023333635, 73.54305791159129058 ) ) ; -#17597 = EDGE_CURVE ( 'NONE', #16772, #30360, #15932, .T. ) ; -#17598 = ADVANCED_FACE ( 'NONE', ( #5943 ), #18398, .T. ) ; -#17599 = ORIENTED_EDGE ( 'NONE', *, *, #6350, .F. ) ; -#17600 = ADVANCED_FACE ( 'NONE', ( #12289 ), #21486, .F. ) ; -#17601 = ORIENTED_EDGE ( 'NONE', *, *, #39414, .T. ) ; -#17602 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17603 = CARTESIAN_POINT ( 'NONE', ( 19.98059076253610300, 209.7097557544199162, 73.04669817794425057 ) ) ; -#17604 = CARTESIAN_POINT ( 'NONE', ( -25.65829064362023004, 196.2716043697412545, 103.7603564967673861 ) ) ; -#17605 = ORIENTED_EDGE ( 'NONE', *, *, #9556, .F. ) ; -#17606 = CARTESIAN_POINT ( 'NONE', ( 46.07851895380935048, 185.2520563475989661, 105.4728131717084949 ) ) ; -#17607 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#17608 = ORIENTED_EDGE ( 'NONE', *, *, #31520, .T. ) ; -#17609 = ADVANCED_FACE ( 'NONE', ( #10023 ), #29021, .T. ) ; -#17610 = CARTESIAN_POINT ( 'NONE', ( 25.69394431265000023, 120.7465094597000075, 90.25074256333999756 ) ) ; -#17611 = CARTESIAN_POINT ( 'NONE', ( 35.48442776063147619, 88.13433118093483642, 282.5337480928039895 ) ) ; -#17613 = DIRECTION ( 'NONE', ( -0.0006039748319388572829, -3.099784637799882324E-15, -0.9999998176071847045 ) ) ; -#17612 = LINE ( 'NONE', #2103, #32382 ) ; -#17614 = ORIENTED_EDGE ( 'NONE', *, *, #20811, .T. ) ; -#17615 = EDGE_CURVE ( 'NONE', #1820, #11064, #20760, .T. ) ; -#17616 = CONICAL_SURFACE ( 'NONE', #12406, 2.503000006865153448, 0.7853981633739405277 ) ; -#17617 = AXIS2_PLACEMENT_3D ( 'NONE', #18625, #24203, #12124 ) ; -#17618 = ORIENTED_EDGE ( 'NONE', *, *, #2515, .T. ) ; -#17619 = AXIS2_PLACEMENT_3D ( 'NONE', #5664, #12397, #15858 ) ; -#17620 = CARTESIAN_POINT ( 'NONE', ( -25.83516676602354778, 119.7245759509484913, 87.30912072347993558 ) ) ; -#17621 = AXIS2_PLACEMENT_3D ( 'NONE', #761, #6894, #10191 ) ; -#17622 = VERTEX_POINT ( 'NONE', #1000 ) ; -#17623 = CARTESIAN_POINT ( 'NONE', ( 39.25497886610000364, 118.8953424551000211, 89.53045808048000254 ) ) ; -#17624 = FACE_OUTER_BOUND ( 'NONE', #5811, .T. ) ; -#17625 = EDGE_CURVE ( 'NONE', #15629, #29127, #4679, .T. ) ; -#17626 = LINE ( 'NONE', #2316, #12873 ) ; -#17627 = CARTESIAN_POINT ( 'NONE', ( -22.78227175507932500, 153.4787728439779357, 97.83686093391889926 ) ) ; -#17628 = CARTESIAN_POINT ( 'NONE', ( 36.12366260232001025, 191.5066187523999872, 103.8330160090000049 ) ) ; -#17629 = ORIENTED_EDGE ( 'NONE', *, *, #23571, .T. ) ; -#17630 = ORIENTED_EDGE ( 'NONE', *, *, #33646, .F. ) ; -#17631 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048994616, 134.2394347309202658, 93.74516030699426494 ) ) ; -#17632 = FACE_OUTER_BOUND ( 'NONE', #21452, .T. ) ; -#17633 = CARTESIAN_POINT ( 'NONE', ( 15.87308592176477795, 186.6781958245231010, 102.7413939128299489 ) ) ; -#17634 = ORIENTED_EDGE ( 'NONE', *, *, #31154, .F. ) ; -#17635 = ORIENTED_EDGE ( 'NONE', *, *, #39262, .F. ) ; -#17636 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; -#17637 = CARTESIAN_POINT ( 'NONE', ( 41.09291594421311089, 217.7719116457018060, 152.4682433584083867 ) ) ; -#17638 = ORIENTED_EDGE ( 'NONE', *, *, #39310, .T. ) ; -#17639 = CARTESIAN_POINT ( 'NONE', ( -20.51848692360195514, 206.3589432834550905, 75.06605631655357058 ) ) ; -#17640 = CIRCLE ( 'NONE', #22896, 7.999999999999992895 ) ; -#17641 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971541255 ) ) ; -#17642 = DIRECTION ( 'NONE', ( 0.0005884949961162573573, -0.2249510543439059151, 0.9743698870671263501 ) ) ; -#17643 = CARTESIAN_POINT ( 'NONE', ( -21.82845864282945669, 129.2731355035732292, 92.07692058346603403 ) ) ; -#17644 = VECTOR ( 'NONE', #36279, 999.9999999999998863 ) ; -#17645 = ORIENTED_EDGE ( 'NONE', *, *, #35580, .F. ) ; -#17646 = AXIS2_PLACEMENT_3D ( 'NONE', #35241, #310, #3568 ) ; -#17647 = ADVANCED_FACE ( 'NONE', ( #29231 ), #31708, .T. ) ; -#17648 = EDGE_CURVE ( 'NONE', #27876, #25693, #13491, .T. ) ; -#17649 = DIRECTION ( 'NONE', ( -0.7072735235945706300, -0.6508952239913728954, -0.2758615054829884894 ) ) ; -#17650 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#17651 = ORIENTED_EDGE ( 'NONE', *, *, #15141, .F. ) ; -#17652 = ADVANCED_FACE ( 'NONE', ( #38016 ), #3658, .T. ) ; -#17653 = CARTESIAN_POINT ( 'NONE', ( 39.53379105069361543, 120.3902222971681368, 87.42331650858173475 ) ) ; -#17655 = FACE_OUTER_BOUND ( 'NONE', #15714, .T. ) ; -#17654 = CARTESIAN_POINT ( 'NONE', ( 15.50029467790899496, 185.7974155947267718, 103.0514270424844483 ) ) ; -#17656 = ORIENTED_EDGE ( 'NONE', *, *, #11723, .F. ) ; -#17657 = EDGE_CURVE ( 'NONE', #13026, #31750, #22300, .T. ) ; -#17658 = ORIENTED_EDGE ( 'NONE', *, *, #31666, .F. ) ; -#17659 = ORIENTED_EDGE ( 'NONE', *, *, #35817, .F. ) ; -#17660 = CARTESIAN_POINT ( 'NONE', ( 19.99995599910763389, 165.3414092450989301, 97.81287038969479397 ) ) ; -#17661 = CARTESIAN_POINT ( 'NONE', ( 2.562619485644860973, 196.1181876864285698, 103.6781880485148406 ) ) ; -#17662 = DIRECTION ( 'NONE', ( 0.0004716571195295989473, 0.6225146315353430326, 0.7826080187833355239 ) ) ; -#17663 = EDGE_LOOP ( 'NONE', ( #2864, #13679, #33424, #27547 ) ) ; -#17664 = ORIENTED_EDGE ( 'NONE', *, *, #34361, .F. ) ; -#17665 = CARTESIAN_POINT ( 'NONE', ( -13.50000077923899688, 138.1929969155733318, 91.56544231107801579 ) ) ; -#17666 = VERTEX_POINT ( 'NONE', #35121 ) ; -#17667 = ORIENTED_EDGE ( 'NONE', *, *, #36868, .F. ) ; -#17668 = DIRECTION ( 'NONE', ( -0.7865509479255973213, -0.6175253892086901564, 0.000000000000000000 ) ) ; -#17669 = EDGE_CURVE ( 'NONE', #4296, #13220, #15591, .T. ) ; -#17670 = AXIS2_PLACEMENT_3D ( 'NONE', #23116, #25793, #26389 ) ; -#17671 = CARTESIAN_POINT ( 'NONE', ( -24.02278420256503111, 115.4960067055939277, 202.0650339681855883 ) ) ; -#17672 = ORIENTED_EDGE ( 'NONE', *, *, #22297, .T. ) ; -#17673 = AXIS2_PLACEMENT_3D ( 'NONE', #10752, #13224, #932 ) ; -#17674 = ORIENTED_EDGE ( 'NONE', *, *, #24198, .T. ) ; -#17675 = CARTESIAN_POINT ( 'NONE', ( -20.49711472948942870, 211.0904275233606313, 75.59256565440196596 ) ) ; -#17676 = AXIS2_PLACEMENT_3D ( 'NONE', #39207, #19782, #11015 ) ; -#17677 = CARTESIAN_POINT ( 'NONE', ( -35.75587340871999942, 191.8338532855999858, 104.0497549258000021 ) ) ; -#17678 = CARTESIAN_POINT ( 'NONE', ( 36.67500110392000323, 191.3369781904000320, 103.9170611561000186 ) ) ; -#17679 = CARTESIAN_POINT ( 'NONE', ( -25.50102279335000333, 120.6643622512000036, 88.03908242295000264 ) ) ; -#17680 = ORIENTED_EDGE ( 'NONE', *, *, #17556, .F. ) ; -#17681 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17682 = CARTESIAN_POINT ( 'NONE', ( -35.94780537806226306, 113.8881156701999942, 87.78949595635012315 ) ) ; -#17683 = VERTEX_POINT ( 'NONE', #1205 ) ; -#17684 = CARTESIAN_POINT ( 'NONE', ( -37.67574118798827243, 118.8155645602721222, 87.29053938956874958 ) ) ; -#17685 = DIRECTION ( 'NONE', ( -0.6087116037913344879, 0.7730376917437173923, 0.1785578633197842380 ) ) ; -#17686 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #24888, #37341 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17687 = DIRECTION ( 'NONE', ( 0.0005559617913757295945, -0.3907311284892698300, 0.9205046855589537058 ) ) ; -#17688 = CARTESIAN_POINT ( 'NONE', ( -3.931607349826474529, 167.9092076435330512, 101.0933002075414038 ) ) ; -#17689 = VERTEX_POINT ( 'NONE', #34923 ) ; -#17690 = CARTESIAN_POINT ( 'NONE', ( -24.42746480248682062, 109.6131156702000027, 87.78253795971667728 ) ) ; -#17691 = CARTESIAN_POINT ( 'NONE', ( 2.242171634080408094, 189.9138756023754127, 103.9471229047883014 ) ) ; -#17692 = CARTESIAN_POINT ( 'NONE', ( 30.06443600138266703, 134.9229365128052507, 90.78414315763292564 ) ) ; -#17693 = ORIENTED_EDGE ( 'NONE', *, *, #39270, .F. ) ; -#17694 = CARTESIAN_POINT ( 'NONE', ( 20.48015056202373074, 210.1700361193774143, 73.54651103472254192 ) ) ; -#17695 = ORIENTED_EDGE ( 'NONE', *, *, #28235, .F. ) ; -#17696 = ORIENTED_EDGE ( 'NONE', *, *, #34963, .T. ) ; -#17697 = EDGE_CURVE ( 'NONE', #23821, #38370, #32500, .T. ) ; -#17698 = CARTESIAN_POINT ( 'NONE', ( -42.43581683406742400, 94.00600134306105815, 291.5841741052475413 ) ) ; -#17699 = AXIS2_PLACEMENT_3D ( 'NONE', #2475, #15535, #18774 ) ; -#17700 = ADVANCED_FACE ( 'NONE', ( #13091 ), #17528, .F. ) ; -#17701 = DIRECTION ( 'NONE', ( -0.6087614115774886425, 0.7730004600455401276, 0.1785492440296710948 ) ) ; -#17702 = CARTESIAN_POINT ( 'NONE', ( 25.88353131012999953, 191.8571809995999899, 104.0322739423999963 ) ) ; -#17703 = AXIS2_PLACEMENT_3D ( 'NONE', #32497, #31709, #4468 ) ; -#17704 = CIRCLE ( 'NONE', #18346, 6.000000651512662486 ) ; -#17705 = CARTESIAN_POINT ( 'NONE', ( 16.77614372998638359, 152.4482931959673806, 181.9616063807505384 ) ) ; -#17706 = DIRECTION ( 'NONE', ( 0.0005884950603321816021, -0.2249510543244929717, 0.9743698870715694627 ) ) ; -#17707 = VERTEX_POINT ( 'NONE', #19194 ) ; -#17708 = EDGE_CURVE ( 'NONE', #6620, #35941, #26173, .T. ) ; -#17709 = DIRECTION ( 'NONE', ( -0.0004161288024302700009, 0.8480480898291783420, -0.5299191109725157611 ) ) ; -#17710 = CARTESIAN_POINT ( 'NONE', ( 43.14456005852381537, 112.6780295318855565, 129.4537069268840526 ) ) ; -#17711 = LINE ( 'NONE', #8335, #28404 ) ; -#17712 = CARTESIAN_POINT ( 'NONE', ( 19.71684765030295949, 124.8915327974199130, 176.0741111412129385 ) ) ; -#17713 = DIRECTION ( 'NONE', ( 0.0005884949961256158652, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17714 = CARTESIAN_POINT ( 'NONE', ( -20.89282324149344561, 183.0959377177359215, 101.9365769416837253 ) ) ; -#17715 = CARTESIAN_POINT ( 'NONE', ( -22.54148966027999990, 174.6477734297156985, 27.63001052910568944 ) ) ; -#17716 = CARTESIAN_POINT ( 'NONE', ( 20.28520147395606799, 116.8369336581640709, 90.25553308582213674 ) ) ; -#17717 = EDGE_LOOP ( 'NONE', ( #34414, #23767, #13187, #7471 ) ) ; -#17718 = CARTESIAN_POINT ( 'NONE', ( 4.034499242067735025, 144.1016867008426061, 93.43213283160849869 ) ) ; -#17719 = ADVANCED_FACE ( 'NONE', ( #19405 ), #2527, .F. ) ; -#17720 = CARTESIAN_POINT ( 'NONE', ( -42.83981852382991917, 113.7604137494400476, 123.0507168651698038 ) ) ; -#17721 = ORIENTED_EDGE ( 'NONE', *, *, #27067, .T. ) ; -#17722 = CARTESIAN_POINT ( 'NONE', ( -35.95473150033847531, 205.5673820439000110, 76.32193034924999608 ) ) ; -#17723 = ORIENTED_EDGE ( 'NONE', *, *, #12203, .T. ) ; -#17724 = CARTESIAN_POINT ( 'NONE', ( -38.20553841305000020, 119.1510546080999973, 87.44536496121999392 ) ) ; -#17725 = AXIS2_PLACEMENT_3D ( 'NONE', #24789, #37238, #34157 ) ; -#17726 = CARTESIAN_POINT ( 'NONE', ( -16.17179426088062044, 151.9775549948883508, 184.4787338324457835 ) ) ; -#17727 = EDGE_LOOP ( 'NONE', ( #38698, #13924, #19227, #1899 ) ) ; -#17728 = CARTESIAN_POINT ( 'NONE', ( 35.82807448362839864, 191.6307925291198160, 106.8885444632594499 ) ) ; -#17729 = EDGE_CURVE ( 'NONE', #7664, #23325, #25385, .T. ) ; -#17730 = PLANE ( 'NONE', #19173 ) ; -#17731 = CARTESIAN_POINT ( 'NONE', ( 13.46612284730906950, 158.3062971533392158, 96.19268454968825210 ) ) ; -#17732 = CARTESIAN_POINT ( 'NONE', ( -12.63555412105795561, 130.0309333250218629, 92.32931262750892643 ) ) ; -#17733 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; -#17734 = CARTESIAN_POINT ( 'NONE', ( 39.82491996314075777, 141.3585264024648609, 285.0163987782322579 ) ) ; -#17735 = ORIENTED_EDGE ( 'NONE', *, *, #8930, .F. ) ; -#17736 = CARTESIAN_POINT ( 'NONE', ( 39.45067306616000025, 120.1726932226000031, 87.49420585638002024 ) ) ; -#17737 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#17738 = DIRECTION ( 'NONE', ( -4.163336342262541617E-15, 0.9743700557921591843, 0.2249510932971534871 ) ) ; -#17739 = CARTESIAN_POINT ( 'NONE', ( 16.23201905896638308, 152.0606143167149185, 181.0564827348360382 ) ) ; -#17740 = EDGE_CURVE ( 'NONE', #2098, #35411, #12016, .T. ) ; -#17741 = VERTEX_POINT ( 'NONE', #39221 ) ; -#17742 = CARTESIAN_POINT ( 'NONE', ( 3.334680759033842534, 127.9501515180691769, 92.09838694450060359 ) ) ; -#17743 = ADVANCED_FACE ( 'NONE', ( #29632 ), #39015, .F. ) ; -#17744 = CARTESIAN_POINT ( 'NONE', ( -43.00608122665288136, 121.0191425024765550, 90.97016640535348131 ) ) ; -#17746 = EDGE_CURVE ( 'NONE', #38838, #133, #26056, .T. ) ; -#17745 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927789280832, 0.0005734119022080210902 ) ) ; -#17747 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323826020982455905, 0.0005734119000540774001 ) ) ; -#17748 = CARTESIAN_POINT ( 'NONE', ( -25.71417928276665421, 212.4116159412069464, 73.07403480233796245 ) ) ; -#17749 = ADVANCED_FACE ( 'NONE', ( #26772 ), #38806, .T. ) ; -#17750 = AXIS2_PLACEMENT_3D ( 'NONE', #5526, #15155, #17991 ) ; -#17751 = DIRECTION ( 'NONE', ( -0.0005884949961206531466, 0.2249510543439048327, -0.9743698870671267942 ) ) ; -#17752 = AXIS2_PLACEMENT_3D ( 'NONE', #34637, #22408, #34439 ) ; -#17753 = CARTESIAN_POINT ( 'NONE', ( 6.037027004990604517, 176.9341431689030060, 103.3258622659047461 ) ) ; -#17754 = AXIS2_PLACEMENT_3D ( 'NONE', #6060, #2984, #18709 ) ; -#17755 = CARTESIAN_POINT ( 'NONE', ( 38.13590145119999875, 118.2511992291999974, 87.79762229201999446 ) ) ; -#17756 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; -#17757 = CARTESIAN_POINT ( 'NONE', ( 26.07108133293812813, 121.6493863964714279, 87.72214823715854948 ) ) ; -#17758 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#17759 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#17760 = CARTESIAN_POINT ( 'NONE', ( -23.00006628334871550, 115.6131129681876359, 89.78164257609942922 ) ) ; -#17761 = DIRECTION ( 'NONE', ( 0.0005884949961232180437, -0.2249510543439044996, 0.9743698870671267942 ) ) ; -#17762 = LINE ( 'NONE', #30064, #31108 ) ; -#17763 = VERTEX_POINT ( 'NONE', #36153 ) ; -#17764 = ORIENTED_EDGE ( 'NONE', *, *, #17515, .F. ) ; -#17765 = CARTESIAN_POINT ( 'NONE', ( -1.448782306007865506, 188.8264521967578844, 103.2478200403819955 ) ) ; -#17766 = VERTEX_POINT ( 'NONE', #26371 ) ; -#17767 = CARTESIAN_POINT ( 'NONE', ( -23.36047527027495363, 177.3840784139692346, 100.9652270349779997 ) ) ; -#17768 = CARTESIAN_POINT ( 'NONE', ( -6.037299711038997430, 177.1908694379475264, 101.0774571039573999 ) ) ; -#17769 = CARTESIAN_POINT ( 'NONE', ( -48.00106611543790081, 61.15928328279096604, 291.5875353763605062 ) ) ; -#17770 = ORIENTED_EDGE ( 'NONE', *, *, #36059, .T. ) ; -#17771 = CARTESIAN_POINT ( 'NONE', ( -39.41254998849999680, 119.8270850916999990, 90.55892179784000007 ) ) ; -#17772 = DIRECTION ( 'NONE', ( -0.7933533411653341805, 0.5930537057989598848, 0.1373964268091485141 ) ) ; -#17773 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749096068, 179.1800746285871355, 103.5747911658281168 ) ) ; -#17774 = CARTESIAN_POINT ( 'NONE', ( -35.30169115038999905, 112.8556044416999953, 87.14184160035000559 ) ) ; -#17775 = ORIENTED_EDGE ( 'NONE', *, *, #17313, .F. ) ; -#17776 = DIRECTION ( 'NONE', ( -0.0006039748319391913256, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#17777 = ORIENTED_EDGE ( 'NONE', *, *, #38058, .F. ) ; -#17778 = LINE ( 'NONE', #39666, #8745 ) ; -#17779 = DIRECTION ( 'NONE', ( -0.0006039748319383107366, -1.234791622901071989E-14, -0.9999998176071845934 ) ) ; -#17780 = AXIS2_PLACEMENT_3D ( 'NONE', #27379, #36543, #20596 ) ; -#17781 = CARTESIAN_POINT ( 'NONE', ( 36.04389107617218002, 115.3860002890582734, 90.24601523218206012 ) ) ; -#17782 = CARTESIAN_POINT ( 'NONE', ( -12.63842163636918059, 181.1849447922443233, 104.4215566640188086 ) ) ; -#17783 = ORIENTED_EDGE ( 'NONE', *, *, #5719, .F. ) ; -#17784 = EDGE_CURVE ( 'NONE', #3379, #34917, #15901, .T. ) ; -#17785 = CARTESIAN_POINT ( 'NONE', ( -28.54477463726000508, 187.2491079767000031, 103.0247649423999974 ) ) ; -#17786 = VECTOR ( 'NONE', #13896, 1000.000000000000227 ) ; -#17787 = CARTESIAN_POINT ( 'NONE', ( 0.7115303131630320577, 189.0187413740609941, 103.6993385983880245 ) ) ; -#17788 = CARTESIAN_POINT ( 'NONE', ( -35.97303847993521941, 191.1967732357732075, 106.8821304174405782 ) ) ; -#17789 = ADVANCED_FACE ( 'NONE', ( #33488 ), #33084, .T. ) ; -#17790 = ORIENTED_EDGE ( 'NONE', *, *, #19466, .F. ) ; -#17791 = CARTESIAN_POINT ( 'NONE', ( 30.05503346856145086, 103.6131156702632410, 89.74963226087875512 ) ) ; -#17792 = VERTEX_POINT ( 'NONE', #20830 ) ; -#17793 = EDGE_CURVE ( 'NONE', #13780, #7212, #8430, .T. ) ; -#17794 = EDGE_CURVE ( 'NONE', #17966, #16874, #32693, .T. ) ; -#17795 = EDGE_CURVE ( 'NONE', #20168, #37805, #29433, .T. ) ; -#17796 = ORIENTED_EDGE ( 'NONE', *, *, #11114, .F. ) ; -#17797 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23079, #39003, #29218, #26755 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17798 = ORIENTED_EDGE ( 'NONE', *, *, #3498, .T. ) ; -#17799 = CARTESIAN_POINT ( 'NONE', ( -35.95698934392000012, 192.3172225881000372, 105.8170796091999932 ) ) ; -#17800 = DIRECTION ( 'NONE', ( 0.7856637149787880636, -0.6186538021912818541, 0.000000000000000000 ) ) ; -#17801 = CARTESIAN_POINT ( 'NONE', ( -31.91335489949009130, 137.9985878559502623, 92.04483278691883186 ) ) ; -#17802 = ORIENTED_EDGE ( 'NONE', *, *, #32091, .T. ) ; -#17803 = CARTESIAN_POINT ( 'NONE', ( -22.49852798328017300, 151.4051665355240459, 97.18690819472567455 ) ) ; -#17804 = CONICAL_SURFACE ( 'NONE', #39997, 4.999999999923872451, 0.7853981633990386735 ) ; -#17805 = VERTEX_POINT ( 'NONE', #1402 ) ; -#17806 = CARTESIAN_POINT ( 'NONE', ( 28.35073491905000154, 124.9606733549999973, 91.22198593361000007 ) ) ; -#17807 = CARTESIAN_POINT ( 'NONE', ( -35.92212000658612681, 191.5653759301798686, 103.9005706184658067 ) ) ; -#17808 = VECTOR ( 'NONE', #36076, 1000.000000000000227 ) ; -#17810 = CARTESIAN_POINT ( 'NONE', ( 37.49119510912425568, 212.8449757119041408, 76.03586094040831256 ) ) ; -#17809 = CARTESIAN_POINT ( 'NONE', ( -25.51533646434189961, 211.0902259025884007, 73.57326538444725372 ) ) ; -#17811 = EDGE_LOOP ( 'NONE', ( #16303, #14206, #10103, #39867 ) ) ; -#17812 = VECTOR ( 'NONE', #12762, 1000.000000000000000 ) ; -#17813 = ADVANCED_FACE ( 'NONE', ( #10831 ), #7738, .T. ) ; -#17814 = ORIENTED_EDGE ( 'NONE', *, *, #38173, .T. ) ; -#17815 = ORIENTED_EDGE ( 'NONE', *, *, #14543, .T. ) ; -#17816 = CARTESIAN_POINT ( 'NONE', ( 39.44669341952000252, 119.3098229202999931, 89.86714104326999575 ) ) ; -#17817 = CARTESIAN_POINT ( 'NONE', ( -13.46442671968396709, 158.3027909046028583, 96.20813345690331175 ) ) ; -#17818 = CARTESIAN_POINT ( 'NONE', ( 14.31450538706609521, 182.2837619838007583, 101.7278000795456308 ) ) ; -#17819 = LINE ( 'NONE', #14585, #31821 ) ; -#17820 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672665709, 158.2308735878961556, 98.74100402060588522 ) ) ; -#17821 = ORIENTED_EDGE ( 'NONE', *, *, #5815, .T. ) ; -#17822 = ORIENTED_EDGE ( 'NONE', *, *, #19502, .F. ) ; -#17823 = EDGE_CURVE ( 'NONE', #5875, #32498, #5949, .T. ) ; -#17824 = ORIENTED_EDGE ( 'NONE', *, *, #34713, .T. ) ; -#17825 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 5.029100215316657124E-18, 0.0006039748319386160479 ) ) ; -#17826 = CARTESIAN_POINT ( 'NONE', ( 27.28348237275000088, 124.2320809166999993, 88.31760212342000216 ) ) ; -#17827 = ORIENTED_EDGE ( 'NONE', *, *, #9508, .T. ) ; -#17828 = EDGE_CURVE ( 'NONE', #19997, #5617, #1221, .T. ) ; -#17829 = CARTESIAN_POINT ( 'NONE', ( -3.859508698811262128, 144.1403424298719074, 93.26310401271429384 ) ) ; -#17830 = EDGE_CURVE ( 'NONE', #39132, #14925, #32578, .T. ) ; -#17831 = ORIENTED_EDGE ( 'NONE', *, *, #11295, .F. ) ; -#17832 = AXIS2_PLACEMENT_3D ( 'NONE', #32569, #4346, #36236 ) ; -#17833 = CARTESIAN_POINT ( 'NONE', ( 1.106619553340999929, 188.8408486938999999, 105.9110459091999985 ) ) ; -#17834 = LINE ( 'NONE', #37075, #2056 ) ; -#17835 = EDGE_CURVE ( 'NONE', #22597, #19682, #10565, .T. ) ; -#17836 = CONICAL_SURFACE ( 'NONE', #36150, 22.50000000000898837, 0.7853981633973132759 ) ; -#17837 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#17838 = CARTESIAN_POINT ( 'NONE', ( -82.79477499249559003, 72.19295329727926003, 166.5670822259618262 ) ) ; -#17839 = VERTEX_POINT ( 'NONE', #17331 ) ; -#17840 = CARTESIAN_POINT ( 'NONE', ( 25.75023662782000500, 199.6921533858000259, 89.48600966998000672 ) ) ; -#17841 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34684, #35080, #550, #32060 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17842 = DIRECTION ( 'NONE', ( -0.7933533411653076461, 0.5930537057989941907, 0.1373964268091527330 ) ) ; -#17843 = ORIENTED_EDGE ( 'NONE', *, *, #4633, .F. ) ; -#17844 = CARTESIAN_POINT ( 'NONE', ( 29.91189702434756370, 126.8852189367780170, 89.27071757938477958 ) ) ; -#17845 = ORIENTED_EDGE ( 'NONE', *, *, #32753, .F. ) ; -#17847 = CARTESIAN_POINT ( 'NONE', ( -35.38988506213597418, 77.14301703112144537, 290.1978808180363671 ) ) ; -#17846 = DIRECTION ( 'NONE', ( 0.9999998268371397270, 0.0001323824647179528205, -0.0005734113476489175907 ) ) ; -#17848 = ORIENTED_EDGE ( 'NONE', *, *, #11301, .T. ) ; -#17849 = ORIENTED_EDGE ( 'NONE', *, *, #35017, .T. ) ; -#17850 = CONICAL_SURFACE ( 'NONE', #30288, 2.499997363466079037, 0.7853981633710050980 ) ; -#17851 = AXIS2_PLACEMENT_3D ( 'NONE', #18561, #28400, #27617 ) ; -#17852 = ORIENTED_EDGE ( 'NONE', *, *, #36604, .T. ) ; -#17853 = CARTESIAN_POINT ( 'NONE', ( 2.408274994265000579, 208.8706265008999878, 75.56874651716999836 ) ) ; -#17854 = CARTESIAN_POINT ( 'NONE', ( -25.99978576141418429, 118.1122949349609286, 90.28348809642494643 ) ) ; -#17855 = CARTESIAN_POINT ( 'NONE', ( -15.94527486429822538, 152.8203387458500231, 181.6302711725483050 ) ) ; -#17856 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066635700, 183.5616063994668536, 104.6006436764798195 ) ) ; -#17858 = ORIENTED_EDGE ( 'NONE', *, *, #16584, .F. ) ; -#17857 = AXIS2_PLACEMENT_3D ( 'NONE', #2713, #28251, #6546 ) ; -#17859 = CARTESIAN_POINT ( 'NONE', ( -37.20408499807465574, 178.1325612194088421, 136.7211859319782263 ) ) ; -#17860 = EDGE_LOOP ( 'NONE', ( #733, #5146, #10025, #35211 ) ) ; -#17861 = ORIENTED_EDGE ( 'NONE', *, *, #24383, .F. ) ; -#17862 = CARTESIAN_POINT ( 'NONE', ( -23.36013443158915237, 136.6763330450122567, 94.30332275863374036 ) ) ; -#17863 = AXIS2_PLACEMENT_3D ( 'NONE', #22083, #15922, #24962 ) ; -#17864 = CARTESIAN_POINT ( 'NONE', ( 25.99199080364422443, 211.0901596425212574, 76.04279652306830428 ) ) ; -#17865 = CARTESIAN_POINT ( 'NONE', ( -13.54341419034824945, 127.9461742602649679, 176.4876677107182843 ) ) ; -#17866 = CARTESIAN_POINT ( 'NONE', ( 19.39390165059181825, 124.9043552653802180, 177.8552826716125139 ) ) ; -#17867 = CARTESIAN_POINT ( 'NONE', ( 35.90076804576000313, 192.3671129742999995, 104.2031949967000202 ) ) ; -#17868 = ORIENTED_EDGE ( 'NONE', *, *, #38672, .T. ) ; -#17869 = ADVANCED_FACE ( 'NONE', ( #13885 ), #39074, .T. ) ; -#17870 = ORIENTED_EDGE ( 'NONE', *, *, #1354, .F. ) ; -#17871 = EDGE_CURVE ( 'NONE', #38693, #24898, #14559, .T. ) ; -#17872 = ORIENTED_EDGE ( 'NONE', *, *, #31153, .T. ) ; -#17873 = CARTESIAN_POINT ( 'NONE', ( 3.991644188892757406, 184.7664131289848228, 28.08339314683390242 ) ) ; -#17874 = EDGE_CURVE ( 'NONE', #3122, #11256, #17392, .T. ) ; -#17875 = CARTESIAN_POINT ( 'NONE', ( -35.89350200887000142, 191.4464572824000186, 103.7438032780000015 ) ) ; -#17876 = EDGE_LOOP ( 'NONE', ( #26502, #5700, #1103, #36707, #2571, #2570, #34030, #1464, #19589, #459 ) ) ; -#17877 = CARTESIAN_POINT ( 'NONE', ( -25.66781978934000108, 120.6928363009999998, 87.87473006517001295 ) ) ; -#17878 = EDGE_LOOP ( 'NONE', ( #99, #11348, #6816, #14600, #14906 ) ) ; -#17879 = VERTEX_POINT ( 'NONE', #30849 ) ; -#17880 = DIRECTION ( 'NONE', ( 0.0004161288024604291444, 0.5299192578603125758, 0.8480479980435040588 ) ) ; -#17881 = CARTESIAN_POINT ( 'NONE', ( -40.86425246474745165, 188.5523987672290218, 107.5827897523195560 ) ) ; -#17882 = ORIENTED_EDGE ( 'NONE', *, *, #21090, .F. ) ; -#17883 = EDGE_CURVE ( 'NONE', #12644, #36762, #9174, .T. ) ; -#17884 = CARTESIAN_POINT ( 'NONE', ( 1.993517670461378399, 189.0625354601347397, 103.3002451033650431 ) ) ; -#17885 = CARTESIAN_POINT ( 'NONE', ( 20.50081714887910778, 194.1061032057583873, 105.8792863328844902 ) ) ; -#17886 = CARTESIAN_POINT ( 'NONE', ( 38.68874437559378521, 119.1826339606430878, 90.26160218306198146 ) ) ; -#17887 = VECTOR ( 'NONE', #36635, 1000.000000000000227 ) ; -#17888 = ORIENTED_EDGE ( 'NONE', *, *, #13597, .T. ) ; -#17890 = EDGE_CURVE ( 'NONE', #25001, #31188, #31236, .T. ) ; -#17889 = CARTESIAN_POINT ( 'NONE', ( 12.31735795870903161, 134.2458240057509329, 93.71748532227019268 ) ) ; -#17891 = CARTESIAN_POINT ( 'NONE', ( 2.346033262188341961, 190.0750585238097585, 103.9936005391582654 ) ) ; -#17892 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14445, #26315, #11581, #11172 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17893 = AXIS2_PLACEMENT_3D ( 'NONE', #37823, #15741, #10235 ) ; -#17894 = CIRCLE ( 'NONE', #21190, 2.500000000002172040 ) ; -#17895 = CARTESIAN_POINT ( 'NONE', ( 20.50124949713573841, 118.1127836709285077, 89.08883525397649805 ) ) ; -#17896 = VERTEX_POINT ( 'NONE', #15306 ) ; -#17897 = CARTESIAN_POINT ( 'NONE', ( 26.00056762447263026, 118.1139028608674408, 90.25209678512123901 ) ) ; -#17898 = ORIENTED_EDGE ( 'NONE', *, *, #31991, .F. ) ; -#17899 = AXIS2_PLACEMENT_3D ( 'NONE', #22272, #37990, #6700 ) ; -#17900 = CARTESIAN_POINT ( 'NONE', ( -44.96472012149743591, 114.9735949632774634, 130.1287737409121235 ) ) ; -#17901 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251392786, 179.1753088543749755, 103.5954339977854346 ) ) ; -#17902 = CARTESIAN_POINT ( 'NONE', ( -26.00146729408999491, 120.3902237924986451, 87.46289810595591518 ) ) ; -#17903 = CARTESIAN_POINT ( 'NONE', ( -29.53010039065708270, 181.9152030469051624, 101.6691925721778347 ) ) ; -#17904 = DIRECTION ( 'NONE', ( -0.7933530821293308666, -0.5932640870757669438, -0.1364866662427074440 ) ) ; -#17905 = ORIENTED_EDGE ( 'NONE', *, *, #19954, .T. ) ; -#17906 = FACE_OUTER_BOUND ( 'NONE', #11551, .T. ) ; -#17907 = DIRECTION ( 'NONE', ( -8.673617379883985182E-16, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#17908 = FACE_OUTER_BOUND ( 'NONE', #12330, .T. ) ; -#17909 = CARTESIAN_POINT ( 'NONE', ( 75.24056455973224899, 196.4820008462166641, 189.1802437148639058 ) ) ; -#17910 = CARTESIAN_POINT ( 'NONE', ( 19.71699054648574645, 124.6499361933662158, 177.1222525964093109 ) ) ; -#17911 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#17912 = DIRECTION ( 'NONE', ( -0.4305589114774804327, -0.3870810988319002277, -0.8153448636463075383 ) ) ; -#17913 = DIRECTION ( 'NONE', ( -0.6087616187692346248, 0.7730003051580285334, 0.1785492081725818803 ) ) ; -#17914 = DIRECTION ( 'NONE', ( -0.0004161288024432313669, 0.8480480898092180864, -0.5299191110044590980 ) ) ; -#17915 = ORIENTED_EDGE ( 'NONE', *, *, #20373, .F. ) ; -#17916 = VECTOR ( 'NONE', #8939, 1000.000000000000227 ) ; -#17917 = CARTESIAN_POINT ( 'NONE', ( 3.534327104360340588, 144.2236672556986434, 92.94748474794259607 ) ) ; -#17918 = CIRCLE ( 'NONE', #19869, 2.000000000014617640 ) ; -#17919 = CARTESIAN_POINT ( 'NONE', ( -17.34531841520229634, 127.5687170461390565, 172.4105396402263466 ) ) ; -#17920 = VECTOR ( 'NONE', #16977, 1000.000000000000114 ) ; -#17921 = ORIENTED_EDGE ( 'NONE', *, *, #9784, .T. ) ; -#17922 = CARTESIAN_POINT ( 'NONE', ( 5.661755184049897416, 181.7278491563756972, 101.6571205978850969 ) ) ; -#17923 = ADVANCED_FACE ( 'NONE', ( #18542 ), #6284, .T. ) ; -#17924 = VECTOR ( 'NONE', #14217, 1000.000000000000114 ) ; -#17925 = EDGE_CURVE ( 'NONE', #8275, #7741, #27792, .T. ) ; -#17926 = ORIENTED_EDGE ( 'NONE', *, *, #40376, .F. ) ; -#17927 = CARTESIAN_POINT ( 'NONE', ( -38.48370105922000306, 119.6611731044000067, 87.34165442331999429 ) ) ; -#17928 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#17929 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; -#17930 = ORIENTED_EDGE ( 'NONE', *, *, #39117, .T. ) ; -#17931 = CARTESIAN_POINT ( 'NONE', ( -44.72305387772779284, 186.4890408525310477, 106.4986220546478819 ) ) ; -#17932 = APPROVAL ( #12253, '未' ) ; -#17933 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16535, #22708, #32305, #4270, #38618, #29240 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#17934 = CARTESIAN_POINT ( 'NONE', ( 35.04524255441999259, 226.4002260770880355, 73.53733772517182388 ) ) ; -#17935 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#17936 = DIRECTION ( 'NONE', ( 0.0005559617456005168726, -0.3907311285063747031, 0.9205046855517208249 ) ) ; -#17937 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971554578 ) ) ; -#17938 = VERTEX_POINT ( 'NONE', #15502 ) ; -#17939 = CARTESIAN_POINT ( 'NONE', ( 37.96662911696999743, 119.2513318047000013, 87.13126180806000320 ) ) ; -#17940 = FACE_OUTER_BOUND ( 'NONE', #33475, .T. ) ; -#17941 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#17942 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; -#17943 = EDGE_LOOP ( 'NONE', ( #5015, #24919, #37679, #32136 ) ) ; -#17944 = VERTEX_POINT ( 'NONE', #37181 ) ; -#17945 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971555410 ) ) ; -#17946 = FACE_OUTER_BOUND ( 'NONE', #37675, .T. ) ; -#17947 = VECTOR ( 'NONE', #37335, 1000.000000000000000 ) ; -#17948 = CARTESIAN_POINT ( 'NONE', ( -23.00078011532012212, 115.1133396198523968, 87.28167119284988473 ) ) ; -#17949 = ADVANCED_FACE ( 'NONE', ( #3017 ), #27994, .F. ) ; -#17950 = CARTESIAN_POINT ( 'NONE', ( -16.99952089899032615, 137.4668171152774221, 177.5674675513082263 ) ) ; -#17951 = CIRCLE ( 'NONE', #31029, 2.499999999921701299 ) ; -#17952 = CARTESIAN_POINT ( 'NONE', ( -23.97850471017942198, 213.9398281896897629, 73.07298649838843119 ) ) ; -#17953 = FACE_OUTER_BOUND ( 'NONE', #20269, .T. ) ; -#17954 = VECTOR ( 'NONE', #20650, 1000.000000000000114 ) ; -#17955 = FACE_OUTER_BOUND ( 'NONE', #8627, .T. ) ; -#17956 = DIRECTION ( 'NONE', ( 0.6087614810001747978, -0.7729390313185939831, -0.1788147452386057157 ) ) ; -#17957 = CARTESIAN_POINT ( 'NONE', ( 27.16245655375060153, 124.0804297401828364, 88.28273975555136133 ) ) ; -#17958 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; -#17959 = CARTESIAN_POINT ( 'NONE', ( 14.78500024124773304, 129.1259577792816629, 89.96821972116190125 ) ) ; -#17960 = CARTESIAN_POINT ( 'NONE', ( -5.669730063300002065, 182.0627683766816176, 102.2020018021338927 ) ) ; -#17961 = CARTESIAN_POINT ( 'NONE', ( -19.28798288393075921, 116.9568857464341960, 189.5000423914045484 ) ) ; -#17962 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 1.676366911794336136E-18, 0.0006039748319371601813 ) ) ; -#17964 = ORIENTED_EDGE ( 'NONE', *, *, #14402, .F. ) ; -#17963 = CARTESIAN_POINT ( 'NONE', ( -20.49983153468760833, 192.4566819323742948, 104.3904707837865402 ) ) ; -#17965 = ORIENTED_EDGE ( 'NONE', *, *, #7806, .T. ) ; -#17966 = VERTEX_POINT ( 'NONE', #12428 ) ; -#17967 = ORIENTED_EDGE ( 'NONE', *, *, #39255, .F. ) ; -#17968 = CARTESIAN_POINT ( 'NONE', ( -39.61054748937312553, 129.5177821288435780, 336.3042500576304974 ) ) ; -#17969 = ORIENTED_EDGE ( 'NONE', *, *, #6026, .F. ) ; -#17970 = CARTESIAN_POINT ( 'NONE', ( 20.50147082588080139, 126.8719997938822530, 91.49700837604584081 ) ) ; -#17971 = DIRECTION ( 'NONE', ( -0.7933308265452445607, -0.5932923437231208963, -0.1364932032467742196 ) ) ; -#17972 = CARTESIAN_POINT ( 'NONE', ( -22.78469271946612196, 158.3009118758265004, 96.21332883968871386 ) ) ; -#17973 = ADVANCED_FACE ( 'NONE', ( #24931 ), #7755, .T. ) ; -#17974 = EDGE_CURVE ( 'NONE', #8481, #6206, #27169, .T. ) ; -#17975 = CONICAL_SURFACE ( 'NONE', #10820, 59.40509992922268623, 0.7853981633972876297 ) ; -#17976 = VERTEX_POINT ( 'NONE', #10184 ) ; -#17977 = AXIS2_PLACEMENT_3D ( 'NONE', #11948, #9077, #9478 ) ; -#17978 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 67.27946979429633245, 315.0857197240632672 ) ) ; -#17979 = CARTESIAN_POINT ( 'NONE', ( -13.49836187949013322, 187.2925309095741113, 105.4667247238223524 ) ) ; -#17980 = AXIS2_PLACEMENT_3D ( 'NONE', #5957, #15752, #34158 ) ; -#17981 = AXIS2_PLACEMENT_3D ( 'NONE', #34394, #18847, #1059 ) ; -#17982 = CARTESIAN_POINT ( 'NONE', ( -12.63793204807002901, 135.2920832194301397, 91.40834497133602099 ) ) ; -#17983 = ORIENTED_EDGE ( 'NONE', *, *, #37072, .T. ) ; -#17984 = CONICAL_SURFACE ( 'NONE', #368, 4.999999999982041032, 0.7853981634251984145 ) ; -#17985 = ADVANCED_FACE ( 'NONE', ( #31859 ), #31449, .F. ) ; -#17986 = CARTESIAN_POINT ( 'NONE', ( -63.18208837076905127, 82.27946979429619034, 302.5967063397189349 ) ) ; -#17987 = LINE ( 'NONE', #6722, #13956 ) ; -#17988 = CARTESIAN_POINT ( 'NONE', ( 13.47463546662201317, 153.3581425397641453, 97.61606142177900836 ) ) ; -#17989 = VECTOR ( 'NONE', #3854, 1000.000000000000227 ) ; -#17990 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#17991 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971555133 ) ) ; -#17992 = VERTEX_POINT ( 'NONE', #22656 ) ; -#17993 = EDGE_LOOP ( 'NONE', ( #14362, #2620, #3051, #9833 ) ) ; -#17994 = CARTESIAN_POINT ( 'NONE', ( -25.88211498805000232, 191.5534218900999974, 104.0168860973000022 ) ) ; -#17995 = CARTESIAN_POINT ( 'NONE', ( 0.7245737304257999778, 188.8838344680000034, 103.5294067165000058 ) ) ; -#17996 = CARTESIAN_POINT ( 'NONE', ( -35.43627711891984688, 192.7868339519407357, 106.8766537076977698 ) ) ; -#17997 = ORIENTED_EDGE ( 'NONE', *, *, #10567, .T. ) ; -#17998 = CARTESIAN_POINT ( 'NONE', ( -26.01100183241918984, 209.7097224523000136, 73.07421407572023497 ) ) ; -#17999 = ORIENTED_EDGE ( 'NONE', *, *, #23807, .T. ) ; -#18000 = VERTEX_POINT ( 'NONE', #16097 ) ; -#18001 = ORIENTED_EDGE ( 'NONE', *, *, #16321, .F. ) ; -#18002 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; -#18003 = AXIS2_PLACEMENT_3D ( 'NONE', #29657, #26798, #23722 ) ; -#18004 = CARTESIAN_POINT ( 'NONE', ( -37.98512463470000000, 190.9255745234999893, 106.5168391131000050 ) ) ; -#18005 = DIRECTION ( 'NONE', ( 0.0005884949961228996135, -0.2249510543439057764, 0.9743698870671265722 ) ) ; -#18006 = CARTESIAN_POINT ( 'NONE', ( -37.83658322688275888, 190.9636381155321203, 106.3289620680116343 ) ) ; -#18007 = ORIENTED_EDGE ( 'NONE', *, *, #7822, .T. ) ; -#18008 = CARTESIAN_POINT ( 'NONE', ( 46.07702524554187562, 185.2597197907774955, 105.4745833194638607 ) ) ; -#18009 = LINE ( 'NONE', #18211, #10731 ) ; -#18010 = EDGE_LOOP ( 'NONE', ( #11512, #31985 ) ) ; -#18011 = CARTESIAN_POINT ( 'NONE', ( -13.49953887075311698, 187.7424330182009840, 103.5179849509054435 ) ) ; -#18012 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971573451 ) ) ; -#18014 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971570121 ) ) ; -#18013 = CARTESIAN_POINT ( 'NONE', ( -22.82606489386816406, 174.8555096703654499, 26.73020617941470078 ) ) ; -#18015 = VERTEX_POINT ( 'NONE', #28584 ) ; -#18016 = ORIENTED_EDGE ( 'NONE', *, *, #38066, .T. ) ; -#18017 = CARTESIAN_POINT ( 'NONE', ( 20.10465118437221577, 117.3133951571205813, 87.25564158649584101 ) ) ; -#18018 = CARTESIAN_POINT ( 'NONE', ( -4.037441716910447731, 175.2423114651814160, 100.6263891030057778 ) ) ; -#18019 = EDGE_CURVE ( 'NONE', #8699, #28523, #13443, .T. ) ; -#18020 = EDGE_CURVE ( 'NONE', #37463, #36542, #17841, .T. ) ; -#18021 = EDGE_LOOP ( 'NONE', ( #4493, #28258, #2488, #10458 ) ) ; -#18022 = EDGE_CURVE ( 'NONE', #40344, #18640, #1270, .T. ) ; -#18023 = CARTESIAN_POINT ( 'NONE', ( -13.46665720407698430, 158.4276779027484281, 96.40801793781008655 ) ) ; -#18024 = EDGE_CURVE ( 'NONE', #14927, #19402, #8087, .T. ) ; -#18025 = CARTESIAN_POINT ( 'NONE', ( 42.33252156615733952, 171.7659273071258497, 184.4847811977609524 ) ) ; -#18026 = DIRECTION ( 'NONE', ( -0.7933532411131102302, -0.5932638852154231701, -0.1364866195435442964 ) ) ; -#18027 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#18028 = LINE ( 'NONE', #47, #6041 ) ; -#18029 = ORIENTED_EDGE ( 'NONE', *, *, #15145, .T. ) ; -#18030 = ORIENTED_EDGE ( 'NONE', *, *, #16999, .T. ) ; -#18031 = AXIS2_PLACEMENT_3D ( 'NONE', #285, #2572, #40163 ) ; -#18032 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18033 = AXIS2_PLACEMENT_3D ( 'NONE', #11863, #11246, #24347 ) ; -#18034 = CARTESIAN_POINT ( 'NONE', ( 26.18543207681999974, 122.7183532277000069, 88.13992845963001344 ) ) ; -#18035 = ORIENTED_EDGE ( 'NONE', *, *, #9933, .F. ) ; -#18036 = CARTESIAN_POINT ( 'NONE', ( -25.49122390263418936, 191.6804084528734791, 104.4219781743341287 ) ) ; -#18037 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39968, #30784, #96, #15441, #27542, #36911, #25059, #8918, #24864, #6418, #11976 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000002099987, 0.3750000000002899903, 0.4375000000003124168, 0.4687500000003236300, 0.5000000000003348433, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18038 = CARTESIAN_POINT ( 'NONE', ( -12.63563964607691759, 177.7898056417149917, 100.7065655309022532 ) ) ; -#18039 = VECTOR ( 'NONE', #14841, 1000.000000000000000 ) ; -#18040 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34428, #22596, #13581, #32195 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18041 = CONICAL_SURFACE ( 'NONE', #32420, 7.999999999839934262, 0.7853981633973153853 ) ; -#18042 = CARTESIAN_POINT ( 'NONE', ( 0.7706342105979004931, 188.3655401650390218, 106.2398045854893525 ) ) ; -#18043 = DIRECTION ( 'NONE', ( 0.0006039748319385852566, 1.189165140469103041E-14, 0.9999998176071845934 ) ) ; -#18044 = FACE_BOUND ( 'NONE', #18463, .T. ) ; -#18045 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#18046 = LINE ( 'NONE', #33796, #17591 ) ; -#18047 = ORIENTED_EDGE ( 'NONE', *, *, #30599, .T. ) ; -#18048 = FACE_OUTER_BOUND ( 'NONE', #20807, .T. ) ; -#18049 = DIRECTION ( 'NONE', ( 0.1627648957830039600, -0.3422987685252318890, 0.9253859420624767074 ) ) ; -#18050 = VERTEX_POINT ( 'NONE', #38565 ) ; -#18051 = EDGE_CURVE ( 'NONE', #39751, #34948, #39796, .T. ) ; -#18052 = AXIS2_PLACEMENT_3D ( 'NONE', #31183, #27733, #40365 ) ; -#18053 = CARTESIAN_POINT ( 'NONE', ( 41.39749877257511201, 121.2433985891848067, 87.61916177723681187 ) ) ; -#18054 = ORIENTED_EDGE ( 'NONE', *, *, #5523, .F. ) ; -#18055 = VECTOR ( 'NONE', #37849, 1000.000000000000000 ) ; -#18056 = AXIS2_PLACEMENT_3D ( 'NONE', #14512, #27418, #39838 ) ; -#18058 = FACE_OUTER_BOUND ( 'NONE', #4852, .T. ) ; -#18057 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921596284, -0.2249510932971514610 ) ) ; -#18059 = ORIENTED_EDGE ( 'NONE', *, *, #635, .T. ) ; -#18061 = ORIENTED_EDGE ( 'NONE', *, *, #768, .F. ) ; -#18060 = EDGE_CURVE ( 'NONE', #16952, #33548, #6887, .T. ) ; -#18062 = ORIENTED_EDGE ( 'NONE', *, *, #21338, .F. ) ; -#18064 = AXIS2_PLACEMENT_3D ( 'NONE', #32963, #5568, #24202 ) ; -#18063 = CARTESIAN_POINT ( 'NONE', ( 2.668862736158999827, 209.0672528707999902, 75.76277278460999298 ) ) ; -#18065 = EDGE_CURVE ( 'NONE', #17839, #25158, #7792, .T. ) ; -#18066 = DIRECTION ( 'NONE', ( -0.9914447795421099663, -0.1272537940605282525, -0.02904687618140097335 ) ) ; -#18067 = CARTESIAN_POINT ( 'NONE', ( 12.64072830267882530, 177.6453042594414455, 100.7843295571792197 ) ) ; -#18068 = ORIENTED_EDGE ( 'NONE', *, *, #29131, .F. ) ; -#18069 = ORIENTED_EDGE ( 'NONE', *, *, #7136, .T. ) ; -#18070 = CARTESIAN_POINT ( 'NONE', ( -19.46385842112644582, 125.8687678076213530, 177.6217747046812008 ) ) ; -#18071 = ORIENTED_EDGE ( 'NONE', *, *, #2590, .T. ) ; -#18072 = ORIENTED_EDGE ( 'NONE', *, *, #32790, .T. ) ; -#18073 = EDGE_CURVE ( 'NONE', #20440, #29484, #7286, .T. ) ; -#18074 = LINE ( 'NONE', #15033, #23704 ) ; -#18075 = DIRECTION ( 'NONE', ( 0.0005734119072255677982, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#18076 = CARTESIAN_POINT ( 'NONE', ( -28.55676206495941827, 225.5077044902725163, 73.57575174230528603 ) ) ; -#18077 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; -#18078 = ORIENTED_EDGE ( 'NONE', *, *, #10110, .F. ) ; -#18079 = ORIENTED_EDGE ( 'NONE', *, *, #13926, .T. ) ; -#18080 = CARTESIAN_POINT ( 'NONE', ( -15.49823494792000034, 136.5125476982000237, 94.25759973750000142 ) ) ; -#18081 = CARTESIAN_POINT ( 'NONE', ( -35.88663413247999756, 191.4497865545999957, 103.7448652294000055 ) ) ; -#18082 = CARTESIAN_POINT ( 'NONE', ( -25.83455595018638462, 120.6939522944666834, 87.68857576906727047 ) ) ; -#18083 = VERTEX_POINT ( 'NONE', #28379 ) ; -#18084 = ORIENTED_EDGE ( 'NONE', *, *, #12836, .T. ) ; -#18085 = CARTESIAN_POINT ( 'NONE', ( 40.29675614866165745, 187.8287955346809213, 108.1243603913822824 ) ) ; -#18086 = ORIENTED_EDGE ( 'NONE', *, *, #8450, .T. ) ; -#18087 = CONICAL_SURFACE ( 'NONE', #27270, 2.250000000041454840, 0.7853981633778843729 ) ; -#18088 = DIRECTION ( 'NONE', ( 0.0005884949961251158311, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18089 = LINE ( 'NONE', #15256, #33350 ) ; -#18090 = CARTESIAN_POINT ( 'NONE', ( -3.669581230397975791, 128.4724600144964484, 89.82849395191713882 ) ) ; -#18091 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26868, #32969, #1916, #11519, #17633, #20716, #1712, #33582, #23997, #2522, #4967, #14384, #33169, #5161, #14994, #39308, #19742, #2124, #36455, #8462 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999858169, 0.1874999999999787392, 0.2187499999999648337, 0.2343749999999583111, 0.2499999999999517886, 0.5000000000000051070, 0.6250000000000329736, 0.6875000000000407452, 0.7187500000000440759, 0.7343750000000410783, 0.7500000000000380806, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18092 = DIRECTION ( 'NONE', ( -0.7856007919586942556, -0.6187337033602360314, 0.000000000000000000 ) ) ; -#18093 = CARTESIAN_POINT ( 'NONE', ( 38.51513381718999796, 190.6638049979000016, 106.4702060427000134 ) ) ; -#18094 = ORIENTED_EDGE ( 'NONE', *, *, #17002, .T. ) ; -#18095 = LINE ( 'NONE', #37331, #12542 ) ; -#18096 = ORIENTED_EDGE ( 'NONE', *, *, #15818, .F. ) ; -#18097 = EDGE_LOOP ( 'NONE', ( #13809, #31683, #32352, #12071 ) ) ; -#18098 = DIRECTION ( 'NONE', ( 6.071532165918790121E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#18099 = CARTESIAN_POINT ( 'NONE', ( 36.40558664052492333, 191.8188463803718093, 104.3612499972096117 ) ) ; -#18100 = CARTESIAN_POINT ( 'NONE', ( 36.95307372573000038, 117.6087066819000029, 90.39852571456000874 ) ) ; -#18101 = CARTESIAN_POINT ( 'NONE', ( -25.50117313778553552, 120.2777482655987598, 87.94978106212539615 ) ) ; -#18102 = CARTESIAN_POINT ( 'NONE', ( 39.06361167813316371, 191.1637310494582209, 103.9340057247245142 ) ) ; -#18103 = EDGE_CURVE ( 'NONE', #12599, #36135, #13245, .T. ) ; -#18104 = EDGE_LOOP ( 'NONE', ( #26984, #4253, #40155, #3781 ) ) ; -#18105 = EDGE_CURVE ( 'NONE', #33829, #21029, #30191, .T. ) ; -#18106 = EDGE_CURVE ( 'NONE', #23623, #8275, #20362, .T. ) ; -#18107 = EDGE_CURVE ( 'NONE', #12780, #21071, #16333, .T. ) ; -#18108 = CARTESIAN_POINT ( 'NONE', ( -6.038082992467953325, 135.2621705534379544, 91.35529203372260554 ) ) ; -#18109 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14935, #8404, #27440, #33117 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18110 = CARTESIAN_POINT ( 'NONE', ( 20.49349609279370199, 198.0405739724999989, 94.02009863521665523 ) ) ; -#18111 = VERTEX_POINT ( 'NONE', #11587 ) ; -#18112 = LINE ( 'NONE', #15077, #25144 ) ; -#18113 = ADVANCED_FACE ( 'NONE', ( #1351 ), #35474, .F. ) ; -#18114 = VECTOR ( 'NONE', #591, 1000.000000000000114 ) ; -#18115 = CARTESIAN_POINT ( 'NONE', ( -20.56299248376943112, 183.8327314439351028, 104.6722249315171638 ) ) ; -#18116 = CARTESIAN_POINT ( 'NONE', ( 26.00894374567046441, 191.9425530329557716, 103.9054621679136261 ) ) ; -#18117 = CARTESIAN_POINT ( 'NONE', ( -30.17966072969699454, 126.7544990129442795, 88.93473033871077860 ) ) ; -#18118 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#18119 = CARTESIAN_POINT ( 'NONE', ( 45.51092638067240870, 130.6862150259999282, 92.36248445504377003 ) ) ; -#18120 = AXIS2_PLACEMENT_3D ( 'NONE', #7108, #40102, #28994 ) ; -#18121 = EDGE_LOOP ( 'NONE', ( #37092, #13311, #32416, #14618, #22036, #5540, #38653 ) ) ; -#18122 = ORIENTED_EDGE ( 'NONE', *, *, #8121, .T. ) ; -#18123 = EDGE_CURVE ( 'NONE', #25286, #31100, #29522, .T. ) ; -#18124 = CARTESIAN_POINT ( 'NONE', ( -40.45487666628986290, 217.7719115803249963, 76.08293836134893695 ) ) ; -#18125 = CARTESIAN_POINT ( 'NONE', ( -19.30112294124457861, 148.8672454922145221, 180.8685255073344536 ) ) ; -#18126 = CARTESIAN_POINT ( 'NONE', ( -31.03678255265001695, 135.1035752748423420, 90.86278477189215153 ) ) ; -#18127 = ORIENTED_EDGE ( 'NONE', *, *, #33952, .F. ) ; -#18128 = CARTESIAN_POINT ( 'NONE', ( 34.28793556153255651, 83.33961454349231701, 284.1689683552120300 ) ) ; -#18129 = ORIENTED_EDGE ( 'NONE', *, *, #32571, .F. ) ; -#18130 = CARTESIAN_POINT ( 'NONE', ( -38.77968390195999859, 119.6789568014999929, 87.49970845907000694 ) ) ; -#18131 = EDGE_CURVE ( 'NONE', #6653, #23984, #25130, .T. ) ; -#18132 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058949670, 130.4211554272716000, 90.27959376792703949 ) ) ; -#18133 = CARTESIAN_POINT ( 'NONE', ( -45.30371984282656683, 124.3227729409930618, 91.46136974178456569 ) ) ; -#18134 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5202, #17257, #23832, #29767, #35659, #1959, #38951, #30168, #14424 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 1, 1, 4 ), - ( 0.000000000000000000, 2.226407581420605065E-05, 0.3333477931941779548, 0.6666747780319307592, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18135 = CARTESIAN_POINT ( 'NONE', ( 20.50411903179698214, 118.8156364820424358, 94.25541735824513978 ) ) ; -#18136 = CARTESIAN_POINT ( 'NONE', ( -25.89534614573000226, 190.7439020952000135, 106.6581656403000125 ) ) ; -#18137 = CARTESIAN_POINT ( 'NONE', ( -3.537737212824113353, 144.2088358181959222, 92.94829169108382416 ) ) ; -#18138 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921591843, -0.2249510932971537092 ) ) ; -#18139 = ORIENTED_EDGE ( 'NONE', *, *, #12626, .F. ) ; -#18140 = DIRECTION ( 'NONE', ( -2.508512021221107617E-14, 0.9743700558021061164, 0.2249510932540687291 ) ) ; -#18141 = CARTESIAN_POINT ( 'NONE', ( 20.94615154526903567, 129.3425601203839221, 89.50137061379278691 ) ) ; -#18142 = CARTESIAN_POINT ( 'NONE', ( 36.70606526514563228, 191.6516938454589933, 104.3454524653553932 ) ) ; -#18143 = AXIS2_PLACEMENT_3D ( 'NONE', #25825, #13733, #4514 ) ; -#18144 = CARTESIAN_POINT ( 'NONE', ( 20.16690163351599452, 151.9417136388183849, 94.89044178777534455 ) ) ; -#18145 = VERTEX_POINT ( 'NONE', #39176 ) ; -#18146 = CARTESIAN_POINT ( 'NONE', ( 15.50147165555466522, 173.9550007109359342, 102.3699975152791239 ) ) ; -#18147 = CARTESIAN_POINT ( 'NONE', ( -1.212288473603901240, 143.4871526178525869, 158.5698567282870499 ) ) ; -#18148 = AXIS2_PLACEMENT_3D ( 'NONE', #20798, #33253, #2206 ) ; -#18149 = DIRECTION ( 'NONE', ( -1.363824338041664219E-09, 0.9743700554850293072, 0.2249510946274785039 ) ) ; -#18150 = CARTESIAN_POINT ( 'NONE', ( 12.63701685433996680, 181.1288752993226865, 104.4441903665902203 ) ) ; -#18151 = CARTESIAN_POINT ( 'NONE', ( -14.16859886990510731, 176.0439122282943458, 102.8701808096547126 ) ) ; -#18152 = CARTESIAN_POINT ( 'NONE', ( -30.88168004888737883, 183.4793843894118766, 102.0311286754261744 ) ) ; -#18153 = EDGE_CURVE ( 'NONE', #18185, #29835, #36314, .T. ) ; -#18154 = ADVANCED_FACE ( 'NONE', ( #11178 ), #25448, .T. ) ; -#18155 = ADVANCED_FACE ( 'NONE', ( #23652 ), #7694, .T. ) ; -#18156 = CARTESIAN_POINT ( 'NONE', ( -39.04919065169610803, 128.3857842691216149, 92.39561240981451817 ) ) ; -#18157 = CARTESIAN_POINT ( 'NONE', ( -39.75024793617362917, 128.4756217986020488, 92.41677646255658374 ) ) ; -#18158 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; -#18159 = CARTESIAN_POINT ( 'NONE', ( -9.337769825243999122, 177.4902628103000097, 100.8919948495999961 ) ) ; -#18160 = LINE ( 'NONE', #5714, #16473 ) ; -#18161 = CARTESIAN_POINT ( 'NONE', ( -20.25935325476000060, 199.6921202901999948, 89.51379066862999423 ) ) ; -#18162 = CYLINDRICAL_SURFACE ( 'NONE', #36863, 6.000000000154989799 ) ; -#18163 = EDGE_CURVE ( 'NONE', #2967, #7231, #6549, .T. ) ; -#18164 = CARTESIAN_POINT ( 'NONE', ( -20.51998460911297784, 211.0905570173818546, 73.57089872868714053 ) ) ; -#18165 = CARTESIAN_POINT ( 'NONE', ( 37.68866078465489267, 190.9590569619750511, 106.3031863550690019 ) ) ; -#18166 = EDGE_LOOP ( 'NONE', ( #8393, #37433, #24847, #14225 ) ) ; -#18168 = ORIENTED_EDGE ( 'NONE', *, *, #11073, .T. ) ; -#18167 = CARTESIAN_POINT ( 'NONE', ( 36.09993383802999745, 190.9634858167000004, 106.9436247654000027 ) ) ; -#18169 = VERTEX_POINT ( 'NONE', #20567 ) ; -#18170 = ORIENTED_EDGE ( 'NONE', *, *, #29901, .F. ) ; -#18171 = VERTEX_POINT ( 'NONE', #33232 ) ; -#18172 = ADVANCED_FACE ( 'NONE', ( #5029 ), #4623, .T. ) ; -#18174 = CIRCLE ( 'NONE', #26686, 5.499999999940946793 ) ; -#18173 = CARTESIAN_POINT ( 'NONE', ( -15.74838202838000178, 167.0072215012000072, 101.0414262103000027 ) ) ; -#18175 = ORIENTED_EDGE ( 'NONE', *, *, #31890, .F. ) ; -#18176 = CARTESIAN_POINT ( 'NONE', ( 22.78193024034099423, 147.5136806587757405, 96.26113945965757068 ) ) ; -#18177 = VECTOR ( 'NONE', #25368, 1000.000000000000227 ) ; -#18178 = CARTESIAN_POINT ( 'NONE', ( 33.79593125845812551, 218.5902260770999987, 76.03809273391679824 ) ) ; -#18179 = AXIS2_PLACEMENT_3D ( 'NONE', #28506, #3142, #3535 ) ; -#18180 = ORIENTED_EDGE ( 'NONE', *, *, #8059, .T. ) ; -#18181 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; -#18182 = EDGE_CURVE ( 'NONE', #10098, #15694, #29985, .T. ) ; -#18183 = CARTESIAN_POINT ( 'NONE', ( -28.46737701140906651, 128.5818728498977634, 89.35557899873234078 ) ) ; -#18184 = CARTESIAN_POINT ( 'NONE', ( 17.33070710942128301, 121.2635828526781268, 177.4224744102505440 ) ) ; -#18185 = VERTEX_POINT ( 'NONE', #39371 ) ; -#18186 = CARTESIAN_POINT ( 'NONE', ( 17.25783335673383689, 152.2632692426403196, 183.6728012514050477 ) ) ; -#18187 = CARTESIAN_POINT ( 'NONE', ( 23.36549494770271806, 177.0154873188169233, 103.4424326537949383 ) ) ; -#18188 = PLANE ( 'NONE', #23876 ) ; -#18189 = FACE_OUTER_BOUND ( 'NONE', #5857, .T. ) ; -#18190 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173123658, 184.8502840662089568, 102.8502797338132382 ) ) ; -#18191 = ORIENTED_EDGE ( 'NONE', *, *, #21975, .T. ) ; -#18192 = VERTEX_POINT ( 'NONE', #38974 ) ; -#18193 = DIRECTION ( 'NONE', ( 0.0005884949961244984864, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18194 = CARTESIAN_POINT ( 'NONE', ( 0.5624177495529000259, 188.7437975896999944, 103.3623115639999952 ) ) ; -#18195 = DIRECTION ( 'NONE', ( 0.0006039748319385831966, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#18196 = ORIENTED_EDGE ( 'NONE', *, *, #28156, .F. ) ; -#18197 = ORIENTED_EDGE ( 'NONE', *, *, #4361, .F. ) ; -#18198 = CARTESIAN_POINT ( 'NONE', ( -3.936101898023678825, 136.7687160347144584, 93.89934258040432269 ) ) ; -#18199 = ORIENTED_EDGE ( 'NONE', *, *, #36870, .F. ) ; -#18200 = AXIS2_PLACEMENT_3D ( 'NONE', #23893, #30219, #14082 ) ; -#18201 = AXIS2_PLACEMENT_3D ( 'NONE', #19703, #12570, #18897 ) ; -#18202 = CARTESIAN_POINT ( 'NONE', ( 38.59086485963890567, 79.69179921679354095, 285.2955982571226059 ) ) ; -#18203 = AXIS2_PLACEMENT_3D ( 'NONE', #36272, #24016, #17240 ) ; -#18204 = ADVANCED_FACE ( 'NONE', ( #10980 ), #23446, .T. ) ; -#18205 = EDGE_CURVE ( 'NONE', #12793, #12043, #7570, .T. ) ; -#18206 = CARTESIAN_POINT ( 'NONE', ( -37.05700344865999796, 191.3523728055000106, 104.9609275802999946 ) ) ; -#18207 = AXIS2_PLACEMENT_3D ( 'NONE', #6001, #11538, #30552 ) ; -#18208 = CARTESIAN_POINT ( 'NONE', ( 21.78519456296580259, 199.9748479675050987, 27.79156831217387946 ) ) ; -#18209 = CARTESIAN_POINT ( 'NONE', ( -25.74982265071000143, 119.9604208062000055, 90.18585507400999290 ) ) ; -#18210 = ORIENTED_EDGE ( 'NONE', *, *, #8836, .T. ) ; -#18211 = CARTESIAN_POINT ( 'NONE', ( 0.05270753573795999847, 118.8155666110999960, 87.26775245800000391 ) ) ; -#18212 = CARTESIAN_POINT ( 'NONE', ( -1.330569699202522216, 189.2108882306625333, 105.7992439180508910 ) ) ; -#18213 = ORIENTED_EDGE ( 'NONE', *, *, #29998, .T. ) ; -#18214 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30619, #17507, #15079, #27575, #40000, #12012, #8126, #20587, #32400, #20507, #32205, #17438, #7845, #39317, #14203, #13989, #23800, #35425, #32589, #1722 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000036082, 0.1875000000000047462, 0.2187500000000066613, 0.2343750000000089095, 0.2500000000000111577, 0.5000000000001214584, 0.6250000000001766365, 0.6875000000002058353, 0.7187500000002121636, 0.7343750000002163825, 0.7500000000002206013, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18215 = FACE_OUTER_BOUND ( 'NONE', #5052, .T. ) ; -#18216 = EDGE_CURVE ( 'NONE', #30903, #9305, #24782, .T. ) ; -#18218 = CARTESIAN_POINT ( 'NONE', ( -21.44693882331385026, 135.7861819143374760, 91.01458761472625270 ) ) ; -#18217 = CARTESIAN_POINT ( 'NONE', ( -25.51021417979479011, 210.6319001491000051, 73.57355354290324101 ) ) ; -#18219 = EDGE_LOOP ( 'NONE', ( #11340, #1891, #32240, #40331, #37921, #3132, #27453, #9735, #23686, #13738, #10350, #20895 ) ) ; -#18220 = ORIENTED_EDGE ( 'NONE', *, *, #4238, .F. ) ; -#18221 = FACE_OUTER_BOUND ( 'NONE', #36319, .T. ) ; -#18222 = VERTEX_POINT ( 'NONE', #33443 ) ; -#18223 = CARTESIAN_POINT ( 'NONE', ( 20.15491921390506391, 117.1565408753359065, 87.25561122586560714 ) ) ; -#18224 = ORIENTED_EDGE ( 'NONE', *, *, #8062, .F. ) ; -#18225 = CARTESIAN_POINT ( 'NONE', ( 28.25950385170297352, 125.5846682600628412, 89.14251585184922533 ) ) ; -#18226 = AXIS2_PLACEMENT_3D ( 'NONE', #17176, #4921, #11472 ) ; -#18227 = CARTESIAN_POINT ( 'NONE', ( 12.63088349563799184, 181.6904995670203391, 101.5918601121804556 ) ) ; -#18228 = FACE_OUTER_BOUND ( 'NONE', #35859, .T. ) ; -#18229 = CARTESIAN_POINT ( 'NONE', ( -29.78212383378786399, 185.3139029630853258, 103.9934530775901038 ) ) ; -#18230 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#18231 = CARTESIAN_POINT ( 'NONE', ( 25.50046716662595969, 119.8278461341035523, 89.86771791572004986 ) ) ; -#18232 = ORIENTED_EDGE ( 'NONE', *, *, #39386, .T. ) ; -#18233 = AXIS2_PLACEMENT_3D ( 'NONE', #3921, #22558, #254 ) ; -#18234 = ORIENTED_EDGE ( 'NONE', *, *, #5990, .T. ) ; -#18235 = CARTESIAN_POINT ( 'NONE', ( -23.36013623391100325, 183.4467887557270842, 105.0979734400102217 ) ) ; -#18236 = AXIS2_PLACEMENT_3D ( 'NONE', #24014, #36467, #9283 ) ; -#18237 = DIRECTION ( 'NONE', ( -0.0005884949961221956410, 0.2249510543439041110, -0.9743698870671267942 ) ) ; -#18238 = ORIENTED_EDGE ( 'NONE', *, *, #11597, .T. ) ; -#18239 = ORIENTED_EDGE ( 'NONE', *, *, #23820, .F. ) ; -#18240 = CARTESIAN_POINT ( 'NONE', ( -36.18295178273969981, 190.9538016885580021, 106.8410015666040067 ) ) ; -#18241 = DIRECTION ( 'NONE', ( -0.7072759766252744162, -0.1592272936566939134, 0.6887723585071698906 ) ) ; -#18242 = EDGE_CURVE ( 'NONE', #15233, #14883, #38462, .T. ) ; -#18243 = PERSON ( '未', '未', '未', ('未'), ('未'), ('未') ) ; -#18244 = ORIENTED_EDGE ( 'NONE', *, *, #4685, .F. ) ; -#18245 = CARTESIAN_POINT ( 'NONE', ( 0.5639603665540000588, 188.7958495505000087, 105.8993863219999980 ) ) ; -#18246 = CARTESIAN_POINT ( 'NONE', ( 24.95681190508087965, 159.0107988627873397, 180.5054692823873097 ) ) ; -#18247 = EDGE_CURVE ( 'NONE', #604, #32344, #18493, .T. ) ; -#18248 = CARTESIAN_POINT ( 'NONE', ( -23.01874678158921839, 213.5902083388722303, 75.57231541044464507 ) ) ; -#18249 = DIRECTION ( 'NONE', ( -0.0009686424652863183989, 0.2252351993847905853, -0.9743039395844954598 ) ) ; -#18250 = CARTESIAN_POINT ( 'NONE', ( 5.957091414655063311, 149.1468224720344438, 94.08258114083251655 ) ) ; -#18251 = ORIENTED_EDGE ( 'NONE', *, *, #39861, .T. ) ; -#18252 = ADVANCED_FACE ( 'NONE', ( #31000 ), #5434, .F. ) ; -#18253 = CARTESIAN_POINT ( 'NONE', ( -19.99925998143469030, 118.3555979054333278, 90.27986389109715049 ) ) ; -#18254 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#18255 = EDGE_CURVE ( 'NONE', #11405, #33023, #26568, .T. ) ; -#18256 = VECTOR ( 'NONE', #17531, 1000.000000000000227 ) ; -#18257 = AXIS2_PLACEMENT_3D ( 'NONE', #5367, #32776, #39507 ) ; -#18258 = ORIENTED_EDGE ( 'NONE', *, *, #7407, .T. ) ; -#18259 = CIRCLE ( 'NONE', #643, 2.000000000000011546 ) ; -#18260 = VECTOR ( 'NONE', #32664, 1000.000000000000114 ) ; -#18261 = CARTESIAN_POINT ( 'NONE', ( -20.50275215376747440, 191.9757880780653068, 104.4368574122889299 ) ) ; -#18262 = EDGE_LOOP ( 'NONE', ( #13372, #35347, #25996, #22395 ) ) ; -#18263 = AXIS2_PLACEMENT_3D ( 'NONE', #14307, #25983, #23104 ) ; -#18265 = CARTESIAN_POINT ( 'NONE', ( -17.26183737405610330, 121.4975388230068916, 176.5517749385022057 ) ) ; -#18264 = CARTESIAN_POINT ( 'NONE', ( 37.08917536360815603, 153.0051697192222093, 297.5361440970456215 ) ) ; -#18266 = ORIENTED_EDGE ( 'NONE', *, *, #121, .T. ) ; -#18267 = VERTEX_POINT ( 'NONE', #2966 ) ; -#18268 = ORIENTED_EDGE ( 'NONE', *, *, #5990, .F. ) ; -#18269 = DIRECTION ( 'NONE', ( 0.0001408404318097916858, -0.2249510911089059872, 0.9743700461184576778 ) ) ; -#18270 = CARTESIAN_POINT ( 'NONE', ( 39.71730849539001440, 182.4927982134933302, 106.8443253198619374 ) ) ; -#18271 = CARTESIAN_POINT ( 'NONE', ( 12.64359260118063233, 177.7305216002704071, 100.7310784416387435 ) ) ; -#18272 = ORIENTED_EDGE ( 'NONE', *, *, #36883, .F. ) ; -#18273 = EDGE_LOOP ( 'NONE', ( #10755, #2926, #17514, #19484 ) ) ; -#18274 = ORIENTED_EDGE ( 'NONE', *, *, #13425, .F. ) ; -#18275 = EDGE_LOOP ( 'NONE', ( #8642, #26609, #30687, #3158 ) ) ; -#18276 = DIRECTION ( 'NONE', ( 0.4115636185179725182, -0.6942467237022525994, 0.5904548031315189904 ) ) ; -#18277 = LINE ( 'NONE', #24858, #31555 ) ; -#18278 = FACE_OUTER_BOUND ( 'NONE', #3759, .T. ) ; -#18279 = DIRECTION ( 'NONE', ( 0.0004161288024640698410, -0.8480480897796375261, 0.5299191110517978975 ) ) ; -#18280 = ORIENTED_EDGE ( 'NONE', *, *, #33115, .F. ) ; -#18281 = ORIENTED_EDGE ( 'NONE', *, *, #15282, .F. ) ; -#18282 = LINE ( 'NONE', #24664, #5644 ) ; -#18283 = CARTESIAN_POINT ( 'NONE', ( -2.953326078673281341, 207.8686482947572074, 77.27881662714202093 ) ) ; -#18284 = CARTESIAN_POINT ( 'NONE', ( -27.30234400592999933, 124.8861144825999929, 89.01493418404001545 ) ) ; -#18285 = VECTOR ( 'NONE', #8043, 1000.000000000000227 ) ; -#18286 = ORIENTED_EDGE ( 'NONE', *, *, #33864, .F. ) ; -#18287 = CARTESIAN_POINT ( 'NONE', ( -25.76810376906509958, 158.0179022077391835, 180.2634769281190188 ) ) ; -#18288 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825934671853956, 0.0005734119020480080283 ) ) ; -#18289 = AXIS2_PLACEMENT_3D ( 'NONE', #16375, #13127, #19032 ) ; -#18290 = ORIENTED_EDGE ( 'NONE', *, *, #39389, .F. ) ; -#18292 = EDGE_CURVE ( 'NONE', #21029, #24812, #24189, .T. ) ; -#18291 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18367, #5093, #24132, #27620 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18293 = AXIS2_PLACEMENT_3D ( 'NONE', #4897, #17761, #23719 ) ; -#18294 = AXIS2_PLACEMENT_3D ( 'NONE', #15791, #22155, #253 ) ; -#18295 = CARTESIAN_POINT ( 'NONE', ( 4.035676231532755232, 174.7936433537611265, 102.5705385171684298 ) ) ; -#18296 = CARTESIAN_POINT ( 'NONE', ( -35.95638742416511491, 209.7096535813600156, 73.58022093100927918 ) ) ; -#18297 = EDGE_CURVE ( 'NONE', #1155, #349, #18868, .T. ) ; -#18298 = CARTESIAN_POINT ( 'NONE', ( 28.46384604140093799, 128.5894095540980402, 89.32293395218094645 ) ) ; -#18299 = CARTESIAN_POINT ( 'NONE', ( 20.50100932471902482, 118.1127835883590365, 89.75563873136169946 ) ) ; -#18300 = ORIENTED_EDGE ( 'NONE', *, *, #2537, .F. ) ; -#18301 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319377623471 ) ) ; -#18302 = LINE ( 'NONE', #12198, #13357 ) ; -#18303 = EDGE_CURVE ( 'NONE', #11263, #3990, #37328, .T. ) ; -#18304 = CARTESIAN_POINT ( 'NONE', ( 72.09533725057714548, 197.6701254222500097, 173.3705209015881792 ) ) ; -#18305 = CARTESIAN_POINT ( 'NONE', ( 35.92881332601000111, 113.0022062185000067, 89.86214737193999724 ) ) ; -#18306 = EDGE_CURVE ( 'NONE', #31197, #22792, #35795, .T. ) ; -#18307 = ADVANCED_FACE ( 'NONE', ( #27746 ), #2784, .T. ) ; -#18308 = LINE ( 'NONE', #37888, #23088 ) ; -#18309 = VERTEX_POINT ( 'NONE', #21802 ) ; -#18310 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; -#18311 = ORIENTED_EDGE ( 'NONE', *, *, #17156, .T. ) ; -#18312 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; -#18313 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25085, #37533, #34444, #6439 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18314 = CARTESIAN_POINT ( 'NONE', ( -6.038848507788371123, 135.1370730830105060, 91.15509477705727193 ) ) ; -#18315 = CIRCLE ( 'NONE', #17015, 1.999999997936985352 ) ; -#18316 = AXIS2_PLACEMENT_3D ( 'NONE', #34745, #6749, #3685 ) ; -#18317 = ORIENTED_EDGE ( 'NONE', *, *, #4964, .T. ) ; -#18318 = CARTESIAN_POINT ( 'NONE', ( 76.10748482110098223, 155.7951947758797644, 98.14087069364011029 ) ) ; -#18319 = AXIS2_PLACEMENT_3D ( 'NONE', #7863, #20531, #32808 ) ; -#18320 = LINE ( 'NONE', #25097, #7175 ) ; -#18321 = AXIS2_PLACEMENT_3D ( 'NONE', #14794, #18230, #3103 ) ; -#18322 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18323 = DIRECTION ( 'NONE', ( 0.0005884949961254158299, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18324 = EDGE_LOOP ( 'NONE', ( #20601, #14092, #29316, #30588 ) ) ; -#18325 = ORIENTED_EDGE ( 'NONE', *, *, #16529, .T. ) ; -#18326 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; -#18327 = CARTESIAN_POINT ( 'NONE', ( 26.00069066973446041, 119.1180911281959283, 90.25207238698713752 ) ) ; -#18328 = VERTEX_POINT ( 'NONE', #34238 ) ; -#18329 = CARTESIAN_POINT ( 'NONE', ( 30.06907743352446261, 134.5412604939639039, 93.52416550224677394 ) ) ; -#18330 = CARTESIAN_POINT ( 'NONE', ( -22.21857727096708146, 115.1893093715653151, 90.28120430312861799 ) ) ; -#18331 = ORIENTED_EDGE ( 'NONE', *, *, #19411, .F. ) ; -#18332 = CARTESIAN_POINT ( 'NONE', ( -17.26183737405610330, 121.4975388230068916, 176.5517749385022057 ) ) ; -#18333 = CYLINDRICAL_SURFACE ( 'NONE', #1687, 10.00000000000000000 ) ; -#18334 = CARTESIAN_POINT ( 'NONE', ( -12.19159238061602579, 125.0219911001496058, 178.7972028438273071 ) ) ; -#18335 = ORIENTED_EDGE ( 'NONE', *, *, #24566, .T. ) ; -#18336 = CARTESIAN_POINT ( 'NONE', ( -44.18930552168288273, 185.9402243567042206, 107.0564869194947022 ) ) ; -#18337 = EDGE_CURVE ( 'NONE', #34206, #9250, #9041, .T. ) ; -#18338 = ADVANCED_FACE ( 'NONE', ( #20988 ), #28049, .F. ) ; -#18339 = PLANE ( 'NONE', #914 ) ; -#18340 = CARTESIAN_POINT ( 'NONE', ( -25.86594528267000470, 191.2406205388000160, 106.7635301985999945 ) ) ; -#18341 = CARTESIAN_POINT ( 'NONE', ( 42.83909609183046996, 114.0261269511795632, 121.8710131578908573 ) ) ; -#18342 = CARTESIAN_POINT ( 'NONE', ( 3.326570984746394011, 125.9446392491717290, 88.72752278887659827 ) ) ; -#18343 = VERTEX_POINT ( 'NONE', #36520 ) ; -#18344 = PLANE ( 'NONE', #4328 ) ; -#18345 = ADVANCED_FACE ( 'NONE', ( #2385 ), #11794, .F. ) ; -#18346 = AXIS2_PLACEMENT_3D ( 'NONE', #5286, #27413, #5704 ) ; -#18347 = CARTESIAN_POINT ( 'NONE', ( 37.26954635975619823, 164.8944657675721999, 196.8584033196613916 ) ) ; -#18348 = CARTESIAN_POINT ( 'NONE', ( 36.66457562586903407, 191.6705100315085986, 104.3467321929502702 ) ) ; -#18349 = EDGE_CURVE ( 'NONE', #27237, #33399, #19218, .T. ) ; -#18350 = VECTOR ( 'NONE', #14072, 1000.000000000000000 ) ; -#18351 = VECTOR ( 'NONE', #15492, 1000.000000000000114 ) ; -#18352 = CARTESIAN_POINT ( 'NONE', ( -17.26216147564933223, 152.2838680029373677, 183.5655880739604981 ) ) ; -#18353 = EDGE_LOOP ( 'NONE', ( #21616, #8075, #8477, #4930 ) ) ; -#18354 = ORIENTED_EDGE ( 'NONE', *, *, #17081, .F. ) ; -#18355 = CARTESIAN_POINT ( 'NONE', ( -28.70816885920003614, 148.6529082553554417, 95.52894535674428766 ) ) ; -#18356 = CARTESIAN_POINT ( 'NONE', ( -41.96574953104487093, 121.8296678666196442, 91.00834655609098434 ) ) ; -#18357 = CARTESIAN_POINT ( 'NONE', ( -21.58773827856433769, 112.4042505803195411, 201.3497749872312568 ) ) ; -#18358 = EDGE_CURVE ( 'NONE', #17526, #22377, #31927, .T. ) ; -#18359 = CARTESIAN_POINT ( 'NONE', ( -26.01483129551610674, 211.4946636794494736, 73.07421638861994495 ) ) ; -#18360 = CARTESIAN_POINT ( 'NONE', ( -37.17303481993481284, 80.33007150473585511, 286.7096455229116714 ) ) ; -#18361 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#18362 = APPROVAL_ROLE ( '' ) ; -#18363 = CARTESIAN_POINT ( 'NONE', ( 20.50145491254044927, 188.7781080962309375, 105.7891785871605492 ) ) ; -#18364 = ORIENTED_EDGE ( 'NONE', *, *, #12493, .T. ) ; -#18365 = LINE ( 'NONE', #34698, #7417 ) ; -#18366 = DIRECTION ( 'NONE', ( 0.0005884949961216829218, -0.2249510543439096899, 0.9743698870671256840 ) ) ; -#18367 = CARTESIAN_POINT ( 'NONE', ( -26.00624846271685442, 190.8511609718977127, 106.8090059743847178 ) ) ; -#18368 = CARTESIAN_POINT ( 'NONE', ( 36.67803576733449944, 191.3746321016990066, 106.3708854744160135 ) ) ; -#18370 = ORIENTED_EDGE ( 'NONE', *, *, #34798, .T. ) ; -#18369 = CARTESIAN_POINT ( 'NONE', ( 36.82689161663000021, 191.4975675794999859, 106.2211857680000122 ) ) ; -#18371 = ORIENTED_EDGE ( 'NONE', *, *, #40253, .F. ) ; -#18372 = ORIENTED_EDGE ( 'NONE', *, *, #40320, .F. ) ; -#18373 = ORIENTED_EDGE ( 'NONE', *, *, #13506, .T. ) ; -#18374 = CIRCLE ( 'NONE', #32746, 2.499999999945713647 ) ; -#18375 = CARTESIAN_POINT ( 'NONE', ( -93.54594160988693829, 221.9633383074385051, 197.0821917869895969 ) ) ; -#18376 = AXIS2_PLACEMENT_3D ( 'NONE', #16301, #1167, #10592 ) ; -#18377 = CARTESIAN_POINT ( 'NONE', ( 20.13818639815300671, 126.7931285923730655, 91.85207892258530649 ) ) ; -#18378 = DIRECTION ( 'NONE', ( 0.0005884949961259158639, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18379 = ORIENTED_EDGE ( 'NONE', *, *, #11828, .F. ) ; -#18380 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18381 = CARTESIAN_POINT ( 'NONE', ( 45.67081843470916880, 116.8212980865162507, 122.5178260610734355 ) ) ; -#18382 = CARTESIAN_POINT ( 'NONE', ( 37.63773291092297768, 212.5463736527291303, 73.36910522896195630 ) ) ; -#18383 = CARTESIAN_POINT ( 'NONE', ( -20.89113403792100598, 128.9341314247968455, 92.51124259315015763 ) ) ; -#18384 = LINE ( 'NONE', #30886, #34105 ) ; -#18385 = EDGE_CURVE ( 'NONE', #28271, #282, #15061, .T. ) ; -#18386 = VERTEX_POINT ( 'NONE', #22406 ) ; -#18387 = CARTESIAN_POINT ( 'NONE', ( -15.49970617573983311, 151.8558896894846839, 95.23413014739874427 ) ) ; -#18388 = ADVANCED_FACE ( 'NONE', ( #13194 ), #34826, .F. ) ; -#18390 = EDGE_CURVE ( 'NONE', #27737, #11249, #3653, .T. ) ; -#18389 = CARTESIAN_POINT ( 'NONE', ( -75.39632045840481567, 196.1406929364112273, 190.0907134300437633 ) ) ; -#18391 = PLANE ( 'NONE', #4434 ) ; -#18392 = EDGE_CURVE ( 'NONE', #34227, #7229, #22910, .T. ) ; -#18393 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18394 = DIRECTION ( 'NONE', ( 6.071532165918790121E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#18395 = ORIENTED_EDGE ( 'NONE', *, *, #37612, .F. ) ; -#18396 = CARTESIAN_POINT ( 'NONE', ( -25.91300670584000088, 191.0997758704000091, 103.9121724043999961 ) ) ; -#18397 = CARTESIAN_POINT ( 'NONE', ( 2.302058793142580218, 189.9851746974860305, 103.9779396045330060 ) ) ; -#18398 = PLANE ( 'NONE', #5789 ) ; -#18399 = EDGE_CURVE ( 'NONE', #30625, #24414, #31302, .T. ) ; -#18400 = ORIENTED_EDGE ( 'NONE', *, *, #9416, .F. ) ; -#18401 = AXIS2_PLACEMENT_3D ( 'NONE', #11268, #39460, #8202 ) ; -#18402 = DIRECTION ( 'NONE', ( 0.0005884949960004859240, -0.2249510543438426879, 0.9743698870671410051 ) ) ; -#18403 = EDGE_LOOP ( 'NONE', ( #32218, #31903, #23833, #27572 ) ) ; -#18404 = CIRCLE ( 'NONE', #23606, 7.500000216081117443 ) ; -#18405 = EDGE_CURVE ( 'NONE', #28075, #36287, #8533, .T. ) ; -#18406 = CARTESIAN_POINT ( 'NONE', ( -35.93129677041999770, 192.6782481662999942, 106.5844153425000087 ) ) ; -#18407 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18408 = CARTESIAN_POINT ( 'NONE', ( 38.76181814569937245, 79.33382810079746150, 286.2650635282574854 ) ) ; -#18409 = DIRECTION ( 'NONE', ( -0.6087611427401035114, -0.7731004639645453480, -0.1781166575802727303 ) ) ; -#18410 = CARTESIAN_POINT ( 'NONE', ( -1.732810059889645427, 189.4717104458119934, 105.8744020675210038 ) ) ; -#18411 = ORIENTED_EDGE ( 'NONE', *, *, #36923, .T. ) ; -#18412 = DIRECTION ( 'NONE', ( 0.0006039748319336982153, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#18413 = DIRECTION ( 'NONE', ( -0.0005884949961222158072, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#18414 = CARTESIAN_POINT ( 'NONE', ( 42.98787737432541434, 112.9269645703451204, 127.4744954975476077 ) ) ; -#18416 = LINE ( 'NONE', #9044, #25334 ) ; -#18415 = CARTESIAN_POINT ( 'NONE', ( -15.49852919137054741, 126.2381079287689403, 91.37240600825562353 ) ) ; -#18417 = CARTESIAN_POINT ( 'NONE', ( -22.46175939534000321, 113.1257526802999962, 152.4718672074000381 ) ) ; -#18418 = ORIENTED_EDGE ( 'NONE', *, *, #20500, .T. ) ; -#18419 = CIRCLE ( 'NONE', #17135, 4.499999999978602006 ) ; -#18420 = EDGE_LOOP ( 'NONE', ( #35893, #18059, #6219, #39708 ) ) ; -#18421 = CARTESIAN_POINT ( 'NONE', ( 39.52738687544000129, 119.6025781157000125, 90.19533794253000281 ) ) ; -#18422 = LINE ( 'NONE', #34172, #30919 ) ; -#18423 = AXIS2_PLACEMENT_3D ( 'NONE', #6347, #34152, #34344 ) ; -#18424 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18425 = CARTESIAN_POINT ( 'NONE', ( 30.96384560851001311, 128.7443226152467730, 89.35718851987711275 ) ) ; -#18426 = CARTESIAN_POINT ( 'NONE', ( 12.63772998360747124, 130.8858987390867696, 89.98020666840058368 ) ) ; -#18427 = DIRECTION ( 'NONE', ( 0.6086215548477215131, 0.7730393818215735013, 0.1788572534946829551 ) ) ; -#18428 = ORIENTED_EDGE ( 'NONE', *, *, #147, .T. ) ; -#18429 = ORIENTED_EDGE ( 'NONE', *, *, #9974, .T. ) ; -#18430 = EDGE_CURVE ( 'NONE', #7259, #17944, #25272, .T. ) ; -#18431 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825948752246353, 0.0005734119017240838726 ) ) ; -#18432 = ADVANCED_FACE ( 'NONE', ( #9727 ), #4515, .F. ) ; -#18433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18584, #3, #31283, #24968 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18434 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971520438 ) ) ; -#18435 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#18436 = VERTEX_POINT ( 'NONE', #3768 ) ; -#18437 = CARTESIAN_POINT ( 'NONE', ( -36.61650746187000038, 191.3591660024999896, 106.3831759458000050 ) ) ; -#18438 = CARTESIAN_POINT ( 'NONE', ( 13.47257850444245442, 153.4830319772647442, 97.81594653802845585 ) ) ; -#18439 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38713, #10730, #1931, #30143 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18440 = CARTESIAN_POINT ( 'NONE', ( 2.586271793656000018, 189.7072324810999930, 106.3365748873000030 ) ) ; -#18441 = ORIENTED_EDGE ( 'NONE', *, *, #22024, .T. ) ; -#18442 = DIRECTION ( 'NONE', ( 4.718447854759373813E-13, 0.9743700557921590732, 0.2249510932971540700 ) ) ; -#18443 = DIRECTION ( 'NONE', ( -0.9999998268367693566, -0.0001323826063126660698, 0.0005734119608316798605 ) ) ; -#18444 = CARTESIAN_POINT ( 'NONE', ( -6.635715103306525878E-14, 155.6803346354327289, 98.67347229705578115 ) ) ; -#18445 = CARTESIAN_POINT ( 'NONE', ( 4.385479481597147178, 147.3836199698109795, 93.67646283599650303 ) ) ; -#18446 = AXIS2_PLACEMENT_3D ( 'NONE', #35601, #4541, #19874 ) ; -#18447 = ORIENTED_EDGE ( 'NONE', *, *, #12098, .F. ) ; -#18448 = CARTESIAN_POINT ( 'NONE', ( -36.07329620650741475, 123.8070289312214953, 91.33672588886609844 ) ) ; -#18449 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10451, #22919, #12589, #6448 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18450 = CONICAL_SURFACE ( 'NONE', #11291, 2.502999999880697324, 0.7853981633854106859 ) ; -#18451 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250909262, 179.1753088544093657, 103.5954339977318739 ) ) ; -#18452 = CARTESIAN_POINT ( 'NONE', ( -31.70384873206000265, 225.9002260769261738, 76.07765295985980458 ) ) ; -#18453 = EDGE_CURVE ( 'NONE', #8915, #1951, #16241, .T. ) ; -#18454 = AXIS2_PLACEMENT_3D ( 'NONE', #10613, #32865, #17115 ) ; -#18455 = ORIENTED_EDGE ( 'NONE', *, *, #27299, .T. ) ; -#18456 = CARTESIAN_POINT ( 'NONE', ( -35.69644648028999967, 111.0397749124999933, 90.03934455280000293 ) ) ; -#18457 = VERTEX_POINT ( 'NONE', #19105 ) ; -#18458 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #15169, #5339, #27651 ), - ( #25181, #15359, #9431 ), - ( #6344, #34150, #22102 ), - ( #3077, #24980, #28047 ) ), - .UNSPECIFIED., .F., .F., .T. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), - ( 3, 3 ), - ( 0.5322599266487868519, 0.5322688524717417158 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.7511062204421768973, 1.000000000000000000), - ( 1.000000000000000000, 0.7511101270067886970, 1.000000000000000000), - ( 1.000000000000000000, 0.7511140335275009461, 1.000000000000000000), - ( 1.000000000000000000, 0.7511179400042681253, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#18460 = CARTESIAN_POINT ( 'NONE', ( 13.45852275855000180, 174.6481430188156594, 27.63001052910568944 ) ) ; -#18459 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#18461 = ORIENTED_EDGE ( 'NONE', *, *, #9927, .F. ) ; -#18462 = EDGE_LOOP ( 'NONE', ( #22945, #2762, #20960, #11373 ) ) ; -#18463 = EDGE_LOOP ( 'NONE', ( #31265, #12262 ) ) ; -#18464 = CARTESIAN_POINT ( 'NONE', ( 2.404590060478000169, 209.1519362205000050, 75.46481054992999304 ) ) ; -#18465 = CARTESIAN_POINT ( 'NONE', ( 3.416491666947000017, 127.6382454602999985, 89.37504442651001568 ) ) ; -#18466 = VERTEX_POINT ( 'NONE', #29139 ) ; -#18467 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3935, #31776, #16210, #26439, #13167, #26243, #38680, #38891, #3737, #35395 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998477884, 0.3749999999997217781, 0.4374999999997082889, 0.4999999999996947442, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18468 = ORIENTED_EDGE ( 'NONE', *, *, #26264, .T. ) ; -#18469 = ORIENTED_EDGE ( 'NONE', *, *, #31631, .F. ) ; -#18470 = DIRECTION ( 'NONE', ( -0.0005884949961249498398, 0.2249510543439061649, -0.9743698870671263501 ) ) ; -#18471 = FACE_OUTER_BOUND ( 'NONE', #14241, .T. ) ; -#18472 = CARTESIAN_POINT ( 'NONE', ( 21.68370070337708100, 182.2867715710398784, 101.7240440883198005 ) ) ; -#18473 = CARTESIAN_POINT ( 'NONE', ( 30.10540398896155523, 121.2983238331719917, 152.0219651002330750 ) ) ; -#18474 = ORIENTED_EDGE ( 'NONE', *, *, #29394, .F. ) ; -#18475 = CIRCLE ( 'NONE', #2828, 22.50000000000000000 ) ; -#18476 = VERTEX_POINT ( 'NONE', #16042 ) ; -#18477 = ORIENTED_EDGE ( 'NONE', *, *, #21130, .F. ) ; -#18478 = CARTESIAN_POINT ( 'NONE', ( 36.05533436145224613, 118.8155666260000061, 90.24600832072127332 ) ) ; -#18479 = ADVANCED_FACE ( 'NONE', ( #35025 ), #7237, .T. ) ; -#18480 = LINE ( 'NONE', #30985, #440 ) ; -#18481 = EDGE_CURVE ( 'NONE', #4808, #12828, #7037, .T. ) ; -#18482 = CARTESIAN_POINT ( 'NONE', ( 45.29516381819948379, 180.6442485579885329, 103.8963377076147907 ) ) ; -#18483 = EDGE_LOOP ( 'NONE', ( #35165, #14630, #15065, #38576 ) ) ; -#18484 = ORIENTED_EDGE ( 'NONE', *, *, #28842, .F. ) ; -#18485 = VECTOR ( 'NONE', #8246, 1000.000000000000114 ) ; -#18486 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.298960938811000068E-14, 1.000000000000000000 ) ) ; -#18487 = CARTESIAN_POINT ( 'NONE', ( -20.89128718923779005, 182.4208812217193838, 104.8596338257292757 ) ) ; -#18488 = PLANE ( 'NONE', #29372 ) ; -#18489 = ORIENTED_EDGE ( 'NONE', *, *, #11911, .T. ) ; -#18490 = FACE_OUTER_BOUND ( 'NONE', #16398, .T. ) ; -#18491 = CARTESIAN_POINT ( 'NONE', ( 38.65471576631835404, 119.1564763279458816, 90.25899222980254422 ) ) ; -#18492 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 183.4515543678114966, 105.0773313099631139 ) ) ; -#18493 = LINE ( 'NONE', #27948, #37169 ) ; -#18494 = ORIENTED_EDGE ( 'NONE', *, *, #7262, .T. ) ; -#18495 = DIRECTION ( 'NONE', ( -0.0009705195736481808059, 0.2252351989748601624, -0.9743039378112521298 ) ) ; -#18496 = CARTESIAN_POINT ( 'NONE', ( 40.07937669021247729, 78.31427785818142695, 286.1872286878083855 ) ) ; -#18497 = LINE ( 'NONE', #9528, #7501 ) ; -#18498 = LINE ( 'NONE', #8736, #16369 ) ; -#18499 = EDGE_CURVE ( 'NONE', #13580, #13982, #11048, .T. ) ; -#18500 = CARTESIAN_POINT ( 'NONE', ( -29.43192434859718887, 181.8734812664013702, 101.6595010425561867 ) ) ; -#18501 = ORIENTED_EDGE ( 'NONE', *, *, #22306, .F. ) ; -#18502 = AXIS2_PLACEMENT_3D ( 'NONE', #9671, #851, #15990 ) ; -#18503 = AXIS2_PLACEMENT_3D ( 'NONE', #21963, #9898, #16007 ) ; -#18504 = LINE ( 'NONE', #6640, #23278 ) ; -#18505 = VERTEX_POINT ( 'NONE', #22802 ) ; -#18506 = CIRCLE ( 'NONE', #28347, 4.999999999999990230 ) ; -#18507 = CARTESIAN_POINT ( 'NONE', ( -38.02994714804000864, 118.9093675896999969, 90.44388284059000682 ) ) ; -#18508 = AXIS2_PLACEMENT_3D ( 'NONE', #32042, #15872, #19538 ) ; -#18509 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#18510 = ORIENTED_EDGE ( 'NONE', *, *, #37515, .F. ) ; -#18511 = PLANE ( 'NONE', #40143 ) ; -#18512 = EDGE_CURVE ( 'NONE', #37430, #22764, #10994, .T. ) ; -#18513 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971562072 ) ) ; -#18514 = CARTESIAN_POINT ( 'NONE', ( 23.36349092257420068, 177.5980283123824677, 100.8086092966151597 ) ) ; -#18515 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927775143106, 0.0005734119022065908107 ) ) ; -#18516 = ORIENTED_EDGE ( 'NONE', *, *, #681, .T. ) ; -#18517 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; -#18518 = EDGE_CURVE ( 'NONE', #15550, #33101, #25073, .T. ) ; -#18519 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17917, #14477, #4845, #14275, #39394, #17307, #29814, #1799, #39201, #26961, #11399, #23887, #36344, #20803, #33261, #5255, #17718 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999538980, 0.1874999999999222289, 0.2187499999998853972, 0.2343749999998670230, 0.2499999999998486211, 0.3749999999999342193, 0.4374999999999567568, 0.4687499999999593658, 0.4999999999999619194, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18520 = FACE_OUTER_BOUND ( 'NONE', #16967, .T. ) ; -#18521 = ORIENTED_EDGE ( 'NONE', *, *, #39213, .T. ) ; -#18522 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18524 = EDGE_CURVE ( 'NONE', #23147, #14158, #3365, .T. ) ; -#18523 = CARTESIAN_POINT ( 'NONE', ( 36.64477843738828255, 191.1898283041118987, 106.4830069681582074 ) ) ; -#18525 = EDGE_CURVE ( 'NONE', #39067, #20299, #38298, .T. ) ; -#18526 = ORIENTED_EDGE ( 'NONE', *, *, #32621, .F. ) ; -#18527 = FACE_OUTER_BOUND ( 'NONE', #11503, .T. ) ; -#18528 = EDGE_CURVE ( 'NONE', #24799, #25077, #20508, .T. ) ; -#18529 = EDGE_CURVE ( 'NONE', #8915, #26075, #29528, .T. ) ; -#18530 = DIRECTION ( 'NONE', ( -0.6087116037913345989, 0.7730376917437175033, 0.1785578633197842380 ) ) ; -#18531 = EDGE_LOOP ( 'NONE', ( #9064, #6824, #16218, #5097, #35505 ) ) ; -#18532 = CARTESIAN_POINT ( 'NONE', ( -32.65062852997883880, 153.0051697192221241, 291.5782640967074713 ) ) ; -#18533 = AXIS2_PLACEMENT_3D ( 'NONE', #18790, #9428, #3269 ) ; -#18534 = CARTESIAN_POINT ( 'NONE', ( -25.39139182829000063, 190.7622573589000012, 106.1326039723000036 ) ) ; -#18535 = VECTOR ( 'NONE', #22067, 1000.000000000000114 ) ; -#18536 = CARTESIAN_POINT ( 'NONE', ( 30.07150067443713581, 176.9244726588816832, 103.2915126945589464 ) ) ; -#18537 = CARTESIAN_POINT ( 'NONE', ( 3.652606486068469049, 125.3210731118818444, 88.58336425918274415 ) ) ; -#18538 = ORIENTED_EDGE ( 'NONE', *, *, #39115, .F. ) ; -#18539 = LINE ( 'NONE', #3015, #33641 ) ; -#18540 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2213, #8759, #33671, #11823 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18541 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; -#18542 = FACE_OUTER_BOUND ( 'NONE', #3134, .T. ) ; -#18543 = CARTESIAN_POINT ( 'NONE', ( -45.96127116939970847, 125.1268439885110126, 91.78846319988008418 ) ) ; -#18544 = ORIENTED_EDGE ( 'NONE', *, *, #32882, .F. ) ; -#18545 = VERTEX_POINT ( 'NONE', #8049 ) ; -#18546 = CARTESIAN_POINT ( 'NONE', ( 13.50176802971722978, 137.8352832724987422, 94.54854101738141026 ) ) ; -#18547 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12343, #6204, #37290, #31169 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18548 = CARTESIAN_POINT ( 'NONE', ( 19.55565711859851064, 149.3413318931515619, 181.5431738098612584 ) ) ; -#18549 = CARTESIAN_POINT ( 'NONE', ( 25.62717527879522450, 212.5792673437159408, 73.04302591068935158 ) ) ; -#18550 = ADVANCED_FACE ( 'NONE', ( #14396 ), #26673, .F. ) ; -#18551 = CARTESIAN_POINT ( 'NONE', ( -36.36432404130999885, 191.9041063813000108, 104.5545526819000060 ) ) ; -#18552 = CARTESIAN_POINT ( 'NONE', ( -25.50032095308166902, 190.9623827952989927, 106.3160945275165687 ) ) ; -#18553 = AXIS2_PLACEMENT_3D ( 'NONE', #7550, #20020, #26791 ) ; -#18554 = CIRCLE ( 'NONE', #17330, 5.999999999944997775 ) ; -#18555 = CARTESIAN_POINT ( 'NONE', ( -12.63917517144589731, 181.9396764318221642, 102.0104863414155147 ) ) ; -#18556 = DATE_TIME_ROLE ( 'creation_date' ) ; -#18557 = CARTESIAN_POINT ( 'NONE', ( 39.73108058903446249, 110.6933397802364283, 169.4226323853610268 ) ) ; -#18558 = AXIS2_PLACEMENT_3D ( 'NONE', #24069, #30805, #6050 ) ; -#18559 = CIRCLE ( 'NONE', #1587, 2.000000000000000444 ) ; -#18560 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#18561 = CARTESIAN_POINT ( 'NONE', ( -24.38839406860000025, 109.6131156702000027, 152.4718672074000381 ) ) ; -#18562 = DIRECTION ( 'NONE', ( 0.0001358647759535183165, 0.9743700645145553230, 0.2249510144868518968 ) ) ; -#18563 = EDGE_CURVE ( 'NONE', #6533, #39643, #24626, .T. ) ; -#18564 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, -2.333520449303964377E-14, -0.9999998176071847045 ) ) ; -#18565 = CARTESIAN_POINT ( 'NONE', ( 37.18464229284000311, 191.0646458765000091, 106.3082676759999998 ) ) ; -#18566 = AXIS2_PLACEMENT_3D ( 'NONE', #17909, #34065, #2799 ) ; -#18567 = EDGE_LOOP ( 'NONE', ( #19319, #7062, #25500, #3752 ) ) ; -#18569 = ORIENTED_EDGE ( 'NONE', *, *, #36129, .T. ) ; -#18568 = CARTESIAN_POINT ( 'NONE', ( 36.66889965364000403, 191.2377279513000019, 106.4440485215999956 ) ) ; -#18570 = ORIENTED_EDGE ( 'NONE', *, *, #15038, .T. ) ; -#18571 = ORIENTED_EDGE ( 'NONE', *, *, #8055, .T. ) ; -#18572 = LINE ( 'NONE', #18375, #4232 ) ; -#18573 = EDGE_CURVE ( 'NONE', #7592, #13713, #14908, .T. ) ; -#18574 = CARTESIAN_POINT ( 'NONE', ( -20.23290355681359287, 184.9083160715356371, 102.5937630826569915 ) ) ; -#18575 = ADVANCED_FACE ( 'NONE', ( #26072 ), #1911, .F. ) ; -#18576 = CARTESIAN_POINT ( 'NONE', ( -31.33471866875930800, 177.4784205339375660, 100.6459703763841844 ) ) ; -#18577 = EDGE_LOOP ( 'NONE', ( #39420, #26558, #30548, #22296 ) ) ; -#18578 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#18579 = EDGE_CURVE ( 'NONE', #572, #35627, #38769, .T. ) ; -#18580 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 143.0051697192221241, 291.5295797804307654 ) ) ; -#18581 = DIRECTION ( 'NONE', ( -0.1632030864945562820, 0.3417424273710317761, -0.9255143790850607344 ) ) ; -#18582 = ORIENTED_EDGE ( 'NONE', *, *, #16404, .T. ) ; -#18583 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 1.238758140229869750E-30, -0.0006039748319385906776 ) ) ; -#18584 = CARTESIAN_POINT ( 'NONE', ( 41.55397567426885530, 120.6681361272677577, 87.99940985657048031 ) ) ; -#18585 = LINE ( 'NONE', #12084, #33292 ) ; -#18586 = CARTESIAN_POINT ( 'NONE', ( -20.09648534120855246, 211.8755416198732462, 76.07065348104518421 ) ) ; -#18587 = VECTOR ( 'NONE', #38922, 1000.000000000000227 ) ; -#18588 = ORIENTED_EDGE ( 'NONE', *, *, #35365, .F. ) ; -#18589 = CARTESIAN_POINT ( 'NONE', ( 15.83489064692280124, 137.8671913220991883, 94.38025547595243836 ) ) ; -#18590 = CARTESIAN_POINT ( 'NONE', ( -0.04020359587071823532, 115.7390747894103953, 347.0321741129275210 ) ) ; -#18591 = AXIS2_PLACEMENT_3D ( 'NONE', #29791, #14249, #36099 ) ; -#18592 = CARTESIAN_POINT ( 'NONE', ( 21.70633521009782640, 123.1952238384177605, 176.5176797919971250 ) ) ; -#18593 = VECTOR ( 'NONE', #34015, 999.9999999999997726 ) ; -#18594 = VERTEX_POINT ( 'NONE', #13990 ) ; -#18595 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319346908024 ) ) ; -#18596 = ORIENTED_EDGE ( 'NONE', *, *, #23301, .F. ) ; -#18597 = CARTESIAN_POINT ( 'NONE', ( -19.99850934198748931, 160.0545621481389844, 99.69532483852709959 ) ) ; -#18598 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21742, #40121, #39924, #15777 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.0003335382722436411817 ), - .UNSPECIFIED. ) ; -#18599 = DIRECTION ( 'NONE', ( 0.6068733047655823221, 0.7745082036644093115, 0.1784428043363773253 ) ) ; -#18600 = CARTESIAN_POINT ( 'NONE', ( 16.55846291764536105, 123.0757855049963467, 172.1961118494296556 ) ) ; -#18601 = CARTESIAN_POINT ( 'NONE', ( -37.35479255310585245, 191.0186931307436851, 106.3350318144467366 ) ) ; -#18602 = CARTESIAN_POINT ( 'NONE', ( 19.85164219301282884, 148.9679372099747638, 184.3407892933917651 ) ) ; -#18603 = CYLINDRICAL_SURFACE ( 'NONE', #39518, 59.40509898897002472 ) ; -#18604 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999902300, 132.9679238121838978, 90.36185680191219660 ) ) ; -#18605 = EDGE_LOOP ( 'NONE', ( #20687, #34271, #37423, #4732 ) ) ; -#18606 = EDGE_CURVE ( 'NONE', #4577, #36211, #27427, .T. ) ; -#18607 = DIRECTION ( 'NONE', ( 0.9999998268368962551, 0.0001323827092387665195, -0.0005734117158298909301 ) ) ; -#18608 = EDGE_CURVE ( 'NONE', #15233, #32479, #39719, .T. ) ; -#18609 = CARTESIAN_POINT ( 'NONE', ( -0.09191864964710037833, 291.0964424001293196, 217.1925188927256158 ) ) ; -#18610 = CARTESIAN_POINT ( 'NONE', ( -10.03744067673693152, 168.3831169150392668, 99.04644282438005121 ) ) ; -#18611 = EDGE_CURVE ( 'NONE', #10977, #15233, #9090, .T. ) ; -#18612 = EDGE_CURVE ( 'NONE', #20961, #982, #4077, .T. ) ; -#18614 = LINE ( 'NONE', #4035, #23372 ) ; -#18613 = DIRECTION ( 'NONE', ( -0.0005884949961239888030, 0.2249510543439063315, -0.9743698870671262391 ) ) ; -#18615 = CIRCLE ( 'NONE', #14057, 6.000000000000007994 ) ; -#18616 = ORIENTED_EDGE ( 'NONE', *, *, #10947, .F. ) ; -#18617 = AXIS2_PLACEMENT_3D ( 'NONE', #3223, #8984, #19155 ) ; -#18618 = ORIENTED_EDGE ( 'NONE', *, *, #4825, .T. ) ; -#18619 = VECTOR ( 'NONE', #22642, 1000.000000000000114 ) ; -#18620 = VECTOR ( 'NONE', #13360, 999.9999999999998863 ) ; -#18621 = ORIENTED_EDGE ( 'NONE', *, *, #15673, .F. ) ; -#18622 = CARTESIAN_POINT ( 'NONE', ( -21.44517132691637329, 129.4739009503746558, 92.63619159901811884 ) ) ; -#18623 = EDGE_CURVE ( 'NONE', #20022, #37794, #35179, .T. ) ; -#18624 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 1.540743955509788340E-33, 0.0006039748319384538513 ) ) ; -#18625 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498903273, 179.0675991014140607, 104.0619761093665971 ) ) ; -#18626 = CARTESIAN_POINT ( 'NONE', ( 12.63749343440153439, 130.8796612142295146, 89.98410442299223178 ) ) ; -#18627 = DIRECTION ( 'NONE', ( 0.7075337269147008445, -0.000000000000000000, 0.7066795775160008564 ) ) ; -#18628 = ORIENTED_EDGE ( 'NONE', *, *, #29073, .T. ) ; -#18629 = CARTESIAN_POINT ( 'NONE', ( -37.28964750938936845, 162.8083416849163996, 206.0112259113205084 ) ) ; -#18630 = EDGE_LOOP ( 'NONE', ( #32717, #34843, #11191, #7943, #38834 ) ) ; -#18631 = CARTESIAN_POINT ( 'NONE', ( 5.661195405889541732, 124.4055252125605620, 88.42320396559895812 ) ) ; -#18632 = CARTESIAN_POINT ( 'NONE', ( 30.05202364329594289, 126.8409241029880832, 91.48406572323723651 ) ) ; -#18633 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; -#18634 = EDGE_CURVE ( 'NONE', #25706, #4731, #17233, .T. ) ; -#18635 = VERTEX_POINT ( 'NONE', #17643 ) ; -#18636 = CARTESIAN_POINT ( 'NONE', ( -36.18185695497940202, 190.9522038446160082, 106.8424817839080134 ) ) ; -#18637 = CARTESIAN_POINT ( 'NONE', ( 2.893047872412550348, 190.2073145499105635, 103.5639949355635281 ) ) ; -#18638 = CARTESIAN_POINT ( 'NONE', ( 13.47463546662201317, 153.3581425397641453, 97.61606142177900836 ) ) ; -#18639 = AXIS2_PLACEMENT_3D ( 'NONE', #3247, #31475, #9811 ) ; -#18640 = VERTEX_POINT ( 'NONE', #35837 ) ; -#18641 = CARTESIAN_POINT ( 'NONE', ( 0.5641629861702882609, 188.3739978860623410, 106.2349422265271812 ) ) ; -#18642 = AXIS2_PLACEMENT_3D ( 'NONE', #40301, #34547, #9043 ) ; -#18643 = DIRECTION ( 'NONE', ( 0.0005884979656576173456, -0.2249510543434622978, 0.9743698870654352584 ) ) ; -#18644 = CARTESIAN_POINT ( 'NONE', ( 36.23987951694048348, 191.4462391905814229, 103.8298826277539177 ) ) ; -#18645 = CARTESIAN_POINT ( 'NONE', ( -26.13534276609000173, 120.0011205343000000, 90.59101258731999451 ) ) ; -#18646 = VECTOR ( 'NONE', #14377, 1000.000000000000114 ) ; -#18647 = EDGE_LOOP ( 'NONE', ( #20449, #9176, #17845, #16775 ) ) ; -#18648 = CARTESIAN_POINT ( 'NONE', ( -14.29767978178728960, 209.7096097237614742, 73.06713952287860536 ) ) ; -#18649 = CIRCLE ( 'NONE', #7539, 6.499999999988696153 ) ; -#18650 = CARTESIAN_POINT ( 'NONE', ( 15.05197310825490398, 136.6013035982805661, 91.18072662319218580 ) ) ; -#18651 = CARTESIAN_POINT ( 'NONE', ( 15.45514460193059847, 202.1125837722002245, 28.07875028728494371 ) ) ; -#18652 = ORIENTED_EDGE ( 'NONE', *, *, #37118, .T. ) ; -#18653 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282899430, 164.6343173020728443, 97.67551052995993643 ) ) ; -#18654 = ORIENTED_EDGE ( 'NONE', *, *, #14174, .T. ) ; -#18655 = ADVANCED_FACE ( 'NONE', ( #39123 ), #29376, .F. ) ; -#18656 = EDGE_CURVE ( 'NONE', #14925, #39132, #15012, .T. ) ; -#18658 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; -#18657 = CARTESIAN_POINT ( 'NONE', ( 36.20042881978272931, 192.0106638782634718, 104.3804419661056926 ) ) ; -#18659 = ORIENTED_EDGE ( 'NONE', *, *, #10577, .F. ) ; -#18660 = ORIENTED_EDGE ( 'NONE', *, *, #15423, .F. ) ; -#18661 = ORIENTED_EDGE ( 'NONE', *, *, #3030, .T. ) ; -#18662 = CARTESIAN_POINT ( 'NONE', ( 2.337161295297999875, 209.5153078266000364, 75.42148145382999758 ) ) ; -#18663 = VECTOR ( 'NONE', #8294, 1000.000000000000114 ) ; -#18664 = CARTESIAN_POINT ( 'NONE', ( 13.85666887053580787, 124.6499588255688309, 174.6121027900639717 ) ) ; -#18665 = CARTESIAN_POINT ( 'NONE', ( 44.83277154663306874, 186.3180907337439578, 107.7244483083414508 ) ) ; -#18666 = CARTESIAN_POINT ( 'NONE', ( 13.50176814620886390, 151.2963865131595753, 97.65648528510170934 ) ) ; -#18667 = ORIENTED_EDGE ( 'NONE', *, *, #11829, .F. ) ; -#18668 = CIRCLE ( 'NONE', #18003, 2.499999999869602085 ) ; -#18669 = ORIENTED_EDGE ( 'NONE', *, *, #12922, .F. ) ; -#18670 = CARTESIAN_POINT ( 'NONE', ( -14.16859883678303689, 135.5379567964818648, 93.51864244317933128 ) ) ; -#18671 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37857, #4301, #32135, #22738 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999999706563479362 ), - .UNSPECIFIED. ) ; -#18672 = CARTESIAN_POINT ( 'NONE', ( 13.50281259258426658, 187.5541529417837694, 105.8642044353590705 ) ) ; -#18673 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; -#18674 = DIRECTION ( 'NONE', ( -0.9999998268368042176, -0.0001323825929795902155, 0.0005734119030926363879 ) ) ; -#18675 = ORIENTED_EDGE ( 'NONE', *, *, #40004, .T. ) ; -#18676 = AXIS2_PLACEMENT_3D ( 'NONE', #1383, #5413, #35504 ) ; -#18677 = VERTEX_POINT ( 'NONE', #35426 ) ; -#18678 = ORIENTED_EDGE ( 'NONE', *, *, #31069, .T. ) ; -#18679 = PLANE ( 'NONE', #8268 ) ; -#18680 = CARTESIAN_POINT ( 'NONE', ( 24.53499375990451270, 104.1131156706254473, 90.25296631794056168 ) ) ; -#18681 = CARTESIAN_POINT ( 'NONE', ( -20.49913213830728864, 118.1134457197417902, 88.44668923520308113 ) ) ; -#18682 = EDGE_CURVE ( 'NONE', #38161, #37905, #19895, .T. ) ; -#18683 = ORIENTED_EDGE ( 'NONE', *, *, #38617, .T. ) ; -#18684 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023854076 ) ) ; -#18685 = CARTESIAN_POINT ( 'NONE', ( -41.01266184249756463, 189.0687663645294663, 107.2394220196258203 ) ) ; -#18686 = ORIENTED_EDGE ( 'NONE', *, *, #17537, .F. ) ; -#18687 = CARTESIAN_POINT ( 'NONE', ( -36.83654042100931036, 116.2424538687594833, 89.73867524819259245 ) ) ; -#18688 = DIRECTION ( 'NONE', ( -0.7066905233759539495, -0.1590641512579268335, 0.6894106903401016062 ) ) ; -#18689 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825925011399283, 0.0005734119022738485335 ) ) ; -#18690 = CARTESIAN_POINT ( 'NONE', ( -37.62305393521922525, 212.3970732061812896, 73.58122755549422322 ) ) ; -#18691 = CARTESIAN_POINT ( 'NONE', ( 26.11095176941643814, 190.7356467402886722, 103.6719484086482765 ) ) ; -#18692 = AXIS2_PLACEMENT_3D ( 'NONE', #18969, #3231, #12643 ) ; -#18693 = VERTEX_POINT ( 'NONE', #5796 ) ; -#18694 = CARTESIAN_POINT ( 'NONE', ( 26.00076055413803999, 117.7169937519419278, 90.25208103135760496 ) ) ; -#18695 = LINE ( 'NONE', #3772, #3558 ) ; -#18696 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32653, #10195, #19568, #38575 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18697 = AXIS2_PLACEMENT_3D ( 'NONE', #34754, #38047, #31733 ) ; -#18698 = CYLINDRICAL_SURFACE ( 'NONE', #23841, 2.000000000000001332 ) ; -#18699 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #38950, #32817, #14637, #36077 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 2.893989844277871981, 4.712388980384664805 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7429183312171808717, 0.7429183312171808717, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#18700 = CARTESIAN_POINT ( 'NONE', ( -22.64184747305000300, 154.1036202365000065, 95.50079732685999545 ) ) ; -#18701 = EDGE_LOOP ( 'NONE', ( #11589, #13314, #28743, #39162 ) ) ; -#18702 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#18703 = ORIENTED_EDGE ( 'NONE', *, *, #18798, .F. ) ; -#18704 = AXIS2_PLACEMENT_3D ( 'NONE', #9500, #30978, #19284 ) ; -#18705 = EDGE_CURVE ( 'NONE', #8699, #15600, #39805, .T. ) ; -#18706 = ADVANCED_FACE ( 'NONE', ( #9075 ), #36547, .F. ) ; -#18707 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38081, #26375, #37477, #10838 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.02880200696896740784, 0.02994545772932011643 ), - .UNSPECIFIED. ) ; -#18708 = LINE ( 'NONE', #37940, #5025 ) ; -#18709 = DIRECTION ( 'NONE', ( -3.295974604355914547E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#18710 = CARTESIAN_POINT ( 'NONE', ( 38.57040784642907028, 118.4633227499596018, 89.66268640670058687 ) ) ; -#18711 = ORIENTED_EDGE ( 'NONE', *, *, #2314, .T. ) ; -#18712 = CARTESIAN_POINT ( 'NONE', ( 23.36189990591568133, 175.3591898460452114, 100.1205101937285349 ) ) ; -#18713 = DIRECTION ( 'NONE', ( 0.0005884949961279498272, -0.2249510543439066645, 0.9743698870671262391 ) ) ; -#18714 = CARTESIAN_POINT ( 'NONE', ( 15.89469151744206421, 128.5927809666073927, 173.0004654942144384 ) ) ; -#18715 = DIRECTION ( 'NONE', ( 1.117039843155982209E-18, 1.000000000000000000, -1.110223092091563281E-14 ) ) ; -#18716 = VERTEX_POINT ( 'NONE', #30952 ) ; -#18717 = EDGE_LOOP ( 'NONE', ( #25445, #17105, #22533, #1802 ) ) ; -#18718 = CARTESIAN_POINT ( 'NONE', ( 1.176830695733112941, 189.0959465685911027, 105.7644401730694170 ) ) ; -#18719 = DIRECTION ( 'NONE', ( -0.0005884949961247390709, 0.2249510543439058041, -0.9743698870671265722 ) ) ; -#18720 = CONICAL_SURFACE ( 'NONE', #28535, 6.503000000032579386, 0.7853981634494727748 ) ; -#18721 = ORIENTED_EDGE ( 'NONE', *, *, #34355, .F. ) ; -#18722 = CARTESIAN_POINT ( 'NONE', ( 36.04524237818177568, 209.7096540190999860, 73.53673375003081958 ) ) ; -#18723 = LINE ( 'NONE', #12605, #23095 ) ; -#18724 = ORIENTED_EDGE ( 'NONE', *, *, #24351, .T. ) ; -#18725 = CARTESIAN_POINT ( 'NONE', ( 20.89486103759118052, 175.7095848683153463, 103.2849699440975826 ) ) ; -#18726 = AXIS2_PLACEMENT_3D ( 'NONE', #14672, #30404, #2403 ) ; -#18727 = PLANE ( 'NONE', #5589 ) ; -#18728 = CARTESIAN_POINT ( 'NONE', ( 55.75981625165690048, 6.558920741114762976, 161.6918666634598196 ) ) ; -#18729 = ORIENTED_EDGE ( 'NONE', *, *, #39700, .T. ) ; -#18730 = DIRECTION ( 'NONE', ( 0.1305263947812629333, 0.9659212020967675727, 0.2235153050807516528 ) ) ; -#18731 = CARTESIAN_POINT ( 'NONE', ( 3.773549070401551742, 167.8775999163818256, 101.2431827948426246 ) ) ; -#18732 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38905, #28914, #26661, #10323 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18733 = PLANE ( 'NONE', #39045 ) ; -#18734 = CARTESIAN_POINT ( 'NONE', ( 25.49919833444198858, 118.8155663768459505, 87.75236248755290092 ) ) ; -#18735 = CARTESIAN_POINT ( 'NONE', ( -5.668107859520512548, 127.9093576421573601, 92.26856186482403643 ) ) ; -#18736 = ORIENTED_EDGE ( 'NONE', *, *, #37560, .F. ) ; -#18737 = CARTESIAN_POINT ( 'NONE', ( -12.63809837006106918, 177.7897768145701036, 100.7065200156251166 ) ) ; -#18738 = CARTESIAN_POINT ( 'NONE', ( -37.78472778768890805, 118.9454232552457142, 87.29152118331340660 ) ) ; -#18739 = CARTESIAN_POINT ( 'NONE', ( 36.75897388210037775, 191.6299679312680837, 104.3441452898864128 ) ) ; -#18740 = EDGE_CURVE ( 'NONE', #8209, #23911, #20934, .T. ) ; -#18741 = CARTESIAN_POINT ( 'NONE', ( 21.70383484956424525, 182.1705797945729444, 104.4340183909650079 ) ) ; -#18742 = ORIENTED_EDGE ( 'NONE', *, *, #21101, .T. ) ; -#18743 = CARTESIAN_POINT ( 'NONE', ( 38.40137274602947315, 118.9610368294954981, 90.24693936499792812 ) ) ; -#18744 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#18745 = CARTESIAN_POINT ( 'NONE', ( -23.01844285970464909, 211.0902260919000355, 76.07552203529617429 ) ) ; -#18746 = CARTESIAN_POINT ( 'NONE', ( 15.75161875086000052, 167.0113677096000231, 101.0233582269000010 ) ) ; -#18747 = EDGE_CURVE ( 'NONE', #23946, #37955, #14321, .T. ) ; -#18748 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5075, #17132, #8573, #23910, #14500, #26372, #17739 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 4 ), - ( -0.001237974900710671388, 0.000000000000000000, 0.0005872420382195917433 ), - .UNSPECIFIED. ) ; -#18749 = CARTESIAN_POINT ( 'NONE', ( -26.00624730612000235, 190.8511792187000253, 106.8090103475999939 ) ) ; -#18750 = ORIENTED_EDGE ( 'NONE', *, *, #34642, .F. ) ; -#18751 = EDGE_CURVE ( 'NONE', #22101, #17938, #21353, .T. ) ; -#18752 = EDGE_CURVE ( 'NONE', #39941, #32129, #24832, .T. ) ; -#18753 = AXIS2_PLACEMENT_3D ( 'NONE', #8850, #19580, #21322 ) ; -#18754 = EDGE_CURVE ( 'NONE', #16835, #7892, #27699, .T. ) ; -#18755 = CARTESIAN_POINT ( 'NONE', ( -19.70043221429562053, 148.9676548935424307, 183.8355817469811768 ) ) ; -#18756 = CARTESIAN_POINT ( 'NONE', ( -39.35442116922705935, 128.7733328792070893, 92.48526942430152076 ) ) ; -#18757 = VERTEX_POINT ( 'NONE', #33593 ) ; -#18758 = CARTESIAN_POINT ( 'NONE', ( 28.44085705255995222, 124.7864337255197995, 91.35282390664609409 ) ) ; -#18759 = CARTESIAN_POINT ( 'NONE', ( 23.36366720388904383, 183.4529741750082508, 105.0711814503917765 ) ) ; -#18760 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567900 ) ) ; -#18761 = CARTESIAN_POINT ( 'NONE', ( 36.19055538703000252, 192.0349938880000025, 106.4032480048999929 ) ) ; -#18762 = ORIENTED_EDGE ( 'NONE', *, *, #24003, .F. ) ; -#18763 = CARTESIAN_POINT ( 'NONE', ( 36.32855195652999925, 192.0751620672000115, 106.2604880945000048 ) ) ; -#18764 = VERTEX_POINT ( 'NONE', #5387 ) ; -#18765 = ORIENTED_EDGE ( 'NONE', *, *, #11955, .F. ) ; -#18766 = CARTESIAN_POINT ( 'NONE', ( -5.199337174292492314, 135.0593233550645493, 90.83696323977939358 ) ) ; -#18767 = CARTESIAN_POINT ( 'NONE', ( 37.96513776071897439, 190.5638673691689178, 106.5329861992229752 ) ) ; -#18768 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319359794851 ) ) ; -#18769 = FACE_OUTER_BOUND ( 'NONE', #18630, .T. ) ; -#18770 = ORIENTED_EDGE ( 'NONE', *, *, #31281, .F. ) ; -#18771 = EDGE_CURVE ( 'NONE', #20395, #31506, #2332, .T. ) ; -#18772 = DIRECTION ( 'NONE', ( 0.0004161288024119937133, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#18773 = CARTESIAN_POINT ( 'NONE', ( -50.65318414753016185, 137.7514108297640121, 291.5891371891943891 ) ) ; -#18774 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.271205131337280331E-14, 1.000000000000000000 ) ) ; -#18775 = ORIENTED_EDGE ( 'NONE', *, *, #1642, .T. ) ; -#18776 = CARTESIAN_POINT ( 'NONE', ( -3.535970564837537466, 118.9425530769304515, 90.19402121340444012 ) ) ; -#18777 = VECTOR ( 'NONE', #14143, 1000.000000000000000 ) ; -#18778 = CARTESIAN_POINT ( 'NONE', ( 32.75367228194463110, 191.5260139691676500, 103.8504056717556523 ) ) ; -#18779 = CARTESIAN_POINT ( 'NONE', ( -32.61688159666169184, 141.9329143176964863, 280.9718830317659695 ) ) ; -#18780 = CARTESIAN_POINT ( 'NONE', ( 37.81020286017945153, 118.4154792045343214, 90.24494842412454432 ) ) ; -#18781 = AXIS2_PLACEMENT_3D ( 'NONE', #16457, #32223, #22823 ) ; -#18782 = CARTESIAN_POINT ( 'NONE', ( -14.42521491161324043, 130.0078947141052765, 89.84737174885860611 ) ) ; -#18783 = ORIENTED_EDGE ( 'NONE', *, *, #33490, .F. ) ; -#18784 = DIRECTION ( 'NONE', ( -0.7933535594326887042, 0.5932204071694016090, 0.1366736194488628042 ) ) ; -#18785 = CARTESIAN_POINT ( 'NONE', ( 2.076830482329000027, 189.1135835803999896, 103.3113577132999978 ) ) ; -#18786 = DIRECTION ( 'NONE', ( 0.9999998176071716038, -2.143130385943402919E-11, -0.0006039748533745596714 ) ) ; -#18787 = EDGE_CURVE ( 'NONE', #1318, #2629, #15747, .T. ) ; -#18788 = ORIENTED_EDGE ( 'NONE', *, *, #2816, .F. ) ; -#18789 = ORIENTED_EDGE ( 'NONE', *, *, #39391, .F. ) ; -#18790 = CARTESIAN_POINT ( 'NONE', ( 77.76885812527426367, 193.5821525182410880, 188.5104908262173637 ) ) ; -#18791 = ORIENTED_EDGE ( 'NONE', *, *, #6638, .T. ) ; -#18792 = CARTESIAN_POINT ( 'NONE', ( -40.62325456460077078, 220.4002261231981947, 73.24970620723485126 ) ) ; -#18793 = EDGE_CURVE ( 'NONE', #18505, #17427, #18046, .T. ) ; -#18794 = CARTESIAN_POINT ( 'NONE', ( -20.35321988482620270, 209.7094481592175157, 73.40406779581955732 ) ) ; -#18796 = ADVANCED_FACE ( 'NONE', ( #15209 ), #36877, .F. ) ; -#18795 = DIRECTION ( 'NONE', ( 0.6087613508342253343, 0.7731002149716631466, 0.1781170270952703305 ) ) ; -#18797 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#18798 = EDGE_CURVE ( 'NONE', #13713, #16030, #20883, .T. ) ; -#18799 = CARTESIAN_POINT ( 'NONE', ( -15.94527486429822538, 152.8203387458500231, 181.6302711725483050 ) ) ; -#18800 = EDGE_CURVE ( 'NONE', #20316, #29017, #8678, .T. ) ; -#18801 = CARTESIAN_POINT ( 'NONE', ( 28.46460725226640065, 186.8972851080696387, 105.8632825901553218 ) ) ; -#18802 = EDGE_LOOP ( 'NONE', ( #14016, #10515, #20929, #25094 ) ) ; -#18803 = CARTESIAN_POINT ( 'NONE', ( -12.63757342683317653, 134.6434190354682983, 93.48128548710673158 ) ) ; -#18804 = CARTESIAN_POINT ( 'NONE', ( 32.37049208056998140, 174.4092940747139551, 99.89893022217735563 ) ) ; -#18805 = ORIENTED_EDGE ( 'NONE', *, *, #2686, .F. ) ; -#18806 = CARTESIAN_POINT ( 'NONE', ( -5.674480817841737412, 181.6879534348617824, 101.6022789869470131 ) ) ; -#18807 = AXIS2_PLACEMENT_3D ( 'NONE', #4010, #946, #25923 ) ; -#18808 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36831, #21304, #5542, #11280, #8003, #23548 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 4 ), - ( 0.000000000000000000, 0.3333331262867959000, 0.6666662542695979132, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18809 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749386919, 179.6299767372458689, 101.6260513916243866 ) ) ; -#18810 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#18811 = VECTOR ( 'NONE', #37099, 1000.000000000000114 ) ; -#18812 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; -#18813 = VERTEX_POINT ( 'NONE', #30547 ) ; -#18814 = VERTEX_POINT ( 'NONE', #25633 ) ; -#18815 = CARTESIAN_POINT ( 'NONE', ( -5.668109640120363224, 181.0132088949428919, 104.5254489105664817 ) ) ; -#18816 = DIRECTION ( 'NONE', ( -0.0005884949961245158337, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#18817 = CARTESIAN_POINT ( 'NONE', ( 37.18881752615094882, 185.3408534924642765, 105.4986827685707453 ) ) ; -#18818 = ORIENTED_EDGE ( 'NONE', *, *, #28702, .F. ) ; -#18819 = LINE ( 'NONE', #31324, #12005 ) ; -#18820 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058949670, 130.4211554272716000, 90.27959376792703949 ) ) ; -#18821 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16037, #28723, #28529, #38320 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18822 = CARTESIAN_POINT ( 'NONE', ( 23.68358947171641304, 134.6471046790361754, 93.46116000412756364 ) ) ; -#18823 = CARTESIAN_POINT ( 'NONE', ( -25.49120152668656303, 192.3458706269117897, 104.4614799839995953 ) ) ; -#18824 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971580390 ) ) ; -#18825 = FACE_OUTER_BOUND ( 'NONE', #36749, .T. ) ; -#18826 = ORIENTED_EDGE ( 'NONE', *, *, #14019, .F. ) ; -#18827 = FACE_OUTER_BOUND ( 'NONE', #34562, .T. ) ; -#18828 = ORIENTED_EDGE ( 'NONE', *, *, #34773, .T. ) ; -#18829 = CARTESIAN_POINT ( 'NONE', ( 14.78617723117088190, 128.6760556706539091, 91.91695949461106352 ) ) ; -#18830 = LINE ( 'NONE', #15582, #28834 ) ; -#18831 = EDGE_LOOP ( 'NONE', ( #32005, #6194, #4505, #11616 ) ) ; -#18832 = AXIS2_PLACEMENT_3D ( 'NONE', #15971, #21537, #3101 ) ; -#18833 = DIRECTION ( 'NONE', ( 0.0005884949961251572477, -0.2249510543439052768, 0.9743698870671265722 ) ) ; -#18834 = CARTESIAN_POINT ( 'NONE', ( 1.116395081135951539, 188.6745468192101498, 103.2112006113849247 ) ) ; -#18835 = EDGE_CURVE ( 'NONE', #5720, #31583, #9798, .T. ) ; -#18836 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971519606 ) ) ; -#18837 = EDGE_CURVE ( 'NONE', #26136, #28651, #5181, .T. ) ; -#18838 = CONICAL_SURFACE ( 'NONE', #30612, 2.500000000143204115, 0.7853981634269987522 ) ; -#18839 = CONICAL_SURFACE ( 'NONE', #40392, 2.749999999702389175, 0.7853981633701920817 ) ; -#18840 = EDGE_CURVE ( 'NONE', #30394, #36508, #11077, .T. ) ; -#18841 = VERTEX_POINT ( 'NONE', #25028 ) ; -#18842 = DIRECTION ( 'NONE', ( 0.6088835995545408553, 0.7728434649458199024, 0.1788120266761852317 ) ) ; -#18843 = DIRECTION ( 'NONE', ( 4.905797990098339101E-13, 0.9743700557921592953, 0.2249510932971531540 ) ) ; -#18844 = ORIENTED_EDGE ( 'NONE', *, *, #26548, .T. ) ; -#18845 = AXIS2_PLACEMENT_3D ( 'NONE', #32108, #38817, #10840 ) ; -#18846 = EDGE_CURVE ( 'NONE', #38021, #24364, #10925, .T. ) ; -#18847 = DIRECTION ( 'NONE', ( -0.7933530821293338642, -0.5932640870757631690, -0.1364866662427065280 ) ) ; -#18848 = CARTESIAN_POINT ( 'NONE', ( 36.48627557462513948, 191.3199122529084093, 103.8005689337988144 ) ) ; -#18849 = CARTESIAN_POINT ( 'NONE', ( 16.55529869184574210, 151.5392854340460360, 184.4105441063242097 ) ) ; -#18850 = EDGE_CURVE ( 'NONE', #13020, #7718, #11415, .T. ) ; -#18851 = VERTEX_POINT ( 'NONE', #19463 ) ; -#18852 = CARTESIAN_POINT ( 'NONE', ( -19.99839448797337482, 118.1131156702000169, 87.27644273471670999 ) ) ; -#18853 = FACE_OUTER_BOUND ( 'NONE', #10462, .T. ) ; -#18854 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2249510911124609769, 0.9743700461176366678 ) ) ; -#18855 = EDGE_CURVE ( 'NONE', #16187, #27723, #18707, .T. ) ; -#18856 = VERTEX_POINT ( 'NONE', #23299 ) ; -#18857 = FACE_OUTER_BOUND ( 'NONE', #34810, .T. ) ; -#18858 = DIRECTION ( 'NONE', ( 0.0005884949961231208991, -0.2249510543439063315, 0.9743698870671262391 ) ) ; -#18860 = CARTESIAN_POINT ( 'NONE', ( -15.94446068766880487, 121.2107412334159591, 177.4020268254936923 ) ) ; -#18859 = CARTESIAN_POINT ( 'NONE', ( -28.52494644200928064, 186.7521494213145559, 105.8641958179564568 ) ) ; -#18861 = ORIENTED_EDGE ( 'NONE', *, *, #35124, .F. ) ; -#18862 = EDGE_CURVE ( 'NONE', #23375, #15218, #66, .T. ) ; -#18863 = CIRCLE ( 'NONE', #16247, 2.000000000000011546 ) ; -#18864 = FACE_OUTER_BOUND ( 'NONE', #29950, .T. ) ; -#18865 = ORIENTED_EDGE ( 'NONE', *, *, #19370, .F. ) ; -#18866 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 132.6352630048999970, 91.80276880046000088 ) ) ; -#18867 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16593, #19858, #16988, #26639 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18868 = CIRCLE ( 'NONE', #30669, 4.999999999999990230 ) ; -#18869 = CARTESIAN_POINT ( 'NONE', ( -32.37225756577250024, 137.6262283585609794, 94.52490471072836442 ) ) ; -#18870 = CONICAL_SURFACE ( 'NONE', #23473, 2.500001241545478869, 0.7853981633776581095 ) ; -#18871 = DIRECTION ( 'NONE', ( -0.6075493383219849886, 0.7739051213223927528, 0.1787586772592889839 ) ) ; -#18872 = ORIENTED_EDGE ( 'NONE', *, *, #2214, .T. ) ; -#18873 = CONICAL_SURFACE ( 'NONE', #35846, 2.503080759488892415, 0.7853981633955684494 ) ; -#18874 = EDGE_LOOP ( 'NONE', ( #37646, #13329, #21763, #23022 ) ) ; -#18875 = DIRECTION ( 'NONE', ( -0.0005884949961248158324, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#18876 = CARTESIAN_POINT ( 'NONE', ( -19.73804990392530812, 124.3515837127999788, 178.1521725410697741 ) ) ; -#18877 = CARTESIAN_POINT ( 'NONE', ( 2.461057949780893317, 209.5714396328634450, 73.55701857314350889 ) ) ; -#18878 = VERTEX_POINT ( 'NONE', #15792 ) ; -#18879 = EDGE_LOOP ( 'NONE', ( #35856, #18910, #16609, #16802 ) ) ; -#18880 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#18881 = DIRECTION ( 'NONE', ( 1.156482317317869950E-15, 0.9743700557921587402, 0.2249510932971554578 ) ) ; -#18882 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#18883 = CARTESIAN_POINT ( 'NONE', ( -28.53213015704000100, 125.2791341444000039, 88.59304627238000762 ) ) ; -#18884 = ORIENTED_EDGE ( 'NONE', *, *, #16133, .T. ) ; -#18885 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #29698, #32553, #16987, #1466, #13952, #26431, #10896 ), - ( #23362, #32750, #35794, #7804, #4737, #1680, #39079 ), - ( #11089, #23551, #6293, #40438, #15312, #12439, #34103 ), - ( #6691, #34888, #27804, #3421, #31458, #37985, #31868 ), - ( #22056, #22264, #3028, #18961, #12248, #6896, #9986 ), - ( #31057, #19159, #13052, #24938, #15514, #31661, #34299 ), - ( #18749, #40236, #15896, #24738, #16107, #12637, #37191 ), - ( #28392, #28003, #25134, #366, #3623, #12853, #28200 ), - ( #22464, #9183, #25331, #37776, #37386, #6101, #18552 ), - ( #9384, #31249, #28591, #21855, #3226, #15700, #168 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 3, 4 ), - ( 4, 3, 4 ), - ( -2.263537866221000035E-13, 0.2499980354206000066, 0.4999962054489999752, 0.7499943754775000304, 0.9999965259027999709, 1.009996491161830212 ), - ( 0.1756339864888999958, 0.8243141701313000391, 0.8308009719677240668 ), - .UNSPECIFIED. ) ; -#18886 = DIRECTION ( 'NONE', ( 6.071532165918830352E-15, -0.9743700557921586292, -0.2249510932971559296 ) ) ; -#18887 = FACE_OUTER_BOUND ( 'NONE', #19704, .T. ) ; -#18888 = ORIENTED_EDGE ( 'NONE', *, *, #18105, .T. ) ; -#18889 = EDGE_CURVE ( 'NONE', #32946, #37217, #35208, .T. ) ; -#18890 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26740, #29403, #5243, #1371 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18891 = ADVANCED_FACE ( 'NONE', ( #10081 ), #34887, .F. ) ; -#18892 = EDGE_CURVE ( 'NONE', #18856, #7935, #31332, .T. ) ; -#18893 = FACE_OUTER_BOUND ( 'NONE', #29317, .T. ) ; -#18894 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391919761 ) ) ; -#18895 = AXIS2_PLACEMENT_3D ( 'NONE', #27451, #1660, #14340 ) ; -#18896 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971566513 ) ) ; -#18897 = DIRECTION ( 'NONE', ( 0.0002331579778304189888, 0.000000000000000000, -0.9999999728186783621 ) ) ; -#18898 = EDGE_CURVE ( 'NONE', #13580, #29223, #33348, .T. ) ; -#18899 = AXIS2_PLACEMENT_3D ( 'NONE', #32590, #10534, #23000 ) ; -#18900 = ORIENTED_EDGE ( 'NONE', *, *, #26914, .F. ) ; -#18901 = FACE_OUTER_BOUND ( 'NONE', #14114, .T. ) ; -#18902 = AXIS2_PLACEMENT_3D ( 'NONE', #36046, #4770, #20102 ) ; -#18903 = ORIENTED_EDGE ( 'NONE', *, *, #21653, .T. ) ; -#18904 = CARTESIAN_POINT ( 'NONE', ( -20.89285663966641238, 176.3787109218369551, 100.3857757381706222 ) ) ; -#18905 = CARTESIAN_POINT ( 'NONE', ( 36.30826696690632360, 191.7212304793147837, 104.1902916582040888 ) ) ; -#18906 = VECTOR ( 'NONE', #28635, 1000.000000000000227 ) ; -#18907 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#18908 = EDGE_CURVE ( 'NONE', #2995, #3644, #32701, .T. ) ; -#18909 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #13828, #1764 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18910 = ORIENTED_EDGE ( 'NONE', *, *, #25404, .T. ) ; -#18911 = CARTESIAN_POINT ( 'NONE', ( -5.631665583173067091, 110.1833198944677008, 152.0219651185256566 ) ) ; -#18912 = VERTEX_POINT ( 'NONE', #32893 ) ; -#18913 = CARTESIAN_POINT ( 'NONE', ( -25.89361811542643110, 209.7107217741274781, 73.19061257701807222 ) ) ; -#18914 = EDGE_CURVE ( 'NONE', #3576, #18912, #3081, .T. ) ; -#18915 = CARTESIAN_POINT ( 'NONE', ( -38.36762371684000072, 118.5381708343000042, 89.85085864944001344 ) ) ; -#18916 = EDGE_CURVE ( 'NONE', #16019, #11837, #39215, .T. ) ; -#18917 = CARTESIAN_POINT ( 'NONE', ( 15.50029466670349620, 151.8594625334012278, 95.21623178078017702 ) ) ; -#18918 = ORIENTED_EDGE ( 'NONE', *, *, #12774, .T. ) ; -#18919 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 130.2884061588697477, 89.74324129540521255 ) ) ; -#18920 = LINE ( 'NONE', #13410, #7536 ) ; -#18921 = CARTESIAN_POINT ( 'NONE', ( -29.20104124293470349, 162.9607637445586192, 100.3719287999282130 ) ) ; -#18922 = CARTESIAN_POINT ( 'NONE', ( -20.23762457072344745, 159.6993819354047162, 96.53465277977143444 ) ) ; -#18923 = CARTESIAN_POINT ( 'NONE', ( 17.27144951970729991, 122.5453306081213043, 172.0736587966182469 ) ) ; -#18924 = CARTESIAN_POINT ( 'NONE', ( -35.44629553183553838, 112.4664344014998818, 90.28919351346762312 ) ) ; -#18925 = ORIENTED_EDGE ( 'NONE', *, *, #36923, .F. ) ; -#18926 = ORIENTED_EDGE ( 'NONE', *, *, #20337, .T. ) ; -#18928 = AXIS2_PLACEMENT_3D ( 'NONE', #25362, #12468, #31485 ) ; -#18927 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319380584428 ) ) ; -#18929 = AXIS2_PLACEMENT_3D ( 'NONE', #20708, #14586, #14379 ) ; -#18930 = CARTESIAN_POINT ( 'NONE', ( 12.63986553157402781, 174.6815491745478255, 103.0556938779417067 ) ) ; -#18931 = AXIS2_PLACEMENT_3D ( 'NONE', #39194, #11391, #23878 ) ; -#18932 = ORIENTED_EDGE ( 'NONE', *, *, #12992, .F. ) ; -#18933 = CARTESIAN_POINT ( 'NONE', ( -14.78422084203157461, 175.4439834284964945, 102.7320481277236013 ) ) ; -#18934 = AXIS2_PLACEMENT_3D ( 'NONE', #24631, #2134, #2331 ) ; -#18935 = CARTESIAN_POINT ( 'NONE', ( -35.81350251770196280, 107.3141770694631845, 174.6977881228511080 ) ) ; -#18936 = ORIENTED_EDGE ( 'NONE', *, *, #27494, .F. ) ; -#18937 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; -#18938 = PLANE ( 'NONE', #23226 ) ; -#18939 = ORIENTED_EDGE ( 'NONE', *, *, #28500, .T. ) ; -#18940 = CARTESIAN_POINT ( 'NONE', ( 28.36482613956999899, 125.3392128497000044, 88.74362595223000483 ) ) ; -#18941 = DIRECTION ( 'NONE', ( 0.0005884941600622459624, -0.2249510532593050061, 0.9743698873180312026 ) ) ; -#18942 = DIRECTION ( 'NONE', ( 0.7933532970003751572, 0.5930762008556708098, 0.1372995488602871961 ) ) ; -#18943 = ADVANCED_FACE ( 'NONE', ( #17338 ), #8163, .T. ) ; -#18944 = EDGE_CURVE ( 'NONE', #1845, #32051, #9123, .T. ) ; -#18945 = CARTESIAN_POINT ( 'NONE', ( -19.99998949574776930, 122.8402457258809619, 88.02489516763034771 ) ) ; -#18946 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12670, #21289, #18778, #21890 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#18947 = CARTESIAN_POINT ( 'NONE', ( -18.98889543208580122, 125.5955304196095312, 175.3358149539526778 ) ) ; -#18948 = ORIENTED_EDGE ( 'NONE', *, *, #20055, .F. ) ; -#18949 = CARTESIAN_POINT ( 'NONE', ( 16.55826291764536151, 122.5115568680679559, 174.6303284955642994 ) ) ; -#18950 = CARTESIAN_POINT ( 'NONE', ( -37.72967283144954109, 118.8809476575462583, 87.29057205257689134 ) ) ; -#18951 = DIRECTION ( 'NONE', ( 0.7933535320750499942, -0.5931614265261869745, -0.1369295264925045885 ) ) ; -#18952 = CARTESIAN_POINT ( 'NONE', ( 12.63611452238018984, 129.9736765176137965, 92.21783751031847487 ) ) ; -#18953 = ORIENTED_EDGE ( 'NONE', *, *, #18153, .F. ) ; -#18954 = CARTESIAN_POINT ( 'NONE', ( 35.48442776063147619, 88.13433118093483642, 282.5337480928039895 ) ) ; -#18955 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057990016292, 0.1373964268091235619 ) ) ; -#18956 = FACE_OUTER_BOUND ( 'NONE', #25101, .T. ) ; -#18957 = CARTESIAN_POINT ( 'NONE', ( 19.98483764167631094, 211.0849390754169974, 73.04592155476974824 ) ) ; -#18958 = VECTOR ( 'NONE', #37325, 1000.000000000000114 ) ; -#18959 = AXIS2_PLACEMENT_3D ( 'NONE', #12825, #13027, #31638 ) ; -#18960 = CARTESIAN_POINT ( 'NONE', ( 15.99999293039724257, 151.9655111556795362, 94.72726368743165892 ) ) ; -#18961 = CARTESIAN_POINT ( 'NONE', ( -25.72063744915000427, 189.5948766207999938, 106.0056453769999933 ) ) ; -#18962 = ORIENTED_EDGE ( 'NONE', *, *, #18105, .F. ) ; -#18963 = VECTOR ( 'NONE', #26288, 999.9999999999998863 ) ; -#18964 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#18965 = VECTOR ( 'NONE', #7242, 1000.000000000000000 ) ; -#18966 = DIRECTION ( 'NONE', ( 5.551115123177313463E-15, -0.9743700557921587402, -0.2249510932971553467 ) ) ; -#18967 = EDGE_CURVE ( 'NONE', #10469, #29957, #33914, .T. ) ; -#18968 = FACE_OUTER_BOUND ( 'NONE', #38710, .T. ) ; -#18969 = CARTESIAN_POINT ( 'NONE', ( 3.047144816654127730, 209.7096538831000032, 78.05666459524968559 ) ) ; -#18970 = ORIENTED_EDGE ( 'NONE', *, *, #575, .T. ) ; -#18971 = CARTESIAN_POINT ( 'NONE', ( -36.45739912719590592, 115.9577502964445301, 87.74842822314147384 ) ) ; -#18972 = CARTESIAN_POINT ( 'NONE', ( 17.33070710942128301, 121.2635828526781268, 177.4224744102505440 ) ) ; -#18973 = PLANE ( 'NONE', #31977 ) ; -#18974 = CARTESIAN_POINT ( 'NONE', ( 37.68865279781829969, 190.9621098111250319, 106.2899631106229918 ) ) ; -#18976 = ORIENTED_EDGE ( 'NONE', *, *, #20375, .F. ) ; -#18975 = CARTESIAN_POINT ( 'NONE', ( 36.57849226294000289, 191.3118430090999880, 106.4570103174000195 ) ) ; -#18977 = EDGE_LOOP ( 'NONE', ( #26433, #29722, #30082, #31674, #29351, #6884, #17585, #31726, #4394, #9700, #5826 ) ) ; -#18978 = CARTESIAN_POINT ( 'NONE', ( -4.520475493760558017, 135.3895221152266117, 90.91278562870999735 ) ) ; -#18979 = CARTESIAN_POINT ( 'NONE', ( -17.99823451464924418, 132.2930705108461495, 93.28496706202059841 ) ) ; -#18980 = ADVANCED_FACE ( 'NONE', ( #1825 ), #5081, .T. ) ; -#18981 = DIRECTION ( 'NONE', ( -0.0005884949961219008464, 0.2249510543439048049, -0.9743698870671267942 ) ) ; -#18982 = CARTESIAN_POINT ( 'NONE', ( -29.78153364950144422, 126.4887807563219440, 91.43890500524419451 ) ) ; -#18983 = ORIENTED_EDGE ( 'NONE', *, *, #9255, .T. ) ; -#18984 = AXIS2_PLACEMENT_3D ( 'NONE', #14042, #8311, #20355 ) ; -#18985 = AXIS2_PLACEMENT_3D ( 'NONE', #21719, #18810, #22321 ) ; -#18986 = CARTESIAN_POINT ( 'NONE', ( -20.00005051927294986, 192.3656549280321997, 103.9335389961495366 ) ) ; -#18987 = CYLINDRICAL_SURFACE ( 'NONE', #4062, 9.000000000000003553 ) ; -#18988 = ORIENTED_EDGE ( 'NONE', *, *, #28438, .F. ) ; -#18989 = DIRECTION ( 'NONE', ( 0.6773442687123379935, 0.7356661890032381024, 0.000000000000000000 ) ) ; -#18990 = VECTOR ( 'NONE', #30877, 1000.000000000000114 ) ; -#18991 = VECTOR ( 'NONE', #36138, 1000.000000000000227 ) ; -#18992 = DIRECTION ( 'NONE', ( 0.0005884949961252012663, -0.2249510543439044163, 0.9743698870671267942 ) ) ; -#18993 = EDGE_CURVE ( 'NONE', #36593, #39888, #26781, .T. ) ; -#18994 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20083, #23573, #13972, #8243 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.007703849374118843137, 0.008859097743410275852 ), - .UNSPECIFIED. ) ; -#18995 = EDGE_CURVE ( 'NONE', #26666, #2318, #2041, .T. ) ; -#18996 = FACE_OUTER_BOUND ( 'NONE', #25486, .T. ) ; -#18997 = CYLINDRICAL_SURFACE ( 'NONE', #20239, 2.000000000000011546 ) ; -#18998 = PLANE ( 'NONE', #9939 ) ; -#18999 = ORIENTED_EDGE ( 'NONE', *, *, #33494, .T. ) ; -#19000 = DIRECTION ( 'NONE', ( -0.0005884949961299158110, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#19001 = CARTESIAN_POINT ( 'NONE', ( 1.382070334880999951, 189.0309197301999973, 103.5690980493999973 ) ) ; -#19002 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971529042 ) ) ; -#19003 = EDGE_CURVE ( 'NONE', #2592, #28925, #25555, .T. ) ; -#19004 = ORIENTED_EDGE ( 'NONE', *, *, #16184, .F. ) ; -#19005 = ORIENTED_EDGE ( 'NONE', *, *, #13776, .T. ) ; -#19006 = DIRECTION ( 'NONE', ( -0.7763856147932157725, 0.5343480027610243432, 0.3342118924985533757 ) ) ; -#19007 = VERTEX_POINT ( 'NONE', #5285 ) ; -#19008 = DIRECTION ( 'NONE', ( -0.7066903926851649809, 0.000000000000000000, 0.7075229246367126246 ) ) ; -#19009 = CARTESIAN_POINT ( 'NONE', ( 35.80367347626000196, 109.6131156806000035, 87.49615981601000669 ) ) ; -#19010 = DIRECTION ( 'NONE', ( 3.469446952028437646E-15, 0.9743700557921590732, 0.2249510932971540700 ) ) ; -#19011 = CARTESIAN_POINT ( 'NONE', ( -12.63562264099845223, 176.9317098760967895, 103.3366312265686702 ) ) ; -#19012 = AXIS2_PLACEMENT_3D ( 'NONE', #11529, #24218, #30746 ) ; -#19013 = PLANE ( 'NONE', #39611 ) ; -#19014 = VECTOR ( 'NONE', #27800, 1000.000000000000227 ) ; -#19015 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#19016 = CARTESIAN_POINT ( 'NONE', ( -1.203883532793524225, 189.1531580572220719, 105.7825619712950385 ) ) ; -#19017 = VERTEX_POINT ( 'NONE', #37604 ) ; -#19018 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 1.676366911644155200E-18, 0.0006039748319336982153 ) ) ; -#19019 = CARTESIAN_POINT ( 'NONE', ( -39.03036842907830106, 121.1728496032269078, 123.5553118490896907 ) ) ; -#19020 = FACE_OUTER_BOUND ( 'NONE', #36445, .T. ) ; -#19021 = CARTESIAN_POINT ( 'NONE', ( -20.51880467302672173, 211.0905570380611493, 75.57084890002228406 ) ) ; -#19022 = ORIENTED_EDGE ( 'NONE', *, *, #2769, .T. ) ; -#19023 = ORIENTED_EDGE ( 'NONE', *, *, #34752, .F. ) ; -#19024 = CARTESIAN_POINT ( 'NONE', ( 0.5456353394454329653, 210.9999999999944578, 75.55817498829796364 ) ) ; -#19025 = EDGE_CURVE ( 'NONE', #22970, #29453, #4404, .T. ) ; -#19026 = CARTESIAN_POINT ( 'NONE', ( 21.87486947896477929, 115.3317988067956321, 87.25457241900384986 ) ) ; -#19027 = DIRECTION ( 'NONE', ( -0.9914448496661262267, 0.1271494159038595584, 0.02949806952699904686 ) ) ; -#19028 = VERTEX_POINT ( 'NONE', #1143 ) ; -#19029 = FACE_OUTER_BOUND ( 'NONE', #21121, .T. ) ; -#19030 = EDGE_CURVE ( 'NONE', #29413, #32027, #4002, .T. ) ; -#19031 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#19032 = DIRECTION ( 'NONE', ( -0.0006039748319386439119, 0.000000000000000000, -0.9999998176071845934 ) ) ; -#19033 = DIRECTION ( 'NONE', ( 0.0005884949961220700904, -0.2249510543439053878, 0.9743698870671265722 ) ) ; -#19034 = CARTESIAN_POINT ( 'NONE', ( 3.535970564806534266, 118.9434892789997917, 90.18996607748785266 ) ) ; -#19035 = ORIENTED_EDGE ( 'NONE', *, *, #32488, .F. ) ; -#19036 = DIRECTION ( 'NONE', ( -8.326672684584947048E-14, 0.9743700557921587402, 0.2249510932971554023 ) ) ; -#19037 = ORIENTED_EDGE ( 'NONE', *, *, #23748, .F. ) ; -#19038 = ORIENTED_EDGE ( 'NONE', *, *, #13716, .T. ) ; -#19039 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#19040 = AXIS2_PLACEMENT_3D ( 'NONE', #10066, #6979, #19446 ) ; -#19041 = EDGE_CURVE ( 'NONE', #14192, #6308, #26302, .T. ) ; -#19042 = ADVANCED_FACE ( 'NONE', ( #23033 ), #38955, .F. ) ; -#19043 = VECTOR ( 'NONE', #10982, 1000.000000000000114 ) ; -#19044 = ORIENTED_EDGE ( 'NONE', *, *, #40135, .F. ) ; -#19045 = CARTESIAN_POINT ( 'NONE', ( -2.940658112151719905, 191.1132255574039789, 103.7732427199960057 ) ) ; -#19046 = EDGE_CURVE ( 'NONE', #5859, #30529, #23469, .T. ) ; -#19047 = AXIS2_PLACEMENT_3D ( 'NONE', #26380, #19616, #3876 ) ; -#19048 = CARTESIAN_POINT ( 'NONE', ( 2.917437660352353301, 190.2735791520341024, 103.5792785963609788 ) ) ; -#19049 = CARTESIAN_POINT ( 'NONE', ( 42.51962411156773669, 182.5729458539040593, 104.8564411487018049 ) ) ; -#19050 = EDGE_LOOP ( 'NONE', ( #13661, #10357, #30321, #37487 ) ) ; -#19051 = CARTESIAN_POINT ( 'NONE', ( -22.23902781740747869, 214.0141975910763961, 73.07193589793287458 ) ) ; -#19052 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#19053 = VERTEX_POINT ( 'NONE', #23428 ) ; -#19054 = CARTESIAN_POINT ( 'NONE', ( 2.896165866612135265, 191.4885083221446962, 104.0308307092542606 ) ) ; -#19055 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28961, #25507, #31635, #32431 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( -2.096239065088066676E-09, 0.9999999999999998890 ), - .UNSPECIFIED. ) ; -#19056 = DIRECTION ( 'NONE', ( 0.7856007465113961086, 0.6187337610642700270, 0.000000000000000000 ) ) ; -#19057 = CARTESIAN_POINT ( 'NONE', ( -26.62285416470999877, 123.4451883726000005, 90.85907200423000063 ) ) ; -#19058 = ORIENTED_EDGE ( 'NONE', *, *, #11824, .T. ) ; -#19059 = CARTESIAN_POINT ( 'NONE', ( -17.26183737405610330, 121.4975388230068916, 176.5517749385022057 ) ) ; -#19060 = CARTESIAN_POINT ( 'NONE', ( 26.00064436918396282, 118.5819532798333427, 90.25208110153040764 ) ) ; -#19061 = LINE ( 'NONE', #15603, #7118 ) ; -#19062 = EDGE_CURVE ( 'NONE', #36789, #16580, #38550, .T. ) ; -#19063 = ORIENTED_EDGE ( 'NONE', *, *, #6724, .F. ) ; -#19064 = LINE ( 'NONE', #22568, #26059 ) ; -#19065 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971561239 ) ) ; -#19066 = CIRCLE ( 'NONE', #36712, 6.000000000042818193 ) ; -#19067 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16509, #21017, #11615, #30424, #26553, #14478, #26963, #5256, #39395, #24088, #39000, #33468, #11400, #14276, #8135, #18126, #26749, #39202, #5462, #5676 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000270062, 0.1875000000000286160, 0.2187500000000286715, 0.2343750000000307532, 0.2500000000000328626, 0.4999999999999928946, 0.6249999999999711342, 0.6874999999999596989, 0.7187499999999539257, 0.7343749999999555911, 0.7499999999999572564, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19069 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433776002355 ) ) ; -#19068 = CARTESIAN_POINT ( 'NONE', ( -36.08528539247640765, 191.6236262332290323, 104.0629932494446024 ) ) ; -#19070 = ORIENTED_EDGE ( 'NONE', *, *, #18073, .F. ) ; -#19071 = VECTOR ( 'NONE', #12714, 1000.000000000000000 ) ; -#19072 = VECTOR ( 'NONE', #39188, 1000.000000000000114 ) ; -#19073 = ORIENTED_EDGE ( 'NONE', *, *, #29188, .T. ) ; -#19074 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; -#19075 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3201, #28181, #151, #12610, #25110, #35667, #8461, #20922, #13235, #19545 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000526246, 0.3750000000000134892, 0.4375000000000093814, 0.5000000000000052180, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19076 = ADVANCED_FACE ( 'NONE', ( #35870 ), #32322, .F. ) ; -#19077 = FACE_OUTER_BOUND ( 'NONE', #34623, .T. ) ; -#19078 = VERTEX_POINT ( 'NONE', #2253 ) ; -#19079 = EDGE_LOOP ( 'NONE', ( #2006, #3252, #38528, #26206 ) ) ; -#19080 = CARTESIAN_POINT ( 'NONE', ( 39.32399170537503608, 175.4331703188547920, 136.0698303701354348 ) ) ; -#19081 = CARTESIAN_POINT ( 'NONE', ( -13.47030235340321980, 153.5044711432410907, 96.98191525122514633 ) ) ; -#19082 = EDGE_CURVE ( 'NONE', #37526, #5222, #24169, .T. ) ; -#19083 = CARTESIAN_POINT ( 'NONE', ( -19.73768723704201378, 124.3505960279316014, 178.1528323905962452 ) ) ; -#19084 = CARTESIAN_POINT ( 'NONE', ( -2.814039137602999840, 190.9186751583000330, 106.6856912745000017 ) ) ; -#19085 = CARTESIAN_POINT ( 'NONE', ( 36.24311113342000112, 191.7667988338999976, 104.2009492968000046 ) ) ; -#19086 = ORIENTED_EDGE ( 'NONE', *, *, #37521, .T. ) ; -#19087 = ADVANCED_FACE ( 'NONE', ( #1841 ), #16936, .F. ) ; -#19088 = ORIENTED_EDGE ( 'NONE', *, *, #3245, .F. ) ; -#19089 = VERTEX_POINT ( 'NONE', #39040 ) ; -#19090 = CARTESIAN_POINT ( 'NONE', ( 3.062737380639022344, 196.5784460000043055, 103.8732377138169483 ) ) ; -#19091 = CARTESIAN_POINT ( 'NONE', ( 20.50147081420385931, 173.9561948828717561, 102.3672533376207952 ) ) ; -#19092 = LINE ( 'NONE', #6419, #37661 ) ; -#19093 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#19094 = EDGE_CURVE ( 'NONE', #31088, #40142, #24345, .T. ) ; -#19095 = ORIENTED_EDGE ( 'NONE', *, *, #20741, .F. ) ; -#19096 = CARTESIAN_POINT ( 'NONE', ( 20.00025828646017345, 174.5279639952516106, 99.93388581131628712 ) ) ; -#19097 = VERTEX_POINT ( 'NONE', #36794 ) ; -#19098 = CONICAL_SURFACE ( 'NONE', #26980, 10.00000000003960210, 0.7853981633972906273 ) ; -#19099 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18116, #30620, #12013, #30817 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19100 = AXIS2_PLACEMENT_3D ( 'NONE', #34283, #2435, #15688 ) ; -#19101 = FACE_OUTER_BOUND ( 'NONE', #34717, .T. ) ; -#19102 = CARTESIAN_POINT ( 'NONE', ( -5.664428473434217182, 187.6140210707962979, 105.9750649276934382 ) ) ; -#19103 = CIRCLE ( 'NONE', #4063, 2.250000000024274360 ) ; -#19104 = CARTESIAN_POINT ( 'NONE', ( -2.811333532546000047, 190.9942814073000079, 106.7041626420000000 ) ) ; -#19105 = CARTESIAN_POINT ( 'NONE', ( 42.94995788232328238, 77.14301703112133168, 281.7122703257673493 ) ) ; -#19106 = ORIENTED_EDGE ( 'NONE', *, *, #36650, .T. ) ; -#19107 = CARTESIAN_POINT ( 'NONE', ( -42.86442090264492322, 113.2940780347909708, 125.2207354701815660 ) ) ; -#19108 = VERTEX_POINT ( 'NONE', #11657 ) ; -#19109 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#19110 = CARTESIAN_POINT ( 'NONE', ( 20.71769855053793208, 213.0587601636507316, 73.04599111161205371 ) ) ; -#19111 = CARTESIAN_POINT ( 'NONE', ( 30.05202367136483588, 184.7526529953215118, 104.8540442558833234 ) ) ; -#19112 = CARTESIAN_POINT ( 'NONE', ( -40.80749064254901981, 126.9113585741826995, 91.54312417625736487 ) ) ; -#19113 = ORIENTED_EDGE ( 'NONE', *, *, #6032, .F. ) ; -#19114 = FACE_OUTER_BOUND ( 'NONE', #30436, .T. ) ; -#19115 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 135.6522072397366401, 90.95982947643871341 ) ) ; -#19116 = ORIENTED_EDGE ( 'NONE', *, *, #14211, .F. ) ; -#19117 = DIRECTION ( 'NONE', ( 3.880623682586550903E-28, -0.9743043966640312359, -0.2252353050503803078 ) ) ; -#19118 = AXIS2_PLACEMENT_3D ( 'NONE', #31362, #2932, #25044 ) ; -#19119 = ORIENTED_EDGE ( 'NONE', *, *, #22208, .T. ) ; -#19120 = EDGE_CURVE ( 'NONE', #288, #2348, #20212, .T. ) ; -#19121 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098504, 179.0628333272192947, 104.0826189413440375 ) ) ; -#19122 = ADVANCED_FACE ( 'NONE', ( #5302 ), #5094, .F. ) ; -#19123 = CARTESIAN_POINT ( 'NONE', ( 25.49929013439215808, 120.2777482667009536, 87.91897806052588749 ) ) ; -#19124 = ADVANCED_FACE ( 'NONE', ( #17155 ), #21264, .F. ) ; -#19125 = CARTESIAN_POINT ( 'NONE', ( 23.36395032469019029, 177.6218452589418177, 100.7937265896866990 ) ) ; -#19126 = AXIS2_PLACEMENT_3D ( 'NONE', #32183, #19486, #38493 ) ; -#19127 = ADVANCED_FACE ( 'NONE', ( #33712 ), #8478, .F. ) ; -#19128 = ORIENTED_EDGE ( 'NONE', *, *, #18107, .T. ) ; -#19129 = CARTESIAN_POINT ( 'NONE', ( -20.16488847591704925, 173.8709817318066371, 102.7143564760062162 ) ) ; -#19130 = ORIENTED_EDGE ( 'NONE', *, *, #21291, .T. ) ; -#19131 = ORIENTED_EDGE ( 'NONE', *, *, #35864, .T. ) ; -#19132 = CARTESIAN_POINT ( 'NONE', ( 41.56443160834000139, 191.1885863319999999, 105.3066393139000070 ) ) ; -#19133 = EDGE_CURVE ( 'NONE', #25237, #20686, #29655, .T. ) ; -#19134 = ORIENTED_EDGE ( 'NONE', *, *, #28006, .F. ) ; -#19135 = CARTESIAN_POINT ( 'NONE', ( -0.02993291085645299193, 92.27946995574508549, 297.5585631083172302 ) ) ; -#19136 = ORIENTED_EDGE ( 'NONE', *, *, #17082, .F. ) ; -#19137 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265204471, 0.1368326740407822539 ) ) ; -#19138 = ADVANCED_FACE ( 'NONE', ( #27004 ), #36581, .F. ) ; -#19139 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#19140 = ORIENTED_EDGE ( 'NONE', *, *, #18306, .T. ) ; -#19141 = CARTESIAN_POINT ( 'NONE', ( 28.39451994135000135, 125.3580671559000024, 88.74806921993000230 ) ) ; -#19142 = DIRECTION ( 'NONE', ( -0.0005884949961221076038, 0.2249510543439052768, -0.9743698870671265722 ) ) ; -#19143 = CARTESIAN_POINT ( 'NONE', ( 39.74775410638153517, 160.4311919331727267, 202.5621339309882956 ) ) ; -#19144 = CARTESIAN_POINT ( 'NONE', ( 3.952010379223754644, 175.2630895677251601, 100.5417517819387854 ) ) ; -#19145 = CARTESIAN_POINT ( 'NONE', ( 5.376318610052984504, 134.9834408144583620, 90.81305694060634437 ) ) ; -#19146 = ORIENTED_EDGE ( 'NONE', *, *, #28430, .F. ) ; -#19147 = EDGE_CURVE ( 'NONE', #27880, #13220, #28021, .T. ) ; -#19148 = CARTESIAN_POINT ( 'NONE', ( 28.70581487919770680, 163.6075652324868486, 97.92051968927451355 ) ) ; -#19149 = CARTESIAN_POINT ( 'NONE', ( 0.8576005917758692254, 189.0218593756178791, 103.6912331318077634 ) ) ; -#19150 = VECTOR ( 'NONE', #22868, 1000.000000000000114 ) ; -#19151 = CARTESIAN_POINT ( 'NONE', ( -38.93814858684476121, 191.0388300950886560, 103.7812318162937686 ) ) ; -#19152 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19153 = AXIS2_PLACEMENT_3D ( 'NONE', #10106, #16416, #13569 ) ; -#19154 = CARTESIAN_POINT ( 'NONE', ( 21.86154689402108886, 164.5254832386265491, 152.7619684927175570 ) ) ; -#19155 = DIRECTION ( 'NONE', ( -0.6087613186456907188, -0.7730177010543248795, -0.1784749023741044327 ) ) ; -#19156 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 67.27946979429630403, 312.5857197240632104 ) ) ; -#19157 = CARTESIAN_POINT ( 'NONE', ( -20.49852807266789867, 190.9630690214611946, 106.3183227610936541 ) ) ; -#19158 = ORIENTED_EDGE ( 'NONE', *, *, #23611, .T. ) ; -#19159 = CARTESIAN_POINT ( 'NONE', ( -25.87250852686999991, 190.4556140285999959, 106.5465554369999950 ) ) ; -#19160 = ORIENTED_EDGE ( 'NONE', *, *, #10429, .T. ) ; -#19161 = FACE_OUTER_BOUND ( 'NONE', #32720, .T. ) ; -#19162 = EDGE_LOOP ( 'NONE', ( #27338, #20069, #17586, #10417 ) ) ; -#19163 = CARTESIAN_POINT ( 'NONE', ( 21.00012074390967243, 116.5765772913270411, 87.75487408089821884 ) ) ; -#19164 = DIRECTION ( 'NONE', ( -0.0006039748319385906776, -1.261220487827980362E-14, -0.9999998176071844824 ) ) ; -#19165 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927780006295, -0.0005734119022043027104 ) ) ; -#19166 = CARTESIAN_POINT ( 'NONE', ( 20.18512051031240873, 118.1105892767045873, 90.07230193432872056 ) ) ; -#19167 = EDGE_CURVE ( 'NONE', #10027, #7238, #1118, .T. ) ; -#19168 = EDGE_CURVE ( 'NONE', #31792, #8044, #33510, .T. ) ; -#19169 = CARTESIAN_POINT ( 'NONE', ( 13.50160360306296958, 188.0812229192828511, 103.2930363115666808 ) ) ; -#19170 = ORIENTED_EDGE ( 'NONE', *, *, #34134, .F. ) ; -#19171 = CARTESIAN_POINT ( 'NONE', ( -2.787442447965000181, 209.0946215584000072, 75.98264661685000476 ) ) ; -#19172 = DIRECTION ( 'NONE', ( 0.0005884949961229525225, -0.2249510543439062205, 0.9743698870671264611 ) ) ; -#19173 = AXIS2_PLACEMENT_3D ( 'NONE', #30222, #30023, #21031 ) ; -#19174 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19175 = VERTEX_POINT ( 'NONE', #40050 ) ; -#19176 = CARTESIAN_POINT ( 'NONE', ( -32.57215250014812113, 175.3511933304038735, 100.1556091465108267 ) ) ; -#19177 = ORIENTED_EDGE ( 'NONE', *, *, #34991, .F. ) ; -#19178 = CONICAL_SURFACE ( 'NONE', #17863, 2.503022608189757747, 0.7853981633789286487 ) ; -#19179 = CARTESIAN_POINT ( 'NONE', ( -5.958856854636191969, 162.8886998924887166, 100.3412538487635857 ) ) ; -#19180 = CARTESIAN_POINT ( 'NONE', ( -5.345766047747446237, 131.0199116916220703, 89.90447984510488766 ) ) ; -#19181 = DIRECTION ( 'NONE', ( 3.191891195878054554E-14, 0.9743700557921589622, 0.2249510932971539590 ) ) ; -#19182 = PLANE ( 'NONE', #20993 ) ; -#19183 = ORIENTED_EDGE ( 'NONE', *, *, #35532, .F. ) ; -#19184 = CARTESIAN_POINT ( 'NONE', ( 14.16801031327180738, 129.2779008960638976, 92.05627979598381216 ) ) ; -#19185 = DIRECTION ( 'NONE', ( 0.9999998176071385192, 7.614963149315084172E-11, -0.0006039749080918128607 ) ) ; -#19186 = CARTESIAN_POINT ( 'NONE', ( 23.36219596639585916, 184.0153518109154902, 102.6352567327138559 ) ) ; -#19187 = CARTESIAN_POINT ( 'NONE', ( -19.37461243180795378, 124.8797228958847541, 177.8425101811817797 ) ) ; -#19188 = CARTESIAN_POINT ( 'NONE', ( -59.17051632422617757, 248.4236826516141718, 201.1548740838363187 ) ) ; -#19189 = EDGE_LOOP ( 'NONE', ( #33972, #18828, #9527 ) ) ; -#19190 = VERTEX_POINT ( 'NONE', #25342 ) ; -#19191 = ADVANCED_FACE ( 'NONE', ( #6500 ), #16954, .T. ) ; -#19192 = CARTESIAN_POINT ( 'NONE', ( 85.17681536472505854, 108.1708911099030956, 24.92177785579363203 ) ) ; -#19193 = CARTESIAN_POINT ( 'NONE', ( 30.07027234679766892, 177.3926676393851949, 100.9336419489587655 ) ) ; -#19194 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098148, 134.9725883025580515, 93.90358196965131299 ) ) ; -#19195 = CARTESIAN_POINT ( 'NONE', ( -37.96467306556999688, 191.3263843095000141, 104.2384762941000105 ) ) ; -#19196 = EDGE_LOOP ( 'NONE', ( #3937, #2320, #31444, #34440 ) ) ; -#19197 = ORIENTED_EDGE ( 'NONE', *, *, #22172, .T. ) ; -#19198 = DIRECTION ( 'NONE', ( 0.7933533411653341805, 0.5931840316264885837, 0.1368326740407639630 ) ) ; -#19199 = ORIENTED_EDGE ( 'NONE', *, *, #30365, .T. ) ; -#19200 = CONICAL_SURFACE ( 'NONE', #35497, 3.003158621626311309, 0.7854054549419372533 ) ; -#19201 = LINE ( 'NONE', #31714, #10685 ) ; -#19202 = VECTOR ( 'NONE', #10070, 1000.000000000000114 ) ; -#19203 = CARTESIAN_POINT ( 'NONE', ( -30.05261220090111607, 184.7446961265794698, 104.8885090344142128 ) ) ; -#19204 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; -#19205 = CARTESIAN_POINT ( 'NONE', ( 24.25081341993703887, 213.2747061037831600, 75.54404290781627651 ) ) ; -#19206 = AXIS2_PLACEMENT_3D ( 'NONE', #3632, #6908, #13460 ) ; -#19207 = DIRECTION ( 'NONE', ( 0.0006039748319417797499, -6.167438909947000466E-15, 0.9999998176071845934 ) ) ; -#19208 = CARTESIAN_POINT ( 'NONE', ( -15.99849772754149591, 160.0724928513803036, 99.69724197557108880 ) ) ; -#19209 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19210 = CARTESIAN_POINT ( 'NONE', ( -2.253170442581999833, 209.5024975169000072, 73.69426871254999867 ) ) ; -#19211 = CARTESIAN_POINT ( 'NONE', ( 38.13861604779999936, 118.9104954337999942, 90.39786711313999490 ) ) ; -#19212 = ORIENTED_EDGE ( 'NONE', *, *, #9974, .F. ) ; -#19213 = CARTESIAN_POINT ( 'NONE', ( 19.98635445618997863, 211.0854288155255460, 76.04696776081749476 ) ) ; -#19214 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -4.990135403222676764E-16, -0.0006039748319386972547 ) ) ; -#19215 = CARTESIAN_POINT ( 'NONE', ( -14.78424365577531141, 182.9075039701052958, 104.4551379424934083 ) ) ; -#19216 = EDGE_CURVE ( 'NONE', #19007, #22181, #2155, .T. ) ; -#19217 = ADVANCED_FACE ( 'NONE', ( #25544 ), #7847, .T. ) ; -#19218 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24479, #27557, #3560, #28730 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 6.426987119048715613E-11, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19219 = LINE ( 'NONE', #9850, #33657 ) ; -#19220 = VERTEX_POINT ( 'NONE', #13064 ) ; -#19221 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #6833, #7235, #31397, #4157 ), - ( #32003, #16634, #37718, #6629 ), - ( #28330, #12791, #7036, #38512 ), - ( #9726, #300, #3557, #37927 ), - ( #705, #3767, #3965, #3364 ), - ( #10533, #29137, #22202, #28729 ), - ( #34632, #500, #13193, #13588 ), - ( #16240, #22998, #25683, #35424 ), - ( #34825, #38132, #10128, #12993 ), - ( #22605, #22405, #35024, #19306 ), - ( #16435, #19104, #16041, #25473 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.03247871438895000296, 0.000000000000000000, 0.1666667475158999934, 0.3333334272719000180, 0.5000001070281000493, 0.6666667867843000250, 0.8333334665403999697, 1.000000000000000000, 1.031494677006000060 ), - ( 5.959201254652000376E-06, 0.9994001533858000164 ), - .UNSPECIFIED. ) ; -#19222 = ORIENTED_EDGE ( 'NONE', *, *, #26083, .F. ) ; -#19223 = CARTESIAN_POINT ( 'NONE', ( 12.63839252860101148, 175.2446016636384911, 100.6168460505910360 ) ) ; -#19224 = CARTESIAN_POINT ( 'NONE', ( 28.46318946417061468, 181.4174751352287274, 104.2560874084225588 ) ) ; -#19225 = CARTESIAN_POINT ( 'NONE', ( -25.49999614780579549, 119.8278461530010759, 89.89852083535538441 ) ) ; -#19227 = ORIENTED_EDGE ( 'NONE', *, *, #25115, .F. ) ; -#19226 = AXIS2_PLACEMENT_3D ( 'NONE', #1217, #7749, #20424 ) ; -#19228 = CARTESIAN_POINT ( 'NONE', ( 25.49060739074860749, 211.0902261026000417, 73.54297825541816280 ) ) ; -#19229 = CARTESIAN_POINT ( 'NONE', ( -38.34602178450000309, 118.5791799481999931, 89.90303731784000263 ) ) ; -#19230 = CARTESIAN_POINT ( 'NONE', ( 37.34127192387609284, 166.8872991867534097, 188.4876025152064187 ) ) ; -#19231 = VECTOR ( 'NONE', #36979, 1000.000000000000000 ) ; -#19232 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#19233 = ORIENTED_EDGE ( 'NONE', *, *, #4597, .F. ) ; -#19234 = FACE_OUTER_BOUND ( 'NONE', #15095, .T. ) ; -#19235 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33700, #23498, #11430, #36161 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19236 = EDGE_LOOP ( 'NONE', ( #6802, #9087, #18168, #34407, #12582, #4730, #421, #9099, #5127, #23953, #31833, #27720 ) ) ; -#19237 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19238 = CARTESIAN_POINT ( 'NONE', ( -23.32730709679323056, 115.6131156702003011, 89.78183858414666929 ) ) ; -#19239 = CIRCLE ( 'NONE', #27099, 4.999999999999990230 ) ; -#19240 = CARTESIAN_POINT ( 'NONE', ( 41.39926400812499452, 120.5685452915470108, 90.54227133756512558 ) ) ; -#19241 = ORIENTED_EDGE ( 'NONE', *, *, #15360, .F. ) ; -#19242 = ORIENTED_EDGE ( 'NONE', *, *, #24713, .T. ) ; -#19243 = EDGE_CURVE ( 'NONE', #32409, #34827, #25748, .T. ) ; -#19244 = CARTESIAN_POINT ( 'NONE', ( -19.99903504035571800, 194.7641645988118455, 106.1244872497271672 ) ) ; -#19245 = CARTESIAN_POINT ( 'NONE', ( 1.991510566260412007, 189.0611364870325133, 103.2999233371572529 ) ) ; -#19246 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19247 = ORIENTED_EDGE ( 'NONE', *, *, #21704, .F. ) ; -#19248 = CARTESIAN_POINT ( 'NONE', ( 15.50029466867484551, 138.3983482085316723, 92.10848809867536602 ) ) ; -#19249 = DIRECTION ( 'NONE', ( 0.8135696865073147599, 0.000000000000000000, -0.5814674240199442234 ) ) ; -#19250 = ORIENTED_EDGE ( 'NONE', *, *, #17086, .T. ) ; -#19251 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#19252 = CARTESIAN_POINT ( 'NONE', ( -45.39081410773631831, 123.6896955036549741, 91.26380522522237015 ) ) ; -#19253 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#19254 = ADVANCED_FACE ( 'NONE', ( #32075 ), #9830, .T. ) ; -#19255 = VERTEX_POINT ( 'NONE', #29407 ) ; -#19256 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32756, #39285, #4943, #7607 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.9992950541840658341, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19257 = CARTESIAN_POINT ( 'NONE', ( 26.00056762447263026, 118.1139028608674408, 90.25209678512123901 ) ) ; -#19258 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -5.046468293989541410E-15, -0.0006039748319412812337 ) ) ; -#19259 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971555410 ) ) ; -#19260 = VECTOR ( 'NONE', #22761, 1000.000000000000114 ) ; -#19261 = EDGE_CURVE ( 'NONE', #12107, #31197, #7488, .T. ) ; -#19262 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35519, #13094, #16148, #32298 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19263 = AXIS2_PLACEMENT_3D ( 'NONE', #34477, #6479, #37180 ) ; -#19264 = ORIENTED_EDGE ( 'NONE', *, *, #262, .T. ) ; -#19265 = AXIS2_PLACEMENT_3D ( 'NONE', #9571, #159, #12238 ) ; -#19266 = CARTESIAN_POINT ( 'NONE', ( -23.36190348438398345, 175.3529862697351120, 100.1473808295323096 ) ) ; -#19267 = CARTESIAN_POINT ( 'NONE', ( 6.271009707311050896, 148.6549594042781450, 94.48198805953025214 ) ) ; -#19268 = AXIS2_PLACEMENT_3D ( 'NONE', #25561, #28030, #38007 ) ; -#19269 = ADVANCED_FACE ( 'NONE', ( #32467 ), #35910, .T. ) ; -#19270 = ADVANCED_FACE ( 'NONE', ( #3634 ), #11199, .F. ) ; -#19272 = CARTESIAN_POINT ( 'NONE', ( -30.05261222213120931, 184.7446961453429424, 104.8885090255323718 ) ) ; -#19271 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799611204, 137.3509909075980886, 91.38105903661011098 ) ) ; -#19273 = EDGE_CURVE ( 'NONE', #39956, #2172, #22151, .T. ) ; -#19274 = EDGE_CURVE ( 'NONE', #10482, #13543, #33460, .T. ) ; -#19275 = EDGE_LOOP ( 'NONE', ( #14452, #21068, #4380, #18818 ) ) ; -#19276 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#19277 = DIRECTION ( 'NONE', ( 0.0005884949961272565883, -0.2249510543439071641, 0.9743698870671261281 ) ) ; -#19278 = CARTESIAN_POINT ( 'NONE', ( 77.66057557573886072, 193.1738148078198378, 189.4424374941742144 ) ) ; -#19279 = VERTEX_POINT ( 'NONE', #21008 ) ; -#19280 = ORIENTED_EDGE ( 'NONE', *, *, #3572, .T. ) ; -#19281 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#19282 = CARTESIAN_POINT ( 'NONE', ( -25.98973257537553749, 191.3166157958662836, 106.8934875062374203 ) ) ; -#19283 = LINE ( 'NONE', #3746, #12176 ) ; -#19284 = DIRECTION ( 'NONE', ( -6.938892725157353033E-15, 0.9743700559946818496, 0.2249510924199315531 ) ) ; -#19285 = LINE ( 'NONE', #31789, #29401 ) ; -#19286 = VERTEX_POINT ( 'NONE', #29810 ) ; -#19287 = ORIENTED_EDGE ( 'NONE', *, *, #3611, .F. ) ; -#19288 = ORIENTED_EDGE ( 'NONE', *, *, #9008, .F. ) ; -#19289 = AXIS2_PLACEMENT_3D ( 'NONE', #16127, #3441, #34506 ) ; -#19290 = CARTESIAN_POINT ( 'NONE', ( -15.66486529302079589, 151.3708617756205399, 97.34567295342098703 ) ) ; -#19291 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555133 ) ) ; -#19292 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #1568, #14256 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19293 = CIRCLE ( 'NONE', #4938, 8.000001045079370599 ) ; -#19294 = LINE ( 'NONE', #35413, #17018 ) ; -#19295 = CARTESIAN_POINT ( 'NONE', ( 16.88249520722548169, 148.9778306577506726, 176.8903484419645622 ) ) ; -#19296 = ORIENTED_EDGE ( 'NONE', *, *, #35605, .F. ) ; -#19297 = ADVANCED_FACE ( 'NONE', ( #20588 ), #33055, .T. ) ; -#19298 = DIRECTION ( 'NONE', ( -0.6087611427424954869, -0.7731004630501229213, -0.1781166615410720577 ) ) ; -#19299 = ORIENTED_EDGE ( 'NONE', *, *, #18131, .T. ) ; -#19300 = VECTOR ( 'NONE', #29068, 1000.000000000000000 ) ; -#19301 = VECTOR ( 'NONE', #37120, 1000.000000000000000 ) ; -#19302 = ORIENTED_EDGE ( 'NONE', *, *, #398, .T. ) ; -#19303 = CARTESIAN_POINT ( 'NONE', ( -39.61054748937312553, 129.5177821288435780, 336.3042500576304974 ) ) ; -#19304 = ORIENTED_EDGE ( 'NONE', *, *, #33311, .F. ) ; -#19305 = CARTESIAN_POINT ( 'NONE', ( -38.90357209447083164, 164.7996974313793999, 188.0966889302359561 ) ) ; -#19306 = CARTESIAN_POINT ( 'NONE', ( -2.300096019559000116, 191.0630006485000081, 106.1942960410000012 ) ) ; -#19307 = CARTESIAN_POINT ( 'NONE', ( -3.336458024882414719, 126.7630962693081500, 89.09156782095561766 ) ) ; -#19309 = ADVANCED_FACE ( 'NONE', ( #5247 ), #19576, .F. ) ; -#19308 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24232, #8691, #21148, #2543, #11952, #31772, #16405, #35198, #38091, #37895 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.009024888469274735397, 0.2567686663519560542, 0.5045124442346373694, 0.7522562221173186847, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19310 = ORIENTED_EDGE ( 'NONE', *, *, #863, .T. ) ; -#19311 = LINE ( 'NONE', #22608, #10605 ) ; -#19312 = VERTEX_POINT ( 'NONE', #11002 ) ; -#19313 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#19314 = CARTESIAN_POINT ( 'NONE', ( -37.69582204082962562, 164.0995084088371527, 198.0927439109664476 ) ) ; -#19315 = DIRECTION ( 'NONE', ( 0.0005734119072325883325, 0.000000000000000000, 0.9999998355993788834 ) ) ; -#19316 = EDGE_CURVE ( 'NONE', #31691, #15233, #39597, .T. ) ; -#19317 = LINE ( 'NONE', #27957, #34107 ) ; -#19318 = DIRECTION ( 'NONE', ( 0.0004161288024365940980, -0.8480480898180946525, 0.5299191109902535723 ) ) ; -#19319 = ORIENTED_EDGE ( 'NONE', *, *, #13655, .T. ) ; -#19320 = EDGE_CURVE ( 'NONE', #1973, #4424, #18259, .T. ) ; -#19321 = AXIS2_PLACEMENT_3D ( 'NONE', #38953, #4801, #14641 ) ; -#19322 = CARTESIAN_POINT ( 'NONE', ( -45.30255556275930928, 123.8777291761282129, 93.38906572069882372 ) ) ; -#19323 = AXIS2_PLACEMENT_3D ( 'NONE', #28600, #32273, #31682 ) ; -#19324 = EDGE_CURVE ( 'NONE', #36415, #4594, #16969, .T. ) ; -#19325 = VECTOR ( 'NONE', #38524, 999.9999999999998863 ) ; -#19326 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#19327 = EDGE_CURVE ( 'NONE', #15824, #40142, #33252, .T. ) ; -#19328 = EDGE_LOOP ( 'NONE', ( #39148, #10431, #35775 ) ) ; -#19329 = VERTEX_POINT ( 'NONE', #23462 ) ; -#19331 = VECTOR ( 'NONE', #29003, 1000.000000000000000 ) ; -#19330 = CARTESIAN_POINT ( 'NONE', ( 39.53555642364394629, 119.7153706430301554, 90.34642614193101906 ) ) ; -#19332 = CARTESIAN_POINT ( 'NONE', ( -26.00329743126571813, 121.2302541217067215, 87.65683552929112921 ) ) ; -#19333 = CARTESIAN_POINT ( 'NONE', ( -3.780571208821432272, 174.7337882003822642, 102.8237057398510785 ) ) ; -#19334 = CYLINDRICAL_SURFACE ( 'NONE', #3643, 59.40509898897001051 ) ; -#19335 = ORIENTED_EDGE ( 'NONE', *, *, #26318, .T. ) ; -#19336 = ORIENTED_EDGE ( 'NONE', *, *, #17874, .F. ) ; -#19337 = CARTESIAN_POINT ( 'NONE', ( 39.76231351996260344, 182.5576203638986215, 106.5366729533402719 ) ) ; -#19338 = CARTESIAN_POINT ( 'NONE', ( -1.212288473603901018, 140.3952820277004605, 157.8550920018487318 ) ) ; -#19339 = CARTESIAN_POINT ( 'NONE', ( 8.470678213537377488, 151.0674926792860049, 95.03763680969706229 ) ) ; -#19340 = PLANE ( 'NONE', #37255 ) ; -#19341 = ORIENTED_EDGE ( 'NONE', *, *, #38124, .T. ) ; -#19342 = DIRECTION ( 'NONE', ( -0.1843855713908465477, -0.08049128666858569592, 0.9795525069302342125 ) ) ; -#19343 = CARTESIAN_POINT ( 'NONE', ( 44.05265128906093963, 113.3760414474945009, 85.80123528811638778 ) ) ; -#19344 = ORIENTED_EDGE ( 'NONE', *, *, #3172, .T. ) ; -#19345 = CARTESIAN_POINT ( 'NONE', ( -1.216565595234769148, 136.3705012149207789, 175.2651585126169209 ) ) ; -#19346 = CARTESIAN_POINT ( 'NONE', ( -20.00089539691495233, 118.1272453392662527, 87.27993277136866368 ) ) ; -#19347 = DIRECTION ( 'NONE', ( 0.4303597330247870278, 0.7060138277436147636, -0.5624366410767025481 ) ) ; -#19348 = CARTESIAN_POINT ( 'NONE', ( 0.05421747281792377304, 83.21792371834001756, 89.76775200199907090 ) ) ; -#19349 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #25877, #19673 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19350 = ORIENTED_EDGE ( 'NONE', *, *, #395, .F. ) ; -#19351 = CARTESIAN_POINT ( 'NONE', ( 27.53717704466000171, 125.0577440870000174, 89.02147418570000070 ) ) ; -#19352 = CIRCLE ( 'NONE', #31138, 2.499999999997815525 ) ; -#19353 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971554578 ) ) ; -#19354 = CARTESIAN_POINT ( 'NONE', ( 39.86742295541759518, 165.0107917281946186, 182.9225538859983544 ) ) ; -#19355 = VECTOR ( 'NONE', #4294, 1000.000000000000114 ) ; -#19356 = DIRECTION ( 'NONE', ( 0.0002393071182784984501, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#19357 = CARTESIAN_POINT ( 'NONE', ( -18.91554917980427675, 125.6711736200330165, 175.2587820826857410 ) ) ; -#19358 = AXIS2_PLACEMENT_3D ( 'NONE', #7502, #38578, #29399 ) ; -#19359 = ORIENTED_EDGE ( 'NONE', *, *, #22412, .T. ) ; -#19360 = FACE_OUTER_BOUND ( 'NONE', #35196, .T. ) ; -#19361 = CARTESIAN_POINT ( 'NONE', ( 0.8759982955651735015, 189.0247036241306944, 103.6920166762249664 ) ) ; -#19362 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825911398296938, 0.0005734119025854594051 ) ) ; -#19363 = ADVANCED_FACE ( 'NONE', ( #14470 ), #35912, .T. ) ; -#19364 = VECTOR ( 'NONE', #22150, 1000.000000000000114 ) ; -#19365 = ADVANCED_FACE ( 'NONE', ( #1789 ), #26954, .F. ) ; -#19366 = CARTESIAN_POINT ( 'NONE', ( -21.82963565732912059, 176.4928003187452816, 100.9258332941378455 ) ) ; -#19367 = EDGE_CURVE ( 'NONE', #10943, #6999, #26742, .T. ) ; -#19368 = VECTOR ( 'NONE', #16484, 1000.000000000000227 ) ; -#19369 = CARTESIAN_POINT ( 'NONE', ( -33.46311609814530641, 218.5902260770998282, 61.07871277729011439 ) ) ; -#19370 = EDGE_CURVE ( 'NONE', #30562, #29835, #1303, .T. ) ; -#19371 = PLANE ( 'NONE', #12709 ) ; -#19372 = CARTESIAN_POINT ( 'NONE', ( 21.10734183263222974, 176.0605026285803092, 100.6290478223103975 ) ) ; -#19373 = VERTEX_POINT ( 'NONE', #37542 ) ; -#19374 = EDGE_CURVE ( 'NONE', #24313, #5278, #30047, .T. ) ; -#19375 = CARTESIAN_POINT ( 'NONE', ( -12.64088427125098235, 181.7768506542429066, 101.7499118960562186 ) ) ; -#19376 = EDGE_CURVE ( 'NONE', #1519, #19980, #24699, .T. ) ; -#19377 = DIRECTION ( 'NONE', ( 0.0004726756300157089648, 0.6225146366376117513, 0.7826080141103149979 ) ) ; -#19378 = DIRECTION ( 'NONE', ( -0.6087614109020721420, -0.7729348355671186166, -0.1788331193133692598 ) ) ; -#19379 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19380 = CIRCLE ( 'NONE', #20701, 2.499999999931187933 ) ; -#19381 = FACE_OUTER_BOUND ( 'NONE', #8184, .T. ) ; -#19382 = CARTESIAN_POINT ( 'NONE', ( 36.06425384701000070, 192.4066394740000021, 105.0139338433999967 ) ) ; -#19383 = CARTESIAN_POINT ( 'NONE', ( 22.64184747305000300, 157.9319024309000099, 98.92303659383000536 ) ) ; -#19384 = AXIS2_PLACEMENT_3D ( 'NONE', #37012, #2857, #28414 ) ; -#19385 = CARTESIAN_POINT ( 'NONE', ( 20.89486103759118052, 175.7095848683153463, 103.2849699440975826 ) ) ; -#19386 = CONICAL_SURFACE ( 'NONE', #6978, 4.999999999987116972, 0.7853981633861885081 ) ; -#19387 = ORIENTED_EDGE ( 'NONE', *, *, #15545, .F. ) ; -#19388 = EDGE_CURVE ( 'NONE', #2798, #37821, #33945, .T. ) ; -#19389 = CARTESIAN_POINT ( 'NONE', ( -2.691515551155000185, 209.6623428544999967, 75.89346375227999886 ) ) ; -#19390 = CARTESIAN_POINT ( 'NONE', ( 36.87849788990180144, 117.6060897978989743, 87.24551060340307629 ) ) ; -#19391 = AXIS2_PLACEMENT_3D ( 'NONE', #12553, #24859, #6608 ) ; -#19392 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; -#19393 = ORIENTED_EDGE ( 'NONE', *, *, #21894, .F. ) ; -#19394 = CARTESIAN_POINT ( 'NONE', ( 6.034640325019517526, 177.1924675499267892, 101.0705349078851327 ) ) ; -#19395 = ORIENTED_EDGE ( 'NONE', *, *, #20715, .T. ) ; -#19396 = CARTESIAN_POINT ( 'NONE', ( -3.296694232897449339, 129.3530670243922316, 89.51842077367476236 ) ) ; -#19397 = FACE_OUTER_BOUND ( 'NONE', #14140, .T. ) ; -#19398 = DIRECTION ( 'NONE', ( 2.515349040166355772E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#19399 = CARTESIAN_POINT ( 'NONE', ( -45.49101484277578322, 185.9174214959355709, 105.9473892799664014 ) ) ; -#19400 = CARTESIAN_POINT ( 'NONE', ( -37.07257225381636800, 191.0462222942348376, 103.7818103174439273 ) ) ; -#19401 = FACE_OUTER_BOUND ( 'NONE', #119, .T. ) ; -#19402 = VERTEX_POINT ( 'NONE', #18117 ) ; -#19403 = CARTESIAN_POINT ( 'NONE', ( 15.95613733389899025, 121.8961617987971238, 174.4891947115541484 ) ) ; -#19404 = CARTESIAN_POINT ( 'NONE', ( -3.558845676726785978, 175.7327080916274156, 100.2261648978108468 ) ) ; -#19405 = FACE_OUTER_BOUND ( 'NONE', #36097, .T. ) ; -#19406 = VECTOR ( 'NONE', #30539, 1000.000000000000000 ) ; -#19407 = CARTESIAN_POINT ( 'NONE', ( 25.75054841324000421, 118.4643410412000009, 90.00223210762001713 ) ) ; -#19408 = EDGE_CURVE ( 'NONE', #21071, #39904, #14245, .T. ) ; -#19409 = VERTEX_POINT ( 'NONE', #37150 ) ; -#19410 = CARTESIAN_POINT ( 'NONE', ( -13.49823352225588913, 184.2872290888800819, 105.2891383389777076 ) ) ; -#19411 = EDGE_CURVE ( 'NONE', #9171, #2569, #3903, .T. ) ; -#19412 = ORIENTED_EDGE ( 'NONE', *, *, #26815, .F. ) ; -#19413 = CIRCLE ( 'NONE', #29238, 2.250000000020502711 ) ; -#19414 = CARTESIAN_POINT ( 'NONE', ( -15.74985326587000145, 167.5695991370999991, 98.60550149261000286 ) ) ; -#19415 = LINE ( 'NONE', #19203, #17532 ) ; -#19416 = CARTESIAN_POINT ( 'NONE', ( -28.94629671773202162, 110.6131156702000027, 90.28526767707491274 ) ) ; -#19417 = PLANE ( 'NONE', #35003 ) ; -#19418 = EDGE_CURVE ( 'NONE', #14229, #5686, #10377, .T. ) ; -#19419 = DIRECTION ( 'NONE', ( 1.619075244243125847E-14, -0.9743700557921582961, -0.2249510932971570121 ) ) ; -#19420 = CARTESIAN_POINT ( 'NONE', ( -2.319384444843000104, 208.9645219994999934, 73.76273522338999555 ) ) ; -#19421 = CARTESIAN_POINT ( 'NONE', ( 38.50000310099999723, 118.5649250008000024, 89.80765680167999676 ) ) ; -#19422 = ORIENTED_EDGE ( 'NONE', *, *, #23864, .T. ) ; -#19423 = LINE ( 'NONE', #22521, #29007 ) ; -#19424 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19425 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; -#19426 = LINE ( 'NONE', #625, #21950 ) ; -#19427 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #7432, #28927, #9931, #31804 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.570796320676825619, 2.588537152379762230 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9155302586764009209, 0.9155302586764009209, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#19428 = ORIENTED_EDGE ( 'NONE', *, *, #18787, .F. ) ; -#19429 = VERTEX_POINT ( 'NONE', #34066 ) ; -#19430 = EDGE_CURVE ( 'NONE', #8220, #32422, #12014, .T. ) ; -#19431 = ORIENTED_EDGE ( 'NONE', *, *, #7086, .F. ) ; -#19432 = CARTESIAN_POINT ( 'NONE', ( 40.54675149425525404, 217.7719116180000185, 76.03401540786036605 ) ) ; -#19433 = VECTOR ( 'NONE', #30223, 1000.000000000000000 ) ; -#19434 = LINE ( 'NONE', #29662, #19355 ) ; -#19435 = VECTOR ( 'NONE', #23618, 1000.000000000000114 ) ; -#19436 = ORIENTED_EDGE ( 'NONE', *, *, #4774, .T. ) ; -#19437 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319376442775 ) ) ; -#19438 = CARTESIAN_POINT ( 'NONE', ( -33.88284817031402696, 159.3826839816843233, 187.1022045530551736 ) ) ; -#19439 = CARTESIAN_POINT ( 'NONE', ( 13.50147201673213893, 151.4095814229721668, 97.16618435358425643 ) ) ; -#19440 = CARTESIAN_POINT ( 'NONE', ( -38.25727539327999693, 118.9592153865000057, 87.58113317161999589 ) ) ; -#19441 = CARTESIAN_POINT ( 'NONE', ( 29.05533563819793486, 110.6131156702000027, 90.25023614447037801 ) ) ; -#19442 = ORIENTED_EDGE ( 'NONE', *, *, #35494, .T. ) ; -#19443 = CARTESIAN_POINT ( 'NONE', ( 35.04494057328185619, 220.4002260770999726, 73.03733781617431475 ) ) ; -#19444 = VERTEX_POINT ( 'NONE', #9343 ) ; -#19445 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364818587623, 136.5649596138779884, 181.4686487119677167 ) ) ; -#19446 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971539312 ) ) ; -#19447 = EDGE_LOOP ( 'NONE', ( #10870, #36693, #3374, #20956, #24965 ) ) ; -#19448 = ORIENTED_EDGE ( 'NONE', *, *, #7300, .F. ) ; -#19449 = LINE ( 'NONE', #37868, #38912 ) ; -#19450 = CARTESIAN_POINT ( 'NONE', ( 20.00025828646017345, 174.5279639952516106, 99.93388581131628712 ) ) ; -#19451 = CARTESIAN_POINT ( 'NONE', ( -26.01051778642650092, 208.7352112813564418, 73.14552897845221935 ) ) ; -#19452 = DIRECTION ( 'NONE', ( 0.0006039748319386430446, 1.236414387799018187E-14, 0.9999998176071845934 ) ) ; -#19453 = ORIENTED_EDGE ( 'NONE', *, *, #33124, .F. ) ; -#19454 = EDGE_CURVE ( 'NONE', #4160, #14577, #21210, .T. ) ; -#19455 = ORIENTED_EDGE ( 'NONE', *, *, #4073, .T. ) ; -#19456 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#19457 = LINE ( 'NONE', #31547, #19364 ) ; -#19458 = ADVANCED_FACE ( 'NONE', ( #2610 ), #34453, .F. ) ; -#19459 = VERTEX_POINT ( 'NONE', #33663 ) ; -#19460 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10201, #35847, #371, #23205 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19461 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250611660, 132.8554482850406089, 90.84904174544712419 ) ) ; -#19462 = CARTESIAN_POINT ( 'NONE', ( 36.23355974028325477, 191.4499673472672612, 103.8307471576879379 ) ) ; -#19463 = CARTESIAN_POINT ( 'NONE', ( -12.64347415174542810, 134.2426399615423236, 93.73178815038983203 ) ) ; -#19464 = AXIS2_PLACEMENT_3D ( 'NONE', #29282, #16387, #1453 ) ; -#19465 = EDGE_LOOP ( 'NONE', ( #30872, #17390, #7214, #26063 ) ) ; -#19466 = EDGE_CURVE ( 'NONE', #39537, #7275, #5216, .T. ) ; -#19467 = CARTESIAN_POINT ( 'NONE', ( 0.5641566566382231196, 188.3875244742078223, 106.2241826925672257 ) ) ; -#19468 = DIRECTION ( 'NONE', ( 0.0002393071182785117587, 0.2252352986010041080, -0.9743043687658491381 ) ) ; -#19469 = LINE ( 'NONE', #31770, #29346 ) ; -#19470 = CARTESIAN_POINT ( 'NONE', ( 48.84485507728539488, 75.31855144216289943, 291.5290428667154288 ) ) ; -#19471 = VERTEX_POINT ( 'NONE', #130 ) ; -#19472 = ORIENTED_EDGE ( 'NONE', *, *, #20294, .T. ) ; -#19473 = CARTESIAN_POINT ( 'NONE', ( 26.00178518556128893, 120.0897341375864755, 90.43300729485713418 ) ) ; -#19474 = DIRECTION ( 'NONE', ( -0.6087614115774889756, -0.7729348350621332298, -0.1788331191967985345 ) ) ; -#19475 = CARTESIAN_POINT ( 'NONE', ( 6.065815740701999914, 163.2729245447999915, 152.4718672074000381 ) ) ; -#19477 = CARTESIAN_POINT ( 'NONE', ( -37.28640831843555503, 117.9292370818984352, 123.9370462788764087 ) ) ; -#19476 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561239 ) ) ; -#19478 = CARTESIAN_POINT ( 'NONE', ( 36.04593084803796188, 218.5902260770999987, 76.03673379054495740 ) ) ; -#19479 = DIRECTION ( 'NONE', ( 0.0005734119072324324242, 0.000000000000000000, 0.9999998355993788834 ) ) ; -#19480 = ORIENTED_EDGE ( 'NONE', *, *, #2931, .T. ) ; -#19481 = CARTESIAN_POINT ( 'NONE', ( -20.01829689993581596, 209.7096928646539880, 76.07061354826153377 ) ) ; -#19482 = CARTESIAN_POINT ( 'NONE', ( -35.96566301449503555, 192.2060209908892432, 104.4274987125427714 ) ) ; -#19483 = CARTESIAN_POINT ( 'NONE', ( 25.51819783872340608, 191.5524126122537325, 104.3741215340442920 ) ) ; -#19484 = ORIENTED_EDGE ( 'NONE', *, *, #39955, .F. ) ; -#19485 = ORIENTED_EDGE ( 'NONE', *, *, #6460, .F. ) ; -#19486 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; -#19487 = CIRCLE ( 'NONE', #548, 2.500000720456942105 ) ; -#19488 = CARTESIAN_POINT ( 'NONE', ( -46.26150339730361338, 126.0976992386087261, 91.87172231767381447 ) ) ; -#19489 = CARTESIAN_POINT ( 'NONE', ( -3.070713250341000400, 190.8329090761000089, 106.9302175993999953 ) ) ; -#19490 = ORIENTED_EDGE ( 'NONE', *, *, #11535, .F. ) ; -#19491 = EDGE_CURVE ( 'NONE', #9438, #6175, #18320, .T. ) ; -#19492 = ORIENTED_EDGE ( 'NONE', *, *, #23125, .F. ) ; -#19493 = CARTESIAN_POINT ( 'NONE', ( 14.16801031327180738, 129.2779008960638976, 92.05627979598381216 ) ) ; -#19494 = AXIS2_PLACEMENT_3D ( 'NONE', #15799, #19474, #38480 ) ; -#19495 = CARTESIAN_POINT ( 'NONE', ( -40.95517856244259747, 217.7719116394999901, 75.58324044002641529 ) ) ; -#19496 = DIRECTION ( 'NONE', ( 0.0005884949961209894661, -0.2249510543439065813, 0.9743698870671262391 ) ) ; -#19497 = VECTOR ( 'NONE', #6408, 1000.000000000000114 ) ; -#19498 = ORIENTED_EDGE ( 'NONE', *, *, #36784, .F. ) ; -#19499 = ORIENTED_EDGE ( 'NONE', *, *, #37145, .T. ) ; -#19500 = CARTESIAN_POINT ( 'NONE', ( -22.69283010918674037, 213.5901956524609204, 73.57227693392532331 ) ) ; -#19501 = ORIENTED_EDGE ( 'NONE', *, *, #4029, .T. ) ; -#19502 = EDGE_CURVE ( 'NONE', #33812, #25425, #12410, .T. ) ; -#19503 = CARTESIAN_POINT ( 'NONE', ( 0.05451946023390212559, 83.21792371834001756, 90.26775191081758010 ) ) ; -#19504 = EDGE_CURVE ( 'NONE', #30625, #28499, #14766, .T. ) ; -#19505 = CARTESIAN_POINT ( 'NONE', ( -5.658908186421000686, 187.6682623620686172, 106.0618792668577015 ) ) ; -#19506 = ADVANCED_FACE ( 'NONE', ( #27576 ), #20908, .T. ) ; -#19507 = CARTESIAN_POINT ( 'NONE', ( -26.00145235156885093, 120.5160882189163942, 87.49195619469584528 ) ) ; -#19508 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #6016, #28699 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19509 = VERTEX_POINT ( 'NONE', #15473 ) ; -#19510 = CARTESIAN_POINT ( 'NONE', ( -25.49272530211510812, 191.9759150222000130, 101.9368443075920396 ) ) ; -#19511 = CARTESIAN_POINT ( 'NONE', ( -25.50413503257686898, 209.7096538831000032, 78.07390885283565751 ) ) ; -#19512 = CARTESIAN_POINT ( 'NONE', ( 22.59321899614865714, 214.0705223858939235, 73.04485834425945256 ) ) ; -#19513 = CARTESIAN_POINT ( 'NONE', ( -25.99970180913262041, 119.7153704765195670, 90.38600773184769821 ) ) ; -#19514 = AXIS2_PLACEMENT_3D ( 'NONE', #13431, #19139, #31435 ) ; -#19515 = CARTESIAN_POINT ( 'NONE', ( -41.76244517127567946, 189.2343572370725724, 106.9213286744051175 ) ) ; -#19516 = ORIENTED_EDGE ( 'NONE', *, *, #5514, .F. ) ; -#19517 = AXIS2_PLACEMENT_3D ( 'NONE', #27347, #30598, #2589 ) ; -#19518 = CONICAL_SURFACE ( 'NONE', #38463, 9.999999999997360334, 0.7853981633972983989 ) ; -#19519 = CARTESIAN_POINT ( 'NONE', ( 33.52281821381428983, 83.75585590586079832, 284.9772999313669288 ) ) ; -#19520 = AXIS2_PLACEMENT_3D ( 'NONE', #4474, #10637, #7544 ) ; -#19521 = CARTESIAN_POINT ( 'NONE', ( -37.00494418646000838, 117.3004826001999987, 90.15313654179000480 ) ) ; -#19522 = ORIENTED_EDGE ( 'NONE', *, *, #39307, .T. ) ; -#19523 = EDGE_LOOP ( 'NONE', ( #4794, #4983 ) ) ; -#19524 = CARTESIAN_POINT ( 'NONE', ( 8.724446752596358934, 160.3956799297461373, 96.67791350217905233 ) ) ; -#19525 = DIRECTION ( 'NONE', ( -0.0001408404346092576671, 0.2255194953558363191, -0.9742386449830560124 ) ) ; -#19526 = CARTESIAN_POINT ( 'NONE', ( -15.99823486136621398, 118.9409032897849983, 90.20116722531788866 ) ) ; -#19527 = ORIENTED_EDGE ( 'NONE', *, *, #34488, .T. ) ; -#19528 = ORIENTED_EDGE ( 'NONE', *, *, #7770, .F. ) ; -#19529 = PLANE ( 'NONE', #38296 ) ; -#19530 = ORIENTED_EDGE ( 'NONE', *, *, #22579, .T. ) ; -#19531 = ORIENTED_EDGE ( 'NONE', *, *, #10383, .F. ) ; -#19532 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#19533 = CARTESIAN_POINT ( 'NONE', ( 1.760485921653847319, 189.3960626710020847, 105.8506353753109863 ) ) ; -#19534 = CARTESIAN_POINT ( 'NONE', ( -43.90747471557000381, 97.51241190807002113, 154.5673021613000060 ) ) ; -#19535 = ADVANCED_FACE ( 'NONE', ( #34256 ), #6256, .F. ) ; -#19536 = EDGE_LOOP ( 'NONE', ( #12541, #16011, #7356, #24140 ) ) ; -#19537 = CARTESIAN_POINT ( 'NONE', ( 75.24049004471834223, 196.2565561541850059, 190.1544973454941783 ) ) ; -#19538 = DIRECTION ( 'NONE', ( 3.191891195770216638E-14, 0.9743700557921578520, 0.2249510932971589827 ) ) ; -#19539 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452350121, 0.1781166614240801416 ) ) ; -#19540 = CARTESIAN_POINT ( 'NONE', ( -38.71167219077999988, 118.8429159421000065, 89.85853435920999743 ) ) ; -#19541 = CARTESIAN_POINT ( 'NONE', ( -6.272775217941449988, 148.2033965809511074, 96.43792127017829330 ) ) ; -#19542 = VECTOR ( 'NONE', #33530, 1000.000000000000114 ) ; -#19543 = EDGE_CURVE ( 'NONE', #39586, #30774, #38621, .T. ) ; -#19544 = PLANE ( 'NONE', #1245 ) ; -#19545 = CARTESIAN_POINT ( 'NONE', ( -30.07826481366596738, 134.2402275243734096, 93.74179301315371049 ) ) ; -#19546 = ORIENTED_EDGE ( 'NONE', *, *, #17793, .T. ) ; -#19547 = DIRECTION ( 'NONE', ( -0.9914447795421228449, 0.1270909273342987478, 0.02975139169819295340 ) ) ; -#19548 = AXIS2_PLACEMENT_3D ( 'NONE', #38813, #21954, #16397 ) ; -#19549 = CYLINDRICAL_SURFACE ( 'NONE', #7440, 2.000000000000011546 ) ; -#19550 = VECTOR ( 'NONE', #13784, 1000.000000000000000 ) ; -#19551 = DIRECTION ( 'NONE', ( 0.0005884949961241524091, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#19552 = ADVANCED_FACE ( 'NONE', ( #31624 ), #16456, .T. ) ; -#19553 = CARTESIAN_POINT ( 'NONE', ( 3.585698494325503916, 175.3488639359234469, 100.1860491892580995 ) ) ; -#19554 = ADVANCED_FACE ( 'NONE', ( #13608 ), #518, .T. ) ; -#19555 = AXIS2_PLACEMENT_3D ( 'NONE', #22561, #28492, #37682 ) ; -#19556 = CARTESIAN_POINT ( 'NONE', ( 4.602553811274089135, 124.5979440950363539, 88.41584299628244992 ) ) ; -#19557 = EDGE_CURVE ( 'NONE', #30753, #28523, #25901, .T. ) ; -#19558 = EDGE_LOOP ( 'NONE', ( #18501, #20260, #32476, #35654, #5425, #26401 ) ) ; -#19559 = CARTESIAN_POINT ( 'NONE', ( -40.55663739063058415, 184.8193262793416807, 102.8594742714833075 ) ) ; -#19560 = EDGE_CURVE ( 'NONE', #723, #18111, #38533, .T. ) ; -#19561 = CARTESIAN_POINT ( 'NONE', ( 0.5808265436351435218, 189.0001712365193214, 103.6949147857697398 ) ) ; -#19562 = CARTESIAN_POINT ( 'NONE', ( 36.41214121066919063, 191.8141173754956696, 104.3617157949233700 ) ) ; -#19563 = DIRECTION ( 'NONE', ( 0.6773442687123943928, 0.7356661890031861439, 0.000000000000000000 ) ) ; -#19564 = ORIENTED_EDGE ( 'NONE', *, *, #25071, .F. ) ; -#19565 = CARTESIAN_POINT ( 'NONE', ( -25.87121615895999938, 191.8689891060000150, 104.0514611635999955 ) ) ; -#19566 = CARTESIAN_POINT ( 'NONE', ( -3.760261628207208329, 168.4451244408993773, 98.77232846146148404 ) ) ; -#19567 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #31842, #10564, #16865, #28763 ), - ( #7466, #22640, #13623, #35065 ), - ( #19735, #3052, #4405, #13428 ), - ( #10367, #35267, #3797, #28024 ), - ( #1339, #741, #13818, #26303 ), - ( #40463, #12460, #21883, #24961 ), - ( #38551, #37412, #22834, #25714 ), - ( #32236, #16672, #29173, #23034 ), - ( #33019, #26917, #27126, #1965 ), - ( #11164, #36297, #14433, #39562 ), - ( #8507, #29564, #1754, #17264 ), - ( #1541, #33215, #11571, #14025 ), - ( #23838, #17678, #20345, #29967 ), - ( #32625, #30173, #20138, #23635 ), - ( #2169, #20546, #26507, #8086 ), - ( #29775, #17064, #36084, #39155 ), - ( #14233, #8296, #36501, #7881 ), - ( #14643, #26709, #5010, #20758 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.0009806055231174999002, 0.000000000000000000, 4.212333002590999939E-07, 0.005187662470730000121, 0.01039649399989999931, 0.02081415705823999943, 0.04164948317493000207, 0.06248480929161000230, 0.08332013540829999454, 0.1249907876417000047, 0.1666614398750999870, 0.3333440488084999931, 0.5000118277423000190, 0.6666796066758999828, 1.000000000000000000, 1.050434996582999991 ), - ( 0.001431525339720999927, 0.9999964804755000491 ), - .UNSPECIFIED. ) ; -#19568 = CARTESIAN_POINT ( 'NONE', ( -15.83155413418625379, 173.8826594657223552, 102.7142068274063718 ) ) ; -#19569 = ORIENTED_EDGE ( 'NONE', *, *, #18106, .F. ) ; -#19570 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20422, #26187, #8173, #38624 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19571 = DIRECTION ( 'NONE', ( 0.5614015438085974141, -0.5784168556941973183, 0.5918295765320973345 ) ) ; -#19572 = CIRCLE ( 'NONE', #30043, 9.999999999987798205 ) ; -#19573 = AXIS2_PLACEMENT_3D ( 'NONE', #33827, #33624, #18673 ) ; -#19574 = DIRECTION ( 'NONE', ( -0.0005884949961269095352, 0.2249510543439041110, -0.9743698870671267942 ) ) ; -#19575 = CARTESIAN_POINT ( 'NONE', ( 5.666730638602090586, 181.4890245458614686, 104.2225643677910654 ) ) ; -#19576 = CONICAL_SURFACE ( 'NONE', #37230, 2.500000001920880344, 0.7853981633737419088 ) ; -#19577 = CARTESIAN_POINT ( 'NONE', ( 37.83625397016000136, 190.8148265806999859, 106.3740856161000181 ) ) ; -#19578 = CARTESIAN_POINT ( 'NONE', ( 36.06382944065250484, 192.3722895124269883, 104.3112924986229757 ) ) ; -#19579 = AXIS2_PLACEMENT_3D ( 'NONE', #28388, #3822, #16297 ) ; -#19580 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19581 = CARTESIAN_POINT ( 'NONE', ( 42.51962411156773669, 182.5729458539040593, 104.8564411487018049 ) ) ; -#19582 = CARTESIAN_POINT ( 'NONE', ( -22.49823373577489960, 137.5169523091206543, 94.49371267932974661 ) ) ; -#19583 = ORIENTED_EDGE ( 'NONE', *, *, #18944, .F. ) ; -#19584 = CARTESIAN_POINT ( 'NONE', ( -2.454301599558000202, 209.0000008648000005, 75.66282294831999877 ) ) ; -#19585 = CARTESIAN_POINT ( 'NONE', ( 37.78115515336936880, 118.8155650090541968, 87.24496173037786662 ) ) ; -#19586 = EDGE_CURVE ( 'NONE', #25255, #16953, #22237, .T. ) ; -#19587 = CARTESIAN_POINT ( 'NONE', ( 25.49183423580130636, 211.0903769678246817, 75.54322026927223988 ) ) ; -#19588 = CARTESIAN_POINT ( 'NONE', ( -23.35635573182313607, 131.0183818788550241, 89.91503395410319399 ) ) ; -#19589 = ORIENTED_EDGE ( 'NONE', *, *, #23483, .F. ) ; -#19590 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569047542183, 0.8480481632226759547 ) ) ; -#19591 = EDGE_CURVE ( 'NONE', #26352, #12388, #27484, .T. ) ; -#19592 = ORIENTED_EDGE ( 'NONE', *, *, #19168, .T. ) ; -#19593 = EDGE_CURVE ( 'NONE', #13220, #6773, #29381, .T. ) ; -#19594 = CARTESIAN_POINT ( 'NONE', ( 35.02219272657116278, 120.3902226468004386, 87.42604107993363982 ) ) ; -#19595 = CARTESIAN_POINT ( 'NONE', ( 37.48938149088855454, 212.8449748121827838, 73.03586143537702924 ) ) ; -#19596 = EDGE_CURVE ( 'NONE', #33109, #11983, #27465, .T. ) ; -#19597 = CARTESIAN_POINT ( 'NONE', ( -44.12540495473819391, 185.7838962199085131, 107.1417462355754253 ) ) ; -#19598 = CARTESIAN_POINT ( 'NONE', ( -37.83810969319355166, 191.0388331516561777, 103.7805696149103909 ) ) ; -#19599 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457972811109, -32.89481530046835189, 142.2936922234671613 ) ) ; -#19600 = EDGE_CURVE ( 'NONE', #39158, #16454, #36751, .T. ) ; -#19601 = ORIENTED_EDGE ( 'NONE', *, *, #38254, .T. ) ; -#19602 = AXIS2_PLACEMENT_3D ( 'NONE', #19303, #16432, #31801 ) ; -#19603 = CARTESIAN_POINT ( 'NONE', ( 15.94065427327126550, 152.5997264813005643, 182.6073182000202451 ) ) ; -#19604 = CONICAL_SURFACE ( 'NONE', #36, 2.503011087841876758, 0.7854316141493700165 ) ; -#19605 = CARTESIAN_POINT ( 'NONE', ( 30.07001606276714867, 177.5308891517198902, 100.8472716789253951 ) ) ; -#19606 = CARTESIAN_POINT ( 'NONE', ( 3.599205426421769438, 175.9949742709780764, 100.2823905437740848 ) ) ; -#19607 = AXIS2_PLACEMENT_3D ( 'NONE', #30569, #24446, #34949 ) ; -#19608 = VECTOR ( 'NONE', #22213, 1000.000000000000227 ) ; -#19609 = CARTESIAN_POINT ( 'NONE', ( -20.24838124913999948, 123.4480542337999935, 90.98771610887000350 ) ) ; -#19610 = EDGE_LOOP ( 'NONE', ( #38107, #31370, #14965 ) ) ; -#19611 = CARTESIAN_POINT ( 'NONE', ( 18.90090771971125960, 120.9219860925226300, 173.6350968582803205 ) ) ; -#19612 = ORIENTED_EDGE ( 'NONE', *, *, #24096, .T. ) ; -#19613 = DIRECTION ( 'NONE', ( -0.7075337269147008445, -0.000000000000000000, -0.7066795775160008564 ) ) ; -#19614 = CARTESIAN_POINT ( 'NONE', ( 36.05382442437669965, 112.9281706447458760, 87.74600877593400128 ) ) ; -#19615 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#19616 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#19617 = CARTESIAN_POINT ( 'NONE', ( 28.49403691938354299, 170.5609214717077009, 152.0219651408380912 ) ) ; -#19618 = CARTESIAN_POINT ( 'NONE', ( 38.48171694004999921, 118.5499200410999947, 89.80803649567999969 ) ) ; -#19619 = ORIENTED_EDGE ( 'NONE', *, *, #38836, .T. ) ; -#19620 = CARTESIAN_POINT ( 'NONE', ( 35.56535286263039808, 192.7868339794035251, 106.8337704962199268 ) ) ; -#19621 = DIRECTION ( 'NONE', ( -0.7763856153004775607, 0.5343480021168224292, 0.3342118923501363748 ) ) ; -#19622 = FACE_OUTER_BOUND ( 'NONE', #6921, .T. ) ; -#19623 = CARTESIAN_POINT ( 'NONE', ( -27.50624172263541212, 187.5021564113302190, 106.0367331495152996 ) ) ; -#19624 = ORIENTED_EDGE ( 'NONE', *, *, #2034, .T. ) ; -#19625 = AXIS2_PLACEMENT_3D ( 'NONE', #29788, #26931, #11173 ) ; -#19626 = CIRCLE ( 'NONE', #29454, 6.000000000000001776 ) ; -#19627 = ORIENTED_EDGE ( 'NONE', *, *, #23908, .T. ) ; -#19628 = CARTESIAN_POINT ( 'NONE', ( 25.99886678296517672, 118.8155665066540934, 87.25209012101137773 ) ) ; -#19629 = EDGE_CURVE ( 'NONE', #9250, #9326, #2086, .T. ) ; -#19630 = AXIS2_PLACEMENT_3D ( 'NONE', #36546, #33669, #33263 ) ; -#19631 = FACE_OUTER_BOUND ( 'NONE', #11762, .T. ) ; -#19632 = CARTESIAN_POINT ( 'NONE', ( 15.66800366920011811, 160.1398306428952480, 99.35122504555626222 ) ) ; -#19633 = EDGE_CURVE ( 'NONE', #35236, #19816, #12810, .T. ) ; -#19634 = ORIENTED_EDGE ( 'NONE', *, *, #28849, .F. ) ; -#19635 = ORIENTED_EDGE ( 'NONE', *, *, #20608, .F. ) ; -#19636 = CARTESIAN_POINT ( 'NONE', ( -17.26213291099019997, 152.2612616225560771, 183.6636115490260863 ) ) ; -#19637 = CARTESIAN_POINT ( 'NONE', ( 12.31694666162038132, 134.8454845483305178, 93.34277599231758415 ) ) ; -#19638 = CARTESIAN_POINT ( 'NONE', ( -38.16347685272999968, 118.8553488218999945, 90.29083592950999559 ) ) ; -#19639 = DIRECTION ( 'NONE', ( 0.0002393070154807156044, 0.2243321270822452584, -0.9745127189990429040 ) ) ; -#19640 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971577060 ) ) ; -#19641 = FACE_OUTER_BOUND ( 'NONE', #1399, .T. ) ; -#19642 = ORIENTED_EDGE ( 'NONE', *, *, #24667, .T. ) ; -#19643 = EDGE_CURVE ( 'NONE', #22354, #39827, #4520, .T. ) ; -#19644 = DIRECTION ( 'NONE', ( 0.8094300156679565816, 0.2340581597534485969, -0.5385534584315662121 ) ) ; -#19645 = ORIENTED_EDGE ( 'NONE', *, *, #37429, .F. ) ; -#19646 = CARTESIAN_POINT ( 'NONE', ( 3.666638747404692200, 128.4736512688999994, 89.82433808078000936 ) ) ; -#19647 = CARTESIAN_POINT ( 'NONE', ( 20.00158012229879745, 184.2984082083453359, 105.2684676661315422 ) ) ; -#19648 = CARTESIAN_POINT ( 'NONE', ( 22.53365398945999942, 147.8783627793000051, 152.4718672074000381 ) ) ; -#19649 = PLANE ( 'NONE', #17072 ) ; -#19650 = EDGE_CURVE ( 'NONE', #17466, #19471, #20247, .T. ) ; -#19651 = EDGE_LOOP ( 'NONE', ( #2026, #30707, #17849, #17534 ) ) ; -#19652 = CARTESIAN_POINT ( 'NONE', ( -39.60061239353461815, 123.2105914118956349, 92.88326245006905424 ) ) ; -#19653 = CARTESIAN_POINT ( 'NONE', ( -2.454301921840380096, 209.0000005845445230, 75.66282330657800514 ) ) ; -#19654 = CARTESIAN_POINT ( 'NONE', ( 0.04593741417267090121, 271.9029643395999187, 76.05847688452558941 ) ) ; -#19655 = ORIENTED_EDGE ( 'NONE', *, *, #21562, .F. ) ; -#19656 = VERTEX_POINT ( 'NONE', #14412 ) ; -#19657 = AXIS2_PLACEMENT_3D ( 'NONE', #36968, #36560, #20819 ) ; -#19658 = DIRECTION ( 'NONE', ( -0.0005884949961254158299, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#19659 = DIRECTION ( 'NONE', ( -1.040834085563523426E-15, 0.9743700557921581851, 0.2249510932971578170 ) ) ; -#19660 = ORIENTED_EDGE ( 'NONE', *, *, #12278, .T. ) ; -#19661 = AXIS2_PLACEMENT_3D ( 'NONE', #25650, #10907, #19479 ) ; -#19662 = FACE_OUTER_BOUND ( 'NONE', #39707, .T. ) ; -#19663 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27371, #27165, #5246, #39596 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19664 = ORIENTED_EDGE ( 'NONE', *, *, #11330, .F. ) ; -#19665 = DIRECTION ( 'NONE', ( -0.0005884949961245158337, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#19666 = LINE ( 'NONE', #3728, #11458 ) ; -#19667 = CARTESIAN_POINT ( 'NONE', ( -5.023710534412880513, 124.4265388225056199, 88.38208498629704479 ) ) ; -#19668 = ORIENTED_EDGE ( 'NONE', *, *, #9413, .T. ) ; -#19669 = CARTESIAN_POINT ( 'NONE', ( 26.00948329231449563, 120.3022281478970115, 90.49543144136558226 ) ) ; -#19670 = CARTESIAN_POINT ( 'NONE', ( 13.76437287132147169, 125.3330071254293898, 174.7699841533003564 ) ) ; -#19672 = CARTESIAN_POINT ( 'NONE', ( -8.864578607679121092, 152.4548234462477865, 94.85524532604028991 ) ) ; -#19671 = CARTESIAN_POINT ( 'NONE', ( 20.48147657974056557, 209.1197527550900475, 75.61653826598076478 ) ) ; -#19673 = CARTESIAN_POINT ( 'NONE', ( 25.50879993301148829, 196.1181868571946438, 103.6643310760977670 ) ) ; -#19674 = ORIENTED_EDGE ( 'NONE', *, *, #26396, .T. ) ; -#19675 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19676 = DIRECTION ( 'NONE', ( -0.0002393071182785116774, -0.2252352986010041080, 0.9743043687658491381 ) ) ; -#19677 = CARTESIAN_POINT ( 'NONE', ( -13.49970653172800361, 153.8046016247899956, 95.68281787800398774 ) ) ; -#19678 = EDGE_CURVE ( 'NONE', #16874, #4210, #36482, .T. ) ; -#19679 = ORIENTED_EDGE ( 'NONE', *, *, #32900, .T. ) ; -#19680 = VECTOR ( 'NONE', #24413, 999.9999999999998863 ) ; -#19681 = EDGE_CURVE ( 'NONE', #328, #23937, #17188, .T. ) ; -#19682 = VERTEX_POINT ( 'NONE', #8071 ) ; -#19684 = AXIS2_PLACEMENT_3D ( 'NONE', #23245, #29794, #29988 ) ; -#19683 = CARTESIAN_POINT ( 'NONE', ( -13.47107783232944378, 153.8044057555319739, 95.68275536702104489 ) ) ; -#19685 = CARTESIAN_POINT ( 'NONE', ( -46.63416014034300616, 123.1294690227910138, 92.09012308399532287 ) ) ; -#19686 = CARTESIAN_POINT ( 'NONE', ( -3.070812541647999883, 190.8627820810999935, 106.9366044881000164 ) ) ; -#19687 = CARTESIAN_POINT ( 'NONE', ( 35.86829647990000325, 191.6740030496000031, 103.8700504923999972 ) ) ; -#19688 = ORIENTED_EDGE ( 'NONE', *, *, #32956, .T. ) ; -#19689 = ORIENTED_EDGE ( 'NONE', *, *, #22386, .T. ) ; -#19690 = CARTESIAN_POINT ( 'NONE', ( 46.51720693556681852, 124.8110556520572771, 91.00548902218217506 ) ) ; -#19691 = CARTESIAN_POINT ( 'NONE', ( -23.36156076520060054, 134.6453726937913586, 93.48532686071666831 ) ) ; -#19692 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; -#19693 = ORIENTED_EDGE ( 'NONE', *, *, #35402, .T. ) ; -#19694 = DIRECTION ( 'NONE', ( 0.7865509479255969882, 0.6175253892086907115, 0.000000000000000000 ) ) ; -#19695 = ORIENTED_EDGE ( 'NONE', *, *, #27069, .T. ) ; -#19696 = CARTESIAN_POINT ( 'NONE', ( 21.63968147918147977, 115.2790866430819534, 189.0193985992423791 ) ) ; -#19697 = LINE ( 'NONE', #37713, #33324 ) ; -#19698 = VERTEX_POINT ( 'NONE', #11553 ) ; -#19699 = CARTESIAN_POINT ( 'NONE', ( -30.07656309493742341, 134.9532562613949551, 90.87980234836240356 ) ) ; -#19700 = ADVANCED_FACE ( 'NONE', ( #13803 ), #11809, .T. ) ; -#19701 = CARTESIAN_POINT ( 'NONE', ( -26.00146729410618107, 120.3902237924994836, 87.46289810595230563 ) ) ; -#19702 = CARTESIAN_POINT ( 'NONE', ( -15.49852919541873675, 127.1814504007998892, 91.59019381936052184 ) ) ; -#19703 = CARTESIAN_POINT ( 'NONE', ( 44.73086057231283519, 108.4360122525000492, 169.8450455613742349 ) ) ; -#19704 = EDGE_LOOP ( 'NONE', ( #21360, #16819, #2389, #1781 ) ) ; -#19705 = CARTESIAN_POINT ( 'NONE', ( -25.02112241941476611, 129.9358920626651752, 92.74501084285193997 ) ) ; -#19706 = CIRCLE ( 'NONE', #4715, 2.500000000000002220 ) ; -#19707 = CARTESIAN_POINT ( 'NONE', ( -2.954034027471755142, 205.1071153524148372, 76.10666676077381965 ) ) ; -#19708 = CARTESIAN_POINT ( 'NONE', ( 19.35814820635435041, 126.1315274695410977, 175.4780701241052157 ) ) ; -#19709 = CIRCLE ( 'NONE', #36052, 2.499999999994426236 ) ; -#19710 = CIRCLE ( 'NONE', #24979, 2.500000000048662407 ) ; -#19711 = CARTESIAN_POINT ( 'NONE', ( -41.04085718237605107, 188.5195315767678039, 107.5577504359371375 ) ) ; -#19712 = ORIENTED_EDGE ( 'NONE', *, *, #33565, .F. ) ; -#19713 = CARTESIAN_POINT ( 'NONE', ( 22.77977433793355999, 158.3069438176785582, 96.18720162681876218 ) ) ; -#19714 = CARTESIAN_POINT ( 'NONE', ( 17.48463111787128810, 153.4425669637734586, 179.2163951893537615 ) ) ; -#19715 = VERTEX_POINT ( 'NONE', #39332 ) ; -#19716 = ORIENTED_EDGE ( 'NONE', *, *, #26080, .T. ) ; -#19717 = CARTESIAN_POINT ( 'NONE', ( -20.24985248663000093, 145.0237349194999865, 93.40309554072000253 ) ) ; -#19718 = CARTESIAN_POINT ( 'NONE', ( 28.18621395003418328, 187.0539859719742140, 103.3338670887423376 ) ) ; -#19719 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950524827, 137.3532831589782006, 178.0585834213013072 ) ) ; -#19720 = CARTESIAN_POINT ( 'NONE', ( -2.853038766185818087, 209.7096500570610544, 73.06022702708840200 ) ) ; -#19721 = EDGE_CURVE ( 'NONE', #6712, #36184, #609, .T. ) ; -#19722 = ORIENTED_EDGE ( 'NONE', *, *, #31911, .F. ) ; -#19723 = EDGE_CURVE ( 'NONE', #8845, #9960, #26484, .T. ) ; -#19724 = VERTEX_POINT ( 'NONE', #26692 ) ; -#19725 = CARTESIAN_POINT ( 'NONE', ( -9.583319590155999990, 123.9902035785000010, 91.10643974023000169 ) ) ; -#19726 = VERTEX_POINT ( 'NONE', #17661 ) ; -#19727 = ORIENTED_EDGE ( 'NONE', *, *, #17784, .T. ) ; -#19728 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#19729 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; -#19730 = VERTEX_POINT ( 'NONE', #14009 ) ; -#19731 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24947, #38200, #16117, #34896 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 2.930308335499677012E-08, 0.9999999706969182611 ), - .UNSPECIFIED. ) ; -#19732 = ORIENTED_EDGE ( 'NONE', *, *, #8766, .F. ) ; -#19733 = DIRECTION ( 'NONE', ( -0.7933531821952876095, -0.5932639600228909460, -0.1364866368497979210 ) ) ; -#19734 = DIRECTION ( 'NONE', ( 0.7075280717106061656, 0.1146811194785925248, 0.6973179106954074946 ) ) ; -#19736 = CONICAL_SURFACE ( 'NONE', #35393, 2.503000015584043503, 0.7853981634850645266 ) ; -#19735 = CARTESIAN_POINT ( 'NONE', ( 36.02810672577000162, 191.4409537047000072, 103.6991216587000082 ) ) ; -#19737 = CARTESIAN_POINT ( 'NONE', ( 19.99938796732458712, 193.5973206684549837, 103.1031867269298772 ) ) ; -#19738 = AXIS2_PLACEMENT_3D ( 'NONE', #22336, #34761, #19232 ) ; -#19739 = AXIS2_PLACEMENT_3D ( 'NONE', #36790, #8589, #17958 ) ; -#19740 = CARTESIAN_POINT ( 'NONE', ( -16.26675888560721006, 127.7434586696155066, 175.3198452907780620 ) ) ; -#19741 = ORIENTED_EDGE ( 'NONE', *, *, #35865, .T. ) ; -#19742 = CARTESIAN_POINT ( 'NONE', ( 14.44402852477210430, 188.1654067176696401, 103.0856067790360839 ) ) ; -#19743 = CARTESIAN_POINT ( 'NONE', ( -19.99800679399352532, 151.2849267590962654, 97.67087031631508864 ) ) ; -#19744 = CARTESIAN_POINT ( 'NONE', ( 9.584790827646999745, 187.4829414530000236, 105.7533188981000052 ) ) ; -#19745 = DIRECTION ( 'NONE', ( 4.625929269207597055E-15, -0.9743700557921582961, -0.2249510932971568178 ) ) ; -#19746 = PLANE ( 'NONE', #31522 ) ; -#19747 = ORIENTED_EDGE ( 'NONE', *, *, #31768, .F. ) ; -#19748 = CARTESIAN_POINT ( 'NONE', ( -22.50072399476195528, 158.3009599602069954, 96.21317557253242114 ) ) ; -#19749 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673442394, 160.6295158081618411, 97.24216643309391372 ) ) ; -#19750 = CARTESIAN_POINT ( 'NONE', ( -38.20478932694192764, 191.0388335128845654, 103.7807883132890083 ) ) ; -#19751 = CARTESIAN_POINT ( 'NONE', ( 39.74588592090670147, 161.7500298686462088, 196.6039331146026825 ) ) ; -#19752 = ORIENTED_EDGE ( 'NONE', *, *, #20896, .T. ) ; -#19753 = CARTESIAN_POINT ( 'NONE', ( -25.84175230540873969, 191.4759398539146389, 104.0452857451015660 ) ) ; -#19754 = DIRECTION ( 'NONE', ( -4.631401517333630859E-11, 0.9743700734954054976, 0.2249510166159694735 ) ) ; -#19755 = CARTESIAN_POINT ( 'NONE', ( 21.21457926054944920, 175.8986325760867828, 100.7626612099922454 ) ) ; -#19756 = AXIS2_PLACEMENT_3D ( 'NONE', #10261, #34169, #6364 ) ; -#19757 = CARTESIAN_POINT ( 'NONE', ( -39.39862580925689883, 128.4305629161120805, 92.40616142701088620 ) ) ; -#19758 = ORIENTED_EDGE ( 'NONE', *, *, #21951, .T. ) ; -#19759 = EDGE_CURVE ( 'NONE', #14180, #1138, #35854, .T. ) ; -#19760 = CARTESIAN_POINT ( 'NONE', ( -22.78341386699941040, 154.2035449131175824, 95.43842691770261411 ) ) ; -#19761 = EDGE_CURVE ( 'NONE', #2366, #10263, #1323, .T. ) ; -#19762 = CONICAL_SURFACE ( 'NONE', #7367, 2.249999999870928136, 0.7853981634347139140 ) ; -#19763 = ORIENTED_EDGE ( 'NONE', *, *, #23687, .F. ) ; -#19764 = CARTESIAN_POINT ( 'NONE', ( -25.26021706816886692, 117.1739734221355889, 170.8214860574283591 ) ) ; -#19765 = DIRECTION ( 'NONE', ( -3.172065784687725564E-14, -1.000000000000000000, 1.586032892343862782E-14 ) ) ; -#19766 = CARTESIAN_POINT ( 'NONE', ( -14.99831633147801746, 135.8139285211284175, 93.92495969594287430 ) ) ; -#19767 = CARTESIAN_POINT ( 'NONE', ( 36.06383557508251414, 192.3108559936939912, 104.3213896746180041 ) ) ; -#19768 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#19769 = EDGE_CURVE ( 'NONE', #10767, #34687, #24025, .T. ) ; -#19770 = ADVANCED_FACE ( 'NONE', ( #38726 ), #10741, .T. ) ; -#19771 = CARTESIAN_POINT ( 'NONE', ( 13.50151702522348174, 187.8430237215617069, 103.4418797477903809 ) ) ; -#19772 = VERTEX_POINT ( 'NONE', #4787 ) ; -#19773 = EDGE_CURVE ( 'NONE', #5120, #16970, #27110, .T. ) ; -#19774 = CARTESIAN_POINT ( 'NONE', ( -2.454332449978999797, 209.0617968418999908, 75.63992803070000548 ) ) ; -#19775 = EDGE_CURVE ( 'NONE', #23677, #8441, #32998, .T. ) ; -#19776 = CARTESIAN_POINT ( 'NONE', ( 13.50718655633492382, 188.3455032986072979, 103.1278069412195748 ) ) ; -#19777 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#19778 = ORIENTED_EDGE ( 'NONE', *, *, #10487, .T. ) ; -#19779 = CARTESIAN_POINT ( 'NONE', ( -23.36013624460098725, 134.2411009257855028, 93.73794322563884407 ) ) ; -#19780 = ORIENTED_EDGE ( 'NONE', *, *, #17182, .T. ) ; -#19781 = CARTESIAN_POINT ( 'NONE', ( -3.656326336327488491, 130.0672526925883119, 89.68352076587126476 ) ) ; -#19782 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#19783 = EDGE_LOOP ( 'NONE', ( #24663, #5438, #39551, #22387 ) ) ; -#19784 = FACE_OUTER_BOUND ( 'NONE', #27700, .T. ) ; -#19785 = CARTESIAN_POINT ( 'NONE', ( -41.11490486740327555, 77.14301703112185749, 323.4755791661175408 ) ) ; -#19786 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #252, #9886, #19054, #28876 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19787 = CARTESIAN_POINT ( 'NONE', ( 36.06269812966176858, 123.8464190861335794, 91.30225149133501361 ) ) ; -#19788 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620729128, 0.0004744508866335532104 ) ) ; -#19789 = ORIENTED_EDGE ( 'NONE', *, *, #25307, .F. ) ; -#19790 = CARTESIAN_POINT ( 'NONE', ( 29.05352371370200615, 110.6131156702000027, 87.25023669171606855 ) ) ; -#19791 = EDGE_CURVE ( 'NONE', #35062, #4201, #9394, .T. ) ; -#19792 = CARTESIAN_POINT ( 'NONE', ( 30.06998914975339687, 177.5021616893372141, 100.8652226047939564 ) ) ; -#19793 = CARTESIAN_POINT ( 'NONE', ( 31.51075026500899767, 191.3597297869251292, 106.8916795150186516 ) ) ; -#19794 = CARTESIAN_POINT ( 'NONE', ( -6.042234299931061869, 134.2432640563548318, 93.72802809502178434 ) ) ; -#19795 = EDGE_LOOP ( 'NONE', ( #39509, #10091, #22916, #17695 ) ) ; -#19796 = EDGE_LOOP ( 'NONE', ( #34796, #17965, #34475, #36522 ) ) ; -#19797 = CARTESIAN_POINT ( 'NONE', ( -58.64525294468500505, 28.72802687364639596, 151.8110389321206242 ) ) ; -#19798 = CARTESIAN_POINT ( 'NONE', ( 36.70717078082609675, 115.7236482597848664, 89.70125722292402770 ) ) ; -#19799 = CARTESIAN_POINT ( 'NONE', ( 32.06514546973478019, 137.5830230609005298, 94.13390997160884410 ) ) ; -#19800 = EDGE_CURVE ( 'NONE', #5945, #20371, #23823, .T. ) ; -#19801 = FACE_OUTER_BOUND ( 'NONE', #8495, .T. ) ; -#19802 = DIRECTION ( 'NONE', ( 0.0006039748319389621253, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#19803 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250900735, 132.4055461762762604, 92.79778151960539390 ) ) ; -#19804 = EDGE_CURVE ( 'NONE', #30145, #27328, #20121, .T. ) ; -#19805 = CARTESIAN_POINT ( 'NONE', ( 38.34430631207000317, 119.2562741942000031, 87.36327662843000041 ) ) ; -#19806 = FACE_OUTER_BOUND ( 'NONE', #34593, .T. ) ; -#19807 = CARTESIAN_POINT ( 'NONE', ( 38.70517594201000122, 118.4177626759999953, 89.51241173148000030 ) ) ; -#19808 = AXIS2_PLACEMENT_3D ( 'NONE', #28043, #16, #6140 ) ; -#19809 = CIRCLE ( 'NONE', #40059, 2.499999999890851754 ) ; -#19810 = VERTEX_POINT ( 'NONE', #2757 ) ; -#19811 = EDGE_CURVE ( 'NONE', #10943, #31399, #20935, .T. ) ; -#19812 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#19813 = CARTESIAN_POINT ( 'NONE', ( -26.47922269804969275, 118.7188176348483353, 171.1783167788773596 ) ) ; -#19814 = LINE ( 'NONE', #622, #12461 ) ; -#19815 = CARTESIAN_POINT ( 'NONE', ( -3.589080270957198504, 147.6459880593766343, 129.6608555926431166 ) ) ; -#19816 = VERTEX_POINT ( 'NONE', #22530 ) ; -#19817 = VERTEX_POINT ( 'NONE', #37847 ) ; -#19818 = ADVANCED_FACE ( 'NONE', ( #31730 ), #32694, .T. ) ; -#19819 = EDGE_LOOP ( 'NONE', ( #7176, #16181, #15831, #429, #14930, #15544, #25470, #24470, #4114, #18290, #35983 ) ) ; -#19820 = CARTESIAN_POINT ( 'NONE', ( -10.08030268265000018, 184.7670343400000377, 28.07991271570000080 ) ) ; -#19821 = FACE_OUTER_BOUND ( 'NONE', #24377, .T. ) ; -#19822 = VERTEX_POINT ( 'NONE', #17855 ) ; -#19823 = LINE ( 'NONE', #13521, #30946 ) ; -#19824 = CYLINDRICAL_SURFACE ( 'NONE', #17223, 2.499999999999997335 ) ; -#19825 = DIRECTION ( 'NONE', ( -0.0005884949961240085355, 0.2249510543439064425, -0.9743698870671262391 ) ) ; -#19826 = CARTESIAN_POINT ( 'NONE', ( -38.55421100171000859, 119.2443145780000009, 87.60185880502000089 ) ) ; -#19827 = CYLINDRICAL_SURFACE ( 'NONE', #35970, 2.000000000000011546 ) ; -#19828 = FACE_OUTER_BOUND ( 'NONE', #24887, .T. ) ; -#19829 = ORIENTED_EDGE ( 'NONE', *, *, #29725, .T. ) ; -#19830 = CARTESIAN_POINT ( 'NONE', ( -19.21652826239685652, 125.8330942992555634, 175.8856240629868068 ) ) ; -#19831 = VERTEX_POINT ( 'NONE', #15960 ) ; -#19832 = DIRECTION ( 'NONE', ( -0.5988682214889347044, 0.8008475843072014877, 0.000000000000000000 ) ) ; -#19833 = FACE_OUTER_BOUND ( 'NONE', #24580, .T. ) ; -#19834 = DIRECTION ( 'NONE', ( 0.001086453504404431012, -0.2255832328198436876, 0.9742232930336509611 ) ) ; -#19835 = CARTESIAN_POINT ( 'NONE', ( 46.51603001997818865, 125.2609579198457368, 89.05674941267899669 ) ) ; -#19836 = VECTOR ( 'NONE', #21912, 1000.000000000000227 ) ; -#19837 = ORIENTED_EDGE ( 'NONE', *, *, #34101, .T. ) ; -#19838 = CARTESIAN_POINT ( 'NONE', ( -1.970835579912000091, 189.4718220514999985, 103.6836576495000060 ) ) ; -#19839 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #794, #6726, #16140, #10821, #13084, #26167, #10623, #34724, #22696, #7129, #4251 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999997788436, 0.3749999999996432853, 0.4374999999995754507, 0.4687499999995714539, 0.4999999999995674571, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19840 = LINE ( 'NONE', #38267, #5534 ) ; -#19841 = CONICAL_SURFACE ( 'NONE', #10096, 2.503011062257897379, 0.7853981634071111051 ) ; -#19842 = CONICAL_SURFACE ( 'NONE', #34834, 2.503090949441038493, 0.7853981633487705505 ) ; -#19843 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433776002355 ) ) ; -#19844 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #7982, #35557, #4710, #11260 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 6.154269794435091256, 6.194940170588882467 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9998621647918570776, 0.9998621647918570776, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#19845 = AXIS2_PLACEMENT_3D ( 'NONE', #28991, #38582, #19765 ) ; -#19846 = VERTEX_POINT ( 'NONE', #15225 ) ; -#19847 = LINE ( 'NONE', #7593, #6114 ) ; -#19848 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19849 = ORIENTED_EDGE ( 'NONE', *, *, #14262, .F. ) ; -#19850 = CARTESIAN_POINT ( 'NONE', ( -42.20772307256024192, 120.8083491825531013, 90.64813103358072510 ) ) ; -#19851 = EDGE_CURVE ( 'NONE', #30059, #39941, #5981, .T. ) ; -#19852 = EDGE_CURVE ( 'NONE', #22581, #30982, #25602, .T. ) ; -#19853 = ORIENTED_EDGE ( 'NONE', *, *, #33281, .F. ) ; -#19854 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#19855 = EDGE_CURVE ( 'NONE', #1699, #26164, #29892, .T. ) ; -#19856 = EDGE_CURVE ( 'NONE', #22954, #1917, #26816, .T. ) ; -#19857 = CARTESIAN_POINT ( 'NONE', ( 14.82295868926343019, 114.6164157062401330, 152.8159396943794093 ) ) ; -#19858 = CARTESIAN_POINT ( 'NONE', ( -8.189842673156130459, 150.7129460345074961, 97.36055581103926215 ) ) ; -#19859 = CARTESIAN_POINT ( 'NONE', ( -20.00011960254677845, 119.8743726790490882, 87.34018024778070810 ) ) ; -#19860 = VERTEX_POINT ( 'NONE', #28652 ) ; -#19861 = ADVANCED_FACE ( 'NONE', ( #33816 ), #39870, .F. ) ; -#19862 = CARTESIAN_POINT ( 'NONE', ( 26.00614868755149800, 120.3031002262990086, 90.49221237271520124 ) ) ; -#19863 = CARTESIAN_POINT ( 'NONE', ( -25.45411666281046692, 211.7447201612124843, 75.57429487795135969 ) ) ; -#19864 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33942, #3657, #31905, #25770, #19605, #29020, #32102, #19792, #19193, #7532, #26370 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000001768585, 0.3750000000002153833, 0.4375000000002170486, 0.4687500000001579292, 0.5000000000000986988, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19866 = CARTESIAN_POINT ( 'NONE', ( -9.450221470825175274, 153.0100899376908501, 94.98379243350829881 ) ) ; -#19865 = CARTESIAN_POINT ( 'NONE', ( 20.48212217007521829, 207.7963227301765414, 76.43687548430384027 ) ) ; -#19867 = CIRCLE ( 'NONE', #7469, 6.499999999928477656 ) ; -#19868 = ADVANCED_FACE ( 'NONE', ( #5608 ), #11757, .F. ) ; -#19869 = AXIS2_PLACEMENT_3D ( 'NONE', #7093, #37575, #10188 ) ; -#19870 = CIRCLE ( 'NONE', #36857, 2.500000000000002220 ) ; -#19871 = VERTEX_POINT ( 'NONE', #14832 ) ; -#19872 = CARTESIAN_POINT ( 'NONE', ( 22.50147045826000181, 153.3598638654891886, 97.61100683846059667 ) ) ; -#19873 = CARTESIAN_POINT ( 'NONE', ( -36.10626650516888247, 191.9730893684615864, 104.4211779715851520 ) ) ; -#19874 = DIRECTION ( 'NONE', ( -0.6185863125140933505, -0.7857168535612664151, 0.000000000000000000 ) ) ; -#19875 = CARTESIAN_POINT ( 'NONE', ( -35.94700007828220834, 109.6131156696666693, 89.12282904685666551 ) ) ; -#19877 = ORIENTED_EDGE ( 'NONE', *, *, #18747, .F. ) ; -#19876 = AXIS2_PLACEMENT_3D ( 'NONE', #18318, #21208, #33661 ) ; -#19878 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17322, #10819, #5064, #11413 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19879 = EDGE_LOOP ( 'NONE', ( #24618, #11502, #31474, #6781, #9955, #35406, #5775, #28151, #32958, #25476, #14352, #2819 ) ) ; -#19880 = CARTESIAN_POINT ( 'NONE', ( 116.6747096975787059, 205.3448423347536789, 192.2656634464534591 ) ) ; -#19881 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971546529 ) ) ; -#19882 = CARTESIAN_POINT ( 'NONE', ( -3.070812596811999917, 190.8630721979000384, 106.9366657634000006 ) ) ; -#19883 = ORIENTED_EDGE ( 'NONE', *, *, #37556, .F. ) ; -#19884 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559851 ) ) ; -#19885 = DIRECTION ( 'NONE', ( 0.0005884949961199763876, -0.2249510543439082189, 0.9743698870671259060 ) ) ; -#19886 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#19887 = ORIENTED_EDGE ( 'NONE', *, *, #16626, .F. ) ; -#19888 = VERTEX_POINT ( 'NONE', #28455 ) ; -#19889 = CARTESIAN_POINT ( 'NONE', ( 30.06789428293084043, 135.1172793263938843, 91.09506464709090778 ) ) ; -#19890 = CARTESIAN_POINT ( 'NONE', ( 3.064317959841779349, 190.8642559078977854, 106.7952278870890410 ) ) ; -#19891 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319401588676 ) ) ; -#19892 = DIRECTION ( 'NONE', ( 0.0006039748319382907873, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#19893 = AXIS2_PLACEMENT_3D ( 'NONE', #20776, #33231, #14658 ) ; -#19894 = CARTESIAN_POINT ( 'NONE', ( 39.72739263165712487, 107.0606345199744283, 184.9165446084303426 ) ) ; -#19895 = LINE ( 'NONE', #16833, #28698 ) ; -#19896 = ORIENTED_EDGE ( 'NONE', *, *, #88, .T. ) ; -#19897 = ADVANCED_FACE ( 'NONE', ( #24241 ), #11963, .F. ) ; -#19898 = VECTOR ( 'NONE', #25752, 1000.000000000000114 ) ; -#19899 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700562169598234, -0.2249510914571402620 ) ) ; -#19900 = EDGE_CURVE ( 'NONE', #4711, #15715, #24873, .T. ) ; -#19901 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#19902 = CARTESIAN_POINT ( 'NONE', ( 20.55731024319839406, 211.7441868440044743, 75.54576727287884808 ) ) ; -#19903 = FACE_OUTER_BOUND ( 'NONE', #31255, .T. ) ; -#19904 = ORIENTED_EDGE ( 'NONE', *, *, #29672, .T. ) ; -#19905 = EDGE_CURVE ( 'NONE', #34680, #32839, #5819, .T. ) ; -#19906 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#19907 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22298, #34337, #10, #6333 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19908 = CARTESIAN_POINT ( 'NONE', ( -36.16375936368000055, 113.8378354543000057, 89.62930055153999831 ) ) ; -#19909 = EDGE_CURVE ( 'NONE', #28773, #12858, #27527, .T. ) ; -#19910 = ORIENTED_EDGE ( 'NONE', *, *, #36654, .F. ) ; -#19911 = CARTESIAN_POINT ( 'NONE', ( -38.81266452666582722, 133.7633419217194160, 337.2839330447861812 ) ) ; -#19912 = ORIENTED_EDGE ( 'NONE', *, *, #35543, .F. ) ; -#19913 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19914 = CARTESIAN_POINT ( 'NONE', ( -28.46737701145232791, 128.5818728664343951, 89.35557892710436079 ) ) ; -#19915 = CARTESIAN_POINT ( 'NONE', ( -26.57351927219633581, 123.1588308314834421, 88.10242702663742875 ) ) ; -#19916 = FACE_OUTER_BOUND ( 'NONE', #34390, .T. ) ; -#19917 = DIRECTION ( 'NONE', ( -0.7933532970003721596, -0.5930762008556746956, -0.1372995488602881120 ) ) ; -#19918 = VERTEX_POINT ( 'NONE', #40151 ) ; -#19919 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7677, #938, #20140, #1145, #37963, #32237 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 3.272432770486283937E-05, 0.001540884923091554544, 0.003049045518478246241 ), - .UNSPECIFIED. ) ; -#19920 = EDGE_LOOP ( 'NONE', ( #13258, #33620, #11083, #23023, #13053, #34078, #37698, #4556, #4713, #2547, #14733, #36478, #17229, #13180, #6988, #884, #28201, #6678, #14826, #16844, #19716, #28622, #24996, #31496, #20748 ) ) ; -#19921 = FACE_BOUND ( 'NONE', #13283, .T. ) ; -#19922 = ORIENTED_EDGE ( 'NONE', *, *, #2303, .T. ) ; -#19923 = VERTEX_POINT ( 'NONE', #12163 ) ; -#19924 = VERTEX_POINT ( 'NONE', #24650 ) ; -#19925 = CARTESIAN_POINT ( 'NONE', ( 1.956228930436368030, 189.5641622393101215, 105.8987958274937284 ) ) ; -#19926 = EDGE_CURVE ( 'NONE', #5402, #35793, #34552, .T. ) ; -#19927 = VECTOR ( 'NONE', #35586, 1000.000000000000000 ) ; -#19928 = LINE ( 'NONE', #3792, #38511 ) ; -#19929 = AXIS2_PLACEMENT_3D ( 'NONE', #4110, #16395, #6989 ) ; -#19930 = AXIS2_PLACEMENT_3D ( 'NONE', #9114, #37510, #9512 ) ; -#19931 = ORIENTED_EDGE ( 'NONE', *, *, #29026, .T. ) ; -#19932 = CARTESIAN_POINT ( 'NONE', ( -45.80561840739365920, 187.2331216690805604, 105.4495952916396533 ) ) ; -#19933 = AXIS2_PLACEMENT_3D ( 'NONE', #15730, #27837, #19398 ) ; -#19934 = CARTESIAN_POINT ( 'NONE', ( -18.98889543208580122, 125.5955304196095312, 175.3358149539526778 ) ) ; -#19935 = CARTESIAN_POINT ( 'NONE', ( 36.67125386629000161, 117.6422922943000060, 87.11622953641000322 ) ) ; -#19936 = CARTESIAN_POINT ( 'NONE', ( -38.90145940069999853, 118.6908308601000073, 89.55944009604000655 ) ) ; -#19937 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32522, #17167, #29265, #1031, #1235, #11257, #35552, #36185, #8190, #20659 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.002377699347871517228, 0.2517832745109036541, 0.5011888496739357324, 0.7505944248369678107, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#19938 = LINE ( 'NONE', #32434, #9826 ) ; -#19939 = ORIENTED_EDGE ( 'NONE', *, *, #16094, .F. ) ; -#19940 = CARTESIAN_POINT ( 'NONE', ( 19.99991105671495362, 118.5778858161331470, 87.25549460550637093 ) ) ; -#19941 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971547361 ) ) ; -#19942 = EDGE_LOOP ( 'NONE', ( #13585, #11250, #37122, #18983 ) ) ; -#19943 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971519328 ) ) ; -#19944 = CARTESIAN_POINT ( 'NONE', ( -29.30090432678149170, 112.1830789903917349, 175.8249585680744644 ) ) ; -#19945 = CARTESIAN_POINT ( 'NONE', ( 20.50029387904210765, 120.2778657767349841, 87.92202505056270923 ) ) ; -#19946 = CARTESIAN_POINT ( 'NONE', ( 44.91139781548088905, 186.4056730800002128, 107.2645705271051781 ) ) ; -#19947 = VERTEX_POINT ( 'NONE', #6557 ) ; -#19948 = CARTESIAN_POINT ( 'NONE', ( 39.86749636578412748, 165.2362371599454320, 181.9483004261018095 ) ) ; -#19949 = CARTESIAN_POINT ( 'NONE', ( 0.6691617680251428224, 189.0028253544776362, 103.6871807533737808 ) ) ; -#19950 = CARTESIAN_POINT ( 'NONE', ( 32.56862209515505668, 137.3592834573111929, 91.34514006402139330 ) ) ; -#19951 = VECTOR ( 'NONE', #5418, 1000.000000000000227 ) ; -#19952 = CARTESIAN_POINT ( 'NONE', ( -30.17790838424820521, 126.0796625456713826, 91.85784435949031490 ) ) ; -#19953 = CARTESIAN_POINT ( 'NONE', ( -25.87048433357000121, 191.8304227716000128, 104.0529250579999996 ) ) ; -#19954 = EDGE_CURVE ( 'NONE', #35766, #34206, #24472, .T. ) ; -#19955 = AXIS2_PLACEMENT_3D ( 'NONE', #13707, #34945, #26195 ) ; -#19956 = DIRECTION ( 'NONE', ( -0.0005884949961262653023, 0.2249510543439053600, -0.9743698870671265722 ) ) ; -#19957 = CIRCLE ( 'NONE', #7561, 22.50000000000000000 ) ; -#19958 = LINE ( 'NONE', #23454, #39195 ) ; -#19959 = CARTESIAN_POINT ( 'NONE', ( 19.45260910890439021, 147.6922889574200042, 183.5326060071998597 ) ) ; -#19960 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989941907, 0.1373964268091567298 ) ) ; -#19961 = CARTESIAN_POINT ( 'NONE', ( -28.26185612672702518, 125.5768230428473373, 89.17483656727264929 ) ) ; -#19962 = ORIENTED_EDGE ( 'NONE', *, *, #7014, .F. ) ; -#19963 = AXIS2_PLACEMENT_3D ( 'NONE', #24457, #36905, #21384 ) ; -#19964 = CIRCLE ( 'NONE', #4972, 1.749999999999998446 ) ; -#19965 = FACE_OUTER_BOUND ( 'NONE', #25371, .T. ) ; -#19966 = ORIENTED_EDGE ( 'NONE', *, *, #12285, .F. ) ; -#19967 = CARTESIAN_POINT ( 'NONE', ( 94.27699944285315325, 220.8868603236405761, 200.9849624698713910 ) ) ; -#19968 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#19969 = CARTESIAN_POINT ( 'NONE', ( 37.80694793874999959, 190.1982698422000055, 106.7585076721000092 ) ) ; -#19970 = CARTESIAN_POINT ( 'NONE', ( 20.24032085432765271, 118.1109234118111431, 90.01703651609138035 ) ) ; -#19971 = DIRECTION ( 'NONE', ( -0.0001422274014914441545, 0.2255205321518429784, -0.9742384047805320302 ) ) ; -#19972 = CARTESIAN_POINT ( 'NONE', ( 13.50520662904530234, 188.2844610440680242, 103.1660372551096145 ) ) ; -#19973 = ORIENTED_EDGE ( 'NONE', *, *, #30589, .T. ) ; -#19974 = CARTESIAN_POINT ( 'NONE', ( -5.669824853826463951, 181.4158645661298692, 104.2738425377782647 ) ) ; -#19975 = FACE_OUTER_BOUND ( 'NONE', #14558, .T. ) ; -#19976 = CARTESIAN_POINT ( 'NONE', ( 37.09343845436652032, 117.9403996252154059, 87.24538078468812330 ) ) ; -#19977 = LINE ( 'NONE', #23470, #27193 ) ; -#19978 = CARTESIAN_POINT ( 'NONE', ( -14.22265864990228401, 129.0629248693782074, 176.7848948385215806 ) ) ; -#19979 = VECTOR ( 'NONE', #1731, 1000.000000000000227 ) ; -#19980 = VERTEX_POINT ( 'NONE', #19024 ) ; -#19981 = CARTESIAN_POINT ( 'NONE', ( -26.00476204355895860, 118.1131156702000169, 87.28007043021332834 ) ) ; -#19982 = AXIS2_PLACEMENT_3D ( 'NONE', #39243, #14523, #30253 ) ; -#19983 = ORIENTED_EDGE ( 'NONE', *, *, #15764, .F. ) ; -#19984 = VECTOR ( 'NONE', #36431, 1000.000000000000000 ) ; -#19985 = FACE_OUTER_BOUND ( 'NONE', #26082, .T. ) ; -#19986 = LINE ( 'NONE', #35318, #39773 ) ; -#19987 = CARTESIAN_POINT ( 'NONE', ( 24.51428771926448036, 115.4939956718079088, 87.25297827652497062 ) ) ; -#19988 = ORIENTED_EDGE ( 'NONE', *, *, #25301, .F. ) ; -#19989 = CARTESIAN_POINT ( 'NONE', ( -2.937969491697683733, 193.8169247291332340, 102.7046841998142241 ) ) ; -#19990 = AXIS2_PLACEMENT_3D ( 'NONE', #29417, #7717, #30579 ) ; -#19991 = EDGE_CURVE ( 'NONE', #10713, #38615, #4953, .T. ) ; -#19992 = CARTESIAN_POINT ( 'NONE', ( 40.67360545558243956, 184.2591260079552740, 105.2468408042174275 ) ) ; -#19993 = CARTESIAN_POINT ( 'NONE', ( -25.66788536014817979, 120.6928529548877833, 87.87466536108948389 ) ) ; -#19994 = VECTOR ( 'NONE', #25570, 1000.000000000000000 ) ; -#19995 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#19996 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#19997 = VERTEX_POINT ( 'NONE', #19432 ) ; -#19998 = VERTEX_POINT ( 'NONE', #7163 ) ; -#19999 = EDGE_CURVE ( 'NONE', #35056, #11575, #7201, .T. ) ; -#20000 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#20001 = CARTESIAN_POINT ( 'NONE', ( -3.663555850038422435, 176.1198545594807570, 100.3156079611679132 ) ) ; -#20002 = CARTESIAN_POINT ( 'NONE', ( -19.31979924309097996, 124.8061162773214079, 177.8324071844828893 ) ) ; -#20003 = FACE_OUTER_BOUND ( 'NONE', #40153, .T. ) ; -#20004 = ADVANCED_FACE ( 'NONE', ( #29456 ), #35351, .F. ) ; -#20005 = ORIENTED_EDGE ( 'NONE', *, *, #8055, .F. ) ; -#20006 = CARTESIAN_POINT ( 'NONE', ( 35.54678067552502796, 205.1071296091747627, 76.08337964645130569 ) ) ; -#20007 = ADVANCED_FACE ( 'NONE', ( #32721 ), #23328, .T. ) ; -#20008 = EDGE_CURVE ( 'NONE', #11405, #1726, #7565, .T. ) ; -#20009 = CARTESIAN_POINT ( 'NONE', ( 5.666344154467410910, 131.0223139869003148, 89.89838483048988849 ) ) ; -#20010 = CARTESIAN_POINT ( 'NONE', ( 36.81642380686323435, 115.9749306341711730, 89.69778768397191016 ) ) ; -#20011 = FACE_OUTER_BOUND ( 'NONE', #12891, .T. ) ; -#20012 = CARTESIAN_POINT ( 'NONE', ( 5.957091414655063311, 149.1468224720344438, 94.08258114083251655 ) ) ; -#20013 = AXIS2_PLACEMENT_3D ( 'NONE', #22592, #38312, #35412 ) ; -#20014 = CARTESIAN_POINT ( 'NONE', ( 20.49980344970378354, 118.1127835573565221, 87.75514417896067698 ) ) ; -#20015 = CIRCLE ( 'NONE', #20703, 16.50000000000598277 ) ; -#20016 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -7.930164461720913721E-15, 0.0006039748319378585159 ) ) ; -#20017 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #35378, #38866, #13140, #1052 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 2.962184725352719816, 4.532607311606953182 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8048259373832478136, 0.8048259373832478136, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#20018 = CIRCLE ( 'NONE', #7619, 5.000000000000007994 ) ; -#20019 = CARTESIAN_POINT ( 'NONE', ( 25.63509192864999875, 191.6570031512000298, 106.5184188570000003 ) ) ; -#20020 = DIRECTION ( 'NONE', ( 0.0006039748319378811757, 1.385389704782810608E-14, 0.9999998176071845934 ) ) ; -#20021 = CARTESIAN_POINT ( 'NONE', ( -37.95805881438000284, 190.5117572160999941, 106.6130310081000090 ) ) ; -#20022 = VERTEX_POINT ( 'NONE', #20033 ) ; -#20023 = CARTESIAN_POINT ( 'NONE', ( 15.50033646246506258, 125.3079633380212670, 88.57318189682698062 ) ) ; -#20024 = AXIS2_PLACEMENT_3D ( 'NONE', #36029, #1702, #11507 ) ; -#20025 = CARTESIAN_POINT ( 'NONE', ( -28.44200545076591524, 125.3783868041292493, 88.78703055465665273 ) ) ; -#20026 = CARTESIAN_POINT ( 'NONE', ( -35.93657502954287253, 192.7057404805565568, 106.3835757455632063 ) ) ; -#20027 = DIRECTION ( 'NONE', ( 1.314737622555947214E-14, -0.9743700557921584071, -0.2249510932971566513 ) ) ; -#20029 = ORIENTED_EDGE ( 'NONE', *, *, #39187, .F. ) ; -#20028 = CARTESIAN_POINT ( 'NONE', ( -26.72558643308320114, 188.4929049624550430, 106.2649940209322921 ) ) ; -#20030 = EDGE_LOOP ( 'NONE', ( #18411, #8431, #28514, #5326 ) ) ; -#20031 = ORIENTED_EDGE ( 'NONE', *, *, #14824, .F. ) ; -#20032 = ORIENTED_EDGE ( 'NONE', *, *, #40103, .F. ) ; -#20033 = CARTESIAN_POINT ( 'NONE', ( 45.29516381819948379, 180.6442485579885329, 103.8963377076147907 ) ) ; -#20034 = DIRECTION ( 'NONE', ( 0.6087614810001779064, -0.7729390313185917627, -0.1788147452386051328 ) ) ; -#20035 = ORIENTED_EDGE ( 'NONE', *, *, #15280, .T. ) ; -#20036 = FACE_OUTER_BOUND ( 'NONE', #2230, .T. ) ; -#20037 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#20038 = CARTESIAN_POINT ( 'NONE', ( -39.34394936606000215, 120.1039698687000055, 87.57589102765001599 ) ) ; -#20039 = CARTESIAN_POINT ( 'NONE', ( -35.82528985044000081, 113.4061984923000068, 87.66687329503000115 ) ) ; -#20040 = ORIENTED_EDGE ( 'NONE', *, *, #15911, .T. ) ; -#20041 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385689936 ) ) ; -#20042 = EDGE_CURVE ( 'NONE', #27317, #14482, #4603, .T. ) ; -#20043 = AXIS2_PLACEMENT_3D ( 'NONE', #18235, #31537, #21940 ) ; -#20044 = CARTESIAN_POINT ( 'NONE', ( 16.56169987041441161, 121.8384666780658563, 177.5555275195565059 ) ) ; -#20045 = CARTESIAN_POINT ( 'NONE', ( 19.98232544185748694, 209.7096131673859816, 76.04619115725449774 ) ) ; -#20046 = LINE ( 'NONE', #22744, #30663 ) ; -#20047 = AXIS2_PLACEMENT_3D ( 'NONE', #2606, #11386, #20791 ) ; -#20048 = CARTESIAN_POINT ( 'NONE', ( -21.69818314611236332, 120.0177369536598775, 190.2070442068906573 ) ) ; -#20049 = ORIENTED_EDGE ( 'NONE', *, *, #5296, .T. ) ; -#20050 = ORIENTED_EDGE ( 'NONE', *, *, #31800, .T. ) ; -#20051 = EDGE_CURVE ( 'NONE', #25148, #10571, #3888, .T. ) ; -#20052 = CARTESIAN_POINT ( 'NONE', ( -2.209344093541980136, 189.3042501796560089, 103.3557222930819961 ) ) ; -#20053 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#20054 = LINE ( 'NONE', #6779, #24729 ) ; -#20055 = EDGE_CURVE ( 'NONE', #23240, #21775, #16555, .T. ) ; -#20056 = ORIENTED_EDGE ( 'NONE', *, *, #4915, .T. ) ; -#20057 = LINE ( 'NONE', #29690, #39406 ) ; -#20058 = CARTESIAN_POINT ( 'NONE', ( 37.19332676480694744, 118.8604558151628794, 122.9910815359380507 ) ) ; -#20059 = EDGE_CURVE ( 'NONE', #35389, #19772, #1042, .T. ) ; -#20060 = ORIENTED_EDGE ( 'NONE', *, *, #23966, .T. ) ; -#20061 = ADVANCED_FACE ( 'NONE', ( #26606 ), #39044, .F. ) ; -#20062 = EDGE_CURVE ( 'NONE', #2348, #23133, #13118, .T. ) ; -#20063 = VERTEX_POINT ( 'NONE', #26201 ) ; -#20064 = EDGE_LOOP ( 'NONE', ( #20906, #7474, #32728, #21724 ) ) ; -#20065 = CARTESIAN_POINT ( 'NONE', ( 30.05503346839188694, 109.6131156702000027, 89.74963226069121447 ) ) ; -#20066 = FACE_OUTER_BOUND ( 'NONE', #37398, .T. ) ; -#20067 = CARTESIAN_POINT ( 'NONE', ( -31.70415073531002292, 226.4002260770687371, 75.57765305101875697 ) ) ; -#20068 = CARTESIAN_POINT ( 'NONE', ( -39.75024793617362917, 128.4756217986020488, 92.41677646255658374 ) ) ; -#20069 = ORIENTED_EDGE ( 'NONE', *, *, #27895, .F. ) ; -#20070 = CARTESIAN_POINT ( 'NONE', ( 25.83394384250999920, 120.1761492849000064, 90.28722222492000071 ) ) ; -#20071 = VECTOR ( 'NONE', #19185, 1000.000000000000114 ) ; -#20072 = DIRECTION ( 'NONE', ( 0.5614017635044570298, 0.2604362742582519430, 0.7854941164544558818 ) ) ; -#20073 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3228, #13056, #34491, #40439, #13256, #37391, #19375, #34106, #12442, #15902, #6695, #15706, #6103, #24942, #18555, #174, #22467 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999995268229, 0.1874999999993464395, 0.2187499999992812416, 0.2343749999992737199, 0.2499999999992661981, 0.3749999999993902655, 0.4374999999995085043, 0.4687499999995676236, 0.4999999999996267430, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20074 = AXIS2_PLACEMENT_3D ( 'NONE', #5866, #18322, #27577 ) ; -#20076 = DIRECTION ( 'NONE', ( 0.7933310414247660702, 0.5931044597393384521, 0.1373060761554397435 ) ) ; -#20075 = DIRECTION ( 'NONE', ( -0.6087614109020721420, -0.7729348355671187276, -0.1788331193133693153 ) ) ; -#20077 = EDGE_LOOP ( 'NONE', ( #22034, #38750, #25979, #27023 ) ) ; -#20078 = CARTESIAN_POINT ( 'NONE', ( -36.00107217495795453, 192.1246088503090164, 104.4282414194491082 ) ) ; -#20079 = DIRECTION ( 'NONE', ( -0.0001408402303593218278, 0.2255194953820404136, -0.9742386449770196188 ) ) ; -#20080 = ORIENTED_EDGE ( 'NONE', *, *, #17082, .T. ) ; -#20081 = CARTESIAN_POINT ( 'NONE', ( -12.63766980425000064, 130.4202329732130465, 90.28358935463637636 ) ) ; -#20082 = CARTESIAN_POINT ( 'NONE', ( 5.675516847681189248, 187.6699105947183170, 106.0554762087619025 ) ) ; -#20083 = CARTESIAN_POINT ( 'NONE', ( -37.56657168646712108, 112.0458133426950695, 151.1389157892933781 ) ) ; -#20084 = ORIENTED_EDGE ( 'NONE', *, *, #36268, .T. ) ; -#20085 = EDGE_CURVE ( 'NONE', #32617, #23829, #29049, .T. ) ; -#20086 = EDGE_LOOP ( 'NONE', ( #22742, #1706, #36977, #34008 ) ) ; -#20087 = EDGE_CURVE ( 'NONE', #37138, #33109, #15676, .T. ) ; -#20088 = ORIENTED_EDGE ( 'NONE', *, *, #2314, .F. ) ; -#20089 = ADVANCED_FACE ( 'NONE', ( #4082 ), #25533, .F. ) ; -#20090 = CARTESIAN_POINT ( 'NONE', ( -23.36212846483814332, 134.4076661005499318, 93.63386271954821893 ) ) ; -#20091 = EDGE_LOOP ( 'NONE', ( #27712, #9243, #34863, #36503, #13382 ) ) ; -#20092 = EDGE_CURVE ( 'NONE', #20475, #25492, #11131, .T. ) ; -#20093 = CARTESIAN_POINT ( 'NONE', ( -35.93657504925000268, 192.7057423503999871, 106.3835754178000172 ) ) ; -#20094 = EDGE_CURVE ( 'NONE', #15161, #15606, #23558, .T. ) ; -#20095 = AXIS2_PLACEMENT_3D ( 'NONE', #16871, #32830, #10772 ) ; -#20096 = DIRECTION ( 'NONE', ( -1.586032892343862782E-14, -1.000000000000000000, 1.586032892343862782E-14 ) ) ; -#20097 = ORIENTED_EDGE ( 'NONE', *, *, #36163, .T. ) ; -#20098 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#20099 = CIRCLE ( 'NONE', #16830, 5.500000000058693495 ) ; -#20100 = EDGE_CURVE ( 'NONE', #33382, #28516, #2469, .T. ) ; -#20101 = CARTESIAN_POINT ( 'NONE', ( 13.85658554608299831, 124.7833813603056683, 174.0357207381452156 ) ) ; -#20102 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971598709 ) ) ; -#20103 = DIRECTION ( 'NONE', ( 1.226844142311109452E-09, -0.9743700560678152378, -0.2249510921031558919 ) ) ; -#20104 = ORIENTED_EDGE ( 'NONE', *, *, #17259, .T. ) ; -#20105 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17864, #13469, #13269, #19587 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20106 = CARTESIAN_POINT ( 'NONE', ( 7.983582054365251146, 181.6899197882616193, 101.5945976457548880 ) ) ; -#20107 = CARTESIAN_POINT ( 'NONE', ( 28.49424211975999910, 172.5096616001999905, 152.4718672074000381 ) ) ; -#20108 = CARTESIAN_POINT ( 'NONE', ( -2.436201573125298392, 191.0000000999000065, 105.6316717966334835 ) ) ; -#20109 = EDGE_CURVE ( 'NONE', #14645, #9305, #8185, .T. ) ; -#20110 = VERTEX_POINT ( 'NONE', #39250 ) ; -#20111 = CARTESIAN_POINT ( 'NONE', ( -13.46162628924000160, 112.1320600213999938, 152.4718672074000381 ) ) ; -#20113 = CARTESIAN_POINT ( 'NONE', ( -38.15628031149999799, 118.6857350137999987, 90.14919392147000110 ) ) ; -#20112 = DIRECTION ( 'NONE', ( -0.0005884949961213889946, 0.2249510543439060262, -0.9743698870671263501 ) ) ; -#20114 = CIRCLE ( 'NONE', #2524, 47.49999999998843236 ) ; -#20115 = ORIENTED_EDGE ( 'NONE', *, *, #37817, .T. ) ; -#20116 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33524, #27636, #21886, #12080 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20117 = CARTESIAN_POINT ( 'NONE', ( 38.58505542112862230, 118.4768865310855546, 89.66249146129999303 ) ) ; -#20118 = VERTEX_POINT ( 'NONE', #17570 ) ; -#20119 = LINE ( 'NONE', #5191, #14694 ) ; -#20120 = CIRCLE ( 'NONE', #18807, 2.000000000000011546 ) ; -#20121 = LINE ( 'NONE', #32608, #37253 ) ; -#20122 = CYLINDRICAL_SURFACE ( 'NONE', #30887, 10.00000000000000178 ) ; -#20123 = VECTOR ( 'NONE', #416, 1000.000000000000114 ) ; -#20124 = CARTESIAN_POINT ( 'NONE', ( -40.80719639505100105, 126.7988830470261092, 92.03030911972437877 ) ) ; -#20125 = VERTEX_POINT ( 'NONE', #5102 ) ; -#20126 = ORIENTED_EDGE ( 'NONE', *, *, #26133, .T. ) ; -#20127 = CARTESIAN_POINT ( 'NONE', ( 0.001369398875241253791, 310.9463197190910364, 131.4405422427762460 ) ) ; -#20128 = ORIENTED_EDGE ( 'NONE', *, *, #26635, .F. ) ; -#20129 = ORIENTED_EDGE ( 'NONE', *, *, #28159, .T. ) ; -#20130 = LINE ( 'NONE', #38948, #26992 ) ; -#20131 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#20132 = CARTESIAN_POINT ( 'NONE', ( 2.877577089652000097, 209.0276610102999939, 73.27023792178999884 ) ) ; -#20133 = ORIENTED_EDGE ( 'NONE', *, *, #14548, .F. ) ; -#20134 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971560684 ) ) ; -#20135 = EDGE_CURVE ( 'NONE', #26903, #23621, #5905, .T. ) ; -#20136 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178570922545E-05, 0.0002331579774915894113 ) ) ; -#20137 = CARTESIAN_POINT ( 'NONE', ( 37.67861426795000312, 118.9189040495000143, 87.12037504482999850 ) ) ; -#20138 = CARTESIAN_POINT ( 'NONE', ( 37.02982213692000357, 191.4383110333000104, 104.2026399808000008 ) ) ; -#20139 = ADVANCED_FACE ( 'NONE', ( #7975 ), #5245, .T. ) ; -#20140 = CARTESIAN_POINT ( 'NONE', ( -44.16761895448573227, 122.1071564039501709, 90.82511025668200944 ) ) ; -#20141 = CARTESIAN_POINT ( 'NONE', ( -26.28499170964820664, 153.7823183505510372, 185.4424242478054055 ) ) ; -#20142 = ORIENTED_EDGE ( 'NONE', *, *, #23637, .F. ) ; -#20143 = CARTESIAN_POINT ( 'NONE', ( -2.372094777808882782, 209.5677220771418376, 75.55993702015497604 ) ) ; -#20144 = LINE ( 'NONE', #11166, #35593 ) ; -#20145 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#20146 = ORIENTED_EDGE ( 'NONE', *, *, #16594, .T. ) ; -#20147 = EDGE_CURVE ( 'NONE', #15604, #35217, #31774, .T. ) ; -#20148 = CARTESIAN_POINT ( 'NONE', ( -6.037555838614446557, 134.4709255380399497, 93.58583283458662549 ) ) ; -#20149 = CARTESIAN_POINT ( 'NONE', ( 14.55482866507330009, 176.2484294118512196, 103.4132012473699973 ) ) ; -#20150 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38142, #32211, #33145, #29145 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20151 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319388554398 ) ) ; -#20152 = DIRECTION ( 'NONE', ( -0.0006039748319368717835, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#20153 = ORIENTED_EDGE ( 'NONE', *, *, #681, .F. ) ; -#20155 = EDGE_CURVE ( 'NONE', #32491, #8481, #40058, .T. ) ; -#20154 = DIRECTION ( 'NONE', ( 0.5989082241854611910, -0.8008175873178838833, -0.0003617255600150170222 ) ) ; -#20156 = CARTESIAN_POINT ( 'NONE', ( 2.503834950870377440, 190.4977034652589509, 104.1155233866760170 ) ) ; -#20157 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#20158 = CIRCLE ( 'NONE', #29318, 2.500000000039518611 ) ; -#20159 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452351231, 0.1781166614240801693 ) ) ; -#20160 = ORIENTED_EDGE ( 'NONE', *, *, #36640, .T. ) ; -#20161 = CIRCLE ( 'NONE', #15615, 6.000000000000007994 ) ; -#20162 = CARTESIAN_POINT ( 'NONE', ( -25.61323588163000053, 191.8524878963000333, 104.3050741500999976 ) ) ; -#20163 = DIRECTION ( 'NONE', ( 0.0005884949961234139590, -0.2249510543439055266, 0.9743698870671265722 ) ) ; -#20164 = VECTOR ( 'NONE', #2336, 1000.000000000000114 ) ; -#20165 = CARTESIAN_POINT ( 'NONE', ( -19.99942535523411635, 128.1006027498353319, 89.23935459048128394 ) ) ; -#20166 = LINE ( 'NONE', #10192, #34026 ) ; -#20167 = CARTESIAN_POINT ( 'NONE', ( 18.98784741603935089, 148.4369364876176292, 183.7046361175107450 ) ) ; -#20168 = VERTEX_POINT ( 'NONE', #2261 ) ; -#20169 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673505100, 126.6917321208253497, 89.40701027384199051 ) ) ; -#20170 = CARTESIAN_POINT ( 'NONE', ( -35.94456900099999785, 192.7584594706000019, 105.7490308641999945 ) ) ; -#20171 = CARTESIAN_POINT ( 'NONE', ( -2.937969491482879114, 193.8169247290916246, 102.7046841997964322 ) ) ; -#20172 = CARTESIAN_POINT ( 'NONE', ( 36.29514527253999745, 190.7638126662999980, 106.9007060872000068 ) ) ; -#20173 = DIRECTION ( 'NONE', ( 0.7933533411653060918, -0.5930537057989945238, -0.1373964268091609486 ) ) ; -#20174 = CARTESIAN_POINT ( 'NONE', ( 23.00070175390608895, 118.1131156702000169, 90.25694839687047022 ) ) ; -#20175 = CARTESIAN_POINT ( 'NONE', ( 39.76231351996260344, 182.5576203638986215, 106.5366729533402719 ) ) ; -#20176 = CARTESIAN_POINT ( 'NONE', ( -38.36106832263448752, 118.8212171802660606, 87.72011982685570786 ) ) ; -#20177 = ORIENTED_EDGE ( 'NONE', *, *, #16950, .F. ) ; -#20178 = CARTESIAN_POINT ( 'NONE', ( 14.17154132021859780, 182.3114712258959571, 104.3000443475247749 ) ) ; -#20180 = AXIS2_PLACEMENT_3D ( 'NONE', #7182, #23136, #32142 ) ; -#20179 = LINE ( 'NONE', #7715, #6694 ) ; -#20181 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561517 ) ) ; -#20182 = AXIS2_PLACEMENT_3D ( 'NONE', #36100, #1983, #8317 ) ; -#20183 = CARTESIAN_POINT ( 'NONE', ( -28.81944710292443546, 225.0820812887928071, 73.07591030630263162 ) ) ; -#20184 = VERTEX_POINT ( 'NONE', #5507 ) ; -#20185 = CARTESIAN_POINT ( 'NONE', ( 6.035604575172206054, 177.4784050041099874, 100.8918608666842260 ) ) ; -#20186 = AXIS2_PLACEMENT_3D ( 'NONE', #6748, #19214, #3472 ) ; -#20187 = EDGE_CURVE ( 'NONE', #14950, #1836, #38063, .T. ) ; -#20188 = EDGE_CURVE ( 'NONE', #35054, #14375, #14931, .T. ) ; -#20189 = CIRCLE ( 'NONE', #31305, 2.000000000000011546 ) ; -#20190 = ORIENTED_EDGE ( 'NONE', *, *, #16682, .T. ) ; -#20191 = CARTESIAN_POINT ( 'NONE', ( 22.99060780684998662, 213.5902260770751866, 73.54442216390444287 ) ) ; -#20192 = ORIENTED_EDGE ( 'NONE', *, *, #33726, .F. ) ; -#20193 = CARTESIAN_POINT ( 'NONE', ( 36.28407941860832864, 191.8749775445511148, 106.3918753536163280 ) ) ; -#20194 = CARTESIAN_POINT ( 'NONE', ( 3.566874771730911498, 167.8344183770249458, 101.4455740320023835 ) ) ; -#20195 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971568455 ) ) ; -#20196 = CARTESIAN_POINT ( 'NONE', ( 3.534237804969728280, 170.7884223425121490, 99.08043590382904142 ) ) ; -#20197 = CARTESIAN_POINT ( 'NONE', ( -3.669188902170177791, 185.6448324164332462, 103.7119811838688861 ) ) ; -#20198 = ORIENTED_EDGE ( 'NONE', *, *, #23858, .F. ) ; -#20199 = ORIENTED_EDGE ( 'NONE', *, *, #34527, .T. ) ; -#20200 = CARTESIAN_POINT ( 'NONE', ( -8.473620771760185022, 151.0652496779955811, 95.04735290400581960 ) ) ; -#20201 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33691, #30450, #18741, #31238 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20202 = CARTESIAN_POINT ( 'NONE', ( -2.955836285853710610, 208.9211498072354800, 73.12285454242802984 ) ) ; -#20203 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319374244013 ) ) ; -#20204 = CARTESIAN_POINT ( 'NONE', ( -41.90907465551327249, 121.4486244169956279, 92.84837845933365941 ) ) ; -#20205 = VERTEX_POINT ( 'NONE', #27438 ) ; -#20206 = CARTESIAN_POINT ( 'NONE', ( 19.99994977660901085, 119.8743760980646016, 87.31602173384072785 ) ) ; -#20207 = CARTESIAN_POINT ( 'NONE', ( -20.50418741012917678, 191.9757880780653068, 101.9338467359436322 ) ) ; -#20208 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#20209 = EDGE_CURVE ( 'NONE', #26904, #13401, #20512, .T. ) ; -#20210 = CARTESIAN_POINT ( 'NONE', ( -20.16668442107143022, 138.1480115094573762, 91.73025317471680751 ) ) ; -#20211 = CARTESIAN_POINT ( 'NONE', ( 18.98784741603935089, 148.4369364876176292, 183.7046361175107450 ) ) ; -#20212 = CIRCLE ( 'NONE', #40446, 7.500000256701354395 ) ; -#20213 = VECTOR ( 'NONE', #5995, 1000.000000000000114 ) ; -#20214 = LINE ( 'NONE', #35740, #15137 ) ; -#20215 = CONICAL_SURFACE ( 'NONE', #25388, 2.249999999984611421, 0.7853981634347277918 ) ; -#20216 = CARTESIAN_POINT ( 'NONE', ( -33.32951419975000107, 226.1502260771000010, 75.82863477539001451 ) ) ; -#20217 = CARTESIAN_POINT ( 'NONE', ( -2.620872059391936126, 209.0473114311415941, 75.82273480382318098 ) ) ; -#20218 = DIRECTION ( 'NONE', ( 0.9914447998358270064, 0.1271190489968018755, 0.02963032670501063170 ) ) ; -#20219 = CARTESIAN_POINT ( 'NONE', ( 26.29147157072674545, 122.5138351861346138, 87.92158889176852199 ) ) ; -#20220 = VERTEX_POINT ( 'NONE', #34503 ) ; -#20221 = CARTESIAN_POINT ( 'NONE', ( -35.75637239799589651, 166.8986143474667756, 183.3403976234064316 ) ) ; -#20222 = EDGE_CURVE ( 'NONE', #10321, #11452, #39222, .T. ) ; -#20223 = FACE_OUTER_BOUND ( 'NONE', #39355, .T. ) ; -#20224 = CARTESIAN_POINT ( 'NONE', ( -36.33853380484101336, 191.6162106434876193, 106.4168239506901301 ) ) ; -#20225 = CARTESIAN_POINT ( 'NONE', ( 18.00000000036189007, 132.9726894484250579, 90.34121456742754219 ) ) ; -#20227 = ORIENTED_EDGE ( 'NONE', *, *, #3637, .F. ) ; -#20226 = CARTESIAN_POINT ( 'NONE', ( 27.30503396996934740, 110.6131156702000027, 89.75129319167177755 ) ) ; -#20228 = ORIENTED_EDGE ( 'NONE', *, *, #13429, .F. ) ; -#20229 = ORIENTED_EDGE ( 'NONE', *, *, #3346, .T. ) ; -#20230 = ADVANCED_FACE ( 'NONE', ( #24550 ), #16123, .T. ) ; -#20231 = VERTEX_POINT ( 'NONE', #9807 ) ; -#20232 = CARTESIAN_POINT ( 'NONE', ( -26.00815500690995918, 208.2808508419710449, 76.62167493815645969 ) ) ; -#20233 = DIRECTION ( 'NONE', ( 0.7947983679126050527, -0.5912140607310475415, -0.1369725839625022812 ) ) ; -#20234 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 138.4461071782706370, 291.5876487235603918 ) ) ; -#20235 = EDGE_CURVE ( 'NONE', #21726, #4758, #3933, .T. ) ; -#20236 = EDGE_CURVE ( 'NONE', #25425, #16199, #3958, .T. ) ; -#20237 = ORIENTED_EDGE ( 'NONE', *, *, #16703, .T. ) ; -#20238 = PLANE ( 'NONE', #13309 ) ; -#20239 = AXIS2_PLACEMENT_3D ( 'NONE', #37025, #18393, #27840 ) ; -#20240 = CIRCLE ( 'NONE', #2653, 51.40509898939924938 ) ; -#20241 = DIRECTION ( 'NONE', ( 0.5634794340701355653, -0.8261300910752492621, 0.000000000000000000 ) ) ; -#20242 = CARTESIAN_POINT ( 'NONE', ( 14.29439949335858984, 129.8697084204042085, 89.96917383280258207 ) ) ; -#20243 = CARTESIAN_POINT ( 'NONE', ( -37.65475944653000084, 119.3162909960000064, 87.08039723494000839 ) ) ; -#20244 = VERTEX_POINT ( 'NONE', #381 ) ; -#20245 = EDGE_CURVE ( 'NONE', #40361, #26865, #6708, .T. ) ; -#20246 = CARTESIAN_POINT ( 'NONE', ( 30.11350050138999990, 127.0266740211999945, 89.21772768451999980 ) ) ; -#20247 = CIRCLE ( 'NONE', #35938, 2.250000000041454840 ) ; -#20248 = CIRCLE ( 'NONE', #39166, 2.000000000000011546 ) ; -#20249 = ORIENTED_EDGE ( 'NONE', *, *, #14355, .F. ) ; -#20250 = CARTESIAN_POINT ( 'NONE', ( 5.665061383869522516, 124.5483335507806260, 88.65174210881859551 ) ) ; -#20251 = CARTESIAN_POINT ( 'NONE', ( 5.669556187319027885, 130.2057153021515887, 92.59464791233423853 ) ) ; -#20252 = CARTESIAN_POINT ( 'NONE', ( -20.49970531963089115, 127.6304983849970398, 89.64427665959277647 ) ) ; -#20253 = CARTESIAN_POINT ( 'NONE', ( -3.316445002960699107, 186.7295836731814234, 102.7648477304885688 ) ) ; -#20254 = FACE_OUTER_BOUND ( 'NONE', #35751, .T. ) ; -#20255 = ORIENTED_EDGE ( 'NONE', *, *, #27450, .T. ) ; -#20256 = CARTESIAN_POINT ( 'NONE', ( -20.33427348652767463, 194.1237406430038561, 102.8453134758369742 ) ) ; -#20257 = CARTESIAN_POINT ( 'NONE', ( 20.50147078032796344, 191.2995707972209800, 106.3712455992080095 ) ) ; -#20258 = CARTESIAN_POINT ( 'NONE', ( -35.98731795423564250, 191.1787413534061670, 106.8792589541737357 ) ) ; -#20259 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #363, #12852, #25329, #2837 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20260 = ORIENTED_EDGE ( 'NONE', *, *, #32131, .T. ) ; -#20261 = DIRECTION ( 'NONE', ( -0.9999998176056756893, -1.060373006915629092E-09, 0.0006039773300193558179 ) ) ; -#20262 = CARTESIAN_POINT ( 'NONE', ( -25.63832272700906501, 212.6000592722514284, 76.07217362786134629 ) ) ; -#20263 = ORIENTED_EDGE ( 'NONE', *, *, #34225, .F. ) ; -#20264 = VERTEX_POINT ( 'NONE', #12656 ) ; -#20265 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #35862, #26907, #5414, #24035 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.679923615753293298, 4.712388980384685233 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999121686036021028, 0.9999121686036021028, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#20266 = ADVANCED_FACE ( 'NONE', ( #31688 ), #15718, .T. ) ; -#20267 = ORIENTED_EDGE ( 'NONE', *, *, #9829, .F. ) ; -#20268 = LINE ( 'NONE', #29088, #11950 ) ; -#20269 = EDGE_LOOP ( 'NONE', ( #920, #23747, #12354, #37603 ) ) ; -#20270 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825880664215480, 0.0005734119032936251361 ) ) ; -#20271 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 132.6352630048999970, 91.80276880046000088 ) ) ; -#20272 = LINE ( 'NONE', #20067, #15210 ) ; -#20273 = AXIS2_PLACEMENT_3D ( 'NONE', #8724, #15641, #11988 ) ; -#20274 = CONICAL_SURFACE ( 'NONE', #11152, 2.503068098927295537, 0.7853981634093413211 ) ; -#20275 = CARTESIAN_POINT ( 'NONE', ( -5.670114813667185949, 182.0317179319149261, 102.1523109898032828 ) ) ; -#20276 = ORIENTED_EDGE ( 'NONE', *, *, #10789, .T. ) ; -#20277 = ADVANCED_FACE ( 'NONE', ( #5920 ), #2855, .T. ) ; -#20278 = AXIS2_PLACEMENT_3D ( 'NONE', #13117, #9646, #2352 ) ; -#20279 = CARTESIAN_POINT ( 'NONE', ( 26.00345064650588256, 120.0893543522608269, 90.43463095281319397 ) ) ; -#20280 = CONICAL_SURFACE ( 'NONE', #37279, 2.503077409001481790, 0.7853981634551400193 ) ; -#20281 = DIRECTION ( 'NONE', ( 0.0006039748319390937474, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#20282 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4574, #35239, #22609, #3969, #35030, #4373, #16440, #29531, #28932, #32208 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20284 = CARTESIAN_POINT ( 'NONE', ( -42.70458103469926670, 67.79617006382294164, 322.0565592465368354 ) ) ; -#20283 = DIRECTION ( 'NONE', ( -0.0005884949961244357111, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#20285 = ORIENTED_EDGE ( 'NONE', *, *, #30889, .F. ) ; -#20286 = EDGE_CURVE ( 'NONE', #17411, #14482, #11156, .T. ) ; -#20287 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391913256 ) ) ; -#20288 = ORIENTED_EDGE ( 'NONE', *, *, #17037, .F. ) ; -#20289 = EDGE_CURVE ( 'NONE', #29223, #33670, #20307, .T. ) ; -#20290 = EDGE_CURVE ( 'NONE', #40179, #17419, #22279, .T. ) ; -#20291 = ORIENTED_EDGE ( 'NONE', *, *, #27232, .T. ) ; -#20292 = EDGE_CURVE ( 'NONE', #456, #14326, #23004, .T. ) ; -#20293 = LINE ( 'NONE', #17009, #17195 ) ; -#20294 = EDGE_CURVE ( 'NONE', #23937, #34665, #6402, .T. ) ; -#20295 = CARTESIAN_POINT ( 'NONE', ( 17.18127995227040117, 121.6259304897876774, 177.7629839600756156 ) ) ; -#20296 = DIRECTION ( 'NONE', ( 0.7066795775423997394, 4.436109046689753065E-15, -0.7075337268883338249 ) ) ; -#20297 = PLANE ( 'NONE', #18257 ) ; -#20298 = CARTESIAN_POINT ( 'NONE', ( 36.31598756814000240, 191.7186560094999948, 104.1922410006000064 ) ) ; -#20299 = VERTEX_POINT ( 'NONE', #24958 ) ; -#20300 = ORIENTED_EDGE ( 'NONE', *, *, #23613, .T. ) ; -#20301 = CARTESIAN_POINT ( 'NONE', ( -44.77033340054011745, 107.3146598463498691, 174.6956997662179560 ) ) ; -#20302 = ORIENTED_EDGE ( 'NONE', *, *, #9195, .F. ) ; -#20303 = ORIENTED_EDGE ( 'NONE', *, *, #15093, .T. ) ; -#20304 = CARTESIAN_POINT ( 'NONE', ( 5.667731215173129833, 181.6143669964321248, 104.1442412133662998 ) ) ; -#20305 = VECTOR ( 'NONE', #21853, 1000.000000000000227 ) ; -#20306 = CARTESIAN_POINT ( 'NONE', ( -38.27073585962602209, 118.2708731254052452, 89.71117186317353287 ) ) ; -#20307 = CIRCLE ( 'NONE', #26202, 4.499999385342085212 ) ; -#20308 = AXIS2_PLACEMENT_3D ( 'NONE', #6926, #28027, #15727 ) ; -#20309 = LINE ( 'NONE', #17637, #18285 ) ; -#20310 = ORIENTED_EDGE ( 'NONE', *, *, #31061, .T. ) ; -#20311 = CARTESIAN_POINT ( 'NONE', ( 39.00418697206374929, 118.8512999931317040, 89.67778981664979199 ) ) ; -#20312 = ADVANCED_FACE ( 'NONE', ( #26349 ), #35705, .F. ) ; -#20313 = CARTESIAN_POINT ( 'NONE', ( 6.028443089694566659, 134.2450043241766195, 93.72108952724657627 ) ) ; -#20314 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049013801, 181.0091974213876540, 104.5428127881306466 ) ) ; -#20315 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#20316 = VERTEX_POINT ( 'NONE', #25957 ) ; -#20317 = LINE ( 'NONE', #11134, #27129 ) ; -#20318 = CARTESIAN_POINT ( 'NONE', ( -12.63569525989105458, 131.0198822475661586, 89.90887598198150954 ) ) ; -#20319 = ORIENTED_EDGE ( 'NONE', *, *, #769, .T. ) ; -#20320 = EDGE_CURVE ( 'NONE', #12828, #28145, #13152, .T. ) ; -#20321 = PLANE ( 'NONE', #18203 ) ; -#20322 = VECTOR ( 'NONE', #37757, 1000.000000000000227 ) ; -#20323 = CARTESIAN_POINT ( 'NONE', ( -37.07468550886999736, 116.4345806408999948, 89.58399973487999546 ) ) ; -#20325 = ORIENTED_EDGE ( 'NONE', *, *, #34878, .T. ) ; -#20324 = EDGE_CURVE ( 'NONE', #29784, #38065, #30310, .T. ) ; -#20326 = AXIS2_PLACEMENT_3D ( 'NONE', #35690, #32655, #26948 ) ; -#20327 = ORIENTED_EDGE ( 'NONE', *, *, #5909, .T. ) ; -#20328 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#20329 = EDGE_CURVE ( 'NONE', #37303, #16617, #5907, .T. ) ; -#20330 = CARTESIAN_POINT ( 'NONE', ( -52.65110396967892115, 67.06234983503514968, 291.5903438827041896 ) ) ; -#20331 = CARTESIAN_POINT ( 'NONE', ( 28.46953594426098277, 131.0252485042709338, 89.88531577736306133 ) ) ; -#20332 = CARTESIAN_POINT ( 'NONE', ( -13.49923265964514307, 124.2402241865850669, 90.95213100867620426 ) ) ; -#20333 = ORIENTED_EDGE ( 'NONE', *, *, #30144, .T. ) ; -#20334 = ORIENTED_EDGE ( 'NONE', *, *, #20324, .T. ) ; -#20335 = ORIENTED_EDGE ( 'NONE', *, *, #16047, .T. ) ; -#20336 = VERTEX_POINT ( 'NONE', #29213 ) ; -#20337 = EDGE_CURVE ( 'NONE', #23280, #14032, #16599, .T. ) ; -#20338 = LINE ( 'NONE', #1530, #17808 ) ; -#20339 = CARTESIAN_POINT ( 'NONE', ( 2.704416956323000054, 209.1895506582999928, 73.41360722180999687 ) ) ; -#20340 = CARTESIAN_POINT ( 'NONE', ( 37.33701730692213516, 104.0256123824346446, 184.2143347311343859 ) ) ; -#20341 = VERTEX_POINT ( 'NONE', #13468 ) ; -#20342 = ORIENTED_EDGE ( 'NONE', *, *, #39955, .T. ) ; -#20343 = LINE ( 'NONE', #14021, #19951 ) ; -#20344 = CARTESIAN_POINT ( 'NONE', ( -32.54948526281216203, 154.4229389456382080, 204.0724398423583352 ) ) ; -#20345 = CARTESIAN_POINT ( 'NONE', ( 36.76761661513999968, 191.5224872912000080, 104.2108918073000012 ) ) ; -#20346 = CARTESIAN_POINT ( 'NONE', ( -26.00149624230000356, 120.7678355711999956, 87.55002952287999562 ) ) ; -#20347 = VERTEX_POINT ( 'NONE', #7716 ) ; -#20348 = DIRECTION ( 'NONE', ( 7.205774438685422002E-15, 0.9743700557921587402, 0.2249510932971556798 ) ) ; -#20349 = CARTESIAN_POINT ( 'NONE', ( 26.80352412410122653, 110.6131156702000027, 87.25159563508790939 ) ) ; -#20350 = ORIENTED_EDGE ( 'NONE', *, *, #28173, .T. ) ; -#20351 = CARTESIAN_POINT ( 'NONE', ( 0.6112267146314604993, 188.6153602092752806, 103.1978414123530428 ) ) ; -#20352 = CARTESIAN_POINT ( 'NONE', ( 14.17154134345668126, 176.0476639716964939, 102.8539302333655172 ) ) ; -#20353 = AXIS2_PLACEMENT_3D ( 'NONE', #35325, #28820, #34517 ) ; -#20354 = CARTESIAN_POINT ( 'NONE', ( 37.88647102489763796, 118.9430397943745135, 87.24490182366666602 ) ) ; -#20355 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; -#20356 = ORIENTED_EDGE ( 'NONE', *, *, #36409, .T. ) ; -#20357 = AXIS2_PLACEMENT_3D ( 'NONE', #36768, #30850, #25127 ) ; -#20358 = LINE ( 'NONE', #1559, #38941 ) ; -#20359 = CIRCLE ( 'NONE', #2754, 6.000000000000001776 ) ; -#20360 = CARTESIAN_POINT ( 'NONE', ( -4.037441717428633225, 144.1002716341167229, 93.43668138785120902 ) ) ; -#20361 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12034, #156, #30841, #18734 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20362 = LINE ( 'NONE', #5226, #23447 ) ; -#20363 = ORIENTED_EDGE ( 'NONE', *, *, #5340, .F. ) ; -#20364 = CARTESIAN_POINT ( 'NONE', ( 13.55367387944100521, 148.0748368286726873, 93.83050549135094798 ) ) ; -#20365 = ORIENTED_EDGE ( 'NONE', *, *, #26228, .F. ) ; -#20366 = CARTESIAN_POINT ( 'NONE', ( -25.87045016268000097, 191.8520160948000068, 104.0542010324000017 ) ) ; -#20367 = CARTESIAN_POINT ( 'NONE', ( 38.29411851305506076, 218.5902260770999987, 73.03537539447567895 ) ) ; -#20368 = CARTESIAN_POINT ( 'NONE', ( 26.15601811298000001, 191.6340342645000021, 103.7468180973999949 ) ) ; -#20369 = DIRECTION ( 'NONE', ( 0.0005884969506430524347, -0.2249510543435863097, 0.9743698870660195688 ) ) ; -#20370 = EDGE_CURVE ( 'NONE', #27000, #27115, #36638, .T. ) ; -#20371 = VERTEX_POINT ( 'NONE', #7113 ) ; -#20372 = UNCERTAINTY_MEASURE_WITH_UNIT (LENGTH_MEASURE( 1.000000000000000082E-05 ), #20638, 'distance_accuracy_value', 'NONE'); -#20373 = EDGE_CURVE ( 'NONE', #29818, #9665, #28805, .T. ) ; -#20374 = EDGE_CURVE ( 'NONE', #11012, #20941, #21569, .T. ) ; -#20375 = EDGE_CURVE ( 'NONE', #127, #38213, #36165, .T. ) ; -#20376 = CARTESIAN_POINT ( 'NONE', ( -22.78353008612967301, 154.0036580403303219, 95.56333016833679039 ) ) ; -#20377 = FACE_OUTER_BOUND ( 'NONE', #2581, .T. ) ; -#20378 = CARTESIAN_POINT ( 'NONE', ( 20.00135278145989659, 174.8851862048874182, 100.0162692476921649 ) ) ; -#20379 = CARTESIAN_POINT ( 'NONE', ( 20.14922697058586110, 211.0865878849932358, 73.21573723756705476 ) ) ; -#20380 = EDGE_CURVE ( 'NONE', #10977, #37463, #12293, .T. ) ; -#20381 = CARTESIAN_POINT ( 'NONE', ( -14.89127950026240654, 135.9758345030836892, 93.79122248673127160 ) ) ; -#20382 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#20383 = CARTESIAN_POINT ( 'NONE', ( 47.96253192634828366, 82.27946979429619034, 302.5295777741103507 ) ) ; -#20384 = LINE ( 'NONE', #20591, #33129 ) ; -#20385 = CARTESIAN_POINT ( 'NONE', ( -38.43507781192505490, 118.8935719617735458, 87.72377630256418968 ) ) ; -#20386 = ORIENTED_EDGE ( 'NONE', *, *, #13434, .T. ) ; -#20387 = ORIENTED_EDGE ( 'NONE', *, *, #19316, .T. ) ; -#20388 = CONICAL_SURFACE ( 'NONE', #21054, 3.003059068065875081, 0.7854054309186528915 ) ; -#20389 = EDGE_CURVE ( 'NONE', #1120, #34551, #31251, .T. ) ; -#20390 = CARTESIAN_POINT ( 'NONE', ( -40.45668859077597546, 220.4002261445999693, 73.08293890851697938 ) ) ; -#20391 = CIRCLE ( 'NONE', #15808, 47.49999999997262279 ) ; -#20392 = CARTESIAN_POINT ( 'NONE', ( 25.99285328132001283, 207.8686442202362343, 77.26134345908540979 ) ) ; -#20393 = EDGE_LOOP ( 'NONE', ( #39559, #2907, #8274, #2625 ) ) ; -#20394 = CARTESIAN_POINT ( 'NONE', ( 2.563994175896955774, 190.9709097722040099, 106.3045652864306874 ) ) ; -#20395 = VERTEX_POINT ( 'NONE', #32083 ) ; -#20396 = EDGE_CURVE ( 'NONE', #29495, #3941, #19067, .T. ) ; -#20397 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455648630811, -31.54510897440487938, 136.4474729010643443 ) ) ; -#20398 = CARTESIAN_POINT ( 'NONE', ( -3.169906973602109712, 126.7999172216492099, 88.92891361563410157 ) ) ; -#20399 = ORIENTED_EDGE ( 'NONE', *, *, #38791, .F. ) ; -#20400 = DIRECTION ( 'NONE', ( -0.0005884949961233868539, 0.2249510543439054988, -0.9743698870671265722 ) ) ; -#20401 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, -1.295171136338797037E-14 ) ) ; -#20402 = CARTESIAN_POINT ( 'NONE', ( -12.63503821882216194, 130.2039158256102951, 92.60614216895966422 ) ) ; -#20403 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#20404 = CARTESIAN_POINT ( 'NONE', ( 39.80650967021875175, 141.4494999055034725, 284.7279790684100931 ) ) ; -#20405 = ORIENTED_EDGE ( 'NONE', *, *, #30483, .T. ) ; -#20406 = VERTEX_POINT ( 'NONE', #1801 ) ; -#20407 = DIRECTION ( 'NONE', ( 0.0004269737726122545892, -0.7071067811864967245, 0.7071066522763517215 ) ) ; -#20408 = CARTESIAN_POINT ( 'NONE', ( -15.10537787283572619, 182.4218088933851050, 104.8563524828814764 ) ) ; -#20409 = VECTOR ( 'NONE', #27853, 1000.000000000000227 ) ; -#20410 = CARTESIAN_POINT ( 'NONE', ( 15.50147166925602527, 127.1825504195482353, 91.57172455528431954 ) ) ; -#20411 = DIRECTION ( 'NONE', ( -0.9999998268367796816, -0.0001323826439079756935, 0.0005734119341589764265 ) ) ; -#20412 = ORIENTED_EDGE ( 'NONE', *, *, #19851, .F. ) ; -#20413 = CIRCLE ( 'NONE', #2803, 4.499999998673683166 ) ; -#20414 = DIRECTION ( 'NONE', ( -0.7933530821293314217, -0.5932640870757661666, -0.1364866662427072774 ) ) ; -#20415 = CARTESIAN_POINT ( 'NONE', ( 15.10890892604210478, 182.4258086152457849, 104.8390273514353481 ) ) ; -#20416 = CARTESIAN_POINT ( 'NONE', ( -14.55132762993606477, 129.4747796237930118, 92.63223137880015656 ) ) ; -#20417 = AXIS2_PLACEMENT_3D ( 'NONE', #1062, #19854, #4326 ) ; -#20418 = FACE_OUTER_BOUND ( 'NONE', #26197, .T. ) ; -#20419 = EDGE_CURVE ( 'NONE', #21765, #19772, #11192, .T. ) ; -#20420 = EDGE_CURVE ( 'NONE', #11556, #23778, #33997, .T. ) ; -#20421 = CARTESIAN_POINT ( 'NONE', ( -40.96777089817398121, 130.0214998612392208, 92.77440595303380633 ) ) ; -#20422 = CARTESIAN_POINT ( 'NONE', ( 28.46953594426098277, 131.0252485042709338, 89.88531577736306133 ) ) ; -#20423 = CARTESIAN_POINT ( 'NONE', ( 37.73713366997999685, 118.5781713341999932, 87.34687967086999549 ) ) ; -#20424 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597599 ) ) ; -#20425 = CARTESIAN_POINT ( 'NONE', ( 26.13661543724075287, 121.9717845184987368, 87.79654014103218174 ) ) ; -#20426 = ORIENTED_EDGE ( 'NONE', *, *, #6305, .T. ) ; -#20427 = CARTESIAN_POINT ( 'NONE', ( -44.12429222051905242, 188.3338783572263253, 106.2387882118758995 ) ) ; -#20428 = DIRECTION ( 'NONE', ( -0.0006039748319375786833, -1.154910271103230591E-14, -0.9999998176071847045 ) ) ; -#20429 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#20430 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3214, #6679, #15690, #21648 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20431 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30523, #14976, #33562, #29708 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0005089247275372631900, 0.003508924730680751218 ), - .UNSPECIFIED. ) ; -#20432 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#20433 = ORIENTED_EDGE ( 'NONE', *, *, #15634, .F. ) ; -#20434 = ORIENTED_EDGE ( 'NONE', *, *, #2856, .F. ) ; -#20435 = ORIENTED_EDGE ( 'NONE', *, *, #28530, .F. ) ; -#20436 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#20437 = CIRCLE ( 'NONE', #24394, 2.499999999932184025 ) ; -#20438 = CARTESIAN_POINT ( 'NONE', ( -21.44693694427656538, 176.9185168219783009, 100.5107344958116897 ) ) ; -#20439 = VECTOR ( 'NONE', #32961, 1000.000000000000114 ) ; -#20440 = VERTEX_POINT ( 'NONE', #23681 ) ; -#20441 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#20442 = ADVANCED_FACE ( 'NONE', ( #20806, #2417, #23888 ), #29816, .F. ) ; -#20443 = AXIS2_PLACEMENT_3D ( 'NONE', #6021, #9498, #19281 ) ; -#20444 = CARTESIAN_POINT ( 'NONE', ( -36.63704418209608349, 161.0545052254310576, 189.2590029874323250 ) ) ; -#20445 = CARTESIAN_POINT ( 'NONE', ( 14.42196567089940551, 130.0116138273199624, 89.83080764171403132 ) ) ; -#20446 = CARTESIAN_POINT ( 'NONE', ( -35.83126867952999817, 112.8257052805000171, 87.67285600459000250 ) ) ; -#20447 = VERTEX_POINT ( 'NONE', #17919 ) ; -#20448 = CYLINDRICAL_SURFACE ( 'NONE', #15379, 2.000000000000001332 ) ; -#20449 = ORIENTED_EDGE ( 'NONE', *, *, #15506, .T. ) ; -#20450 = CARTESIAN_POINT ( 'NONE', ( 20.24340012504648456, 184.3478868362093124, 105.0315358237107262 ) ) ; -#20451 = CARTESIAN_POINT ( 'NONE', ( 31.94703631595417903, 124.0076240133925154, 152.6463441463639299 ) ) ; -#20452 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001011, 118.9382625071999939, 90.21260570929000266 ) ) ; -#20453 = CARTESIAN_POINT ( 'NONE', ( 23.36940079100686063, 177.7945392694463749, 100.6858723966742843 ) ) ; -#20454 = ORIENTED_EDGE ( 'NONE', *, *, #26594, .F. ) ; -#20455 = VERTEX_POINT ( 'NONE', #17720 ) ; -#20456 = CARTESIAN_POINT ( 'NONE', ( -25.88023834311999849, 191.5854047303000414, 104.0242687773999961 ) ) ; -#20457 = CARTESIAN_POINT ( 'NONE', ( 0.5757405066256999771, 188.5879547071000104, 103.1867946966000176 ) ) ; -#20458 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; -#20459 = EDGE_LOOP ( 'NONE', ( #9460, #29789, #17206, #17250 ) ) ; -#20460 = VERTEX_POINT ( 'NONE', #20597 ) ; -#20461 = DIRECTION ( 'NONE', ( 0.1943643238945209628, -0.07321898756438961764, 0.9781929714821464561 ) ) ; -#20462 = ORIENTED_EDGE ( 'NONE', *, *, #22665, .T. ) ; -#20463 = ORIENTED_EDGE ( 'NONE', *, *, #38650, .F. ) ; -#20464 = CONICAL_SURFACE ( 'NONE', #10071, 2.503093604169667863, 0.7853981634373672360 ) ; -#20465 = CIRCLE ( 'NONE', #27042, 4.500000000037911008 ) ; -#20466 = ORIENTED_EDGE ( 'NONE', *, *, #17795, .F. ) ; -#20467 = ORIENTED_EDGE ( 'NONE', *, *, #35122, .T. ) ; -#20468 = EDGE_CURVE ( 'NONE', #22597, #37703, #15109, .T. ) ; -#20469 = VECTOR ( 'NONE', #20706, 1000.000000000000227 ) ; -#20470 = ADVANCED_FACE ( 'NONE', ( #24303 ), #14885, .T. ) ; -#20471 = FACE_OUTER_BOUND ( 'NONE', #10394, .T. ) ; -#20472 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#20473 = CARTESIAN_POINT ( 'NONE', ( 23.69156854525416733, 130.3499206859899857, 92.81120348820789445 ) ) ; -#20474 = VECTOR ( 'NONE', #19237, 1000.000000000000000 ) ; -#20475 = VERTEX_POINT ( 'NONE', #32862 ) ; -#20476 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118781, 170.6398910447159949, 189.3556964435907446 ) ) ; -#20477 = ORIENTED_EDGE ( 'NONE', *, *, #23387, .F. ) ; -#20478 = CARTESIAN_POINT ( 'NONE', ( 28.44086645079000064, 124.7864354190000000, 91.35282799386999386 ) ) ; -#20479 = CARTESIAN_POINT ( 'NONE', ( -25.51924826026508342, 211.4175472833761376, 75.57438331478515181 ) ) ; -#20481 = CARTESIAN_POINT ( 'NONE', ( 10.03567519174115574, 167.9358719820149588, 100.9836731081407777 ) ) ; -#20480 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 132.6352630048999970, 91.80276880046000088 ) ) ; -#20482 = ORIENTED_EDGE ( 'NONE', *, *, #31125, .T. ) ; -#20483 = ORIENTED_EDGE ( 'NONE', *, *, #4353, .F. ) ; -#20484 = ORIENTED_EDGE ( 'NONE', *, *, #10052, .F. ) ; -#20485 = DIRECTION ( 'NONE', ( -8.673617379883984985E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#20486 = EDGE_CURVE ( 'NONE', #89, #31534, #2211, .T. ) ; -#20487 = CYLINDRICAL_SURFACE ( 'NONE', #2430, 5.999999999902005499 ) ; -#20488 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 81.56522751071939581, 291.5295797804316180 ) ) ; -#20489 = EDGE_LOOP ( 'NONE', ( #35611, #36318, #27522, #9577 ) ) ; -#20490 = AXIS2_PLACEMENT_3D ( 'NONE', #17690, #36715, #27555 ) ; -#20491 = VECTOR ( 'NONE', #37561, 1000.000000000000227 ) ; -#20492 = ORIENTED_EDGE ( 'NONE', *, *, #32395, .T. ) ; -#20493 = ORIENTED_EDGE ( 'NONE', *, *, #40436, .F. ) ; -#20494 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; -#20495 = CIRCLE ( 'NONE', #8074, 5.500000707771594222 ) ; -#20496 = FACE_OUTER_BOUND ( 'NONE', #30196, .T. ) ; -#20497 = EDGE_LOOP ( 'NONE', ( #12821, #23099, #13363, #10694 ) ) ; -#20498 = CARTESIAN_POINT ( 'NONE', ( -35.43294179687799783, 192.7873747655199850, 106.8799408643880042 ) ) ; -#20499 = CARTESIAN_POINT ( 'NONE', ( -38.44508659247977533, 118.4462124937045218, 89.70884898329646262 ) ) ; -#20500 = EDGE_CURVE ( 'NONE', #9773, #10082, #1586, .T. ) ; -#20501 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19096, #1099, #22794, #25670 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20502 = CARTESIAN_POINT ( 'NONE', ( 2.563981052588999887, 190.9709182148999957, 106.3045539368000050 ) ) ; -#20503 = ORIENTED_EDGE ( 'NONE', *, *, #37105, .F. ) ; -#20504 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; -#20505 = ADVANCED_FACE ( 'NONE', ( #39803 ), #11008, .T. ) ; -#20506 = CARTESIAN_POINT ( 'NONE', ( 39.76618942616960339, 163.8081586012825710, 187.7763762584039853 ) ) ; -#20507 = CARTESIAN_POINT ( 'NONE', ( 20.97958059557665678, 153.9356402334431095, 95.17909375711693087 ) ) ; -#20508 = LINE ( 'NONE', #29738, #16251 ) ; -#20509 = EDGE_LOOP ( 'NONE', ( #23227, #8088, #8713, #283 ) ) ; -#20510 = CARTESIAN_POINT ( 'NONE', ( 44.73086057231283519, 106.6863158914248402, 169.4405586320514487 ) ) ; -#20511 = EDGE_CURVE ( 'NONE', #5373, #30736, #2010, .T. ) ; -#20512 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17970, #30478, #39855, #8805, #11871, #36801, #21273, #33720, #33923, #3047, #9600, #18377, #22078, #576, #21875 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000038303, 0.3749999999999905076, 0.4374999999999594769, 0.4999999999999283906, 0.6249999999999291678, 0.6874999999999332756, 0.7499999999999372724, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20513 = ADVANCED_FACE ( 'NONE', ( #39602 ), #23468, .T. ) ; -#20514 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265220014, -0.1368326740407744824 ) ) ; -#20515 = DIRECTION ( 'NONE', ( -0.9999998268370088317, -0.0001323825148140369483, 0.0005734115644994438417 ) ) ; -#20516 = CIRCLE ( 'NONE', #18553, 2.500000000051350924 ) ; -#20517 = EDGE_CURVE ( 'NONE', #1633, #35236, #36085, .T. ) ; -#20518 = ADVANCED_FACE ( 'NONE', ( #18520 ), #16368, .T. ) ; -#20519 = VECTOR ( 'NONE', #40282, 1000.000000000000227 ) ; -#20520 = AXIS2_PLACEMENT_3D ( 'NONE', #30448, #27404, #33486 ) ; -#20521 = VERTEX_POINT ( 'NONE', #40408 ) ; -#20522 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32482, #23085, #16915, #19987, #26357, #7934, #23689, #32095, #987, #39403 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2498237635460164585, 0.4996475270920329170, 0.7494712906380494033, 0.9992950541840658341 ), - .UNSPECIFIED. ) ; -#20523 = FACE_OUTER_BOUND ( 'NONE', #29613, .T. ) ; -#20524 = VECTOR ( 'NONE', #12646, 1000.000000000000114 ) ; -#20526 = CARTESIAN_POINT ( 'NONE', ( 15.99970520780110483, 160.7332544674666508, 96.75156078672274873 ) ) ; -#20525 = PLANE ( 'NONE', #13527 ) ; -#20527 = ORIENTED_EDGE ( 'NONE', *, *, #34773, .F. ) ; -#20528 = FACE_OUTER_BOUND ( 'NONE', #31771, .T. ) ; -#20529 = VERTEX_POINT ( 'NONE', #2809 ) ; -#20530 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825997698160678, 0.0005734119005972442571 ) ) ; -#20531 = DIRECTION ( 'NONE', ( 0.0004270746993329993849, -0.7071067811864992780, 0.7071066522153991452 ) ) ; -#20532 = CARTESIAN_POINT ( 'NONE', ( 26.87765175238869730, 131.0250772092131228, 89.88625090952056951 ) ) ; -#20533 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971560406 ) ) ; -#20534 = EDGE_LOOP ( 'NONE', ( #21036, #16616, #30575, #169 ) ) ; -#20535 = ORIENTED_EDGE ( 'NONE', *, *, #14580, .T. ) ; -#20536 = CARTESIAN_POINT ( 'NONE', ( -42.84344863773063850, 120.8780380861919070, 92.13377048202671915 ) ) ; -#20537 = VERTEX_POINT ( 'NONE', #6657 ) ; -#20538 = ORIENTED_EDGE ( 'NONE', *, *, #18182, .F. ) ; -#20539 = DIRECTION ( 'NONE', ( 0.0005884949961246526600, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#20540 = EDGE_CURVE ( 'NONE', #16662, #10050, #12408, .T. ) ; -#20541 = CARTESIAN_POINT ( 'NONE', ( 19.31742904446021214, 125.1883107725499400, 178.1765085822854928 ) ) ; -#20542 = EDGE_LOOP ( 'NONE', ( #17366, #14847, #23528, #36496, #30152 ) ) ; -#20543 = ORIENTED_EDGE ( 'NONE', *, *, #20573, .T. ) ; -#20544 = CARTESIAN_POINT ( 'NONE', ( 20.24096834406000056, 201.9934486150999930, 90.46617277008999736 ) ) ; -#20545 = CARTESIAN_POINT ( 'NONE', ( -36.20356047594999893, 191.7540012393999973, 104.2845888805000101 ) ) ; -#20546 = CARTESIAN_POINT ( 'NONE', ( 37.37622315816000906, 191.1580451908000100, 103.8827374828999979 ) ) ; -#20547 = ORIENTED_EDGE ( 'NONE', *, *, #27017, .T. ) ; -#20548 = CARTESIAN_POINT ( 'NONE', ( -25.50343790679000122, 120.8386615232000167, 88.07942342773999655 ) ) ; -#20549 = AXIS2_PLACEMENT_3D ( 'NONE', #21611, #33652, #37723 ) ; -#20550 = ORIENTED_EDGE ( 'NONE', *, *, #29776, .F. ) ; -#20551 = CARTESIAN_POINT ( 'NONE', ( 46.04999121755292890, 184.7621468979810970, 107.4123344626420220 ) ) ; -#20552 = FACE_OUTER_BOUND ( 'NONE', #16797, .T. ) ; -#20553 = CARTESIAN_POINT ( 'NONE', ( -23.35929995763761369, 176.9091105951141571, 103.3088857729690488 ) ) ; -#20554 = EDGE_LOOP ( 'NONE', ( #34188, #30139, #39352, #7668 ) ) ; -#20555 = AXIS2_PLACEMENT_3D ( 'NONE', #5439, #36525, #20572 ) ; -#20556 = CONICAL_SURFACE ( 'NONE', #19893, 47.99999999999141664, 0.7853981633972882959 ) ; -#20557 = ADVANCED_FACE ( 'NONE', ( #3195 ), #34265, .F. ) ; -#20558 = CARTESIAN_POINT ( 'NONE', ( 0.6442863471694358912, 188.6132303553982865, 103.1973297295617442 ) ) ; -#20559 = FACE_OUTER_BOUND ( 'NONE', #5917, .T. ) ; -#20560 = VECTOR ( 'NONE', #31415, 1000.000000000000000 ) ; -#20561 = DIRECTION ( 'NONE', ( 0.0006039748319388572829, 3.099784637799882324E-15, 0.9999998176071847045 ) ) ; -#20562 = CARTESIAN_POINT ( 'NONE', ( 44.99461912816793330, 186.3824492941473352, 106.8827324323605268 ) ) ; -#20563 = ORIENTED_EDGE ( 'NONE', *, *, #5508, .T. ) ; -#20564 = CARTESIAN_POINT ( 'NONE', ( 15.50147166947062871, 184.4041534623167991, 104.7823749529912760 ) ) ; -#20565 = ADVANCED_FACE ( 'NONE', ( #30823 ), #4635, .F. ) ; -#20566 = CARTESIAN_POINT ( 'NONE', ( -25.99734782913206388, 118.8155664120999973, 94.28348731542583039 ) ) ; -#20567 = CARTESIAN_POINT ( 'NONE', ( 25.50832794965532457, 194.2771770615957507, 102.8828691708982035 ) ) ; -#20568 = ADVANCED_FACE ( 'NONE', ( #6070 ), #8572, .T. ) ; -#20569 = VERTEX_POINT ( 'NONE', #40014 ) ; -#20570 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366368657916, 137.4659008082770697, 177.5714312369256049 ) ) ; -#20571 = EDGE_LOOP ( 'NONE', ( #3453, #32616, #29455, #14279 ) ) ; -#20572 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971572064 ) ) ; -#20573 = EDGE_CURVE ( 'NONE', #33199, #11353, #13649, .T. ) ; -#20574 = FACE_OUTER_BOUND ( 'NONE', #30016, .T. ) ; -#20575 = CARTESIAN_POINT ( 'NONE', ( 25.42017281157999875, 191.1447232209999925, 104.4148045236999991 ) ) ; -#20576 = CARTESIAN_POINT ( 'NONE', ( 16.00178211024919861, 127.0692136201035680, 92.05841426505114100 ) ) ; -#20577 = ADVANCED_FACE ( 'NONE', ( #31028 ), #9754, .T. ) ; -#20578 = CARTESIAN_POINT ( 'NONE', ( -21.01972750631221132, 212.6267245168959903, 75.57113062347616506 ) ) ; -#20579 = CARTESIAN_POINT ( 'NONE', ( 30.08094848415407796, 173.6961895202413189, 152.7448404810986062 ) ) ; -#20580 = ORIENTED_EDGE ( 'NONE', *, *, #12544, .F. ) ; -#20581 = CARTESIAN_POINT ( 'NONE', ( 36.05442839919999898, 113.8881156701999942, 88.74600859430999833 ) ) ; -#20582 = CARTESIAN_POINT ( 'NONE', ( 18.08181496610683325, 152.6337752236594270, 184.7490501355361232 ) ) ; -#20583 = AXIS2_PLACEMENT_3D ( 'NONE', #24528, #31052, #3418 ) ; -#20584 = FACE_OUTER_BOUND ( 'NONE', #5730, .T. ) ; -#20586 = VECTOR ( 'NONE', #37361, 1000.000000000000227 ) ; -#20585 = CARTESIAN_POINT ( 'NONE', ( -75.43109585698152841, 195.4393986266174750, 195.0604493769935459 ) ) ; -#20587 = CARTESIAN_POINT ( 'NONE', ( 21.60217933682451985, 154.2468726602517393, 95.25057140358079266 ) ) ; -#20588 = FACE_OUTER_BOUND ( 'NONE', #4665, .T. ) ; -#20589 = CARTESIAN_POINT ( 'NONE', ( 37.19332676460864917, 118.8604558150308463, 122.9910815359075116 ) ) ; -#20590 = AXIS2_PLACEMENT_3D ( 'NONE', #22575, #28901, #37693 ) ; -#20591 = CARTESIAN_POINT ( 'NONE', ( -22.49964039506760471, 137.3544959182455045, 178.0533373667986439 ) ) ; -#20592 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #40043, #24538, #5086, #33301, #21468, #17549, #5295, #17753, #25740, #25538, #31060 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999995211608, 0.3749999999993379185, 0.4374999999992462696, 0.4687499999992686961, 0.4999999999992911226, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20593 = CARTESIAN_POINT ( 'NONE', ( -13.83205090698264605, 124.7811071226292938, 174.0455584457899079 ) ) ; -#20594 = CARTESIAN_POINT ( 'NONE', ( 21.98730234560195029, 115.2895908701552798, 90.25450505954673019 ) ) ; -#20595 = VERTEX_POINT ( 'NONE', #37354 ) ; -#20596 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971549859 ) ) ; -#20597 = CARTESIAN_POINT ( 'NONE', ( 17.15851712144672447, 126.2135305925408062, 179.0798665085958703 ) ) ; -#20598 = VERTEX_POINT ( 'NONE', #2618 ) ; -#20599 = CARTESIAN_POINT ( 'NONE', ( 5.663781961983408664, 181.7799031239528631, 101.7404227914676937 ) ) ; -#20600 = CARTESIAN_POINT ( 'NONE', ( 3.953345342120641259, 136.7756878582844706, 93.87799634107939539 ) ) ; -#20601 = ORIENTED_EDGE ( 'NONE', *, *, #28253, .T. ) ; -#20602 = CARTESIAN_POINT ( 'NONE', ( 13.51095425345201129, 187.6707999454940818, 106.0508869016509266 ) ) ; -#20603 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#20604 = ORIENTED_EDGE ( 'NONE', *, *, #2853, .F. ) ; -#20605 = CARTESIAN_POINT ( 'NONE', ( 36.27208580333611110, 191.8965914794161449, 106.3926531859080171 ) ) ; -#20606 = EDGE_CURVE ( 'NONE', #30446, #13611, #9352, .T. ) ; -#20607 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9131, #20995, #15464, #40186 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20608 = EDGE_CURVE ( 'NONE', #21069, #28767, #27376, .T. ) ; -#20609 = VECTOR ( 'NONE', #33065, 1000.000000000000114 ) ; -#20610 = DIRECTION ( 'NONE', ( -0.0001358700408348381271, -0.9743680519818410657, -0.2249597315442128931 ) ) ; -#20612 = EDGE_CURVE ( 'NONE', #27638, #7714, #36616, .T. ) ; -#20611 = CARTESIAN_POINT ( 'NONE', ( 21.83022412997393502, 182.7623874074516266, 102.3469123272103189 ) ) ; -#20613 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564847 ) ) ; -#20614 = CARTESIAN_POINT ( 'NONE', ( -2.954034027524032879, 205.1071153523706698, 76.10666676075513237 ) ) ; -#20615 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#20616 = ORIENTED_EDGE ( 'NONE', *, *, #5400, .T. ) ; -#20617 = ORIENTED_EDGE ( 'NONE', *, *, #62, .F. ) ; -#20618 = CARTESIAN_POINT ( 'NONE', ( 39.79355934349000989, 120.0246790264999959, 87.73041059682999787 ) ) ; -#20619 = CARTESIAN_POINT ( 'NONE', ( -28.46708276390721792, 128.4693973224412105, 89.84276394412744082 ) ) ; -#20620 = CARTESIAN_POINT ( 'NONE', ( 28.52919418227002879, 125.2871234584923883, 88.56050369811191558 ) ) ; -#20621 = AXIS2_PLACEMENT_3D ( 'NONE', #22483, #12267, #21879 ) ; -#20622 = CARTESIAN_POINT ( 'NONE', ( 22.54464659634000157, 110.3681964162000071, 162.9824824849000322 ) ) ; -#20623 = AXIS2_PLACEMENT_3D ( 'NONE', #16430, #7227, #19694 ) ; -#20624 = ORIENTED_EDGE ( 'NONE', *, *, #28033, .T. ) ; -#20625 = CARTESIAN_POINT ( 'NONE', ( 39.31997709954917042, 182.6349382312036767, 104.8726857259417926 ) ) ; -#20626 = CARTESIAN_POINT ( 'NONE', ( -42.30728356964600323, 121.5171895888447722, 91.19632820234058102 ) ) ; -#20627 = DIRECTION ( 'NONE', ( 0.0005884949961249847511, -0.2249510543439063592, 0.9743698870671262391 ) ) ; -#20628 = CARTESIAN_POINT ( 'NONE', ( -2.954034027429888631, 205.1071153524133308, 76.10666676077315174 ) ) ; -#20629 = CARTESIAN_POINT ( 'NONE', ( -2.937264483575730001, 191.5260295967991340, 103.8719657111370367 ) ) ; -#20630 = ADVANCED_FACE ( 'NONE', ( #40207 ), #12020, .T. ) ; -#20631 = CARTESIAN_POINT ( 'NONE', ( 20.00175897098971589, 118.8155681873422651, 90.25573236258343002 ) ) ; -#20632 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#20633 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3913, #15588, #34573, #34966, #31542, #12517, #3503, #19451, #12940, #9875 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20634 = FACE_OUTER_BOUND ( 'NONE', #22638, .T. ) ; -#20635 = DIRECTION ( 'NONE', ( -0.7856637149787866203, 0.6186538021912836305, 0.000000000000000000 ) ) ; -#20636 = CARTESIAN_POINT ( 'NONE', ( -2.954012481561790970, 209.1419323005786737, 76.14255792608456375 ) ) ; -#20637 = EDGE_CURVE ( 'NONE', #6941, #19724, #37747, .T. ) ; -#20638 =( LENGTH_UNIT ( ) NAMED_UNIT ( * ) SI_UNIT ( .MILLI., .METRE. ) ); -#20639 = DIRECTION ( 'NONE', ( -2.580909394681725950E-08, 0.9743700499795614478, 0.2249511184742725434 ) ) ; -#20640 = ORIENTED_EDGE ( 'NONE', *, *, #17551, .T. ) ; -#20641 = LINE ( 'NONE', #32906, #25088 ) ; -#20642 = DIRECTION ( 'NONE', ( 0.0006039748319395906373, 1.314021223879979485E-14, 0.9999998176071844824 ) ) ; -#20643 = CARTESIAN_POINT ( 'NONE', ( 32.36187368851994961, 209.7096486318000075, 76.03895886878429167 ) ) ; -#20644 = CARTESIAN_POINT ( 'NONE', ( -20.38344128331733174, 116.5964058994408674, 87.28009537979973231 ) ) ; -#20645 = CONICAL_SURFACE ( 'NONE', #3010, 2.503093604169667863, 0.7853981634373672360 ) ; -#20646 = LINE ( 'NONE', #17564, #36973 ) ; -#20647 = AXIS2_PLACEMENT_3D ( 'NONE', #35037, #9945, #7049 ) ; -#20648 = ORIENTED_EDGE ( 'NONE', *, *, #23038, .T. ) ; -#20649 = VERTEX_POINT ( 'NONE', #24504 ) ; -#20650 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#20651 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23691, #30022, #29423, #32484, #8143, #35715, #11217, #1394, #4248, #23087, #8356, #35511, #20605, #33073, #11410, #20193, #1599, #26972, #7936, #16917, #16726, #29224, #14085, #7524, #13871, #26359, #38797, #7726, #26562, #32683 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 1, 1, 2, 2, 2, 2, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.06250000000189853688, 0.1250000000037970738, 0.1875000000056956106, 0.2187500000066624761, 0.2343750000071459227, 0.2421875000073611395, 0.2460937500074432405, 0.2500000000075253137, 0.3750000000075452422, 0.4375000000075314199, 0.4687500000075252027, 0.4843750000075221496, 0.4921875000075311424, 0.4960937500075226492, 0.4980468750075085493, 0.5000000000074944495, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20652 = ORIENTED_EDGE ( 'NONE', *, *, #32799, .T. ) ; -#20653 = CARTESIAN_POINT ( 'NONE', ( 77.66418106072950422, 192.0495531737880697, 194.3144031859467020 ) ) ; -#20654 = AXIS2_PLACEMENT_3D ( 'NONE', #22880, #13470, #34505 ) ; -#20655 = DIRECTION ( 'NONE', ( 0.7933533405432852126, -0.5930537065887689918, -0.1373964269918706016 ) ) ; -#20656 = AXIS2_PLACEMENT_3D ( 'NONE', #27034, #18193, #12088 ) ; -#20657 = ORIENTED_EDGE ( 'NONE', *, *, #16538, .F. ) ; -#20658 = EDGE_LOOP ( 'NONE', ( #26482, #5162, #15595, #17667 ) ) ; -#20659 = CARTESIAN_POINT ( 'NONE', ( -15.99998595512920652, 185.9065961375156348, 102.5825112407314634 ) ) ; -#20660 = DIRECTION ( 'NONE', ( 0.0005884949961156549746, -0.2249510543439098842, 0.9743698870671255730 ) ) ; -#20661 = CARTESIAN_POINT ( 'NONE', ( 20.16571866901157151, 193.9703124975374067, 102.7561131839733122 ) ) ; -#20662 = CARTESIAN_POINT ( 'NONE', ( -37.42772058735000229, 118.3648470007000100, 87.39136188095001501 ) ) ; -#20663 = ORIENTED_EDGE ( 'NONE', *, *, #13267, .F. ) ; -#20664 = CARTESIAN_POINT ( 'NONE', ( -42.07083071865692858, 121.3276643233232619, 92.82055031282301627 ) ) ; -#20665 = EDGE_CURVE ( 'NONE', #19923, #372, #20973, .T. ) ; -#20666 = VERTEX_POINT ( 'NONE', #15287 ) ; -#20668 = EDGE_CURVE ( 'NONE', #13982, #1155, #31836, .T. ) ; -#20667 = CARTESIAN_POINT ( 'NONE', ( 16.55946513390808406, 121.8573583107191780, 177.5776958584335148 ) ) ; -#20669 = LINE ( 'NONE', #11470, #6391 ) ; -#20670 = EDGE_CURVE ( 'NONE', #1120, #37138, #25909, .T. ) ; -#20671 = FACE_OUTER_BOUND ( 'NONE', #11980, .T. ) ; -#20672 = CARTESIAN_POINT ( 'NONE', ( 39.70674893776387648, 114.9516458920610660, 150.7368254606779772 ) ) ; -#20673 = ORIENTED_EDGE ( 'NONE', *, *, #29904, .F. ) ; -#20674 = CARTESIAN_POINT ( 'NONE', ( -2.620399866750759532, 189.8256140888599930, 103.4746636074519870 ) ) ; -#20675 = CARTESIAN_POINT ( 'NONE', ( 0.5625186772154999737, 188.8757079055000077, 103.5281422730000003 ) ) ; -#20676 = CARTESIAN_POINT ( 'NONE', ( -35.84664934362761812, 191.3612728695171654, 106.9073814223122838 ) ) ; -#20677 = EDGE_CURVE ( 'NONE', #11101, #14526, #13022, .T. ) ; -#20678 = VECTOR ( 'NONE', #28205, 1000.000000000000114 ) ; -#20679 = EDGE_LOOP ( 'NONE', ( #20801, #19350, #27648, #23619 ) ) ; -#20680 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265227786, 0.1368326740407719844 ) ) ; -#20681 = CONICAL_SURFACE ( 'NONE', #26557, 2.502986411962893953, 0.7853981633941236051 ) ; -#20682 = ORIENTED_EDGE ( 'NONE', *, *, #6435, .F. ) ; -#20683 = CIRCLE ( 'NONE', #19358, 4.500000000175836234 ) ; -#20684 = ADVANCED_FACE ( 'NONE', ( #35261 ), #10525, .F. ) ; -#20685 = VECTOR ( 'NONE', #40159, 1000.000000000000114 ) ; -#20686 = VERTEX_POINT ( 'NONE', #10363 ) ; -#20687 = ORIENTED_EDGE ( 'NONE', *, *, #15330, .F. ) ; -#20688 = CARTESIAN_POINT ( 'NONE', ( 3.062737380639022344, 196.5784460000043055, 103.8732377138169483 ) ) ; -#20689 = CARTESIAN_POINT ( 'NONE', ( -20.01904012474069106, 206.5436284133448055, 74.17009909478734642 ) ) ; -#20690 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#20691 = EDGE_CURVE ( 'NONE', #8706, #31838, #35293, .T. ) ; -#20692 = ORIENTED_EDGE ( 'NONE', *, *, #577, .T. ) ; -#20693 = LINE ( 'NONE', #20068, #29094 ) ; -#20694 = ORIENTED_EDGE ( 'NONE', *, *, #10229, .F. ) ; -#20695 = CARTESIAN_POINT ( 'NONE', ( 25.56568947770999856, 121.0913649998000068, 90.15922698159999982 ) ) ; -#20696 = LINE ( 'NONE', #4948, #37829 ) ; -#20698 = PLANE ( 'NONE', #27302 ) ; -#20697 = CARTESIAN_POINT ( 'NONE', ( 44.41839271451227233, 188.4409858425211155, 106.0389898025652684 ) ) ; -#20699 = VERTEX_POINT ( 'NONE', #35658 ) ; -#20700 = ORIENTED_EDGE ( 'NONE', *, *, #39876, .F. ) ; -#20701 = AXIS2_PLACEMENT_3D ( 'NONE', #22269, #28397, #14213 ) ; -#20702 = CARTESIAN_POINT ( 'NONE', ( -36.01025967986358012, 192.1075852240773827, 104.4279189550095168 ) ) ; -#20703 = AXIS2_PLACEMENT_3D ( 'NONE', #14329, #39450, #30070 ) ; -#20704 = CONICAL_SURFACE ( 'NONE', #4376, 4.999999999982071230, 0.7853981633822315622 ) ; -#20705 = ORIENTED_EDGE ( 'NONE', *, *, #31850, .T. ) ; -#20706 = DIRECTION ( 'NONE', ( 0.0001358647818257961324, 0.9743700622685637081, 0.2249510242153081319 ) ) ; -#20707 = LINE ( 'NONE', #27070, #38975 ) ; -#20708 = CARTESIAN_POINT ( 'NONE', ( 13.50176625667807428, 160.0671410552039333, 99.67807866355113333 ) ) ; -#20709 = CARTESIAN_POINT ( 'NONE', ( 36.11507279325000042, 191.5161335024000095, 103.8351628704999996 ) ) ; -#20710 = ORIENTED_EDGE ( 'NONE', *, *, #30044, .T. ) ; -#20711 = ORIENTED_EDGE ( 'NONE', *, *, #33811, .F. ) ; -#20712 = EDGE_LOOP ( 'NONE', ( #29360, #35800, #21297, #25962 ) ) ; -#20713 = ADVANCED_FACE ( 'NONE', ( #4189 ), #25709, .T. ) ; -#20714 = CARTESIAN_POINT ( 'NONE', ( -35.44629553178003079, 0.000000000000000000, 90.28919351349927069 ) ) ; -#20715 = EDGE_CURVE ( 'NONE', #30682, #11066, #27540, .T. ) ; -#20716 = CARTESIAN_POINT ( 'NONE', ( 15.85327786988247745, 186.7325363318280722, 102.7539513733114802 ) ) ; -#20717 = ORIENTED_EDGE ( 'NONE', *, *, #26774, .F. ) ; -#20718 = CARTESIAN_POINT ( 'NONE', ( 30.06787517242528551, 135.1370919582721228, 91.12677150993297914 ) ) ; -#20719 = EDGE_LOOP ( 'NONE', ( #21812, #34904, #1326, #28014 ) ) ; -#20720 = CARTESIAN_POINT ( 'NONE', ( 2.897653083742676383, 190.9155335423768349, 106.6359108618391645 ) ) ; -#20721 = VERTEX_POINT ( 'NONE', #13619 ) ; -#20722 = CARTESIAN_POINT ( 'NONE', ( -20.51956765322097453, 208.6217303766487419, 73.70372706148434361 ) ) ; -#20723 = DIRECTION ( 'NONE', ( -0.0005884949961245237483, 0.2249510543439061649, -0.9743698870671263501 ) ) ; -#20724 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1819, #8371, #39626, #23295 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20725 = FACE_OUTER_BOUND ( 'NONE', #33759, .T. ) ; -#20726 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#20727 = VECTOR ( 'NONE', #2123, 1000.000000000000000 ) ; -#20728 = EDGE_LOOP ( 'NONE', ( #22946, #11279, #34266, #17605 ) ) ; -#20729 = DIRECTION ( 'NONE', ( -0.0005884949954653724124, 0.2249971753701230093, -0.9743592380375456496 ) ) ; -#20730 = AXIS2_PLACEMENT_3D ( 'NONE', #36226, #14576, #2509 ) ; -#20731 = CARTESIAN_POINT ( 'NONE', ( 22.99181599359000217, 213.5902260771004819, 75.54481431629028521 ) ) ; -#20732 = EDGE_CURVE ( 'NONE', #17419, #15229, #32231, .T. ) ; -#20733 = VERTEX_POINT ( 'NONE', #19339 ) ; -#20734 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971562904 ) ) ; -#20735 = CARTESIAN_POINT ( 'NONE', ( 15.93316958989016108, 160.0956563697703245, 96.60429370500047241 ) ) ; -#20736 = ORIENTED_EDGE ( 'NONE', *, *, #6537, .F. ) ; -#20737 = ORIENTED_EDGE ( 'NONE', *, *, #22290, .T. ) ; -#20738 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387284797 ) ) ; -#20739 = VERTEX_POINT ( 'NONE', #31633 ) ; -#20740 = CARTESIAN_POINT ( 'NONE', ( 20.00025828646017345, 174.5279639952516106, 99.93388581131628712 ) ) ; -#20741 = EDGE_CURVE ( 'NONE', #11269, #14324, #26850, .T. ) ; -#20742 = CARTESIAN_POINT ( 'NONE', ( 25.50924666640047178, 191.9759150222000130, 104.4060420921210692 ) ) ; -#20743 = CARTESIAN_POINT ( 'NONE', ( 6.035971952557307674, 174.6806538430182911, 103.0595719845621261 ) ) ; -#20744 = ORIENTED_EDGE ( 'NONE', *, *, #16923, .F. ) ; -#20745 = EDGE_LOOP ( 'NONE', ( #226, #28135 ) ) ; -#20746 = CARTESIAN_POINT ( 'NONE', ( -37.68439733255148383, 188.7463803737940395, 106.3301322885044016 ) ) ; -#20747 = EDGE_LOOP ( 'NONE', ( #37801, #18266, #13620, #26239 ) ) ; -#20748 = ORIENTED_EDGE ( 'NONE', *, *, #20670, .F. ) ; -#20749 = CARTESIAN_POINT ( 'NONE', ( 12.63456555637604772, 128.5879888860239078, 89.32908754111066685 ) ) ; -#20750 = CARTESIAN_POINT ( 'NONE', ( 2.941287612453000300, 209.7096559091000074, 73.05672761937999837 ) ) ; -#20751 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#20752 = ORIENTED_EDGE ( 'NONE', *, *, #5855, .F. ) ; -#20753 = CONICAL_SURFACE ( 'NONE', #3127, 4.999999999934928496, 0.7853981633665815254 ) ; -#20754 = ORIENTED_EDGE ( 'NONE', *, *, #4073, .F. ) ; -#20755 = CYLINDRICAL_SURFACE ( 'NONE', #2351, 6.000000000000001776 ) ; -#20756 = ADVANCED_FACE ( 'NONE', ( #16665 ), #5277, .F. ) ; -#20757 = CARTESIAN_POINT ( 'NONE', ( -36.19862354458000198, 191.7578647985999964, 104.2851651960999959 ) ) ; -#20758 = CARTESIAN_POINT ( 'NONE', ( 38.06062437970000190, 191.5239802229999952, 104.5086379071999971 ) ) ; -#20759 = EDGE_CURVE ( 'NONE', #21867, #15824, #9889, .T. ) ; -#20760 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20002, #13290, #28627, #16527 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( -0.0005424209979737538209, 0.0007183273991515231899 ), - .UNSPECIFIED. ) ; -#20761 = CARTESIAN_POINT ( 'NONE', ( -25.50098156286000162, 120.6553366659000091, 88.03708033630999807 ) ) ; -#20762 = CONICAL_SURFACE ( 'NONE', #12283, 2.503093757893994464, 0.7853981633779187899 ) ; -#20763 = ADVANCED_FACE ( 'NONE', ( #32428 ), #16075, .F. ) ; -#20764 = ORIENTED_EDGE ( 'NONE', *, *, #6616, .T. ) ; -#20765 = CARTESIAN_POINT ( 'NONE', ( 3.882702609227124846, 148.9606115484772602, 129.9617790688552077 ) ) ; -#20766 = ORIENTED_EDGE ( 'NONE', *, *, #14189, .F. ) ; -#20767 = CARTESIAN_POINT ( 'NONE', ( 26.00773540302725451, 191.9759150222000130, 101.9057393198873882 ) ) ; -#20768 = LINE ( 'NONE', #8304, #12377 ) ; -#20769 = ORIENTED_EDGE ( 'NONE', *, *, #24206, .T. ) ; -#20770 = CARTESIAN_POINT ( 'NONE', ( -6.037342800704852408, 134.5082041216288644, 93.56253848326802824 ) ) ; -#20771 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#20772 = CARTESIAN_POINT ( 'NONE', ( 28.46561152637904257, 183.4536495838093231, 105.0682559342871798 ) ) ; -#20773 = CARTESIAN_POINT ( 'NONE', ( 44.88097455134456482, 186.3872722715140355, 107.5207334959314807 ) ) ; -#20774 = ORIENTED_EDGE ( 'NONE', *, *, #31268, .F. ) ; -#20775 = DIRECTION ( 'NONE', ( 0.0005884949961219661154, -0.2249510543439071364, 0.9743698870671262391 ) ) ; -#20776 = CARTESIAN_POINT ( 'NONE', ( -76.10807331611901816, 155.7750440820818199, 98.22815292147129185 ) ) ; -#20777 = CARTESIAN_POINT ( 'NONE', ( -15.99985838160595719, 147.3843139169566712, 93.68908089291861074 ) ) ; -#20778 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24834, #37479, #30954, #21957 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20779 = ORIENTED_EDGE ( 'NONE', *, *, #3901, .F. ) ; -#20780 = FACE_OUTER_BOUND ( 'NONE', #31948, .T. ) ; -#20781 = ORIENTED_EDGE ( 'NONE', *, *, #19905, .T. ) ; -#20782 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971571509 ) ) ; -#20783 = CARTESIAN_POINT ( 'NONE', ( -35.78841217721779344, 209.7096535896600358, 75.74678653814358142 ) ) ; -#20784 = CARTESIAN_POINT ( 'NONE', ( 25.62658393337000007, 191.8386319365000077, 104.2890221055999973 ) ) ; -#20785 = CARTESIAN_POINT ( 'NONE', ( -16.53460274203917635, 121.8354022778151204, 177.5673403339679055 ) ) ; -#20786 = LINE ( 'NONE', #27150, #30406 ) ; -#20787 = CARTESIAN_POINT ( 'NONE', ( 30.06878009388999473, 135.2977368436336292, 91.38385643049517171 ) ) ; -#20788 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#20789 = EDGE_LOOP ( 'NONE', ( #20535, #12205, #22867, #15259 ) ) ; -#20790 = CIRCLE ( 'NONE', #3150, 2.250000000025644820 ) ; -#20791 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971561239 ) ) ; -#20792 = CARTESIAN_POINT ( 'NONE', ( 20.08022773305264863, 175.2265315334001912, 100.0950274021143542 ) ) ; -#20793 = CARTESIAN_POINT ( 'NONE', ( 5.659893952243699289, 181.0147214850249782, 104.5189528120545646 ) ) ; -#20794 = EDGE_CURVE ( 'NONE', #25434, #7776, #34857, .T. ) ; -#20795 = CARTESIAN_POINT ( 'NONE', ( 41.43279363010753258, 73.81335444380819411, 323.3949191073975271 ) ) ; -#20796 = CARTESIAN_POINT ( 'NONE', ( 0.04427648338465999672, 211.2500000000000000, 73.30847738610999897 ) ) ; -#20797 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2490, #2700, #31101, #27463, #8832, #20885 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.0009283347615722905340, 0.001856669523144581068 ), - .UNSPECIFIED. ) ; -#20798 = CARTESIAN_POINT ( 'NONE', ( -38.93769506783858958, 183.1686750955933576, 104.5300206044594091 ) ) ; -#20799 = CARTESIAN_POINT ( 'NONE', ( 37.96499115479794284, 190.9636352758437567, 106.2831835360932615 ) ) ; -#20800 = CARTESIAN_POINT ( 'NONE', ( 22.53004187958038784, 115.1395609704796641, 90.25417725846811834 ) ) ; -#20801 = ORIENTED_EDGE ( 'NONE', *, *, #20085, .T. ) ; -#20802 = ORIENTED_EDGE ( 'NONE', *, *, #947, .T. ) ; -#20803 = CARTESIAN_POINT ( 'NONE', ( 3.776208428536367290, 144.1607590108100396, 93.18099764601012680 ) ) ; -#20804 = EDGE_CURVE ( 'NONE', #31462, #19997, #19928, .T. ) ; -#20805 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1554, #30185, #20354, #36308 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20806 = FACE_BOUND ( 'NONE', #2850, .T. ) ; -#20807 = EDGE_LOOP ( 'NONE', ( #38219, #10823, #37540, #21575 ) ) ; -#20808 = DIRECTION ( 'NONE', ( 0.0005884949961209279918, -0.2249510543439041388, 0.9743698870671267942 ) ) ; -#20810 = ADVANCED_FACE ( 'NONE', ( #22635 ), #35059, .F. ) ; -#20809 = CARTESIAN_POINT ( 'NONE', ( -22.60121221446328121, 115.1131394343234859, 90.28143540504643738 ) ) ; -#20811 = EDGE_CURVE ( 'NONE', #18343, #25248, #25401, .T. ) ; -#20812 = VERTEX_POINT ( 'NONE', #33011 ) ; -#20813 = CARTESIAN_POINT ( 'NONE', ( -38.39707737110000352, 119.0972084867999996, 87.58953676641999664 ) ) ; -#20814 = EDGE_CURVE ( 'NONE', #2286, #28821, #18699, .T. ) ; -#20815 = AXIS2_PLACEMENT_3D ( 'NONE', #16562, #20037, #28660 ) ; -#20816 = ADVANCED_FACE ( 'NONE', ( #14423 ), #1298, .F. ) ; -#20817 = CARTESIAN_POINT ( 'NONE', ( -31.95188145317385420, 152.7252871959512106, 28.25650152248850944 ) ) ; -#20818 = VERTEX_POINT ( 'NONE', #7671 ) ; -#20819 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560129 ) ) ; -#20820 = AXIS2_PLACEMENT_3D ( 'NONE', #33745, #21699, #6336 ) ; -#20821 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 3.780719906273090593E-12, 291.5295797804326980 ) ) ; -#20822 = AXIS2_PLACEMENT_3D ( 'NONE', #3520, #3733, #31970 ) ; -#20823 = CARTESIAN_POINT ( 'NONE', ( 12.64700864260225366, 177.1180462903230364, 103.6150826217330803 ) ) ; -#20824 = CARTESIAN_POINT ( 'NONE', ( 3.534206243108678702, 168.5015396740323581, 98.55243403413919623 ) ) ; -#20825 = AXIS2_PLACEMENT_3D ( 'NONE', #24532, #30046, #20838 ) ; -#20826 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; -#20827 = ORIENTED_EDGE ( 'NONE', *, *, #2120, .F. ) ; -#20828 = CARTESIAN_POINT ( 'NONE', ( 38.13084791448000033, 119.4318491095000070, 87.14044217235999668 ) ) ; -#20829 = PLANE ( 'NONE', #20520 ) ; -#20830 = CARTESIAN_POINT ( 'NONE', ( -15.49970618539471268, 185.7934281236995844, 103.0692296848312282 ) ) ; -#20831 = VERTEX_POINT ( 'NONE', #30367 ) ; -#20832 = CARTESIAN_POINT ( 'NONE', ( -20.51745969899640087, 207.4083551867479116, 77.09396086730279762 ) ) ; -#20833 = ORIENTED_EDGE ( 'NONE', *, *, #21789, .F. ) ; -#20834 = CARTESIAN_POINT ( 'NONE', ( 15.66829157622652602, 173.9153742532822662, 102.5318555933223479 ) ) ; -#20835 = CARTESIAN_POINT ( 'NONE', ( -43.29012348651439623, 120.5557648100765249, 92.00614762530858570 ) ) ; -#20836 = PLANE ( 'NONE', #30049 ) ; -#20837 = DIRECTION ( 'NONE', ( 0.0003164010435218795225, -0.8480480961507480542, 0.5299191697848559812 ) ) ; -#20838 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971574562 ) ) ; -#20839 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21747, #12518, #31343, #5987 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20840 = FACE_OUTER_BOUND ( 'NONE', #12425, .T. ) ; -#20841 = AXIS2_PLACEMENT_3D ( 'NONE', #38363, #538, #940 ) ; -#20842 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#20843 = CARTESIAN_POINT ( 'NONE', ( 38.70942909611000005, 119.0583547086000067, 90.11453506928999957 ) ) ; -#20844 = ORIENTED_EDGE ( 'NONE', *, *, #25447, .T. ) ; -#20845 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; -#20846 = CARTESIAN_POINT ( 'NONE', ( -20.50037936456179821, 118.1134456052949560, 87.78011095654957785 ) ) ; -#20847 = EDGE_CURVE ( 'NONE', #29235, #21316, #15601, .T. ) ; -#20848 = DIRECTION ( 'NONE', ( 0.0006039748319392653766, -1.164951251755207723E-15, 0.9999998176071847045 ) ) ; -#20849 = CARTESIAN_POINT ( 'NONE', ( -20.00111550347676115, 117.9148692135038488, 87.27986446460897696 ) ) ; -#20850 = AXIS2_PLACEMENT_3D ( 'NONE', #29906, #29706, #26646 ) ; -#20851 = VECTOR ( 'NONE', #18049, 1000.000000000000114 ) ; -#20852 = CARTESIAN_POINT ( 'NONE', ( -42.84985448536668429, 114.0190474468247146, 121.9016368595544151 ) ) ; -#20853 = VERTEX_POINT ( 'NONE', #17671 ) ; -#20854 = ORIENTED_EDGE ( 'NONE', *, *, #14827, .F. ) ; -#20855 = CARTESIAN_POINT ( 'NONE', ( -16.53681909317384324, 122.5194902194745055, 174.6067105814985609 ) ) ; -#20856 = EDGE_CURVE ( 'NONE', #654, #14670, #964, .T. ) ; -#20857 = ORIENTED_EDGE ( 'NONE', *, *, #16949, .F. ) ; -#20858 = DIRECTION ( 'NONE', ( 0.7933533411653073131, 0.5931840316265220014, 0.1368326740407738717 ) ) ; -#20859 = EDGE_CURVE ( 'NONE', #11205, #27587, #2617, .T. ) ; -#20860 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971570121 ) ) ; -#20861 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26235, #4329, #11485, #38668, #16798, #1678, #14166, #29290, #39078, #17400, #23550, #23973 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000033307, 0.5000000000000066613, 0.6250000000000014433, 0.7499999999999962252, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20862 = CARTESIAN_POINT ( 'NONE', ( 17.08567597318895892, 152.1079231434187591, 183.8451549712952442 ) ) ; -#20863 = CARTESIAN_POINT ( 'NONE', ( 29.77977082001254061, 126.9465717062777372, 89.45601244832610632 ) ) ; -#20864 = ORIENTED_EDGE ( 'NONE', *, *, #37881, .T. ) ; -#20865 = CARTESIAN_POINT ( 'NONE', ( -0.4373761302338000645, 189.0000000000009095, 103.6849941534999999 ) ) ; -#20866 = ADVANCED_FACE ( 'NONE', ( #23423 ), #29559, .F. ) ; -#20867 = PLANE ( 'NONE', #36838 ) ; -#20868 = DIRECTION ( 'NONE', ( -0.7947985590179719173, 0.5913221741348984040, 0.1365039814779489546 ) ) ; -#20869 = CARTESIAN_POINT ( 'NONE', ( -38.04112740183000341, 118.7060968625000186, 87.44750983263999444 ) ) ; -#20870 = ORIENTED_EDGE ( 'NONE', *, *, #28213, .T. ) ; -#20871 = CARTESIAN_POINT ( 'NONE', ( -42.69707587204211308, 120.8996466381492496, 92.53868120850997059 ) ) ; -#20872 = VERTEX_POINT ( 'NONE', #39754 ) ; -#20873 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#20874 = DIRECTION ( 'NONE', ( -0.0005884949961255136249, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#20875 = CYLINDRICAL_SURFACE ( 'NONE', #34950, 6.000000000000011546 ) ; -#20876 = CARTESIAN_POINT ( 'NONE', ( 35.79285166799878937, 114.5355110621730717, 90.24616685369409197 ) ) ; -#20877 = CARTESIAN_POINT ( 'NONE', ( -12.63758525726122883, 181.4885551368883227, 104.2318394346509649 ) ) ; -#20878 = VERTEX_POINT ( 'NONE', #8502 ) ; -#20879 = CONICAL_SURFACE ( 'NONE', #33909, 2.999999999998151257, 0.7853981634371727250 ) ; -#20880 = CARTESIAN_POINT ( 'NONE', ( -25.40281222480000167, 190.9098522726999931, 104.3953673413000018 ) ) ; -#20881 = CARTESIAN_POINT ( 'NONE', ( 0.6370597539463290770, 189.0086924880019410, 103.7002870655890092 ) ) ; -#20882 = CARTESIAN_POINT ( 'NONE', ( 27.32241654998495406, 123.5931195352329865, 91.24905158260060034 ) ) ; -#20883 = CIRCLE ( 'NONE', #14348, 9.500000000008954615 ) ; -#20884 = ORIENTED_EDGE ( 'NONE', *, *, #21795, .T. ) ; -#20885 = CARTESIAN_POINT ( 'NONE', ( -39.42815928026088557, 120.3902238028007616, 87.47100753998802247 ) ) ; -#20886 = ORIENTED_EDGE ( 'NONE', *, *, #32556, .F. ) ; -#20887 = AXIS2_PLACEMENT_3D ( 'NONE', #7148, #16748, #35741 ) ; -#20888 = ORIENTED_EDGE ( 'NONE', *, *, #4413, .T. ) ; -#20889 = ORIENTED_EDGE ( 'NONE', *, *, #27103, .F. ) ; -#20890 = FACE_OUTER_BOUND ( 'NONE', #34168, .T. ) ; -#20891 = DIRECTION ( 'NONE', ( -0.0005884949961245158337, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#20892 = CARTESIAN_POINT ( 'NONE', ( 39.11388936584986453, 77.23415618633558211, 290.4399554335766993 ) ) ; -#20893 = ORIENTED_EDGE ( 'NONE', *, *, #21296, .F. ) ; -#20894 = DIRECTION ( 'NONE', ( -0.6087614810001747978, 0.7729390313185946493, 0.1788147452386024683 ) ) ; -#20895 = ORIENTED_EDGE ( 'NONE', *, *, #30611, .T. ) ; -#20896 = EDGE_CURVE ( 'NONE', #32498, #38540, #20265, .T. ) ; -#20897 = CARTESIAN_POINT ( 'NONE', ( 26.03107217181060662, 120.6373387495500253, 90.57271201131170812 ) ) ; -#20898 = ADVANCED_FACE ( 'NONE', ( #29766 ), #32651, .F. ) ; -#20899 = CARTESIAN_POINT ( 'NONE', ( -35.89743280148279325, 191.5812194053145276, 103.9038232423688584 ) ) ; -#20900 = ADVANCED_FACE ( 'NONE', ( #36699 ), #6024, .F. ) ; -#20901 = EDGE_CURVE ( 'NONE', #6504, #30059, #6829, .T. ) ; -#20903 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#20902 = FACE_OUTER_BOUND ( 'NONE', #3849, .T. ) ; -#20904 = ORIENTED_EDGE ( 'NONE', *, *, #13557, .F. ) ; -#20905 = AXIS2_PLACEMENT_3D ( 'NONE', #14896, #20403, #36563 ) ; -#20906 = ORIENTED_EDGE ( 'NONE', *, *, #6305, .F. ) ; -#20907 = EDGE_CURVE ( 'NONE', #34652, #32946, #34029, .T. ) ; -#20908 = CONICAL_SURFACE ( 'NONE', #8514, 5.000000000099491082, 0.7853981633997491052 ) ; -#20909 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -6.071530832037190021E-16, -0.0006039748319384735838 ) ) ; -#20910 = VECTOR ( 'NONE', #38570, 1000.000000000000114 ) ; -#20911 = ORIENTED_EDGE ( 'NONE', *, *, #27064, .T. ) ; -#20912 = CARTESIAN_POINT ( 'NONE', ( -35.93925692297263197, 191.9759150222000130, 101.9431537509077259 ) ) ; -#20913 = ADVANCED_FACE ( 'NONE', ( #21386 ), #37310, .F. ) ; -#20914 = CARTESIAN_POINT ( 'NONE', ( -14.59022374134706901, 128.1503308081717876, 179.4782974412063936 ) ) ; -#20915 = DIRECTION ( 'NONE', ( -0.7933531821996063771, -0.5932639600174075545, -0.1364866368485285197 ) ) ; -#20916 = CARTESIAN_POINT ( 'NONE', ( 3.534179144852753307, 139.6466882096548261, 91.89073863240385265 ) ) ; -#20917 = ORIENTED_EDGE ( 'NONE', *, *, #4537, .T. ) ; -#20918 = ORIENTED_EDGE ( 'NONE', *, *, #5428, .T. ) ; -#20919 = VERTEX_POINT ( 'NONE', #21780 ) ; -#20920 = CARTESIAN_POINT ( 'NONE', ( 5.958856853884591409, 162.8902775912074787, 100.3344200888616200 ) ) ; -#20921 = FACE_OUTER_BOUND ( 'NONE', #35565, .T. ) ; -#20922 = CARTESIAN_POINT ( 'NONE', ( -30.07145675046769284, 134.4269501514953618, 93.62510490720951850 ) ) ; -#20923 = CARTESIAN_POINT ( 'NONE', ( 26.66104490297999874, 123.3439525863999933, 88.11293733339999790 ) ) ; -#20924 = ORIENTED_EDGE ( 'NONE', *, *, #23814, .T. ) ; -#20925 = ORIENTED_EDGE ( 'NONE', *, *, #18051, .F. ) ; -#20926 = CARTESIAN_POINT ( 'NONE', ( -35.93727186606000146, 191.2092751614000292, 106.8903646179000049 ) ) ; -#20927 = LINE ( 'NONE', #24418, #15304 ) ; -#20928 = CARTESIAN_POINT ( 'NONE', ( 1.632345292716000040, 189.0492994540000211, 105.9662563011000032 ) ) ; -#20929 = ORIENTED_EDGE ( 'NONE', *, *, #8292, .T. ) ; -#20930 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319385852566 ) ) ; -#20931 = CIRCLE ( 'NONE', #30075, 5.000000000000007994 ) ; -#20932 = CARTESIAN_POINT ( 'NONE', ( 13.49924681881780764, 124.6650593666242344, 88.83239057565374708 ) ) ; -#20933 = CARTESIAN_POINT ( 'NONE', ( -14.22271344828364903, 128.9395125011611754, 177.3181667287759069 ) ) ; -#20934 = LINE ( 'NONE', #9276, #22842 ) ; -#20935 = CIRCLE ( 'NONE', #19607, 5.999999999759224600 ) ; -#20936 = EDGE_LOOP ( 'NONE', ( #21018, #4130, #35571, #31293 ) ) ; -#20937 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6343, #3668, #15555, #6737 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20938 = VECTOR ( 'NONE', #24687, 999.9999999999998863 ) ; -#20939 = CARTESIAN_POINT ( 'NONE', ( -6.858865372957902551, 155.8781062955033576, 98.72327407370771368 ) ) ; -#20940 = CARTESIAN_POINT ( 'NONE', ( -20.21854228498681394, 127.1165482757314891, 91.86524267595261506 ) ) ; -#20941 = VERTEX_POINT ( 'NONE', #30779 ) ; -#20942 = LINE ( 'NONE', #7853, #11694 ) ; -#20943 = VERTEX_POINT ( 'NONE', #93 ) ; -#20944 = EDGE_CURVE ( 'NONE', #14541, #34227, #9105, .T. ) ; -#20945 = EDGE_CURVE ( 'NONE', #10469, #38882, #6414, .T. ) ; -#20947 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825852987664379, 0.0005734119039362157175 ) ) ; -#20946 = CARTESIAN_POINT ( 'NONE', ( 15.83342444354847522, 184.9284620445380654, 102.5085181819803495 ) ) ; -#20948 = ORIENTED_EDGE ( 'NONE', *, *, #18019, .F. ) ; -#20949 = ORIENTED_EDGE ( 'NONE', *, *, #2631, .F. ) ; -#20950 = VERTEX_POINT ( 'NONE', #39963 ) ; -#20951 = CARTESIAN_POINT ( 'NONE', ( 2.345797604942000181, 209.4826787798999987, 75.42228542885000309 ) ) ; -#20952 = CARTESIAN_POINT ( 'NONE', ( -20.49970530398912771, 127.6304983571866813, 89.64427666219336288 ) ) ; -#20953 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#20954 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9421, #3262, #12892, #15736, #38014, #37622, #9825, #31289, #10020, #28236, #202, #9620, #28625, #3860 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000594524, 0.3750000000000891509, 0.5000000000001189049, 0.6250000000001486589, 0.6875000000001635359, 0.7500000000001783018, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#20955 = DIRECTION ( 'NONE', ( 0.0005884949961216158097, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#20956 = ORIENTED_EDGE ( 'NONE', *, *, #5523, .T. ) ; -#20957 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8234, #17410, #8445, #5143 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 3.498928553401127738E-05, 0.0009596819072843342392 ), - .UNSPECIFIED. ) ; -#20958 = ORIENTED_EDGE ( 'NONE', *, *, #33244, .T. ) ; -#20959 = FACE_OUTER_BOUND ( 'NONE', #21161, .T. ) ; -#20960 = ORIENTED_EDGE ( 'NONE', *, *, #308, .F. ) ; -#20961 = VERTEX_POINT ( 'NONE', #5829 ) ; -#20962 = ORIENTED_EDGE ( 'NONE', *, *, #17359, .F. ) ; -#20963 = DIRECTION ( 'NONE', ( -0.0002331579778304450367, 0.000000000000000000, 0.9999999728186783621 ) ) ; -#20964 = VECTOR ( 'NONE', #38831, 1000.000000000000000 ) ; -#20965 = CARTESIAN_POINT ( 'NONE', ( -15.49931385410608797, 126.5379994198332128, 90.07323617695428197 ) ) ; -#20966 = CARTESIAN_POINT ( 'NONE', ( 28.90769808291203091, 225.0820812890804348, 73.04104455706797694 ) ) ; -#20967 = ORIENTED_EDGE ( 'NONE', *, *, #4254, .F. ) ; -#20968 = ORIENTED_EDGE ( 'NONE', *, *, #9102, .T. ) ; -#20969 = FACE_OUTER_BOUND ( 'NONE', #30387, .T. ) ; -#20970 = CIRCLE ( 'NONE', #2714, 59.40509992922265070 ) ; -#20971 = CARTESIAN_POINT ( 'NONE', ( -36.01420119997000313, 191.6214486215999955, 104.0185275158000024 ) ) ; -#20972 = PLANE ( 'NONE', #6780 ) ; -#20973 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5873, #37157, #21633, #26103 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.004429580596844295143, 0.005383752238790704553 ), - .UNSPECIFIED. ) ; -#20974 = CARTESIAN_POINT ( 'NONE', ( -26.00156157406000190, 120.7704101891000050, 87.55230281532000447 ) ) ; -#20975 = EDGE_CURVE ( 'NONE', #29413, #36900, #15237, .T. ) ; -#20976 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927785862613, -0.0005734119022076208027 ) ) ; -#20977 = ORIENTED_EDGE ( 'NONE', *, *, #8872, .F. ) ; -#20978 = CARTESIAN_POINT ( 'NONE', ( -35.93878493987468659, 193.8169247291150441, 102.7246158654215407 ) ) ; -#20979 = CARTESIAN_POINT ( 'NONE', ( -10.03773492422904035, 144.2121259786891585, 92.95297688159946858 ) ) ; -#20980 = CARTESIAN_POINT ( 'NONE', ( -40.50060808723890204, 187.9905118568378839, 108.0074710440303534 ) ) ; -#20981 = EDGE_LOOP ( 'NONE', ( #33692, #13913, #28684, #25266, #19116, #24953 ) ) ; -#20982 = CARTESIAN_POINT ( 'NONE', ( 0.9069838061199879675, 188.6357051019811024, 103.2023597719151695 ) ) ; -#20983 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971566235 ) ) ; -#20984 = CARTESIAN_POINT ( 'NONE', ( 38.86765437999894601, 119.3076485421969295, 90.27457848768588633 ) ) ; -#20985 = ORIENTED_EDGE ( 'NONE', *, *, #38352, .F. ) ; -#20986 = CARTESIAN_POINT ( 'NONE', ( -19.32686018148266172, 125.5899111567603512, 176.6758355686243931 ) ) ; -#20987 = CARTESIAN_POINT ( 'NONE', ( 2.243271862260145522, 189.9155782016669320, 103.9476138140318824 ) ) ; -#20988 = FACE_OUTER_BOUND ( 'NONE', #35721, .T. ) ; -#20989 = ORIENTED_EDGE ( 'NONE', *, *, #12359, .T. ) ; -#20990 = CARTESIAN_POINT ( 'NONE', ( 28.22275640945365893, 173.0857027608089709, 163.8371377877124075 ) ) ; -#20991 = ORIENTED_EDGE ( 'NONE', *, *, #15997, .T. ) ; -#20992 = CARTESIAN_POINT ( 'NONE', ( -26.16677798958000523, 191.4023415389999911, 103.7088623374999941 ) ) ; -#20993 = AXIS2_PLACEMENT_3D ( 'NONE', #37808, #25156, #6927 ) ; -#20994 = DIRECTION ( 'NONE', ( -0.7933533411653341805, 0.5930537057989598848, 0.1373964268091485141 ) ) ; -#20995 = CARTESIAN_POINT ( 'NONE', ( 25.65860218431893358, 209.7091953648101708, 75.70969353744057173 ) ) ; -#20996 = AXIS2_PLACEMENT_3D ( 'NONE', #1921, #36043, #20098 ) ; -#20997 = CIRCLE ( 'NONE', #9239, 2.000000000000000000 ) ; -#20998 = CARTESIAN_POINT ( 'NONE', ( 22.78189145297202245, 157.6320869253407011, 99.11031191928994133 ) ) ; -#20999 = ORIENTED_EDGE ( 'NONE', *, *, #17708, .F. ) ; -#21000 = EDGE_CURVE ( 'NONE', #37846, #34146, #5872, .T. ) ; -#21001 = ADVANCED_FACE ( 'NONE', ( #12554, #2765 ), #25055, .T. ) ; -#21002 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#21003 = LINE ( 'NONE', #4834, #38026 ) ; -#21004 = CARTESIAN_POINT ( 'NONE', ( -25.62047675601055374, 116.5971733958860312, 87.28325841799609464 ) ) ; -#21005 = CARTESIAN_POINT ( 'NONE', ( 22.50071842841086678, 154.4094130781474803, 95.28756121982962668 ) ) ; -#21006 = EDGE_CURVE ( 'NONE', #28275, #7159, #15437, .T. ) ; -#21007 = DIRECTION ( 'NONE', ( -0.0005884949961246856197, 0.2249510543439059984, -0.9743698870671264611 ) ) ; -#21008 = CARTESIAN_POINT ( 'NONE', ( 21.72603247161529438, 129.4256177271351760, 92.59897021125679828 ) ) ; -#21009 = FACE_OUTER_BOUND ( 'NONE', #18104, .T. ) ; -#21010 = CARTESIAN_POINT ( 'NONE', ( 29.19927575787174234, 149.0747586894985659, 94.05190613317014936 ) ) ; -#21011 = CARTESIAN_POINT ( 'NONE', ( 22.05420076943320140, 115.2658143850467241, 90.25446465457505951 ) ) ; -#21012 = ORIENTED_EDGE ( 'NONE', *, *, #15579, .F. ) ; -#21013 = VERTEX_POINT ( 'NONE', #7415 ) ; -#21014 = LINE ( 'NONE', #5672, #29597 ) ; -#21015 = CARTESIAN_POINT ( 'NONE', ( 25.99211731546482795, 209.7096512574500480, 76.04280604205342797 ) ) ; -#21016 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14687, #2415, #11203, #36130 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.002613673017241889291 ), - .UNSPECIFIED. ) ; -#21017 = CARTESIAN_POINT ( 'NONE', ( -32.57215242110157050, 137.1961775011903626, 91.34682747567867978 ) ) ; -#21018 = ORIENTED_EDGE ( 'NONE', *, *, #25902, .F. ) ; -#21019 = CARTESIAN_POINT ( 'NONE', ( 39.76268190624871579, 165.1489056186390485, 181.9689639978837192 ) ) ; -#21020 = CARTESIAN_POINT ( 'NONE', ( 36.74499328828947142, 191.3591568088928909, 106.3388620510278457 ) ) ; -#21021 = EDGE_LOOP ( 'NONE', ( #7977, #30007, #12549, #6560 ) ) ; -#21022 = CARTESIAN_POINT ( 'NONE', ( -17.26181899215141158, 121.5888068968943827, 176.1573250596364062 ) ) ; -#21023 = AXIS2_PLACEMENT_3D ( 'NONE', #11590, #38760, #26727 ) ; -#21024 = EDGE_CURVE ( 'NONE', #19097, #9106, #22587, .T. ) ; -#21025 = AXIS2_PLACEMENT_3D ( 'NONE', #40441, #9387, #18361 ) ; -#21026 = CARTESIAN_POINT ( 'NONE', ( 26.01073959733328067, 191.4239670711786516, 106.8751801458234496 ) ) ; -#21027 = FACE_OUTER_BOUND ( 'NONE', #7265, .T. ) ; -#21028 = CARTESIAN_POINT ( 'NONE', ( 1.222756100067673435, 140.3958132876599620, 157.8527939211185753 ) ) ; -#21029 = VERTEX_POINT ( 'NONE', #35008 ) ; -#21030 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620729128, 0.0004744508866335443741 ) ) ; -#21031 = DIRECTION ( 'NONE', ( 0.0005734119072255677982, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#21032 = CARTESIAN_POINT ( 'NONE', ( 16.57899994050853465, 122.1654929642032101, 174.6492536331854808 ) ) ; -#21033 = DIRECTION ( 'NONE', ( 0.6087611427401035114, 0.7731004639645453480, 0.1781166575802727303 ) ) ; -#21034 = CARTESIAN_POINT ( 'NONE', ( 5.666342389698421300, 128.5870658017565233, 89.33308585708306282 ) ) ; -#21035 = ORIENTED_EDGE ( 'NONE', *, *, #3306, .F. ) ; -#21036 = ORIENTED_EDGE ( 'NONE', *, *, #33627, .F. ) ; -#21037 = CARTESIAN_POINT ( 'NONE', ( 39.95940241497999779, 119.7619408805000063, 87.93975461783000469 ) ) ; -#21038 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250611660, 132.8554482850406089, 90.84904174544712419 ) ) ; -#21039 = CARTESIAN_POINT ( 'NONE', ( 35.04675249778818369, 217.7719116314000303, 76.03733726961077366 ) ) ; -#21040 = ADVANCED_FACE ( 'NONE', ( #7217 ), #38306, .T. ) ; -#21041 = CARTESIAN_POINT ( 'NONE', ( -17.94609826156584731, 126.0030689616275197, 174.3309067019738734 ) ) ; -#21042 = ORIENTED_EDGE ( 'NONE', *, *, #35881, .T. ) ; -#21043 = DIRECTION ( 'NONE', ( -1.974915567353954948E-14, 0.9743700556569576676, 0.2249510938827756212 ) ) ; -#21044 = CARTESIAN_POINT ( 'NONE', ( -41.68575839595558108, 120.6855336692081266, 90.61946157941947888 ) ) ; -#21045 = CARTESIAN_POINT ( 'NONE', ( 12.31694666162038132, 134.8454845483305178, 93.34277599231758415 ) ) ; -#21046 = CARTESIAN_POINT ( 'NONE', ( -14.16859889492986468, 129.2741495211867004, 92.07252832466726034 ) ) ; -#21047 = EDGE_CURVE ( 'NONE', #7827, #29667, #3947, .T. ) ; -#21048 = CARTESIAN_POINT ( 'NONE', ( -20.00009287209055131, 187.1460516500350195, 102.8711691885999500 ) ) ; -#21049 = EDGE_CURVE ( 'NONE', #28516, #21533, #13717, .T. ) ; -#21050 = AXIS2_PLACEMENT_3D ( 'NONE', #4670, #14493, #10624 ) ; -#21051 = EDGE_CURVE ( 'NONE', #8665, #17763, #28728, .T. ) ; -#21052 = DIRECTION ( 'NONE', ( -0.0005884949961204158147, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#21053 = EDGE_CURVE ( 'NONE', #29822, #21381, #16614, .T. ) ; -#21054 = AXIS2_PLACEMENT_3D ( 'NONE', #25608, #16565, #35363 ) ; -#21055 = DIRECTION ( 'NONE', ( 0.0006039748319392010834, 1.387181216573299978E-14, 0.9999998176071847045 ) ) ; -#21056 = ADVANCED_FACE ( 'NONE', ( #34612 ), #22528, .F. ) ; -#21057 = CIRCLE ( 'NONE', #5365, 4.999999999999990230 ) ; -#21058 = COORDINATED_UNIVERSAL_TIME_OFFSET ( 8, 0, .AHEAD. ) ; -#21059 = CARTESIAN_POINT ( 'NONE', ( 27.30892892946447148, 124.2550657910854142, 88.32296920643761950 ) ) ; -#21060 = CARTESIAN_POINT ( 'NONE', ( 25.51004206032530064, 191.6308693524351554, 105.7209185049416931 ) ) ; -#21061 = CARTESIAN_POINT ( 'NONE', ( 5.659931281361317623, 181.6896837046558346, 101.5959228839198687 ) ) ; -#21062 = CARTESIAN_POINT ( 'NONE', ( 39.74188351515407192, 169.2517364656017946, 164.2561587285271969 ) ) ; -#21063 = CARTESIAN_POINT ( 'NONE', ( -20.09733952647779631, 117.3367250912880877, 87.27992258150773353 ) ) ; -#21064 = ORIENTED_EDGE ( 'NONE', *, *, #20222, .T. ) ; -#21066 = ORIENTED_EDGE ( 'NONE', *, *, #31760, .F. ) ; -#21065 = CARTESIAN_POINT ( 'NONE', ( -20.49997183667262490, 192.9349667875385137, 104.2562123716132447 ) ) ; -#21067 = VERTEX_POINT ( 'NONE', #22382 ) ; -#21068 = ORIENTED_EDGE ( 'NONE', *, *, #31240, .T. ) ; -#21069 = VERTEX_POINT ( 'NONE', #16420 ) ; -#21070 = CARTESIAN_POINT ( 'NONE', ( -17.02518187280848494, 122.0151939964033119, 175.1199121015164337 ) ) ; -#21071 = VERTEX_POINT ( 'NONE', #6609 ) ; -#21072 = CARTESIAN_POINT ( 'NONE', ( -23.35907867311044228, 177.6446616419575548, 100.8023958600040686 ) ) ; -#21073 = CARTESIAN_POINT ( 'NONE', ( -43.56994142101562062, 121.4012961811330626, 90.41976514615660676 ) ) ; -#21074 = VERTEX_POINT ( 'NONE', #31581 ) ; -#21075 = CARTESIAN_POINT ( 'NONE', ( 13.88517613221250713, 135.5848694388539002, 93.51252930518586481 ) ) ; -#21076 = CARTESIAN_POINT ( 'NONE', ( 14.31397849533732725, 130.4269649200152230, 89.75571327846994052 ) ) ; -#21077 = CARTESIAN_POINT ( 'NONE', ( -32.54948496751784148, 154.4229393206493057, 204.0724399287581434 ) ) ; -#21078 = CIRCLE ( 'NONE', #9985, 58.90509898899683350 ) ; -#21079 = ORIENTED_EDGE ( 'NONE', *, *, #3482, .F. ) ; -#21080 = PLANE ( 'NONE', #32980 ) ; -#21081 = CIRCLE ( 'NONE', #36049, 22.00000000001089973 ) ; -#21082 = FACE_OUTER_BOUND ( 'NONE', #24695, .T. ) ; -#21083 = CARTESIAN_POINT ( 'NONE', ( -2.935421602322794588, 191.9759150222000130, 106.9232211747876278 ) ) ; -#21084 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21085 = ORIENTED_EDGE ( 'NONE', *, *, #21281, .T. ) ; -#21086 = LINE ( 'NONE', #8823, #10225 ) ; -#21087 = VECTOR ( 'NONE', #8432, 1000.000000000000114 ) ; -#21088 = CARTESIAN_POINT ( 'NONE', ( 0.7499007542371000090, 188.6218793108000114, 103.1994418971000016 ) ) ; -#21089 = CARTESIAN_POINT ( 'NONE', ( -40.96659390818172852, 129.5715977525514120, 94.72314572716805969 ) ) ; -#21090 = EDGE_CURVE ( 'NONE', #22698, #22776, #26336, .T. ) ; -#21091 = ORIENTED_EDGE ( 'NONE', *, *, #15811, .F. ) ; -#21092 = CARTESIAN_POINT ( 'NONE', ( 2.547144903132902094, 209.7096538831000032, 78.05696658267085297 ) ) ; -#21093 = ORIENTED_EDGE ( 'NONE', *, *, #14309, .T. ) ; -#21094 = EDGE_CURVE ( 'NONE', #14326, #14324, #3541, .T. ) ; -#21095 = VERTEX_POINT ( 'NONE', #6814 ) ; -#21096 = EDGE_CURVE ( 'NONE', #33655, #20063, #19285, .T. ) ; -#21097 = VERTEX_POINT ( 'NONE', #689 ) ; -#21098 = VERTEX_POINT ( 'NONE', #25661 ) ; -#21099 = CARTESIAN_POINT ( 'NONE', ( -37.60508999318000178, 191.0942080147000013, 105.7280175294000060 ) ) ; -#21100 = CARTESIAN_POINT ( 'NONE', ( -20.00004361580415591, 118.8155695144462669, 87.27991261026372172 ) ) ; -#21101 = EDGE_CURVE ( 'NONE', #27687, #38501, #18994, .T. ) ; -#21102 = FACE_OUTER_BOUND ( 'NONE', #28433, .T. ) ; -#21103 = ORIENTED_EDGE ( 'NONE', *, *, #8536, .T. ) ; -#21104 = CARTESIAN_POINT ( 'NONE', ( -13.49869758878028669, 124.2895155517476127, 90.92133008179847309 ) ) ; -#21105 = VECTOR ( 'NONE', #18459, 1000.000000000000000 ) ; -#21106 = ORIENTED_EDGE ( 'NONE', *, *, #2901, .T. ) ; -#21107 = CARTESIAN_POINT ( 'NONE', ( 25.79908993445999954, 121.4038166283999942, 90.40237219540999547 ) ) ; -#21108 = CARTESIAN_POINT ( 'NONE', ( -39.71509910335698379, 121.1775733798183552, 123.9347607182968574 ) ) ; -#21109 = AXIS2_PLACEMENT_3D ( 'NONE', #23422, #35861, #20131 ) ; -#21111 = FACE_OUTER_BOUND ( 'NONE', #15639, .T. ) ; -#21110 = CARTESIAN_POINT ( 'NONE', ( 18.92701962846999919, 158.4561920815999940, 97.76344171338000422 ) ) ; -#21112 = ORIENTED_EDGE ( 'NONE', *, *, #26367, .F. ) ; -#21113 = CARTESIAN_POINT ( 'NONE', ( 3.804321419319733444, 143.6008336270662937, 95.60682967125522680 ) ) ; -#21114 = ORIENTED_EDGE ( 'NONE', *, *, #25837, .T. ) ; -#21115 = ORIENTED_EDGE ( 'NONE', *, *, #19560, .F. ) ; -#21116 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971573729 ) ) ; -#21117 = DIRECTION ( 'NONE', ( 0.0006039748319386906410, -0.000000000000000000, 0.9999998176071844824 ) ) ; -#21118 = CYLINDRICAL_SURFACE ( 'NONE', #13089, 2.000000000000001332 ) ; -#21119 = CARTESIAN_POINT ( 'NONE', ( 20.50029382537679723, 138.3995138256450446, 92.10573732898133414 ) ) ; -#21120 = ORIENTED_EDGE ( 'NONE', *, *, #27164, .T. ) ; -#21121 = EDGE_LOOP ( 'NONE', ( #12390, #38121, #16422, #7972 ) ) ; -#21122 = CARTESIAN_POINT ( 'NONE', ( 44.86515336672587040, 186.3325894068457274, 107.7750559962146752 ) ) ; -#21123 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555133 ) ) ; -#21124 = CARTESIAN_POINT ( 'NONE', ( 25.49917220875000012, 120.6644043121000038, 88.00842120017000525 ) ) ; -#21125 = ORIENTED_EDGE ( 'NONE', *, *, #14646, .F. ) ; -#21126 = VERTEX_POINT ( 'NONE', #17820 ) ; -#21127 = CARTESIAN_POINT ( 'NONE', ( -15.49852919464750833, 127.1814504007330839, 91.59019381971197049 ) ) ; -#21128 = CONICAL_SURFACE ( 'NONE', #15238, 4.999999999914826354, 0.7853981634347279028 ) ; -#21130 = EDGE_CURVE ( 'NONE', #26863, #29325, #1488, .T. ) ; -#21129 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684796025, 220.4002260771000010, 75.57961659102821272 ) ) ; -#21131 = EDGE_CURVE ( 'NONE', #12858, #4754, #26452, .T. ) ; -#21132 = EDGE_CURVE ( 'NONE', #33491, #3175, #4538, .T. ) ; -#21133 = VECTOR ( 'NONE', #33778, 1000.000000000000000 ) ; -#21134 = EDGE_CURVE ( 'NONE', #22424, #34827, #23381, .T. ) ; -#21135 = CARTESIAN_POINT ( 'NONE', ( 1.148461899826000110, 188.6401437957000269, 106.0734205451999941 ) ) ; -#21136 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#21137 = AXIS2_PLACEMENT_3D ( 'NONE', #28420, #25762, #22694 ) ; -#21138 = DIRECTION ( 'NONE', ( 0.0006039748319381496242, 1.231904546584163304E-14, 0.9999998176071845934 ) ) ; -#21139 = PLANE ( 'NONE', #37231 ) ; -#21140 = CARTESIAN_POINT ( 'NONE', ( -77.81044467944656162, 193.2853083808247163, 188.4036545891195544 ) ) ; -#21141 = EDGE_CURVE ( 'NONE', #2058, #22348, #11111, .T. ) ; -#21142 = EDGE_LOOP ( 'NONE', ( #40273, #32284, #26293, #15617 ) ) ; -#21143 = CARTESIAN_POINT ( 'NONE', ( 15.91461714735487654, 137.7804811271876986, 91.45243982764233692 ) ) ; -#21144 = CARTESIAN_POINT ( 'NONE', ( 17.33275958572512110, 132.4033582165222072, 151.6354730222171554 ) ) ; -#21145 = EDGE_CURVE ( 'NONE', #10469, #17896, #35814, .T. ) ; -#21146 = VERTEX_POINT ( 'NONE', #7624 ) ; -#21147 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5316, #12271, #36607, #37017 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21148 = CARTESIAN_POINT ( 'NONE', ( -14.14964769712242720, 154.3421575665795444, 95.29416286922138113 ) ) ; -#21149 = EDGE_LOOP ( 'NONE', ( #800, #20962, #38040, #20060 ) ) ; -#21151 = CARTESIAN_POINT ( 'NONE', ( -13.46991461394048706, 153.3545038370762654, 97.63149519329859061 ) ) ; -#21150 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2249510911124609769, 0.9743700461176366678 ) ) ; -#21152 = VERTEX_POINT ( 'NONE', #32573 ) ; -#21153 = EDGE_CURVE ( 'NONE', #22508, #3193, #21498, .T. ) ; -#21154 = EDGE_LOOP ( 'NONE', ( #1528, #23847, #37100, #28904 ) ) ; -#21155 = CIRCLE ( 'NONE', #29649, 2.000000000040191850 ) ; -#21156 = ORIENTED_EDGE ( 'NONE', *, *, #22259, .T. ) ; -#21157 = CARTESIAN_POINT ( 'NONE', ( 3.178648524536999975, 209.0894144632000007, 76.29602415331001453 ) ) ; -#21158 = FACE_OUTER_BOUND ( 'NONE', #2887, .T. ) ; -#21159 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319383098692 ) ) ; -#21160 = CARTESIAN_POINT ( 'NONE', ( 12.63909433778480462, 177.5476369569251744, 100.8453596693047700 ) ) ; -#21161 = EDGE_LOOP ( 'NONE', ( #31786, #35714, #14464, #11307, #19428, #11277, #25296 ) ) ; -#21162 = ORIENTED_EDGE ( 'NONE', *, *, #22625, .F. ) ; -#21163 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178662923876E-05, -0.0002331579774918193435 ) ) ; -#21164 = ORIENTED_EDGE ( 'NONE', *, *, #15556, .T. ) ; -#21165 = EDGE_LOOP ( 'NONE', ( #20426, #25320, #25411, #36636 ) ) ; -#21166 = DIRECTION ( 'NONE', ( 0.5976534202554322217, -0.8017545692149086189, 0.000000000000000000 ) ) ; -#21167 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 82.27946979429631824, 312.5857197240630967 ) ) ; -#21168 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#21169 = CARTESIAN_POINT ( 'NONE', ( 14.20046068010607421, 171.2571027691364804, 152.1817658904702171 ) ) ; -#21170 = ORIENTED_EDGE ( 'NONE', *, *, #11593, .F. ) ; -#21171 = VERTEX_POINT ( 'NONE', #1907 ) ; -#21172 = CARTESIAN_POINT ( 'NONE', ( 25.74916992513999858, 120.5273334846000068, 87.71987236393999865 ) ) ; -#21173 = FACE_OUTER_BOUND ( 'NONE', #40161, .T. ) ; -#21174 = CARTESIAN_POINT ( 'NONE', ( -36.04262883852999977, 191.6038256765999961, 104.0150152128000087 ) ) ; -#21175 = ORIENTED_EDGE ( 'NONE', *, *, #35227, .F. ) ; -#21176 = CARTESIAN_POINT ( 'NONE', ( -25.50107848504000074, 120.6980294115000021, 88.04691121081999938 ) ) ; -#21177 = ORIENTED_EDGE ( 'NONE', *, *, #2312, .T. ) ; -#21178 = ORIENTED_EDGE ( 'NONE', *, *, #36025, .T. ) ; -#21179 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501101346, 134.9725883025117810, 93.90358196957727444 ) ) ; -#21180 = CARTESIAN_POINT ( 'NONE', ( 40.67160727233613926, 188.2341991642046821, 107.8019268565751645 ) ) ; -#21181 = VERTEX_POINT ( 'NONE', #20488 ) ; -#21182 = ADVANCED_FACE ( 'NONE', ( #4553 ), #31356, .F. ) ; -#21183 = ADVANCED_FACE ( 'NONE', ( #10709 ), #7814, .F. ) ; -#21184 = ADVANCED_FACE ( 'NONE', ( #17424 ), #20297, .T. ) ; -#21185 = FACE_OUTER_BOUND ( 'NONE', #33374, .T. ) ; -#21186 = CARTESIAN_POINT ( 'NONE', ( -14.95236425134362257, 124.8050312121227705, 88.47546351363439499 ) ) ; -#21187 = DIRECTION ( 'NONE', ( -0.7069397881080353718, 0.6509003778324177203, 0.2767035130376589436 ) ) ; -#21188 = CARTESIAN_POINT ( 'NONE', ( 42.08971007137151332, 189.5930990985782216, 106.5991435967087710 ) ) ; -#21189 = AXIS2_PLACEMENT_3D ( 'NONE', #36771, #5282, #8779 ) ; -#21190 = AXIS2_PLACEMENT_3D ( 'NONE', #23283, #11411, #35717 ) ; -#21191 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#21192 = EDGE_CURVE ( 'NONE', #32173, #5686, #4753, .T. ) ; -#21193 = ORIENTED_EDGE ( 'NONE', *, *, #33124, .T. ) ; -#21194 = DIRECTION ( 'NONE', ( 0.0006039748319392586546, 1.665208279866278382E-14, 0.9999998176071847045 ) ) ; -#21195 = ORIENTED_EDGE ( 'NONE', *, *, #11756, .F. ) ; -#21196 = ORIENTED_EDGE ( 'NONE', *, *, #10307, .T. ) ; -#21197 = CIRCLE ( 'NONE', #26423, 10.00000000000000533 ) ; -#21198 = CARTESIAN_POINT ( 'NONE', ( -25.38982233400999888, 191.1550647745000049, 104.4477984829999997 ) ) ; -#21199 = CARTESIAN_POINT ( 'NONE', ( -38.21285156308999831, 118.8458964008000009, 87.61704921257999956 ) ) ; -#21200 = CARTESIAN_POINT ( 'NONE', ( -14.55306305638819886, 182.5568561273574630, 101.8082842025129366 ) ) ; -#21201 = EDGE_CURVE ( 'NONE', #11382, #20569, #26256, .T. ) ; -#21202 = CARTESIAN_POINT ( 'NONE', ( 20.00140612192502942, 118.1043503129110093, 90.25575274657424529 ) ) ; -#21203 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#21204 = ORIENTED_EDGE ( 'NONE', *, *, #3858, .T. ) ; -#21205 = CARTESIAN_POINT ( 'NONE', ( -6.038826999385723759, 135.1142834552483407, 91.11862372168455693 ) ) ; -#21206 = EDGE_CURVE ( 'NONE', #29513, #28170, #32200, .T. ) ; -#21207 = ORIENTED_EDGE ( 'NONE', *, *, #2856, .T. ) ; -#21208 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21209 = CARTESIAN_POINT ( 'NONE', ( -21.21281380558005125, 182.9066539643694966, 104.4588199671594850 ) ) ; -#21210 = LINE ( 'NONE', #8749, #1974 ) ; -#21211 = CARTESIAN_POINT ( 'NONE', ( -36.88585087101509430, 165.0203428823977845, 195.0301372465660847 ) ) ; -#21212 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971557908 ) ) ; -#21213 = CARTESIAN_POINT ( 'NONE', ( 30.77440290267000123, 184.0596580533000122, 103.6673131442999960 ) ) ; -#21214 = ORIENTED_EDGE ( 'NONE', *, *, #38473, .F. ) ; -#21215 = AXIS2_PLACEMENT_3D ( 'NONE', #713, #25886, #25482 ) ; -#21216 = ORIENTED_EDGE ( 'NONE', *, *, #27759, .F. ) ; -#21217 = DIRECTION ( 'NONE', ( 0.0006039748319383739456, -3.094196748328522329E-15, 0.9999998176071845934 ) ) ; -#21218 = CARTESIAN_POINT ( 'NONE', ( 40.24910017280793539, 69.86439126638083508, 297.5342355816429745 ) ) ; -#21219 = CIRCLE ( 'NONE', #37523, 2.499999999946084017 ) ; -#21220 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363196004925E-14, 0.9999998176071845934 ) ) ; -#21221 = AXIS2_PLACEMENT_3D ( 'NONE', #34673, #6880, #19353 ) ; -#21222 = ORIENTED_EDGE ( 'NONE', *, *, #33805, .F. ) ; -#21223 = CARTESIAN_POINT ( 'NONE', ( 38.59086485963890567, 79.69179921679354095, 285.2955982571226059 ) ) ; -#21224 = AXIS2_PLACEMENT_3D ( 'NONE', #37946, #22421, #23612 ) ; -#21225 = ORIENTED_EDGE ( 'NONE', *, *, #31892, .T. ) ; -#21226 = CARTESIAN_POINT ( 'NONE', ( -38.44420815374000000, 119.3830914533000112, 87.46411065086999770 ) ) ; -#21227 = CARTESIAN_POINT ( 'NONE', ( -43.57128771414367918, 121.9172130293124212, 88.19101713714755419 ) ) ; -#21228 = ORIENTED_EDGE ( 'NONE', *, *, #35824, .F. ) ; -#21229 = CARTESIAN_POINT ( 'NONE', ( 35.56535286263039808, 192.7868339794035251, 106.8337704962199268 ) ) ; -#21230 = CARTESIAN_POINT ( 'NONE', ( 25.99018610745488900, 211.0908525021142168, 73.04280463953621449 ) ) ; -#21231 = CARTESIAN_POINT ( 'NONE', ( 17.12152900317391513, 122.0605713307357263, 174.6251451077950776 ) ) ; -#21232 = EDGE_CURVE ( 'NONE', #9304, #10943, #25325, .T. ) ; -#21233 = EDGE_CURVE ( 'NONE', #6430, #37955, #23869, .T. ) ; -#21234 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501096727, 179.0628333272140367, 104.0826189413666043 ) ) ; -#21235 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21236 = ORIENTED_EDGE ( 'NONE', *, *, #30002, .F. ) ; -#21237 = ORIENTED_EDGE ( 'NONE', *, *, #14080, .F. ) ; -#21238 = LINE ( 'NONE', #33687, #2401 ) ; -#21239 = LINE ( 'NONE', #40428, #13358 ) ; -#21240 = CARTESIAN_POINT ( 'NONE', ( 37.23958122199455545, 191.4853617004306159, 104.3373353119450258 ) ) ; -#21241 = CARTESIAN_POINT ( 'NONE', ( -46.39364199823201318, 124.7770151420462525, 91.05374585112593877 ) ) ; -#21242 = EDGE_CURVE ( 'NONE', #14524, #3978, #30118, .T. ) ; -#21243 = ORIENTED_EDGE ( 'NONE', *, *, #38187, .T. ) ; -#21244 = LINE ( 'NONE', #27196, #38783 ) ; -#21245 = CARTESIAN_POINT ( 'NONE', ( -41.90795178536294685, 120.7420511615134728, 90.63264387236358743 ) ) ; -#21246 = VECTOR ( 'NONE', #35386, 1000.000000000000000 ) ; -#21247 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971564015 ) ) ; -#21248 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29635, #26576, #11031, #23491, #35940, #7948, #4875, #31047, #28193, #18543, #9575, #24932, #24730, #34481, #5698, #2830, #12429, #3020 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 2, 4 ), - ( 7.505561329662602745E-17, 0.0006195336865909711627, 0.001239067373181867299, 0.001858601059772763651, 0.002168367903068206190, 0.002323251324715956950, 0.002400693035539833847, 0.002439413890951765140, 0.002478134746363696433 ), - .UNSPECIFIED. ) ; -#21249 = AXIS2_PLACEMENT_3D ( 'NONE', #23002, #13992, #35428 ) ; -#21250 = AXIS2_PLACEMENT_3D ( 'NONE', #19749, #38372, #7483 ) ; -#21251 = FACE_OUTER_BOUND ( 'NONE', #27552, .T. ) ; -#21252 = FACE_OUTER_BOUND ( 'NONE', #27650, .T. ) ; -#21253 = VECTOR ( 'NONE', #11840, 1000.000000000000114 ) ; -#21254 = CARTESIAN_POINT ( 'NONE', ( -30.96737657857003256, 183.9660670339539479, 102.1435399962739297 ) ) ; -#21255 = AXIS2_PLACEMENT_3D ( 'NONE', #21482, #37594, #3436 ) ; -#21256 = CARTESIAN_POINT ( 'NONE', ( -25.52810189352114634, 209.7152177947368443, 73.55569084695761717 ) ) ; -#21257 = LINE ( 'NONE', #30860, #37663 ) ; -#21258 = EDGE_CURVE ( 'NONE', #15288, #17741, #40433, .T. ) ; -#21259 = CARTESIAN_POINT ( 'NONE', ( 0.000000000000000000, 0.000000000000000000, 0.000000000000000000 ) ) ; -#21260 = CARTESIAN_POINT ( 'NONE', ( 5.658901668160544851, 123.6924101227050699, 91.28505159842420369 ) ) ; -#21261 = PLANE ( 'NONE', #27689 ) ; -#21262 = DIRECTION ( 'NONE', ( 0.6087611434179116543, -0.7728348325624403437, -0.1792657018023851578 ) ) ; -#21263 = CARTESIAN_POINT ( 'NONE', ( -18.04546768527096035, 119.4165901137118198, 183.0978515824491240 ) ) ; -#21264 = PLANE ( 'NONE', #38487 ) ; -#21265 = VERTEX_POINT ( 'NONE', #6371 ) ; -#21267 = VERTEX_POINT ( 'NONE', #21733 ) ; -#21266 = CARTESIAN_POINT ( 'NONE', ( -20.49977814371478146, 192.2078853970874661, 104.4261425811200752 ) ) ; -#21268 = ORIENTED_EDGE ( 'NONE', *, *, #23176, .F. ) ; -#21269 = ORIENTED_EDGE ( 'NONE', *, *, #9636, .F. ) ; -#21270 = ORIENTED_EDGE ( 'NONE', *, *, #39463, .F. ) ; -#21271 = CARTESIAN_POINT ( 'NONE', ( -39.76450099176925335, 182.5239991202462306, 106.7001999176872715 ) ) ; -#21272 = EDGE_LOOP ( 'NONE', ( #2158, #11661, #36797, #35432 ) ) ; -#21273 = CARTESIAN_POINT ( 'NONE', ( 20.26447891146207425, 126.8205566995678168, 91.72864402998783362 ) ) ; -#21274 = EDGE_CURVE ( 'NONE', #31339, #34253, #11, .T. ) ; -#21275 = CARTESIAN_POINT ( 'NONE', ( 19.00982909665260934, 124.9426515599988079, 178.2686586979558570 ) ) ; -#21276 = DIRECTION ( 'NONE', ( -0.7933533175743878729, 0.5931616988744193852, 0.1369295895054284395 ) ) ; -#21277 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15696, #166, #12245, #15115 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21278 = VECTOR ( 'NONE', #31725, 1000.000000000000114 ) ; -#21279 = VERTEX_POINT ( 'NONE', #24407 ) ; -#21280 = CARTESIAN_POINT ( 'NONE', ( -39.57601231736000358, 119.6892406455000071, 90.26371608389000301 ) ) ; -#21281 = EDGE_CURVE ( 'NONE', #26700, #31921, #37227, .T. ) ; -#21282 = CARTESIAN_POINT ( 'NONE', ( 37.56355726554620134, 212.6956742645159011, 73.20248333212254011 ) ) ; -#21283 = VECTOR ( 'NONE', #26844, 1000.000000000000000 ) ; -#21284 = VECTOR ( 'NONE', #32160, 999.9999999999998863 ) ; -#21285 = DIRECTION ( 'NONE', ( 0.0006039748319386906410, -0.000000000000000000, 0.9999998176071845934 ) ) ; -#21286 = ORIENTED_EDGE ( 'NONE', *, *, #674, .F. ) ; -#21287 = VECTOR ( 'NONE', #36557, 999.9999999999998863 ) ; -#21288 = LINE ( 'NONE', #9014, #332 ) ; -#21289 = CARTESIAN_POINT ( 'NONE', ( 29.39370237474554770, 191.5260169245929092, 103.8524356916996396 ) ) ; -#21290 = CIRCLE ( 'NONE', #19933, 2.000000000000011546 ) ; -#21291 = EDGE_CURVE ( 'NONE', #34215, #9595, #27276, .T. ) ; -#21292 = ADVANCED_FACE ( 'NONE', ( #40111 ), #33573, .T. ) ; -#21293 = FACE_OUTER_BOUND ( 'NONE', #3804, .T. ) ; -#21294 = CARTESIAN_POINT ( 'NONE', ( -3.656136860141406153, 187.3893018360669203, 102.9173608625563361 ) ) ; -#21295 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568178 ) ) ; -#21296 = EDGE_CURVE ( 'NONE', #37440, #24578, #12407, .T. ) ; -#21297 = ORIENTED_EDGE ( 'NONE', *, *, #2494, .T. ) ; -#21298 = CARTESIAN_POINT ( 'NONE', ( -31.84898476996059813, 157.9423125112969331, 186.4027463543498584 ) ) ; -#21299 = CARTESIAN_POINT ( 'NONE', ( 1.206895876459000094, 188.8306159436000087, 103.3834228997999958 ) ) ; -#21300 = FACE_OUTER_BOUND ( 'NONE', #17158, .T. ) ; -#21301 = ORIENTED_EDGE ( 'NONE', *, *, #34047, .F. ) ; -#21302 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058996743, 130.4211554272961280, 90.27959376775912403 ) ) ; -#21303 = ORIENTED_EDGE ( 'NONE', *, *, #27056, .F. ) ; -#21304 = CARTESIAN_POINT ( 'NONE', ( -38.81769244209999670, 118.7847089182999980, 89.71781930851000197 ) ) ; -#21305 = VECTOR ( 'NONE', #22639, 1000.000000000000114 ) ; -#21306 = ORIENTED_EDGE ( 'NONE', *, *, #33542, .T. ) ; -#21307 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971561517 ) ) ; -#21308 = AXIS2_PLACEMENT_3D ( 'NONE', #25704, #10158, #22425 ) ; -#21309 = CARTESIAN_POINT ( 'NONE', ( -35.93960179980999925, 192.7068948186999933, 105.7594716616000028 ) ) ; -#21310 = CARTESIAN_POINT ( 'NONE', ( -37.39932010222903358, 212.8449755639020111, 76.08109288175667473 ) ) ; -#21311 = AXIS2_PLACEMENT_3D ( 'NONE', #21713, #3085, #5347 ) ; -#21312 = CARTESIAN_POINT ( 'NONE', ( 38.97366284846734175, 78.18638126909256414, 288.5917584186810814 ) ) ; -#21313 = VERTEX_POINT ( 'NONE', #27488 ) ; -#21314 = CARTESIAN_POINT ( 'NONE', ( -29.94659852520202037, 103.6131156702491865, 89.78587174319537212 ) ) ; -#21315 = CARTESIAN_POINT ( 'NONE', ( -1.630689202969549667, 189.3908836070928032, 105.8511190046429107 ) ) ; -#21316 = VERTEX_POINT ( 'NONE', #24608 ) ; -#21317 = CONICAL_SURFACE ( 'NONE', #27836, 2.500000073598442896, 0.7853981634226060438 ) ; -#21318 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21319 = CYLINDRICAL_SURFACE ( 'NONE', #24134, 2.000000000000014655 ) ; -#21320 = CONICAL_SURFACE ( 'NONE', #25232, 2.499999999987588595, 0.7853981634197695350 ) ; -#21322 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#21321 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#21323 = ORIENTED_EDGE ( 'NONE', *, *, #16359, .T. ) ; -#21324 = ADVANCED_FACE ( 'NONE', ( #37062 ), #11716, .F. ) ; -#21325 = CARTESIAN_POINT ( 'NONE', ( 15.94065395167610788, 152.5983745658832902, 182.6131612411744527 ) ) ; -#21326 = ORIENTED_EDGE ( 'NONE', *, *, #25267, .F. ) ; -#21327 = DIRECTION ( 'NONE', ( 0.6087611434179116543, -0.7728348325624403437, -0.1792657018023851578 ) ) ; -#21328 = ADVANCED_FACE ( 'NONE', ( #9454 ), #21118, .F. ) ; -#21329 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971544308 ) ) ; -#21330 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; -#21331 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21332 = EDGE_CURVE ( 'NONE', #24453, #32145, #16991, .T. ) ; -#21333 = ORIENTED_EDGE ( 'NONE', *, *, #19586, .T. ) ; -#21334 = ORIENTED_EDGE ( 'NONE', *, *, #16896, .F. ) ; -#21335 = VECTOR ( 'NONE', #16025, 1000.000000000000227 ) ; -#21336 = CARTESIAN_POINT ( 'NONE', ( 36.03687122555673739, 218.5902260770998282, 61.03673652646995862 ) ) ; -#21337 = VECTOR ( 'NONE', #11967, 1000.000000000000227 ) ; -#21338 = EDGE_CURVE ( 'NONE', #38178, #31820, #36532, .T. ) ; -#21339 = AXIS2_PLACEMENT_3D ( 'NONE', #28637, #37437, #19615 ) ; -#21340 = FACE_OUTER_BOUND ( 'NONE', #8936, .T. ) ; -#21341 = EDGE_LOOP ( 'NONE', ( #22991, #18400, #23787, #39852 ) ) ; -#21342 = EDGE_CURVE ( 'NONE', #5436, #28807, #16519, .T. ) ; -#21343 = ORIENTED_EDGE ( 'NONE', *, *, #37789, .F. ) ; -#21344 = CARTESIAN_POINT ( 'NONE', ( -3.692940375663182451, 144.1765304566810642, 93.10030759800980604 ) ) ; -#21345 = EDGE_CURVE ( 'NONE', #19726, #19846, #28756, .T. ) ; -#21346 = AXIS2_PLACEMENT_3D ( 'NONE', #35783, #1254, #38869 ) ; -#21347 = VECTOR ( 'NONE', #3412, 1000.000000000000114 ) ; -#21348 = ORIENTED_EDGE ( 'NONE', *, *, #31299, .F. ) ; -#21349 = CARTESIAN_POINT ( 'NONE', ( 2.332801095514406509, 189.0539861093840273, 106.3967151195623728 ) ) ; -#21350 = CARTESIAN_POINT ( 'NONE', ( -20.51938464653014549, 208.0070366894154006, 73.88096774075889073 ) ) ; -#21351 = CARTESIAN_POINT ( 'NONE', ( -13.59923565109000165, 180.7017300104000128, 28.07991271570000080 ) ) ; -#21352 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; -#21353 = LINE ( 'NONE', #8472, #22204 ) ; -#21354 = ORIENTED_EDGE ( 'NONE', *, *, #32354, .F. ) ; -#21355 = CARTESIAN_POINT ( 'NONE', ( 39.75749670546768044, 190.3327792175265074, 106.6496084232941683 ) ) ; -#21356 = LINE ( 'NONE', #12150, #20164 ) ; -#21357 = ORIENTED_EDGE ( 'NONE', *, *, #13099, .T. ) ; -#21358 = VECTOR ( 'NONE', #7854, 1000.000000000000114 ) ; -#21359 = FACE_OUTER_BOUND ( 'NONE', #29512, .T. ) ; -#21360 = ORIENTED_EDGE ( 'NONE', *, *, #37790, .T. ) ; -#21361 = CONICAL_SURFACE ( 'NONE', #1018, 2.749999999950583973, 0.7853981633811774055 ) ; -#21362 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #16816, #26451, #16221 ), - ( #25858, #35606, #19685 ), - ( #10108, #7623, #28709 ), - ( #688, #38690, #29510 ), - ( #13178, #23178, #13766 ), - ( #25660, #16613, #29112 ), - ( #13572, #35007, #22981 ), - ( #19488, #31982, #26052 ), - ( #1487, #38305, #10708 ), - ( #32572, #4348, #13971 ) ), - .UNSPECIFIED., .F., .F., .T. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 2, 2, 2, 4 ), - ( 3, 3 ), - ( 0.0006290844662723365198, 0.001453074859921644037, 0.002277065253570951554, 0.003101055647220258855, 0.003925046040869566155 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.8214630073245949848, 1.000000000000000000), - ( 1.000000000000000000, 0.8179501931302566309, 1.000000000000000000), - ( 1.000000000000000000, 0.8120421346113418926, 1.000000000000000000), - ( 1.000000000000000000, 0.7953930622375270376, 1.000000000000000000), - ( 1.000000000000000000, 0.7845309420939873268, 1.000000000000000000), - ( 1.000000000000000000, 0.7575129545167481604, 1.000000000000000000), - ( 1.000000000000000000, 0.7411181031346090187, 1.000000000000000000), - ( 1.000000000000000000, 0.7023451256331760817, 1.000000000000000000), - ( 1.000000000000000000, 0.6795235542076561996, 1.000000000000000000), - ( 1.000000000000000000, 0.6536732819161872321, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#21363 = VECTOR ( 'NONE', #36274, 1000.000000000000000 ) ; -#21365 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 179.4002599087000078, 102.6210641108000061 ) ) ; -#21364 = CARTESIAN_POINT ( 'NONE', ( 13.84826647186673654, 135.4318207773943641, 90.91145678624771165 ) ) ; -#21366 = ORIENTED_EDGE ( 'NONE', *, *, #37569, .T. ) ; -#21367 = ORIENTED_EDGE ( 'NONE', *, *, #6812, .T. ) ; -#21368 = CARTESIAN_POINT ( 'NONE', ( 25.49202135914930523, 205.7387363836115526, 75.88112788460828995 ) ) ; -#21369 = ORIENTED_EDGE ( 'NONE', *, *, #16823, .T. ) ; -#21370 = EDGE_CURVE ( 'NONE', #267, #4577, #7257, .T. ) ; -#21372 = CONICAL_SURFACE ( 'NONE', #18064, 2.749999999949247709, 0.7853981633862016087 ) ; -#21371 = CARTESIAN_POINT ( 'NONE', ( 2.385423998479000218, 209.2946138833000020, 75.43815394924999396 ) ) ; -#21373 = EDGE_CURVE ( 'NONE', #25751, #18083, #15972, .T. ) ; -#21374 = DIRECTION ( 'NONE', ( 0.0005734119072316638333, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#21375 = EDGE_CURVE ( 'NONE', #27561, #28078, #34560, .T. ) ; -#21376 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825964864930728, 0.0005734119013526018391 ) ) ; -#21377 = VERTEX_POINT ( 'NONE', #1034 ) ; -#21378 = ORIENTED_EDGE ( 'NONE', *, *, #24583, .T. ) ; -#21379 = CARTESIAN_POINT ( 'NONE', ( -20.49960732757744353, 118.8154816606033393, 87.78015075453545535 ) ) ; -#21380 = ORIENTED_EDGE ( 'NONE', *, *, #3839, .F. ) ; -#21381 = VERTEX_POINT ( 'NONE', #19230 ) ; -#21382 = FACE_OUTER_BOUND ( 'NONE', #22690, .T. ) ; -#21383 = EDGE_CURVE ( 'NONE', #22385, #6692, #23401, .T. ) ; -#21384 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384972194 ) ) ; -#21385 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524157562, 149.3470289647612219, 130.0514119197758305 ) ) ; -#21386 = FACE_OUTER_BOUND ( 'NONE', #22433, .T. ) ; -#21387 = CARTESIAN_POINT ( 'NONE', ( 35.55365739661999669, 192.3091292246000421, 103.8613361242999957 ) ) ; -#21388 = ADVANCED_FACE ( 'NONE', ( #26006 ), #9181, .F. ) ; -#21389 = EDGE_LOOP ( 'NONE', ( #39246, #12037, #23448, #18029 ) ) ; -#21390 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33702, #15122, #24740, #12052 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21391 = EDGE_LOOP ( 'NONE', ( #36072, #4153, #2471, #18999 ) ) ; -#21392 = DIRECTION ( 'NONE', ( 1.249000902704392418E-14, 0.9743700557921585181, 0.2249510932971566235 ) ) ; -#21393 = LINE ( 'NONE', #5834, #39383 ) ; -#21394 = CARTESIAN_POINT ( 'NONE', ( 31.50927902734200359, 191.9221074921661057, 104.4557544969390506 ) ) ; -#21395 = CARTESIAN_POINT ( 'NONE', ( -25.56609382933000063, 121.5324527806999981, 88.23963119317001258 ) ) ; -#21396 = EDGE_CURVE ( 'NONE', #33783, #26891, #33968, .T. ) ; -#21397 = ORIENTED_EDGE ( 'NONE', *, *, #4139, .T. ) ; -#21398 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989908600, -0.1373964268091705798 ) ) ; -#21399 = CARTESIAN_POINT ( 'NONE', ( -39.78547281363039900, 190.3169928286148718, 106.6940055862042271 ) ) ; -#21400 = ORIENTED_EDGE ( 'NONE', *, *, #23814, .F. ) ; -#21401 = AXIS2_PLACEMENT_3D ( 'NONE', #24818, #37662, #11931 ) ; -#21402 = LINE ( 'NONE', #15255, #18958 ) ; -#21403 = CARTESIAN_POINT ( 'NONE', ( -4.036264727110095762, 167.9338357148023704, 100.9917020970900410 ) ) ; -#21404 = AXIS2_PLACEMENT_3D ( 'NONE', #36117, #24077, #36533 ) ; -#21405 = ADVANCED_FACE ( 'NONE', ( #16177 ), #35224, .F. ) ; -#21406 = DIRECTION ( 'NONE', ( -0.6087613502019256773, 0.7729389820454566351, 0.1788154035167601741 ) ) ; -#21407 = CARTESIAN_POINT ( 'NONE', ( -15.99847796691061852, 137.5244930513001975, 94.49161329741416182 ) ) ; -#21408 = ORIENTED_EDGE ( 'NONE', *, *, #17146, .F. ) ; -#21409 = CARTESIAN_POINT ( 'NONE', ( -2.438441564891038915, 191.9759150222000130, 101.9229200978912075 ) ) ; -#21410 = VERTEX_POINT ( 'NONE', #1440 ) ; -#21411 = EDGE_LOOP ( 'NONE', ( #8630, #8082, #28466, #6830, #22983, #1874 ) ) ; -#21412 = CARTESIAN_POINT ( 'NONE', ( 3.009765127882288116, 209.4523184236957434, 73.05668452217646802 ) ) ; -#21413 = CARTESIAN_POINT ( 'NONE', ( 3.578322037540619505, 149.3470289647403320, 130.0514119197709988 ) ) ; -#21414 = CARTESIAN_POINT ( 'NONE', ( 38.53393130996000338, 118.5935268415999957, 89.80359806433999381 ) ) ; -#21415 = CARTESIAN_POINT ( 'NONE', ( -29.91895087148420629, 182.1247778028852622, 101.7178115817681032 ) ) ; -#21416 = ORIENTED_EDGE ( 'NONE', *, *, #22489, .T. ) ; -#21417 = LINE ( 'NONE', #33853, #30472 ) ; -#21418 = ORIENTED_EDGE ( 'NONE', *, *, #9842, .F. ) ; -#21419 = CARTESIAN_POINT ( 'NONE', ( 18.08235529168842604, 152.6330892152822685, 184.7488916507021202 ) ) ; -#21420 = DIRECTION ( 'NONE', ( -0.0006039748319356123742, 6.151140898304641511E-15, -0.9999998176071847045 ) ) ; -#21421 = EDGE_LOOP ( 'NONE', ( #37906, #31165, #12854, #7218, #16605, #100, #2121, #19359, #7562 ) ) ; -#21422 = ADVANCED_FACE ( 'NONE', ( #27588 ), #6555, .T. ) ; -#21423 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#21424 = EDGE_CURVE ( 'NONE', #34711, #9488, #24094, .T. ) ; -#21425 = VECTOR ( 'NONE', #35323, 1000.000000000000227 ) ; -#21426 = DIRECTION ( 'NONE', ( -0.7936449239197745920, 0.5927912671287571822, 0.1368438831378941400 ) ) ; -#21427 = EDGE_CURVE ( 'NONE', #2373, #33167, #35638, .T. ) ; -#21428 = CARTESIAN_POINT ( 'NONE', ( -14.16977583430312926, 135.9878589137828726, 91.56990267135316230 ) ) ; -#21429 = EDGE_CURVE ( 'NONE', #21678, #26191, #39609, .T. ) ; -#21430 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091564245 ) ) ; -#21431 = AXIS2_PLACEMENT_3D ( 'NONE', #2300, #17613, #14368 ) ; -#21432 = EDGE_LOOP ( 'NONE', ( #24604, #19516, #24245, #9004 ) ) ; -#21433 = VERTEX_POINT ( 'NONE', #12226 ) ; -#21434 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457972811109, -32.89481530046835189, 142.2936922234671613 ) ) ; -#21435 = CARTESIAN_POINT ( 'NONE', ( 13.47116993038426358, 154.0079171905443047, 95.54241653341313167 ) ) ; -#21436 = ADVANCED_FACE ( 'NONE', ( #6271 ), #15678, .F. ) ; -#21437 = ORIENTED_EDGE ( 'NONE', *, *, #40103, .T. ) ; -#21438 = CARTESIAN_POINT ( 'NONE', ( -35.93686737616000215, 193.5538913732000026, 105.8995219524000078 ) ) ; -#21439 = PLANE ( 'NONE', #34789 ) ; -#21440 = ORIENTED_EDGE ( 'NONE', *, *, #39463, .T. ) ; -#21441 = FACE_OUTER_BOUND ( 'NONE', #11079, .T. ) ; -#21442 = EDGE_CURVE ( 'NONE', #32994, #30422, #26171, .T. ) ; -#21443 = CARTESIAN_POINT ( 'NONE', ( 35.56284489036890051, 193.8169247291054376, 102.6814306727405750 ) ) ; -#21444 = CARTESIAN_POINT ( 'NONE', ( -26.00800983458967508, 191.5260122442129216, 103.8858970416150385 ) ) ; -#21445 = ORIENTED_EDGE ( 'NONE', *, *, #26676, .T. ) ; -#21446 = CARTESIAN_POINT ( 'NONE', ( -20.99850207568253424, 135.8130112225352661, 93.92837029496691059 ) ) ; -#21447 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21448 = CARTESIAN_POINT ( 'NONE', ( -26.13262776858000080, 190.9207843215999958, 106.9673394545999940 ) ) ; -#21449 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #25264, #28524, #890, #10523 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 5.933558708143790383, 7.730894538220764112 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7484352496336026395, 0.7484352496336026395, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#21450 = CARTESIAN_POINT ( 'NONE', ( -24.82787921266102771, 115.6987712569605833, 90.28278025611777480 ) ) ; -#21451 = CARTESIAN_POINT ( 'NONE', ( 3.251699916679381630, 126.1628332823677709, 88.77794208007185262 ) ) ; -#21452 = EDGE_LOOP ( 'NONE', ( #8600, #10776, #25453, #26549 ) ) ; -#21453 = ORIENTED_EDGE ( 'NONE', *, *, #25916, .F. ) ; -#21454 = LINE ( 'NONE', #5069, #10253 ) ; -#21455 = CARTESIAN_POINT ( 'NONE', ( -0.4543644846840136919, 210.9999999999990621, 75.55877896310728659 ) ) ; -#21456 = CARTESIAN_POINT ( 'NONE', ( 37.31639193983529879, 111.9096183688354245, 150.0649592369359766 ) ) ; -#21457 = CONICAL_SURFACE ( 'NONE', #25359, 2.502965858498830354, 0.7853981633840887433 ) ; -#21458 = CARTESIAN_POINT ( 'NONE', ( -15.94475015168131726, 152.3695000724660531, 183.5849529441521781 ) ) ; -#21459 = VERTEX_POINT ( 'NONE', #25108 ) ; -#21460 = EDGE_LOOP ( 'NONE', ( #18239, #3991, #247, #38205, #5504, #28929, #20774, #13756, #2755, #8800 ) ) ; -#21461 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971531540 ) ) ; -#21462 = CARTESIAN_POINT ( 'NONE', ( 2.546082943913467123, 205.5673828937494534, 76.29867481864103240 ) ) ; -#21463 = CIRCLE ( 'NONE', #34457, 5.500000000097090336 ) ; -#21464 = CARTESIAN_POINT ( 'NONE', ( 23.74081244260071344, 214.0195164535212200, 73.04416522657409416 ) ) ; -#21465 = CARTESIAN_POINT ( 'NONE', ( -25.64792389571747933, 212.5442448628288901, 73.07399478574440366 ) ) ; -#21466 = CARTESIAN_POINT ( 'NONE', ( -30.80669558541512387, 183.2612378953851362, 101.9807202910270405 ) ) ; -#21467 = CARTESIAN_POINT ( 'NONE', ( -35.94659742851874284, 109.6131156826799895, 89.78949559170979455 ) ) ; -#21468 = CARTESIAN_POINT ( 'NONE', ( 6.037083992585445813, 176.9518112263966714, 103.3541370315850259 ) ) ; -#21469 = LINE ( 'NONE', #31670, #10583 ) ; -#21470 = CARTESIAN_POINT ( 'NONE', ( 4.603077704204733500, 181.9200065296383286, 101.6496859594862627 ) ) ; -#21471 = DIRECTION ( 'NONE', ( 0.0004270746993300993609, -0.7071067811864992780, 0.7071066522153991452 ) ) ; -#21472 = CARTESIAN_POINT ( 'NONE', ( 25.49929013439852099, 120.2777482667000015, 87.91897806053000863 ) ) ; -#21473 = LINE ( 'NONE', #11446, #22844 ) ; -#21474 = CARTESIAN_POINT ( 'NONE', ( 37.68744678548170413, 191.4230900328749954, 104.2932531994780021 ) ) ; -#21475 = ADVANCED_FACE ( 'NONE', ( #24715 ), #145, .T. ) ; -#21476 = ADVANCED_FACE ( 'NONE', ( #21441 ), #19604, .F. ) ; -#21477 = ORIENTED_EDGE ( 'NONE', *, *, #9550, .T. ) ; -#21478 = CARTESIAN_POINT ( 'NONE', ( 36.60667824930000336, 191.2880709291999892, 106.4529399168999930 ) ) ; -#21479 = ORIENTED_EDGE ( 'NONE', *, *, #11912, .T. ) ; -#21480 = EDGE_LOOP ( 'NONE', ( #34182, #30844 ) ) ; -#21481 = ORIENTED_EDGE ( 'NONE', *, *, #14174, .F. ) ; -#21483 = AXIS2_PLACEMENT_3D ( 'NONE', #36608, #35977, #39053 ) ; -#21482 = CARTESIAN_POINT ( 'NONE', ( 2.561557522426482159, 191.9759150222000130, 101.9199002238076162 ) ) ; -#21484 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15630, #3950, #4146, #19493 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21485 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#21486 = CONICAL_SURFACE ( 'NONE', #4485, 6.499999999957617014, 0.7853981634197665374 ) ; -#21487 = CARTESIAN_POINT ( 'NONE', ( 45.11685896322114786, 125.4654678076909846, 91.67056992293602491 ) ) ; -#21488 = CIRCLE ( 'NONE', #1882, 2.000000000223707275 ) ; -#21489 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4746, #36016, #39698, #8019 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21490 = VERTEX_POINT ( 'NONE', #18725 ) ; -#21491 = CARTESIAN_POINT ( 'NONE', ( -39.33809393978000202, 119.3098376324000043, 89.91474602178001874 ) ) ; -#21492 = LINE ( 'NONE', #24359, #7426 ) ; -#21493 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21494 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; -#21495 = ORIENTED_EDGE ( 'NONE', *, *, #24156, .F. ) ; -#21496 = CARTESIAN_POINT ( 'NONE', ( -42.50703640508957903, 189.8244386586393375, 106.5819344532048234 ) ) ; -#21497 = CARTESIAN_POINT ( 'NONE', ( 23.37050237754266391, 177.1040287634355650, 103.5841246925966601 ) ) ; -#21498 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5153, #33373, #14191, #36030, #23783, #29919 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21499 = CARTESIAN_POINT ( 'NONE', ( 5.669001395941777766, 130.0333311697188492, 92.31877599091235709 ) ) ; -#21500 = CARTESIAN_POINT ( 'NONE', ( -3.537744320960331645, 175.3497732290038300, 100.1377481765469355 ) ) ; -#21501 = CARTESIAN_POINT ( 'NONE', ( -15.49970618479461137, 184.8500655517521807, 102.8514372352811108 ) ) ; -#21502 = ORIENTED_EDGE ( 'NONE', *, *, #23720, .F. ) ; -#21503 = ADVANCED_FACE ( 'NONE', ( #37754 ), #34669, .T. ) ; -#21504 = CARTESIAN_POINT ( 'NONE', ( -26.62773329666000421, 189.0698272449000115, 103.4439533488999956 ) ) ; -#21505 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971556798 ) ) ; -#21506 = CARTESIAN_POINT ( 'NONE', ( -22.78373664920998465, 158.6756214348941967, 96.81298893720612853 ) ) ; -#21507 = ORIENTED_EDGE ( 'NONE', *, *, #20975, .T. ) ; -#21508 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#21509 = EDGE_LOOP ( 'NONE', ( #30557, #30566, #24179, #23013 ) ) ; -#21510 = CONICAL_SURFACE ( 'NONE', #20841, 2.749999999928335992, 0.7853981634201930850 ) ; -#21511 = LINE ( 'NONE', #15939, #20409 ) ; -#21512 = AXIS2_PLACEMENT_3D ( 'NONE', #7484, #26323, #20157 ) ; -#21513 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; -#21514 = CIRCLE ( 'NONE', #35180, 3.500000265863834947 ) ; -#21515 = CARTESIAN_POINT ( 'NONE', ( -36.23875406263000087, 191.8022506627999917, 105.0197184015000005 ) ) ; -#21516 = VECTOR ( 'NONE', #1619, 1000.000000000000227 ) ; -#21517 = CARTESIAN_POINT ( 'NONE', ( -20.01999405515273622, 209.2223495200929619, 73.07050896365778669 ) ) ; -#21519 = ADVANCED_FACE ( 'NONE', ( #12416, #25309 ), #34079, .T. ) ; -#21518 = CARTESIAN_POINT ( 'NONE', ( -37.77017277285205665, 190.9635658029147010, 106.3292223135493941 ) ) ; -#21520 = ORIENTED_EDGE ( 'NONE', *, *, #38117, .T. ) ; -#21521 = CARTESIAN_POINT ( 'NONE', ( -12.63753158754559180, 134.7187973715719522, 93.43418384966304302 ) ) ; -#21522 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971557631 ) ) ; -#21523 = EDGE_LOOP ( 'NONE', ( #19896, #36281, #31037, #1768 ) ) ; -#21524 = DIRECTION ( 'NONE', ( -0.0005559617641341623026, 0.3907311285998608663, -0.9205046855120270211 ) ) ; -#21525 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37674, #25225, #22356, #38272 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21526 = CARTESIAN_POINT ( 'NONE', ( 20.00140612192502942, 118.1043503129110093, 90.25575274657424529 ) ) ; -#21527 = DIRECTION ( 'NONE', ( -0.0005884949961280444780, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#21528 = ADVANCED_FACE ( 'NONE', ( #18527 ), #16337, .F. ) ; -#21529 = EDGE_CURVE ( 'NONE', #38636, #15042, #1997, .T. ) ; -#21531 = CARTESIAN_POINT ( 'NONE', ( 14.27749844727565076, 135.1700550567618961, 93.92967703643782329 ) ) ; -#21530 = CARTESIAN_POINT ( 'NONE', ( -3.668404236601097601, 185.3449489774860979, 105.0111528754605530 ) ) ; -#21532 = VERTEX_POINT ( 'NONE', #15291 ) ; -#21533 = VERTEX_POINT ( 'NONE', #3199 ) ; -#21534 = ORIENTED_EDGE ( 'NONE', *, *, #20517, .F. ) ; -#21535 = CARTESIAN_POINT ( 'NONE', ( 8.189646510984831096, 160.7227069166503668, 99.66159882002607162 ) ) ; -#21536 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319386171321 ) ) ; -#21537 = DIRECTION ( 'NONE', ( 0.0006039748319386430446, 1.236414387799018187E-14, 0.9999998176071845934 ) ) ; -#21538 = CARTESIAN_POINT ( 'NONE', ( 35.04494057328201961, 217.7719116313999734, 73.03733781645851764 ) ) ; -#21539 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; -#21540 = DIRECTION ( 'NONE', ( -0.7933532970003740470, -0.5930762008556723641, -0.1372995488602875569 ) ) ; -#21541 = ORIENTED_EDGE ( 'NONE', *, *, #17002, .F. ) ; -#21542 = VECTOR ( 'NONE', #19734, 999.9999999999998863 ) ; -#21543 = ORIENTED_EDGE ( 'NONE', *, *, #26039, .T. ) ; -#21544 = VECTOR ( 'NONE', #21007, 999.9999999999998863 ) ; -#21545 = CARTESIAN_POINT ( 'NONE', ( 32.37225756566472512, 173.7344409119733086, 102.8220398834807980 ) ) ; -#21546 = AXIS2_PLACEMENT_3D ( 'NONE', #6791, #6397, #19258 ) ; -#21547 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#21548 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#21549 = ORIENTED_EDGE ( 'NONE', *, *, #18846, .T. ) ; -#21550 = CARTESIAN_POINT ( 'NONE', ( 35.71331820330245677, 209.7096552214366909, 75.87026816044664201 ) ) ; -#21551 = CARTESIAN_POINT ( 'NONE', ( -19.99806018810932429, 127.0618145191346713, 92.07850957579123019 ) ) ; -#21552 = CARTESIAN_POINT ( 'NONE', ( 2.745160164167272487, 189.5703853151680676, 106.5150923011538993 ) ) ; -#21553 = CARTESIAN_POINT ( 'NONE', ( 23.36940079100686063, 177.7945392694463749, 100.6858723966742843 ) ) ; -#21554 = CARTESIAN_POINT ( 'NONE', ( 13.49917495365670739, 124.5253171415348845, 88.60875626113156045 ) ) ; -#21555 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319363512580 ) ) ; -#21556 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988562940165, 156.3551877983851170, 95.75036263592699015 ) ) ; -#21557 = EDGE_CURVE ( 'NONE', #27979, #31021, #24221, .T. ) ; -#21558 = EDGE_LOOP ( 'NONE', ( #19106, #12165, #32732, #32797 ) ) ; -#21559 = PLANE ( 'NONE', #29092 ) ; -#21560 = DIRECTION ( 'NONE', ( -0.0002393071182782277790, -0.2252352986010052460, 0.9743043687658488050 ) ) ; -#21561 = AXIS2_PLACEMENT_3D ( 'NONE', #30228, #30027, #35719 ) ; -#21562 = EDGE_CURVE ( 'NONE', #17896, #21784, #27482, .T. ) ; -#21563 = VECTOR ( 'NONE', #15388, 1000.000000000000114 ) ; -#21564 = ORIENTED_EDGE ( 'NONE', *, *, #624, .T. ) ; -#21565 = AXIS2_PLACEMENT_3D ( 'NONE', #8162, #20627, #33092 ) ; -#21566 = LINE ( 'NONE', #18261, #22789 ) ; -#21567 = ORIENTED_EDGE ( 'NONE', *, *, #11674, .F. ) ; -#21568 = ADVANCED_FACE ( 'NONE', ( #15488 ), #21829, .T. ) ; -#21569 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7312, #32277, #23075, #26156 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.002691258517243560675, 0.003374075896545886393 ), - .UNSPECIFIED. ) ; -#21570 = EDGE_CURVE ( 'NONE', #37986, #407, #3399, .T. ) ; -#21572 = CARTESIAN_POINT ( 'NONE', ( 35.66415592867893025, 191.9426605352722106, 103.8996477256188484 ) ) ; -#21571 = CARTESIAN_POINT ( 'NONE', ( 12.69440440448767937, 134.9200954942802468, 90.79401257800917335 ) ) ; -#21573 = EDGE_CURVE ( 'NONE', #34987, #39550, #20931, .T. ) ; -#21574 = ORIENTED_EDGE ( 'NONE', *, *, #30652, .F. ) ; -#21575 = ORIENTED_EDGE ( 'NONE', *, *, #4545, .T. ) ; -#21576 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557741681312, -0.2249510933750812069 ) ) ; -#21577 = EDGE_CURVE ( 'NONE', #20244, #12970, #25510, .T. ) ; -#21578 = ORIENTED_EDGE ( 'NONE', *, *, #10349, .T. ) ; -#21579 = CARTESIAN_POINT ( 'NONE', ( 2.335069725756000025, 209.5243782654999904, 75.42221763621000719 ) ) ; -#21580 = CARTESIAN_POINT ( 'NONE', ( 1.218001437391567077, 135.9198998882713170, 177.2143327488629154 ) ) ; -#21581 = PLANE ( 'NONE', #35116 ) ; -#21582 = ORIENTED_EDGE ( 'NONE', *, *, #29539, .T. ) ; -#21583 = VERTEX_POINT ( 'NONE', #5880 ) ; -#21584 = VERTEX_POINT ( 'NONE', #13430 ) ; -#21585 = DIRECTION ( 'NONE', ( -0.7942818278044030400, -0.5920830005357836656, -0.1362134299408093163 ) ) ; -#21586 = CARTESIAN_POINT ( 'NONE', ( -19.73823131666757291, 124.3520775053762719, 178.1518425532499919 ) ) ; -#21587 = CARTESIAN_POINT ( 'NONE', ( 22.68181547863324710, 135.1246333993239830, 90.83520173675087506 ) ) ; -#21588 = ORIENTED_EDGE ( 'NONE', *, *, #4215, .T. ) ; -#21589 = ORIENTED_EDGE ( 'NONE', *, *, #16051, .F. ) ; -#21590 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; -#21591 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21592 = DIRECTION ( 'NONE', ( -0.0005884952006634126126, 0.2255194586134631751, -0.9742384859263615304 ) ) ; -#21593 = ORIENTED_EDGE ( 'NONE', *, *, #1673, .F. ) ; -#21594 = CARTESIAN_POINT ( 'NONE', ( 19.99999382154498662, 120.3902235794415816, 87.43511282661482653 ) ) ; -#21595 = AXIS2_PLACEMENT_3D ( 'NONE', #20772, #33225, #8516 ) ; -#21596 = EDGE_LOOP ( 'NONE', ( #8746, #20263, #27682, #12292, #27406, #24655, #3596, #16734, #29286, #23788, #6415, #34219, #21303, #39988, #35212, #1286, #10981, #18616, #38288, #7615, #1274, #19448, #15525, #24706, #6965, #31468, #3167 ) ) ; -#21597 = LINE ( 'NONE', #30378, #33017 ) ; -#21598 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; -#21599 = VECTOR ( 'NONE', #38552, 1000.000000000000114 ) ; -#21600 = VERTEX_POINT ( 'NONE', #19541 ) ; -#21601 = FACE_OUTER_BOUND ( 'NONE', #31545, .T. ) ; -#21602 = VECTOR ( 'NONE', #31816, 1000.000000000000000 ) ; -#21603 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178582671909E-05, -0.0002331579774919533509 ) ) ; -#21604 = CARTESIAN_POINT ( 'NONE', ( -15.83315360615156564, 125.9251344721852917, 88.73459174902453128 ) ) ; -#21605 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21606 = CARTESIAN_POINT ( 'NONE', ( -15.66515283670559100, 137.5952383037110565, 94.16561455557221905 ) ) ; -#21607 = EDGE_CURVE ( 'NONE', #2217, #32971, #32663, .T. ) ; -#21608 = ORIENTED_EDGE ( 'NONE', *, *, #15626, .F. ) ; -#21609 = CARTESIAN_POINT ( 'NONE', ( -31.91335489270172232, 174.4783875135883875, 100.4668596826281970 ) ) ; -#21610 = CARTESIAN_POINT ( 'NONE', ( 39.41132636150051383, 77.88677779677399826, 290.3259969045751063 ) ) ; -#21611 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606776115838874, 137.3532831589803322, 178.0585834212922123 ) ) ; -#21612 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8751, #40006, #33255, #2612 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.442078219984857190, 1.442116544522912047 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999998776024634, 0.9999999998776024634, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#21613 = DIRECTION ( 'NONE', ( 0.7933533411653073131, 0.5931840316265226676, 0.1368326740407721509 ) ) ; -#21614 = EDGE_CURVE ( 'NONE', #39643, #32491, #17640, .T. ) ; -#21615 = CARTESIAN_POINT ( 'NONE', ( -13.49823529424112145, 157.6276863903721051, 99.13120655217578303 ) ) ; -#21616 = ORIENTED_EDGE ( 'NONE', *, *, #13153, .T. ) ; -#21617 = EDGE_CURVE ( 'NONE', #15846, #23762, #3286, .T. ) ; -#21618 = CARTESIAN_POINT ( 'NONE', ( -38.02669066786999963, 118.9111989599000054, 90.44675963502000116 ) ) ; -#21619 = EDGE_CURVE ( 'NONE', #3510, #17327, #1332, .T. ) ; -#21620 = CARTESIAN_POINT ( 'NONE', ( 15.50147166558119594, 185.3474886484798390, 105.0001610792874942 ) ) ; -#21621 = VECTOR ( 'NONE', #31121, 1000.000000000000000 ) ; -#21622 = EDGE_LOOP ( 'NONE', ( #27932, #10625, #23110, #24017 ) ) ; -#21623 = CARTESIAN_POINT ( 'NONE', ( -9.153839578580999614, 181.8749524105000148, 101.9041693016999943 ) ) ; -#21624 = AXIS2_PLACEMENT_3D ( 'NONE', #40254, #12265, #24755 ) ; -#21625 = DIRECTION ( 'NONE', ( -0.6087611434179115433, 0.7728348325624404547, 0.1792657018023851023 ) ) ; -#21626 = DIRECTION ( 'NONE', ( -0.5986917825334797660, -0.8009794122048706777, 0.0003615948347011558174 ) ) ; -#21627 = CARTESIAN_POINT ( 'NONE', ( -34.64484841518558511, 164.3107434246603873, 190.4508713907742674 ) ) ; -#21628 = CARTESIAN_POINT ( 'NONE', ( -37.70556563760820978, 218.5902260770999987, 73.58127739041549376 ) ) ; -#21629 = CARTESIAN_POINT ( 'NONE', ( -37.05329340999391263, 117.5716747318153637, 90.29016409994973458 ) ) ; -#21630 = ORIENTED_EDGE ( 'NONE', *, *, #38471, .F. ) ; -#21631 = FACE_OUTER_BOUND ( 'NONE', #27706, .T. ) ; -#21632 = LINE ( 'NONE', #15868, #9963 ) ; -#21633 = CARTESIAN_POINT ( 'NONE', ( -26.97471921114255267, 119.7805572225935151, 171.4236432547711502 ) ) ; -#21634 = ORIENTED_EDGE ( 'NONE', *, *, #34326, .F. ) ; -#21635 = DIRECTION ( 'NONE', ( -0.0006039748319392907469, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#21636 = ORIENTED_EDGE ( 'NONE', *, *, #2745, .T. ) ; -#21637 = CARTESIAN_POINT ( 'NONE', ( -26.71688049004999854, 135.1028646788000174, 91.11658767897000644 ) ) ; -#21638 = CARTESIAN_POINT ( 'NONE', ( 37.42228677652877877, 190.4043295697634051, 106.6675375349840351 ) ) ; -#21639 = LINE ( 'NONE', #34082, #5279 ) ; -#21640 = ORIENTED_EDGE ( 'NONE', *, *, #40359, .F. ) ; -#21641 = CARTESIAN_POINT ( 'NONE', ( -61.84220049570045319, 78.72323700374752775, 282.5958934331605406 ) ) ; -#21642 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989907490, -0.1373964268091706076 ) ) ; -#21643 = CARTESIAN_POINT ( 'NONE', ( -25.87622840024999959, 190.9583691121999891, 106.7120253463000097 ) ) ; -#21644 = CARTESIAN_POINT ( 'NONE', ( -30.07068226051992355, 174.7890454599799739, 102.5900763959416935 ) ) ; -#21645 = CARTESIAN_POINT ( 'NONE', ( 15.59065710780919289, 127.6518116315415483, 175.3064835111600814 ) ) ; -#21646 = ORIENTED_EDGE ( 'NONE', *, *, #15755, .F. ) ; -#21647 = AXIS2_PLACEMENT_3D ( 'NONE', #38130, #28532, #499 ) ; -#21648 = CARTESIAN_POINT ( 'NONE', ( -28.45663166759245399, 131.0177812377234545, 89.91795229967709702 ) ) ; -#21649 = AXIS2_PLACEMENT_3D ( 'NONE', #36106, #37280, #11188 ) ; -#21650 = PLANE ( 'NONE', #19263 ) ; -#21651 = DIRECTION ( 'NONE', ( 0.4308752614361646138, -0.7059430892986333639, 0.5621306465171763689 ) ) ; -#21652 = ADVANCED_FACE ( 'NONE', ( #38361 ), #17065, .T. ) ; -#21653 = EDGE_CURVE ( 'NONE', #35621, #1138, #11806, .T. ) ; -#21654 = AXIS2_PLACEMENT_3D ( 'NONE', #40120, #9061, #21547 ) ; -#21655 = DIRECTION ( 'NONE', ( -0.0004161288024515960951, -0.5299192578740949955, -0.8480479980348919478 ) ) ; -#21656 = EDGE_CURVE ( 'NONE', #3220, #31100, #39978, .T. ) ; -#21657 = ORIENTED_EDGE ( 'NONE', *, *, #20289, .F. ) ; -#21658 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#21659 = EDGE_CURVE ( 'NONE', #31399, #29634, #32613, .T. ) ; -#21660 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#21661 = FACE_OUTER_BOUND ( 'NONE', #21149, .T. ) ; -#21662 = CARTESIAN_POINT ( 'NONE', ( -23.36013443277664692, 181.0071930014282486, 104.5378893608259574 ) ) ; -#21663 = EDGE_CURVE ( 'NONE', #11457, #10716, #19919, .T. ) ; -#21664 = CARTESIAN_POINT ( 'NONE', ( -30.66586300490362405, 182.9132905847569646, 101.9003052508140286 ) ) ; -#21665 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22768, #17000, #10903, #23373 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21666 = CARTESIAN_POINT ( 'NONE', ( 3.333113470500536302, 184.0886249089593605, 102.3221730663416764 ) ) ; -#21667 = CARTESIAN_POINT ( 'NONE', ( 14.89305388520275208, 183.2744346433559315, 102.2982670498846289 ) ) ; -#21668 = ADVANCED_FACE ( 'NONE', ( #9965 ), #667, .T. ) ; -#21669 = APPLICATION_PROTOCOL_DEFINITION ( 'international standard', 'config_control_design', 1994, #17458 ) ; -#21670 = CARTESIAN_POINT ( 'NONE', ( 5.659931281361317623, 181.6896837046558346, 101.5959228839198687 ) ) ; -#21671 = ORIENTED_EDGE ( 'NONE', *, *, #15811, .T. ) ; -#21672 = CARTESIAN_POINT ( 'NONE', ( -28.46570037481023974, 129.9682353462455353, 92.24140578278095859 ) ) ; -#21673 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16561, #22333, #15970, #19637 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21674 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 132.6352630048999970, 91.80276880046000088 ) ) ; -#21675 = CARTESIAN_POINT ( 'NONE', ( 37.96378318839221322, 191.4261383972079500, 104.2798627878850084 ) ) ; -#21676 = CIRCLE ( 'NONE', #12511, 51.90509898881521877 ) ; -#21677 = CARTESIAN_POINT ( 'NONE', ( 36.33054282364000187, 190.7404929015999926, 106.8950113761000011 ) ) ; -#21678 = VERTEX_POINT ( 'NONE', #35460 ) ; -#21679 = EDGE_LOOP ( 'NONE', ( #11966, #37136, #10496, #20227 ) ) ; -#21680 = EDGE_CURVE ( 'NONE', #20316, #14606, #16673, .T. ) ; -#21681 = FACE_OUTER_BOUND ( 'NONE', #36405, .T. ) ; -#21682 = CIRCLE ( 'NONE', #11897, 22.00000000001092815 ) ; -#21683 = CARTESIAN_POINT ( 'NONE', ( -30.11673635876000077, 127.0186994863999814, 89.25226417157000469 ) ) ; -#21684 = CARTESIAN_POINT ( 'NONE', ( -30.17790838424820521, 126.0796625456713826, 91.85784435949031490 ) ) ; -#21685 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #5661, #12591, #37541, #24493 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.750577995572639267, 3.321000581826867304 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8048259373832490349, 0.8048259373832490349, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#21686 = ORIENTED_EDGE ( 'NONE', *, *, #25084, .T. ) ; -#21687 = DIRECTION ( 'NONE', ( 0.7942820423213359238, 0.5918950211223032998, 0.1370267171630252800 ) ) ; -#21688 = CARTESIAN_POINT ( 'NONE', ( -20.00051264146630459, 193.4048159825563005, 103.3861754394172294 ) ) ; -#21689 = DIRECTION ( 'NONE', ( 0.6087614115774878654, 0.7729348350621346730, 0.1788331191967953149 ) ) ; -#21690 = VERTEX_POINT ( 'NONE', #10566 ) ; -#21691 = CARTESIAN_POINT ( 'NONE', ( 5.666638401078903264, 128.4739160337908288, 89.82319125807045168 ) ) ; -#21692 = LINE ( 'NONE', #2866, #35090 ) ; -#21693 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971562627 ) ) ; -#21694 = CARTESIAN_POINT ( 'NONE', ( -34.20556627594935861, 218.5902260770999987, 73.57916347850368766 ) ) ; -#21695 = ORIENTED_EDGE ( 'NONE', *, *, #6389, .F. ) ; -#21696 = ORIENTED_EDGE ( 'NONE', *, *, #34058, .F. ) ; -#21697 = CARTESIAN_POINT ( 'NONE', ( -25.65790946531999950, 191.0048140716000376, 104.1537698728999999 ) ) ; -#21698 = CARTESIAN_POINT ( 'NONE', ( 2.893325850217000283, 191.0743569784000044, 103.9380752567000030 ) ) ; -#21699 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; -#21700 = EDGE_CURVE ( 'NONE', #32568, #9773, #19938, .T. ) ; -#21701 = ORIENTED_EDGE ( 'NONE', *, *, #30265, .F. ) ; -#21702 = AXIS2_PLACEMENT_3D ( 'NONE', #18190, #2869, #18394 ) ; -#21703 = CARTESIAN_POINT ( 'NONE', ( -3.796900415192997702, 136.7373034043747850, 94.03478540737643243 ) ) ; -#21704 = EDGE_CURVE ( 'NONE', #31968, #9285, #38472, .T. ) ; -#21705 = VERTEX_POINT ( 'NONE', #16866 ) ; -#21706 = VECTOR ( 'NONE', #21540, 1000.000000000000000 ) ; -#21707 = VECTOR ( 'NONE', #38096, 1000.000000000000000 ) ; -#21708 = FACE_OUTER_BOUND ( 'NONE', #3062, .T. ) ; -#21709 = CARTESIAN_POINT ( 'NONE', ( 0.5459373363532030732, 211.4999999999976694, 76.05817489710604207 ) ) ; -#21710 = CARTESIAN_POINT ( 'NONE', ( 25.49273537670449130, 207.4083917605111367, 77.06627999559472642 ) ) ; -#21711 = CARTESIAN_POINT ( 'NONE', ( -36.06180846984999988, 192.0376933189999988, 106.6384909970000194 ) ) ; -#21712 = DIRECTION ( 'NONE', ( 0.0002393071182785538528, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#21713 = CARTESIAN_POINT ( 'NONE', ( -23.00157826576616671, 118.1131156702000169, 87.27825658246501916 ) ) ; -#21714 = CARTESIAN_POINT ( 'NONE', ( -12.63788667702346302, 134.4389615668880822, 93.60904485994920776 ) ) ; -#21715 = CARTESIAN_POINT ( 'NONE', ( -36.91676615048000087, 190.9988463978000084, 106.4471113082999949 ) ) ; -#21716 = ORIENTED_EDGE ( 'NONE', *, *, #7291, .F. ) ; -#21717 = CARTESIAN_POINT ( 'NONE', ( -19.43581021992248381, 124.5763273985873241, 178.2048886345954486 ) ) ; -#21718 = CARTESIAN_POINT ( 'NONE', ( -35.94216947274806984, 191.5529916554748127, 103.8979322272315500 ) ) ; -#21719 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; -#21722 = EDGE_LOOP ( 'NONE', ( #14595, #28720, #12344, #36687, #3777 ) ) ; -#21721 = PLANE ( 'NONE', #3765 ) ; -#21720 = CARTESIAN_POINT ( 'NONE', ( -2.622304094908183725, 208.9737167940518816, 73.45181557642186476 ) ) ; -#21723 = EDGE_CURVE ( 'NONE', #18841, #23325, #24045, .T. ) ; -#21724 = ORIENTED_EDGE ( 'NONE', *, *, #38522, .F. ) ; -#21725 = CARTESIAN_POINT ( 'NONE', ( -3.704309072947313375, 175.3139521501252034, 100.3006306135645644 ) ) ; -#21726 = VERTEX_POINT ( 'NONE', #33217 ) ; -#21727 = CONICAL_SURFACE ( 'NONE', #10635, 5.250000000012835955, 0.7853981634113290644 ) ; -#21728 = ORIENTED_EDGE ( 'NONE', *, *, #18453, .T. ) ; -#21730 = AXIS2_PLACEMENT_3D ( 'NONE', #4857, #14487, #39405 ) ; -#21729 = FACE_OUTER_BOUND ( 'NONE', #39327, .T. ) ; -#21731 = VECTOR ( 'NONE', #33800, 1000.000000000000000 ) ; -#21732 = DIRECTION ( 'NONE', ( -0.0005884949961238380989, 0.2249510543439045829, -0.9743698870671267942 ) ) ; -#21733 = CARTESIAN_POINT ( 'NONE', ( -41.28986358703587456, 120.5685454323574817, 90.59221360106587895 ) ) ; -#21734 = CARTESIAN_POINT ( 'NONE', ( 12.64209925790531308, 131.0231129754641302, 89.89439459407216759 ) ) ; -#21735 = FACE_OUTER_BOUND ( 'NONE', #20091, .T. ) ; -#21736 = ORIENTED_EDGE ( 'NONE', *, *, #16040, .F. ) ; -#21737 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#21738 = ORIENTED_EDGE ( 'NONE', *, *, #14077, .F. ) ; -#21739 = CARTESIAN_POINT ( 'NONE', ( 5.659153654835778369, 124.3673852322629187, 88.36203164978959990 ) ) ; -#21740 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#21741 = FACE_BOUND ( 'NONE', #1501, .T. ) ; -#21742 = CARTESIAN_POINT ( 'NONE', ( 16.22247671335948382, 122.0701589875174164, 174.5870958018068109 ) ) ; -#21743 = ORIENTED_EDGE ( 'NONE', *, *, #7077, .T. ) ; -#21744 = DIRECTION ( 'NONE', ( -0.0005884949961189823910, 0.2249510543439030286, -0.9743698870671271273 ) ) ; -#21745 = CARTESIAN_POINT ( 'NONE', ( 1.079159667266636147, 188.6661133437667672, 103.2092760790662425 ) ) ; -#21746 = LINE ( 'NONE', #12726, #34841 ) ; -#21747 = CARTESIAN_POINT ( 'NONE', ( -23.36581923842090092, 181.0107737450888976, 104.5356085457618889 ) ) ; -#21748 = EDGE_CURVE ( 'NONE', #15091, #24326, #23526, .T. ) ; -#21749 = ORIENTED_EDGE ( 'NONE', *, *, #31281, .T. ) ; -#21750 = CARTESIAN_POINT ( 'NONE', ( 1.969467697532000017, 189.5457934668000064, 105.8936626681000064 ) ) ; -#21751 = EDGE_CURVE ( 'NONE', #35446, #37130, #20240, .T. ) ; -#21752 = CARTESIAN_POINT ( 'NONE', ( -35.95405601968204223, 218.5902260770999987, 76.08021997845068540 ) ) ; -#21753 = CARTESIAN_POINT ( 'NONE', ( 36.13112569603666202, 191.5149598075008726, 103.8458137197516038 ) ) ; -#21754 = CARTESIAN_POINT ( 'NONE', ( 5.770779297447407252, 149.0005910511659408, 94.04893340636374433 ) ) ; -#21755 = AXIS2_PLACEMENT_3D ( 'NONE', #2306, #5360, #2898 ) ; -#21756 = ORIENTED_EDGE ( 'NONE', *, *, #9943, .F. ) ; -#21757 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #642, #37859 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21758 = CONICAL_SURFACE ( 'NONE', #11979, 22.50000000000906653, 0.7853981633972855203 ) ; -#21759 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#21760 = FACE_OUTER_BOUND ( 'NONE', #9084, .T. ) ; -#21761 = AXIS2_PLACEMENT_3D ( 'NONE', #27036, #8207, #39468 ) ; -#21762 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #108, #9725, #28329, #28139, #37926, #6234, #22604, #12567, #19102, #19505 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999849565, 0.3750000000000334732, 0.4375000000000577871, 0.5000000000000820455, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21763 = ORIENTED_EDGE ( 'NONE', *, *, #6190, .T. ) ; -#21764 = CARTESIAN_POINT ( 'NONE', ( 35.54494089926004108, 209.7096602146001487, 73.03703587511542139 ) ) ; -#21765 = VERTEX_POINT ( 'NONE', #14234 ) ; -#21767 = DIRECTION ( 'NONE', ( 0.7933533411653341805, -0.5930537057989598848, -0.1373964268091485141 ) ) ; -#21766 = CARTESIAN_POINT ( 'NONE', ( 36.21922981210563108, 191.9874384596776338, 104.3789711234515210 ) ) ; -#21768 = EDGE_LOOP ( 'NONE', ( #525, #25332, #11070, #11223 ) ) ; -#21769 = ORIENTED_EDGE ( 'NONE', *, *, #9876, .F. ) ; -#21770 = ADVANCED_FACE ( 'NONE', ( #29777 ), #31995, .F. ) ; -#21771 = ORIENTED_EDGE ( 'NONE', *, *, #17556, .T. ) ; -#21772 = CARTESIAN_POINT ( 'NONE', ( 2.665066171023000141, 208.9435558216999880, 75.81117239588000700 ) ) ; -#21773 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#21774 = CARTESIAN_POINT ( 'NONE', ( 12.63839252860180906, 184.0139321654835101, 102.6414058913664178 ) ) ; -#21775 = VERTEX_POINT ( 'NONE', #27936 ) ; -#21776 = ORIENTED_EDGE ( 'NONE', *, *, #28633, .F. ) ; -#21777 = DIRECTION ( 'NONE', ( -0.0006039748319387963508, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#21778 = LINE ( 'NONE', #27534, #28290 ) ; -#21779 = CARTESIAN_POINT ( 'NONE', ( 13.50311538254501009, 187.4520168550668302, 105.7007522453218797 ) ) ; -#21780 = CARTESIAN_POINT ( 'NONE', ( -34.95487770220995571, 225.9002260770353985, 76.07961649987865371 ) ) ; -#21781 = AXIS2_PLACEMENT_3D ( 'NONE', #1164, #13643, #19960 ) ; -#21782 = VERTEX_POINT ( 'NONE', #6224 ) ; -#21783 = ADVANCED_FACE ( 'NONE', ( #31383 ), #12560, .F. ) ; -#21784 = VERTEX_POINT ( 'NONE', #2773 ) ; -#21785 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#21786 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.271205595054999941E-14, 1.000000000000000000 ) ) ; -#21787 = CIRCLE ( 'NONE', #9378, 8.000001494568982352 ) ; -#21788 = CARTESIAN_POINT ( 'NONE', ( -27.41912080593000312, 124.8060542353999978, 88.82539917399999752 ) ) ; -#21789 = EDGE_CURVE ( 'NONE', #18192, #37405, #11127, .T. ) ; -#21790 = EDGE_LOOP ( 'NONE', ( #17967, #29334, #3376, #27711 ) ) ; -#21791 = AXIS2_PLACEMENT_3D ( 'NONE', #23836, #34813, #18881 ) ; -#21792 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#21793 = FACE_OUTER_BOUND ( 'NONE', #31329, .T. ) ; -#21794 = ORIENTED_EDGE ( 'NONE', *, *, #251, .T. ) ; -#21795 = EDGE_CURVE ( 'NONE', #33611, #39608, #12631, .T. ) ; -#21796 = CARTESIAN_POINT ( 'NONE', ( 20.50137524228200192, 192.1862632329211067, 106.4093414499090926 ) ) ; -#21797 = EDGE_CURVE ( 'NONE', #8652, #4634, #5927, .T. ) ; -#21798 = FACE_OUTER_BOUND ( 'NONE', #493, .T. ) ; -#21799 = EDGE_CURVE ( 'NONE', #4109, #978, #40166, .T. ) ; -#21800 = EDGE_CURVE ( 'NONE', #33315, #25840, #25369, .T. ) ; -#21801 = CARTESIAN_POINT ( 'NONE', ( -44.79353637294777002, 181.5138299656995287, 101.5857470109101399 ) ) ; -#21802 = CARTESIAN_POINT ( 'NONE', ( -39.74908053984227507, 182.4717680925825789, 106.9353792437991473 ) ) ; -#21803 = ORIENTED_EDGE ( 'NONE', *, *, #31766, .T. ) ; -#21804 = FACE_OUTER_BOUND ( 'NONE', #22631, .T. ) ; -#21805 = CARTESIAN_POINT ( 'NONE', ( 35.46133700181365356, 82.39441720660606450, 284.2611062593159659 ) ) ; -#21806 = CARTESIAN_POINT ( 'NONE', ( -37.83887613609999789, 119.2344500291000031, 87.17227830417002110 ) ) ; -#21807 = CARTESIAN_POINT ( 'NONE', ( 36.18573331279999650, 112.9861525913999998, 89.60135871797001528 ) ) ; -#21808 = VERTEX_POINT ( 'NONE', #21594 ) ; -#21809 = AXIS2_PLACEMENT_3D ( 'NONE', #37673, #22355, #34778 ) ; -#21810 = AXIS2_PLACEMENT_3D ( 'NONE', #39037, #11046, #14728 ) ; -#21811 = CARTESIAN_POINT ( 'NONE', ( 15.75161875086000052, 144.6230676373999984, 95.85461094414999650 ) ) ; -#21812 = ORIENTED_EDGE ( 'NONE', *, *, #31118, .F. ) ; -#21813 = CARTESIAN_POINT ( 'NONE', ( -38.01550421529999824, 118.9002399435000115, 90.44667324955001675 ) ) ; -#21814 = AXIS2_PLACEMENT_3D ( 'NONE', #15986, #38069, #6185 ) ; -#21815 = EDGE_LOOP ( 'NONE', ( #12178, #36565, #30928, #1282, #23818, #30066 ) ) ; -#21816 = CARTESIAN_POINT ( 'NONE', ( 20.00185907575961153, 191.2197610873820963, 106.8662960061243155 ) ) ; -#21817 = CARTESIAN_POINT ( 'NONE', ( 6.937632354211411504E-13, 155.6803346353071618, 98.67347229716645529 ) ) ; -#21818 = CARTESIAN_POINT ( 'NONE', ( 23.36940079100686063, 177.7945392694463749, 100.6858723966742843 ) ) ; -#21819 = CARTESIAN_POINT ( 'NONE', ( -38.11718854129877343, 118.8155790694493561, 90.29079743518840928 ) ) ; -#21820 = ORIENTED_EDGE ( 'NONE', *, *, #37517, .F. ) ; -#21821 = ORIENTED_EDGE ( 'NONE', *, *, #18892, .T. ) ; -#21822 = CARTESIAN_POINT ( 'NONE', ( 0.8006758311543553663, 189.0100522499311637, 105.7387579588670263 ) ) ; -#21823 = CARTESIAN_POINT ( 'NONE', ( -37.54767055407849341, 212.5463739241209851, 75.74784908760784674 ) ) ; -#21824 = EDGE_CURVE ( 'NONE', #24048, #20022, #6794, .T. ) ; -#21825 = VERTEX_POINT ( 'NONE', #25062 ) ; -#21826 = CARTESIAN_POINT ( 'NONE', ( 6.271009700395496544, 163.8321258783347787, 97.98591366900288335 ) ) ; -#21827 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21828 = EDGE_LOOP ( 'NONE', ( #20692, #6035, #602, #3636, #27877, #27849 ) ) ; -#21829 = PLANE ( 'NONE', #5241 ) ; -#21830 = ADVANCED_FACE ( 'NONE', ( #16426 ), #6821, .F. ) ; -#21831 = CARTESIAN_POINT ( 'NONE', ( 18.60795789290834179, 125.1298367273077616, 178.8296990479766748 ) ) ; -#21832 = CARTESIAN_POINT ( 'NONE', ( 45.54775444177381871, 116.6087611523222023, 153.3386251583491742 ) ) ; -#21833 = ORIENTED_EDGE ( 'NONE', *, *, #33030, .F. ) ; -#21834 = CARTESIAN_POINT ( 'NONE', ( 28.20349900165999912, 125.2316176986000045, 88.71892600564000020 ) ) ; -#21835 = VECTOR ( 'NONE', #24291, 1000.000000000000000 ) ; -#21836 = ADVANCED_FACE ( 'NONE', ( #35222 ), #22989, .F. ) ; -#21837 = CARTESIAN_POINT ( 'NONE', ( 3.677495930535071622, 167.8566700076929692, 101.3370465724240574 ) ) ; -#21838 = CARTESIAN_POINT ( 'NONE', ( -25.35785070895000004, 191.5893649937000021, 106.2870274426000066 ) ) ; -#21839 = CONICAL_SURFACE ( 'NONE', #33580, 4.999999999914826354, 0.7853981634347277918 ) ; -#21840 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825913618700161, 0.0005734119025369202160 ) ) ; -#21841 = EDGE_CURVE ( 'NONE', #16912, #19220, #19294, .T. ) ; -#21842 = EDGE_CURVE ( 'NONE', #21943, #33199, #698, .T. ) ; -#21843 = VERTEX_POINT ( 'NONE', #22393 ) ; -#21844 = CARTESIAN_POINT ( 'NONE', ( -40.69155169351290624, 119.9027463543584275, 92.49074896885643682 ) ) ; -#21845 = ADVANCED_FACE ( 'NONE', ( #28717 ), #33353, .F. ) ; -#21846 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921576300, -0.2249510932971602595 ) ) ; -#21847 = CARTESIAN_POINT ( 'NONE', ( 36.76307291026488855, 191.6283014451216502, 104.3440614356115077 ) ) ; -#21848 = CARTESIAN_POINT ( 'NONE', ( -38.93740081958814159, 183.0561992808241882, 105.0172067937131999 ) ) ; -#21849 = ORIENTED_EDGE ( 'NONE', *, *, #19376, .F. ) ; -#21850 = LINE ( 'NONE', #34291, #23168 ) ; -#21851 = CARTESIAN_POINT ( 'NONE', ( 2.712710242590048448, 205.4139694218411591, 76.23344288180996386 ) ) ; -#21852 = CARTESIAN_POINT ( 'NONE', ( -42.83084823883022807, 121.2593020781266659, 90.75261808358531823 ) ) ; -#21853 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; -#21854 = CARTESIAN_POINT ( 'NONE', ( -36.20721311647999840, 191.7525047693000033, 104.2843089044999942 ) ) ; -#21855 = CARTESIAN_POINT ( 'NONE', ( -25.50393605561328414, 190.9794142776714807, 106.3251602599453776 ) ) ; -#21856 = LOCAL_TIME ( 14, 25, 27.00000000000000000, #9388 ) ; -#21857 = DIRECTION ( 'NONE', ( -0.0005884949961234174284, 0.2249510543439059151, -0.9743698870671263501 ) ) ; -#21858 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; -#21859 = DIRECTION ( 'NONE', ( -0.0005884949961242895607, 0.2249510543439076360, -0.9743698870671260170 ) ) ; -#21860 = VECTOR ( 'NONE', #27562, 999.9999999999998863 ) ; -#21861 = VECTOR ( 'NONE', #32739, 1000.000000000000227 ) ; -#21862 = CARTESIAN_POINT ( 'NONE', ( -13.50000077922901731, 184.9627595935803868, 102.3630947892575307 ) ) ; -#21863 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -5.029100735414826696E-18, -0.0006039748319369899615 ) ) ; -#21864 = CARTESIAN_POINT ( 'NONE', ( 38.06830324738000115, 190.8197764434999897, 106.3743150780999969 ) ) ; -#21865 = CARTESIAN_POINT ( 'NONE', ( 37.18465032402060189, 191.0618976901199915, 106.3215651414160163 ) ) ; -#21866 = AXIS2_PLACEMENT_3D ( 'NONE', #15471, #30618, #31209 ) ; -#21867 = VERTEX_POINT ( 'NONE', #10325 ) ; -#21868 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22941, #13726, #35368, #32338 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21870 = ORIENTED_EDGE ( 'NONE', *, *, #36786, .F. ) ; -#21869 = CARTESIAN_POINT ( 'NONE', ( 36.15716616049000010, 191.3344399890999910, 106.7319169443999982 ) ) ; -#21871 = ORIENTED_EDGE ( 'NONE', *, *, #13506, .F. ) ; -#21872 = VERTEX_POINT ( 'NONE', #22593 ) ; -#21873 = ORIENTED_EDGE ( 'NONE', *, *, #1903, .F. ) ; -#21874 = CARTESIAN_POINT ( 'NONE', ( -5.145159818766837034, 135.0788229529110538, 90.84143235571785624 ) ) ; -#21875 = CARTESIAN_POINT ( 'NONE', ( 20.00192081821563761, 126.7670151487632353, 91.98617178303544506 ) ) ; -#21876 = ADVANCED_FACE ( 'NONE', ( #16027 ), #28521, .F. ) ; -#21878 = ADVANCED_FACE ( 'NONE', ( #16232 ), #13184, .T. ) ; -#21877 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35946, #7144, #25982, #1827, #35334, #1414 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 4 ), - ( 0.000000000000000000, 0.3333323949805780950, 0.6666648884538761699, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21879 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.271205131337281593E-14, 1.000000000000000000 ) ) ; -#21880 = CARTESIAN_POINT ( 'NONE', ( 45.26991834669612302, 123.8840750961899744, 93.35648333539963062 ) ) ; -#21881 = ADVANCED_FACE ( 'NONE', ( #38500 ), #28784, .F. ) ; -#21882 = ORIENTED_EDGE ( 'NONE', *, *, #18835, .T. ) ; -#21883 = CARTESIAN_POINT ( 'NONE', ( 36.35031782592000127, 191.7402427641999907, 104.2390283135000004 ) ) ; -#21884 = PLANE ( 'NONE', #22779 ) ; -#21885 = CARTESIAN_POINT ( 'NONE', ( -36.27950425524976907, 191.8188495074159334, 104.4051415298545180 ) ) ; -#21886 = CARTESIAN_POINT ( 'NONE', ( -20.16657163988445589, 151.9255956737779343, 94.91094380485814952 ) ) ; -#21887 = EDGE_LOOP ( 'NONE', ( #37743, #24594, #22818, #6339, #20005, #26368, #2075, #4454, #29160, #28382, #13810, #20949 ) ) ; -#21888 = EDGE_CURVE ( 'NONE', #34680, #17164, #7224, .T. ) ; -#21889 = CARTESIAN_POINT ( 'NONE', ( -21.44693686545786449, 130.1487540525002657, 89.71308199639462089 ) ) ; -#21890 = CARTESIAN_POINT ( 'NONE', ( 36.11364262193256280, 191.5260145455536929, 103.8483746271915322 ) ) ; -#21891 = CARTESIAN_POINT ( 'NONE', ( -3.537752371395798789, 168.4800613451581910, 98.55175200207808928 ) ) ; -#21892 = CARTESIAN_POINT ( 'NONE', ( -21.50774950077886061, 213.7117741840153826, 76.07152960608476633 ) ) ; -#21893 = VECTOR ( 'NONE', #32844, 1000.000000000000000 ) ; -#21894 = EDGE_CURVE ( 'NONE', #34518, #17427, #3956, .T. ) ; -#21895 = ORIENTED_EDGE ( 'NONE', *, *, #39911, .T. ) ; -#21896 = CARTESIAN_POINT ( 'NONE', ( 15.66818115446893422, 137.9078187121401697, 94.21874166949204721 ) ) ; -#21897 = CARTESIAN_POINT ( 'NONE', ( 2.281943726123000005, 189.4781187019000015, 103.5431292473000013 ) ) ; -#21898 = AXIS2_PLACEMENT_3D ( 'NONE', #4712, #17171, #7174 ) ; -#21899 = AXIS2_PLACEMENT_3D ( 'NONE', #27556, #2384, #39984 ) ; -#21900 = CARTESIAN_POINT ( 'NONE', ( -29.94659852602001138, 103.6131156703197576, 89.78587174324022158 ) ) ; -#21901 = AXIS2_PLACEMENT_3D ( 'NONE', #28307, #13171, #22772 ) ; -#21902 = EDGE_LOOP ( 'NONE', ( #31963, #28548, #16928, #17404 ) ) ; -#21903 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#21904 = ORIENTED_EDGE ( 'NONE', *, *, #10986, .F. ) ; -#21905 = EDGE_CURVE ( 'NONE', #3990, #24029, #34816, .T. ) ; -#21906 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11956, #21571, #39533, #17449, #26889, #4987, #23815, #21364, #11327, #8272, #30147 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000203171, 0.6250000000000158762, 0.6875000000000135447, 0.7500000000000111022, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21907 = LINE ( 'NONE', #15557, #37174 ) ; -#21908 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540931611, 160.6260167145983360, 97.25887387932731087 ) ) ; -#21909 = CARTESIAN_POINT ( 'NONE', ( -25.99154556069859012, 196.5784392978119968, 103.8908015619487060 ) ) ; -#21910 = CARTESIAN_POINT ( 'NONE', ( -37.20408499829227367, 178.1325612192622430, 136.7211859319445466 ) ) ; -#21911 = CARTESIAN_POINT ( 'NONE', ( 30.01356315559810639, 141.5423698496542499, 27.80511976906114668 ) ) ; -#21912 = DIRECTION ( 'NONE', ( -0.1305262607518133389, 0.9660168937933039102, 0.2231014481353405798 ) ) ; -#21913 = CARTESIAN_POINT ( 'NONE', ( -1.871327295256297152, 189.6068325900267553, 105.9136324549362058 ) ) ; -#21914 = ORIENTED_EDGE ( 'NONE', *, *, #22278, .T. ) ; -#21915 = CARTESIAN_POINT ( 'NONE', ( -25.49166333918160987, 196.1181869037000070, 103.6951339686000040 ) ) ; -#21916 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620728018, 0.0004744508866335444284 ) ) ; -#21917 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673393900, 153.8082236412882366, 95.66734676454734654 ) ) ; -#21919 = FACE_OUTER_BOUND ( 'NONE', #32813, .T. ) ; -#21918 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971565680 ) ) ; -#21920 = ORIENTED_EDGE ( 'NONE', *, *, #31525, .F. ) ; -#21921 = ORIENTED_EDGE ( 'NONE', *, *, #16594, .F. ) ; -#21922 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #373, #18758, #9796, #22271 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 2.705159532099978906E-07, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21923 = CONICAL_SURFACE ( 'NONE', #27805, 22.50000000000898837, 0.7853981633973132759 ) ; -#21924 = ADVANCED_FACE ( 'NONE', ( #35015 ), #20274, .F. ) ; -#21925 = LINE ( 'NONE', #18815, #36981 ) ; -#21926 = EDGE_CURVE ( 'NONE', #33981, #38943, #16620, .T. ) ; -#21927 = CIRCLE ( 'NONE', #4264, 58.90509898146415679 ) ; -#21928 = ADVANCED_FACE ( 'NONE', ( #1094 ), #31314, .T. ) ; -#21929 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18225, #2900, #6168, #36653, #39704, #15385 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21930 = ORIENTED_EDGE ( 'NONE', *, *, #13900, .F. ) ; -#21931 = LINE ( 'NONE', #25203, #36089 ) ; -#21932 = DIRECTION ( 'NONE', ( -0.0006039748319367822284, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#21933 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250614502, 179.6252109630515577, 101.6466942236997824 ) ) ; -#21934 = CARTESIAN_POINT ( 'NONE', ( 30.66227699762960412, 129.7971910029650644, 89.60044452426214434 ) ) ; -#21935 = CARTESIAN_POINT ( 'NONE', ( -31.70535868460997619, 226.4002260771022463, 73.57765341574507545 ) ) ; -#21936 = ORIENTED_EDGE ( 'NONE', *, *, #147, .F. ) ; -#21937 = ADVANCED_FACE ( 'NONE', ( #24993 ), #12492, .F. ) ; -#21938 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#21939 = ORIENTED_EDGE ( 'NONE', *, *, #34450, .F. ) ; -#21940 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971566235 ) ) ; -#21941 = CARTESIAN_POINT ( 'NONE', ( 20.89466079040630575, 182.4265417833274796, 104.8357029080749783 ) ) ; -#21942 = EDGE_CURVE ( 'NONE', #4210, #27010, #27870, .T. ) ; -#21943 = VERTEX_POINT ( 'NONE', #21917 ) ; -#21944 = DIRECTION ( 'NONE', ( -0.0004161288024422820394, -0.5299192578930420616, -0.8480479980230526404 ) ) ; -#21945 = CARTESIAN_POINT ( 'NONE', ( 0.9088675734344845436, 188.6359493924010167, 103.2024150330645398 ) ) ; -#21946 = FACE_OUTER_BOUND ( 'NONE', #15815, .T. ) ; -#21947 = VERTEX_POINT ( 'NONE', #5963 ) ; -#21948 = CARTESIAN_POINT ( 'NONE', ( -19.42038588717154113, 126.1613205632184673, 176.0264188615619503 ) ) ; -#21949 = CARTESIAN_POINT ( 'NONE', ( -30.11526512126999933, 126.4563218505000179, 91.68818888923999566 ) ) ; -#21950 = VECTOR ( 'NONE', #23323, 1000.000000000000114 ) ; -#21951 = EDGE_CURVE ( 'NONE', #585, #38693, #29705, .T. ) ; -#21952 = DIRECTION ( 'NONE', ( 0.6087614883550946931, -0.7730004026499608383, -0.1785492307423600933 ) ) ; -#21953 = DIRECTION ( 'NONE', ( -0.5987319960703951782, -0.8009494346596170988, 0.000000000000000000 ) ) ; -#21954 = DIRECTION ( 'NONE', ( 0.6087614115774877543, -0.7730004600455409047, -0.1785492440296705396 ) ) ; -#21955 = AXIS2_PLACEMENT_3D ( 'NONE', #28114, #33613, #27526 ) ; -#21956 = EDGE_LOOP ( 'NONE', ( #2720, #5469, #35806, #8328 ) ) ; -#21957 = CARTESIAN_POINT ( 'NONE', ( 25.99886678296517672, 118.8155665066540934, 87.25209012101137773 ) ) ; -#21958 = VECTOR ( 'NONE', #38503, 1000.000000000000114 ) ; -#21959 = CARTESIAN_POINT ( 'NONE', ( 15.34881605426699025, 136.8304653680823435, 91.23345309747541876 ) ) ; -#21960 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540930012, 174.4013312751985438, 100.4391564142062094 ) ) ; -#21961 = ORIENTED_EDGE ( 'NONE', *, *, #38672, .F. ) ; -#21962 = CARTESIAN_POINT ( 'NONE', ( 16.43146722802687520, 121.9169648965784774, 177.7564454048611253 ) ) ; -#21963 = CARTESIAN_POINT ( 'NONE', ( 3.061557430615667652, 191.9759150222000130, 101.9195982364086888 ) ) ; -#21965 = CARTESIAN_POINT ( 'NONE', ( -2.768682643724713621, 190.8910486004296558, 106.6325679542271985 ) ) ; -#21964 = FACE_OUTER_BOUND ( 'NONE', #36506, .T. ) ; -#21966 = EDGE_LOOP ( 'NONE', ( #35019, #10147, #6139, #13024 ) ) ; -#21967 = ORIENTED_EDGE ( 'NONE', *, *, #28298, .T. ) ; -#21968 = CARTESIAN_POINT ( 'NONE', ( -40.05779377713677292, 77.14301703112144537, 290.6649606259057919 ) ) ; -#21969 = CIRCLE ( 'NONE', #23962, 2.000000000040191850 ) ; -#21970 = CARTESIAN_POINT ( 'NONE', ( -35.95814990381343534, 192.2304528612855847, 104.4264063346583669 ) ) ; -#21971 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#21972 = FACE_OUTER_BOUND ( 'NONE', #35230, .T. ) ; -#21973 = EDGE_CURVE ( 'NONE', #1318, #6960, #31413, .T. ) ; -#21974 = VERTEX_POINT ( 'NONE', #31724 ) ; -#21975 = EDGE_CURVE ( 'NONE', #7592, #22581, #27505, .T. ) ; -#21976 = VECTOR ( 'NONE', #22072, 1000.000000000000114 ) ; -#21977 = AXIS2_PLACEMENT_3D ( 'NONE', #29340, #7244, #20690 ) ; -#21978 = ORIENTED_EDGE ( 'NONE', *, *, #26637, .F. ) ; -#21979 = CARTESIAN_POINT ( 'NONE', ( -36.55077531636867150, 265.2798088768021785, 205.0571533001752584 ) ) ; -#21980 = LINE ( 'NONE', #31373, #1088 ) ; -#21981 = DIRECTION ( 'NONE', ( -0.0006039748319382907873, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#21982 = CARTESIAN_POINT ( 'NONE', ( 35.72740534132000079, 192.3407274401000109, 104.0317702792000034 ) ) ; -#21983 = ORIENTED_EDGE ( 'NONE', *, *, #5580, .T. ) ; -#21984 = AXIS2_PLACEMENT_3D ( 'NONE', #31473, #19777, #32086 ) ; -#21985 = ORIENTED_EDGE ( 'NONE', *, *, #10778, .F. ) ; -#21986 = ORIENTED_EDGE ( 'NONE', *, *, #34582, .F. ) ; -#21987 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#21988 = AXIS2_PLACEMENT_3D ( 'NONE', #17328, #997, #1203 ) ; -#21989 = EDGE_CURVE ( 'NONE', #4671, #14541, #3307, .T. ) ; -#21990 = LINE ( 'NONE', #28128, #29847 ) ; -#21991 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3525, #9289, #9083, #37090, #34205, #30961, #474, #40145, #12156, #3334, #21572, #12751, #28302, #77, #266 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999998769318, 0.1874999999998715194, 0.2499999999998661071, 0.3749999999998618883, 0.4374999999998645528, 0.4687499999998658851, 0.4999999999998672173, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#21992 = CARTESIAN_POINT ( 'NONE', ( -26.40419816585999868, 122.8758340463000138, 88.03691424743999505 ) ) ; -#21993 = EDGE_LOOP ( 'NONE', ( #803, #39747, #21416, #28854 ) ) ; -#21994 = LINE ( 'NONE', #102, #5592 ) ; -#21995 = CARTESIAN_POINT ( 'NONE', ( 15.50029467073742140, 160.6294874787857623, 97.24095194441136414 ) ) ; -#21996 = ORIENTED_EDGE ( 'NONE', *, *, #8536, .F. ) ; -#21997 = CARTESIAN_POINT ( 'NONE', ( 3.608102626577426086, 174.7005586332282121, 102.9883855544077420 ) ) ; -#21998 = CARTESIAN_POINT ( 'NONE', ( -20.49970532888763941, 191.4139234226054498, 104.3698659823340478 ) ) ; -#21999 = ADVANCED_FACE ( 'NONE', ( #19020 ), #28154, .F. ) ; -#22000 = CARTESIAN_POINT ( 'NONE', ( -39.13061847294451923, 119.0370893851462029, 89.74140283572911869 ) ) ; -#22001 = CARTESIAN_POINT ( 'NONE', ( -18.96075656525927400, 149.0999870379767742, 180.7331665572989721 ) ) ; -#22002 = AXIS2_PLACEMENT_3D ( 'NONE', #12857, #31871, #38931 ) ; -#22003 = EDGE_LOOP ( 'NONE', ( #35332, #20160, #16930, #27223 ) ) ; -#22004 = CARTESIAN_POINT ( 'NONE', ( 3.882702611521182234, 148.0331269957187317, 129.7473673645792474 ) ) ; -#22005 = ORIENTED_EDGE ( 'NONE', *, *, #35981, .T. ) ; -#22006 = VERTEX_POINT ( 'NONE', #19215 ) ; -#22007 = CARTESIAN_POINT ( 'NONE', ( 13.55367387944097146, 148.0748368286854486, 93.83050549129562512 ) ) ; -#22008 = AXIS2_PLACEMENT_3D ( 'NONE', #11252, #17572, #39859 ) ; -#22009 = CARTESIAN_POINT ( 'NONE', ( -37.43252112508000096, 118.7416284442000176, 87.16657656499999973 ) ) ; -#22010 = CIRCLE ( 'NONE', #29823, 6.000000367552694058 ) ; -#22011 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927783543234, 0.0005734119022076374994 ) ) ; -#22012 = ORIENTED_EDGE ( 'NONE', *, *, #6393, .T. ) ; -#22013 = CYLINDRICAL_SURFACE ( 'NONE', #10856, 4.999999999999990230 ) ; -#22014 = ORIENTED_EDGE ( 'NONE', *, *, #30553, .F. ) ; -#22015 = AXIS2_PLACEMENT_3D ( 'NONE', #36698, #10610, #33623 ) ; -#22016 = ADVANCED_FACE ( 'NONE', ( #28252 ), #2891, .F. ) ; -#22017 = CARTESIAN_POINT ( 'NONE', ( -25.50922756583905837, 191.3757872987501969, 104.3640622938216183 ) ) ; -#22018 = ADVANCED_FACE ( 'NONE', ( #40100 ), #4631, .F. ) ; -#22019 = EDGE_LOOP ( 'NONE', ( #19531, #21986, #14193, #1572, #5838, #31487, #15239, #37234, #19212, #6207 ) ) ; -#22020 = CARTESIAN_POINT ( 'NONE', ( 11.42879460937821179, 158.6506707231792745, 96.27341295134117161 ) ) ; -#22021 = CARTESIAN_POINT ( 'NONE', ( -32.35856811579363068, 153.0051697192221241, 291.5780876995356721 ) ) ; -#22022 = CARTESIAN_POINT ( 'NONE', ( -31.99382095406631876, 162.7703235776980080, 188.0763422140252317 ) ) ; -#22023 = CARTESIAN_POINT ( 'NONE', ( -20.97965385745949618, 158.7746864580521731, 96.32161813573080167 ) ) ; -#22024 = EDGE_CURVE ( 'NONE', #31599, #7038, #6358, .T. ) ; -#22025 = CARTESIAN_POINT ( 'NONE', ( -16.11981483134459836, 151.5072451357098373, 180.2250316836445165 ) ) ; -#22026 = ADVANCED_FACE ( 'NONE', ( #3473 ), #39219, .F. ) ; -#22027 = CARTESIAN_POINT ( 'NONE', ( -35.65904030449263473, 114.4088988627134285, 90.28932200601107638 ) ) ; -#22028 = ORIENTED_EDGE ( 'NONE', *, *, #37027, .T. ) ; -#22029 = ORIENTED_EDGE ( 'NONE', *, *, #23760, .F. ) ; -#22030 = CARTESIAN_POINT ( 'NONE', ( 5.666806155083023988, 187.7449703091009781, 103.5069947386187295 ) ) ; -#22031 = CARTESIAN_POINT ( 'NONE', ( -22.50007685686057002, 158.5507592289326340, 96.61294483226545537 ) ) ; -#22032 = DIRECTION ( 'NONE', ( -0.0005884949961224831714, 0.2249510543439058596, -0.9743698870671263501 ) ) ; -#22033 = AXIS2_PLACEMENT_3D ( 'NONE', #2342, #14612, #36890 ) ; -#22034 = ORIENTED_EDGE ( 'NONE', *, *, #28386, .F. ) ; -#22035 = CARTESIAN_POINT ( 'NONE', ( 22.78080448403245839, 154.4094593426142978, 95.28739704982865533 ) ) ; -#22036 = ORIENTED_EDGE ( 'NONE', *, *, #21047, .T. ) ; -#22037 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927775716107, 0.0005734119022078446905 ) ) ; -#22038 = VECTOR ( 'NONE', #21002, 1000.000000000000000 ) ; -#22039 = CARTESIAN_POINT ( 'NONE', ( 13.76437287132129406, 125.3330071257134364, 174.7699841520732775 ) ) ; -#22040 = VERTEX_POINT ( 'NONE', #34164 ) ; -#22041 = CARTESIAN_POINT ( 'NONE', ( 28.25636536875000004, 125.5795385150000101, 89.14486926956999469 ) ) ; -#22042 = CARTESIAN_POINT ( 'NONE', ( 3.706555699605236676, 167.8627247553967550, 101.3085851372709811 ) ) ; -#22043 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; -#22044 = CARTESIAN_POINT ( 'NONE', ( -23.94751279123330079, 115.2659257769921481, 90.28224853685935614 ) ) ; -#22045 = CARTESIAN_POINT ( 'NONE', ( 43.77049507405610740, 121.6642732591545695, 90.64092531184280688 ) ) ; -#22046 = VERTEX_POINT ( 'NONE', #9640 ) ; -#22047 = LINE ( 'NONE', #34476, #5658 ) ; -#22048 = CARTESIAN_POINT ( 'NONE', ( 37.34715196620786060, 164.6396645750260745, 198.2231758344085506 ) ) ; -#22049 = CARTESIAN_POINT ( 'NONE', ( 42.65317302408573141, 111.7419529267020692, 132.5528259335349617 ) ) ; -#22050 = CARTESIAN_POINT ( 'NONE', ( -31.65770855640243653, 226.4002260771000010, 152.4718672074029087 ) ) ; -#22051 = VERTEX_POINT ( 'NONE', #34546 ) ; -#22052 = ORIENTED_EDGE ( 'NONE', *, *, #1898, .T. ) ; -#22053 = CARTESIAN_POINT ( 'NONE', ( 38.27279269694903263, 118.8579677785462536, 90.24548094119661812 ) ) ; -#22054 = CARTESIAN_POINT ( 'NONE', ( 19.33664095386789938, 148.6211264722984708, 180.7044371687416344 ) ) ; -#22055 = CARTESIAN_POINT ( 'NONE', ( 0.05451946023377000211, 0.000000000000000000, 90.26775191081999594 ) ) ; -#22056 = CARTESIAN_POINT ( 'NONE', ( -26.20112490964000074, 189.6309950977999961, 106.5274262965999981 ) ) ; -#22057 = ORIENTED_EDGE ( 'NONE', *, *, #18390, .T. ) ; -#22058 = EDGE_CURVE ( 'NONE', #27090, #2067, #3092, .T. ) ; -#22059 = AXIS2_PLACEMENT_3D ( 'NONE', #16619, #19885, #32381 ) ; -#22060 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1073, #13757, #13561, #30067, #2057, #11867, #17568, #30256, #5099, #2259, #24352, #4338, #14527, #36799, #1275, #26247, #39447, #33317, #27222, #17765, #2467, #35600, #14737 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 2, 1, 1, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.06249999999999558686, 0.09374999999999338030, 0.1249999999999911737, 0.2500000000000386913, 0.3750000000000862088, 0.4375000000001109113, 0.4687500000001164624, 0.4843750000001117439, 0.5000000000001070255, 0.6250000000000861533, 0.6875000000000701661, 0.7500000000000540679, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22061 = AXIS2_PLACEMENT_3D ( 'NONE', #12112, #6912, #777 ) ; -#22062 = CARTESIAN_POINT ( 'NONE', ( -3.668404232153524180, 126.2395570190490162, 91.36559546079023164 ) ) ; -#22063 = EDGE_CURVE ( 'NONE', #15187, #23240, #28059, .T. ) ; -#22064 = CARTESIAN_POINT ( 'NONE', ( -25.49166336760104912, 196.1181869298516744, 103.6951339797178804 ) ) ; -#22065 = DIRECTION ( 'NONE', ( -0.0002393070161718421224, -0.2243351686125209798, 0.9745120188359627234 ) ) ; -#22066 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#22067 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#22068 = CARTESIAN_POINT ( 'NONE', ( -24.42625686036400268, 103.6131156702357998, 89.78253759510907628 ) ) ; -#22069 = CARTESIAN_POINT ( 'NONE', ( 36.67680368011099290, 191.6489404259000366, 104.3309255465679968 ) ) ; -#22070 = ADVANCED_FACE ( 'NONE', ( #15954 ), #28448, .T. ) ; -#22071 = ADVANCED_FACE ( 'NONE', ( #13308 ), #14422, .T. ) ; -#22072 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927772634805, -0.0005734119022076526783 ) ) ; -#22073 = VERTEX_POINT ( 'NONE', #28845 ) ; -#22074 = EDGE_CURVE ( 'NONE', #20022, #23754, #10252, .T. ) ; -#22075 = ORIENTED_EDGE ( 'NONE', *, *, #7223, .T. ) ; -#22076 = FACE_OUTER_BOUND ( 'NONE', #32819, .T. ) ; -#22077 = EDGE_CURVE ( 'NONE', #28425, #20406, #13509, .T. ) ; -#22078 = CARTESIAN_POINT ( 'NONE', ( 20.08575548181600823, 126.7829121113273345, 91.90359369817805657 ) ) ; -#22079 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825876548734466, 0.0005734119033856171967 ) ) ; -#22080 = DIRECTION ( 'NONE', ( 2.341876692568676009E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#22081 = EDGE_LOOP ( 'NONE', ( #38490, #8718, #39894, #19197 ) ) ; -#22082 = CARTESIAN_POINT ( 'NONE', ( 35.40134743638000003, 113.4209880517999949, 87.10124724256999684 ) ) ; -#22083 = CARTESIAN_POINT ( 'NONE', ( 5.668111417358427495, 126.1276375062645485, 91.85037204208205708 ) ) ; -#22084 = CARTESIAN_POINT ( 'NONE', ( 3.667423414729225062, 126.3906643772000962, 90.71184782943855396 ) ) ; -#22085 = DIRECTION ( 'NONE', ( 0.6086215548477215131, 0.7730393818215735013, 0.1788572534946829551 ) ) ; -#22086 = CARTESIAN_POINT ( 'NONE', ( -36.74108571740404727, 191.5886187954329785, 104.3865692648879531 ) ) ; -#22087 = ORIENTED_EDGE ( 'NONE', *, *, #4068, .F. ) ; -#22088 = DIRECTION ( 'NONE', ( 0.0006039748319388624871, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#22089 = CARTESIAN_POINT ( 'NONE', ( -45.92426925958796602, 185.3756982569226182, 105.5675847568430896 ) ) ; -#22090 = DIRECTION ( 'NONE', ( -0.0002393071182785117045, -0.2252352986010040525, 0.9743043687658490271 ) ) ; -#22091 = CIRCLE ( 'NONE', #40334, 2.499999999967561948 ) ; -#22092 = PLANE ( 'NONE', #20353 ) ; -#22093 = ORIENTED_EDGE ( 'NONE', *, *, #9685, .F. ) ; -#22094 = ORIENTED_EDGE ( 'NONE', *, *, #9508, .F. ) ; -#22095 = LINE ( 'NONE', #6729, #14165 ) ; -#22096 = EDGE_CURVE ( 'NONE', #7038, #37452, #19626, .T. ) ; -#22097 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 82.27946979429628982, 310.0857197240630967 ) ) ; -#22098 = CARTESIAN_POINT ( 'NONE', ( 16.16729401867695515, 152.0078996042194603, 180.9416867539977716 ) ) ; -#22099 = EDGE_LOOP ( 'NONE', ( #39515, #10749, #27096, #35496 ) ) ; -#22100 = CYLINDRICAL_SURFACE ( 'NONE', #913, 6.000000000000008882 ) ; -#22101 = VERTEX_POINT ( 'NONE', #22719 ) ; -#22102 = CARTESIAN_POINT ( 'NONE', ( -15.94440735842906776, 121.4348066503545311, 176.4336059028145769 ) ) ; -#22103 = DIRECTION ( 'NONE', ( 1.868163743354593614E-15, 0.9743700557921585181, 0.2249510932971562072 ) ) ; -#22104 = EDGE_CURVE ( 'NONE', #14237, #29278, #7228, .T. ) ; -#22105 = CARTESIAN_POINT ( 'NONE', ( 25.17621027598018202, 212.3493493770845930, 75.54347298572716340 ) ) ; -#22106 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457974481995, -32.89481530046831637, 142.2936922234670760 ) ) ; -#22107 = DIRECTION ( 'NONE', ( 0.0004161288024568093728, 0.5299192578742120130, 0.8480479980348188951 ) ) ; -#22108 = EDGE_CURVE ( 'NONE', #12555, #16493, #19814, .T. ) ; -#22109 = CARTESIAN_POINT ( 'NONE', ( -20.89286847790088331, 136.3261294211067138, 91.13890976780785991 ) ) ; -#22110 = CARTESIAN_POINT ( 'NONE', ( -2.826855781103999821, 209.1896615391999887, 73.20597810447000597 ) ) ; -#22111 = FACE_OUTER_BOUND ( 'NONE', #1430, .T. ) ; -#22112 = ORIENTED_EDGE ( 'NONE', *, *, #8590, .T. ) ; -#22113 = EDGE_CURVE ( 'NONE', #8275, #25353, #35289, .T. ) ; -#22114 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#22115 = AXIS2_PLACEMENT_3D ( 'NONE', #1345, #32637, #17071 ) ; -#22116 = CARTESIAN_POINT ( 'NONE', ( -20.49852834234505039, 173.9502348336490059, 102.3906403256567756 ) ) ; -#22117 = DIRECTION ( 'NONE', ( 0.7075227875440994740, -0.1589708073325998561, 0.6885780910846993619 ) ) ; -#22118 = AXIS2_PLACEMENT_3D ( 'NONE', #30294, #18005, #2291 ) ; -#22119 = AXIS2_PLACEMENT_3D ( 'NONE', #3078, #6739, #25781 ) ; -#22120 = CARTESIAN_POINT ( 'NONE', ( 3.667815738790128677, 185.3461555468956590, 105.0070005413519993 ) ) ; -#22121 = ORIENTED_EDGE ( 'NONE', *, *, #38887, .T. ) ; -#22122 = EDGE_CURVE ( 'NONE', #7673, #10087, #35145, .T. ) ; -#22123 = ORIENTED_EDGE ( 'NONE', *, *, #35578, .T. ) ; -#22124 = DIRECTION ( 'NONE', ( -0.0005884949961195158185, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#22125 = CARTESIAN_POINT ( 'NONE', ( 21.26485671578026171, 115.6496691380893935, 87.25494085142716472 ) ) ; -#22126 = LINE ( 'NONE', #9648, #5651 ) ; -#22127 = ORIENTED_EDGE ( 'NONE', *, *, #1191, .T. ) ; -#22128 = CARTESIAN_POINT ( 'NONE', ( 44.24596348240854837, 122.9115719264381710, 88.00256960708196630 ) ) ; -#22129 = LINE ( 'NONE', #3696, #25093 ) ; -#22130 = DIRECTION ( 'NONE', ( -0.7072735235945706300, -0.6508952239913728954, -0.2758615054829884894 ) ) ; -#22131 = CARTESIAN_POINT ( 'NONE', ( -38.37334322435999923, 118.8333358913999973, 87.72073648586000161 ) ) ; -#22132 = LINE ( 'NONE', #10056, #12441 ) ; -#22133 = FACE_OUTER_BOUND ( 'NONE', #9908, .T. ) ; -#22134 = ORIENTED_EDGE ( 'NONE', *, *, #38008, .T. ) ; -#22135 = CARTESIAN_POINT ( 'NONE', ( 16.57457763302071641, 122.6753833417943582, 173.8792011210641704 ) ) ; -#22136 = ORIENTED_EDGE ( 'NONE', *, *, #34487, .T. ) ; -#22137 = FACE_OUTER_BOUND ( 'NONE', #9752, .T. ) ; -#22138 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #28785, #35688 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22139 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749091804, 179.1800746286054675, 103.5747911656487190 ) ) ; -#22140 = ORIENTED_EDGE ( 'NONE', *, *, #811, .F. ) ; -#22141 = AXIS2_PLACEMENT_3D ( 'NONE', #33780, #12927, #31132 ) ; -#22142 = LINE ( 'NONE', #19652, #12811 ) ; -#22143 = CARTESIAN_POINT ( 'NONE', ( 0.7458232703635604421, 188.6195839535141374, 103.1987352477761135 ) ) ; -#22144 = DIRECTION ( 'NONE', ( 0.6087614115774629964, 0.7729348350621531027, 0.1788331191967995615 ) ) ; -#22145 = AXIS2_PLACEMENT_3D ( 'NONE', #16738, #10630, #23097 ) ; -#22146 = VECTOR ( 'NONE', #29098, 1000.000000000000227 ) ; -#22147 = ORIENTED_EDGE ( 'NONE', *, *, #37892, .T. ) ; -#22148 = ORIENTED_EDGE ( 'NONE', *, *, #10800, .F. ) ; -#22149 = CARTESIAN_POINT ( 'NONE', ( 20.29162647263515495, 118.1107816779753250, 87.54680495799553341 ) ) ; -#22150 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#22151 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14064, #7916, #30208, #23669, #17100, #2409, #26542, #8543, #11608, #36123, #2204, #36539, #32855, #35698, #4645, #14879, #1579, #14677, #27166, #27373 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999344136, 0.1874999999998909761, 0.2187499999998807898, 0.2343749999998846756, 0.2499999999998885891, 0.4999999999998846478, 0.6249999999998738787, 0.6874999999998608891, 0.7187499999998606670, 0.7343749999998657740, 0.7499999999998708811, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22152 = EDGE_LOOP ( 'NONE', ( #10522, #27181, #36450, #33156 ) ) ; -#22153 = CIRCLE ( 'NONE', #29323, 2.000000000468127315 ) ; -#22154 = LINE ( 'NONE', #22359, #36259 ) ; -#22155 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#22156 = CARTESIAN_POINT ( 'NONE', ( -25.61730414488999941, 120.5278807943000032, 90.18495103081001218 ) ) ; -#22157 = ADVANCED_FACE ( 'NONE', ( #38241 ), #34650, .F. ) ; -#22158 = ADVANCED_FACE ( 'NONE', ( #35539 ), #6607, .T. ) ; -#22159 = VERTEX_POINT ( 'NONE', #1426 ) ; -#22160 = EDGE_CURVE ( 'NONE', #9253, #16546, #33086, .T. ) ; -#22161 = ADVANCED_FACE ( 'NONE', ( #19622 ), #4487, .T. ) ; -#22162 = DIRECTION ( 'NONE', ( 3.469446951953609456E-15, 0.9743700557921587402, 0.2249510932971554578 ) ) ; -#22163 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2255194953558363191, 0.9742386449830560124 ) ) ; -#22164 = ORIENTED_EDGE ( 'NONE', *, *, #13068, .F. ) ; -#22165 = ADVANCED_FACE ( 'NONE', ( #4697 ), #28645, .T. ) ; -#22166 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37247, #3282, #21720, #31511 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22167 = DIRECTION ( 'NONE', ( -0.0005884939472035798308, 0.2255194584528803226, -0.9742384859642908568 ) ) ; -#22168 = CARTESIAN_POINT ( 'NONE', ( -20.16511123273965111, 137.5482785908162668, 94.32836982820661831 ) ) ; -#22170 = CARTESIAN_POINT ( 'NONE', ( -3.169891427924896199, 127.3945816957879060, 89.06620843884485339 ) ) ; -#22169 = CARTESIAN_POINT ( 'NONE', ( 36.06387094376011504, 192.3198907774919633, 104.3778220165794721 ) ) ; -#22171 = ORIENTED_EDGE ( 'NONE', *, *, #18623, .F. ) ; -#22172 = EDGE_CURVE ( 'NONE', #37452, #31429, #32121, .T. ) ; -#22173 = CIRCLE ( 'NONE', #31950, 9.500000000012004620 ) ; -#22174 = ORIENTED_EDGE ( 'NONE', *, *, #1879, .T. ) ; -#22175 = CARTESIAN_POINT ( 'NONE', ( 28.26008709311996370, 125.3597192996346052, 90.11688057617377012 ) ) ; -#22176 = AXIS2_PLACEMENT_3D ( 'NONE', #28777, #3816, #22454 ) ; -#22177 = VECTOR ( 'NONE', #32712, 1000.000000000000114 ) ; -#22178 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971546806 ) ) ; -#22179 = ORIENTED_EDGE ( 'NONE', *, *, #36767, .T. ) ; -#22180 = CIRCLE ( 'NONE', #16911, 59.40509898823096790 ) ; -#22181 = VERTEX_POINT ( 'NONE', #4076 ) ; -#22182 = CARTESIAN_POINT ( 'NONE', ( -19.44534333246823721, 148.3822623830060365, 180.6034369735336895 ) ) ; -#22183 = CARTESIAN_POINT ( 'NONE', ( 14.12655386339156394, 193.2440397236847218, 28.36825712431430802 ) ) ; -#22184 = CARTESIAN_POINT ( 'NONE', ( 40.67331120850102621, 184.3716013758660779, 104.7596565505194803 ) ) ; -#22185 = CARTESIAN_POINT ( 'NONE', ( -2.300492219183000397, 191.0298810790000061, 106.1837422966000020 ) ) ; -#22186 = ORIENTED_EDGE ( 'NONE', *, *, #6042, .T. ) ; -#22187 = EDGE_LOOP ( 'NONE', ( #14126, #26471, #19642, #32766 ) ) ; -#22188 = CARTESIAN_POINT ( 'NONE', ( -6.028075236889769428, 177.1156665047246008, 103.6258451396837899 ) ) ; -#22189 = DIRECTION ( 'NONE', ( 0.7069397808360943225, -0.6508952239913948778, -0.2767156548816978590 ) ) ; -#22190 = CARTESIAN_POINT ( 'NONE', ( -25.86047652274000086, 121.2837808580000001, 87.84016125891000115 ) ) ; -#22191 = ORIENTED_EDGE ( 'NONE', *, *, #13742, .F. ) ; -#22192 = ORIENTED_EDGE ( 'NONE', *, *, #7573, .T. ) ; -#22193 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #4609, #7676, #38956, #10966, #23429, #35871, #7809 ), - ( #38479, #16803, #1473, #7609, #13960, #10499, #10089 ), - ( #29097, #28890, #1266, #26036, #19473, #20279, #867 ), - ( #13551, #16994, #3929, #32166, #29296, #38884, #38284 ), - ( #669, #31969, #35801, #13351, #1068, #25841, #35591 ), - ( #7397, #38090, #20070, #10901, #34988, #3731, #26240 ), - ( #4531, #29497, #13163, #23369, #16206, #26436, #22567 ), - ( #32559, #22965, #7001, #35390, #28689, #35197, #25642 ), - ( #16597, #16403, #10297, #22765, #19862, #7202, #19669 ), - ( #13751, #4125, #32364, #4333, #38676, #10695, #23159 ), - ( #36639, #17610, #14173, #32950, #8646, #4947, #20897 ), - ( #20695, #5137, #30301, #8442, #17407, #2101, #30108 ), - ( #39899, #21107, #14572, #11707, #14973, #29902, #8013 ), - ( #30519, #1893, #14365, #33559, #11289, #14781, #36223 ), - ( #33360, #11908, #5551, #27057, #24396, #23770, #5351 ), - ( #32758, #26847, #2504, #39287, #27476, #36843, #8846 ), - ( #17202, #23559, #4742, #1688, #27263, #29704, #23980 ), - ( #39693, #8230, #26644, #36013, #11497, #39086, #36437 ), - ( #11094, #17806, #20478, #24187, #39488, #33149, #2297 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 3, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 3, 4 ), - ( -0.009999996581309438665, -1.380576915403000099E-13, 0.006245672222069000197, 0.01249582094693999987, 0.02499611839667999907, 0.03749641584643000070, 0.04999671329618000232, 0.09999790309516000397, 0.1499990928940999890, 0.2000002826931999989, 0.3000001540364999886, 0.4000000253798999816, 0.5999997680666000477, 0.7999995107534000338, 0.9999996581169999788 ), - ( 0.1755984787945999992, 0.8244285363540999612, 0.8309168369296949797 ), - .UNSPECIFIED. ) ; -#22194 = CARTESIAN_POINT ( 'NONE', ( -20.51998460911297784, 211.0905570173818546, 73.57089872868714053 ) ) ; -#22195 = ORIENTED_EDGE ( 'NONE', *, *, #16047, .F. ) ; -#22196 = FACE_OUTER_BOUND ( 'NONE', #5122, .T. ) ; -#22197 = CARTESIAN_POINT ( 'NONE', ( 14.74285125918311756, 136.4206760581051867, 93.70497248843004456 ) ) ; -#22198 = ORIENTED_EDGE ( 'NONE', *, *, #24939, .T. ) ; -#22199 = LINE ( 'NONE', #9930, #22955 ) ; -#22200 = CIRCLE ( 'NONE', #14343, 2.249999999984614973 ) ; -#22201 = VECTOR ( 'NONE', #10919, 1000.000000000000114 ) ; -#22202 = CARTESIAN_POINT ( 'NONE', ( -1.931781717180999891, 189.4344389325000009, 106.0157167347000069 ) ) ; -#22203 = CARTESIAN_POINT ( 'NONE', ( -0.02845919973435177830, 93.66652340833722690, 291.5585611238757906 ) ) ; -#22204 = VECTOR ( 'NONE', #5996, 1000.000000000000227 ) ; -#22205 = ORIENTED_EDGE ( 'NONE', *, *, #20008, .F. ) ; -#22206 = CARTESIAN_POINT ( 'NONE', ( 22.78224836617404137, 153.4848041862170476, 97.81073271791672141 ) ) ; -#22207 = CIRCLE ( 'NONE', #37202, 2.500000000048662407 ) ; -#22208 = EDGE_CURVE ( 'NONE', #20878, #15252, #3883, .T. ) ; -#22209 = DIRECTION ( 'NONE', ( 0.0008702530711002103318, -0.2253087760482092305, 0.9742870203873447155 ) ) ; -#22210 = EDGE_CURVE ( 'NONE', #37005, #29453, #29044, .T. ) ; -#22211 = CARTESIAN_POINT ( 'NONE', ( -26.00138850119475364, 118.1173731751006102, 87.28355378449504087 ) ) ; -#22212 = VECTOR ( 'NONE', #32705, 1000.000000000000000 ) ; -#22213 = DIRECTION ( 'NONE', ( 3.251597278533251339E-13, 0.9743700556678254188, 0.2249510938357014433 ) ) ; -#22214 = CARTESIAN_POINT ( 'NONE', ( 44.97084429314561049, 114.9968340379079166, 129.9902062988158491 ) ) ; -#22215 = ORIENTED_EDGE ( 'NONE', *, *, #33538, .T. ) ; -#22216 = FACE_OUTER_BOUND ( 'NONE', #18166, .T. ) ; -#22217 = ORIENTED_EDGE ( 'NONE', *, *, #28578, .F. ) ; -#22218 = CARTESIAN_POINT ( 'NONE', ( -13.73975480766844370, 125.4641165520392576, 174.2036076464545999 ) ) ; -#22219 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39933, #33591, #20932, #5585, #27292, #40328, #12333, #12523, #30334, #21554, #24630, #31150 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999997571942, 0.3749999999996513345, 0.4374999999996138089, 0.4687499999996104783, 0.4843749999996179723, 0.4999999999996255218, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22220 = CARTESIAN_POINT ( 'NONE', ( -38.00039891565000261, 118.8907101337000114, 90.44953021773000046 ) ) ; -#22221 = ORIENTED_EDGE ( 'NONE', *, *, #24428, .F. ) ; -#22222 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#22223 = CARTESIAN_POINT ( 'NONE', ( 35.04645051036200698, 220.4002260771000294, 75.53733736045835201 ) ) ; -#22224 = EDGE_LOOP ( 'NONE', ( #2442, #29288, #7803, #33837 ) ) ; -#22225 = CARTESIAN_POINT ( 'NONE', ( 11.62516440745127788, 158.5902278274764399, 96.25934000436126325 ) ) ; -#22226 = CARTESIAN_POINT ( 'NONE', ( -28.94629671773198965, 110.6131156702000027, 90.28526767713175616 ) ) ; -#22227 = CARTESIAN_POINT ( 'NONE', ( -32.70191599978576136, 163.2145672798008889, 188.5682430650827826 ) ) ; -#22228 = CARTESIAN_POINT ( 'NONE', ( -3.535839359701232087, 174.6735602432432586, 103.0605886135060700 ) ) ; -#22229 = FACE_BOUND ( 'NONE', #6205, .T. ) ; -#22230 = ORIENTED_EDGE ( 'NONE', *, *, #34985, .F. ) ; -#22231 = EDGE_LOOP ( 'NONE', ( #32155, #32182, #21369, #5369 ) ) ; -#22233 = AXIS2_PLACEMENT_3D ( 'NONE', #16684, #19356, #22846 ) ; -#22232 = CARTESIAN_POINT ( 'NONE', ( -6.036160832484147143, 177.5628022570028861, 100.8450471008263065 ) ) ; -#22234 = EDGE_CURVE ( 'NONE', #11287, #38686, #18449, .T. ) ; -#22235 = DIRECTION ( 'NONE', ( -0.6771712326826390127, 0.7358254695422518088, 0.000000000000000000 ) ) ; -#22236 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31823, #19519, #16449, #28939, #32214, #10945, #4780, #23406, #29745, #13797, #35845, #29940, #38717, #32989, #11542, #23811 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 4 ), - ( 6.245004513516505540E-17, 0.002671159371488287821, 0.004006739057232330467, 0.005342318742976373547, 0.006677898428720415759, 0.008013478114464457971, 0.009349057800208501051, 0.01068463748595254413 ), - .UNSPECIFIED. ) ; -#22237 = CIRCLE ( 'NONE', #4571, 6.000000000011024071 ) ; -#22238 = EDGE_LOOP ( 'NONE', ( #16712, #3894 ) ) ; -#22239 = CARTESIAN_POINT ( 'NONE', ( -23.36251194011130039, 135.0730551530189700, 91.06624837206607026 ) ) ; -#22240 = AXIS2_PLACEMENT_3D ( 'NONE', #11428, #23918, #14716 ) ; -#22241 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524656274, 149.3470289647502511, 130.0514119197545142 ) ) ; -#22242 = VERTEX_POINT ( 'NONE', #9340 ) ; -#22243 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#22244 = CARTESIAN_POINT ( 'NONE', ( 37.46412981905668005, 124.0392836328241088, 91.34593135885953075 ) ) ; -#22245 = ORIENTED_EDGE ( 'NONE', *, *, #21258, .T. ) ; -#22246 = CARTESIAN_POINT ( 'NONE', ( 10.03596943923905549, 167.8233964549057760, 101.4708580514027148 ) ) ; -#22247 = LINE ( 'NONE', #34872, #13998 ) ; -#22248 = CARTESIAN_POINT ( 'NONE', ( 15.50147165590422205, 151.4095604219332643, 97.16497155034561217 ) ) ; -#22249 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567345 ) ) ; -#22250 = DIRECTION ( 'NONE', ( 0.6068733047655823221, 0.7745082036644093115, 0.1784428043363773253 ) ) ; -#22251 = ORIENTED_EDGE ( 'NONE', *, *, #10944, .F. ) ; -#22252 = CARTESIAN_POINT ( 'NONE', ( 20.48673967653602901, 211.0896571907997554, 75.54495990469186495 ) ) ; -#22253 = CARTESIAN_POINT ( 'NONE', ( 0.6537733827144348586, 189.0019688857385347, 103.6874789632729659 ) ) ; -#22254 = CARTESIAN_POINT ( 'NONE', ( -2.801236327734337284, 190.0641490399931115, 106.6132946571331956 ) ) ; -#22255 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927876389700, -0.0005734119022052573504 ) ) ; -#22256 = ORIENTED_EDGE ( 'NONE', *, *, #24089, .T. ) ; -#22257 = ADVANCED_FACE ( 'NONE', ( #6853 ), #23586, .T. ) ; -#22258 = DIRECTION ( 'NONE', ( 0.9914447795421099663, -0.1270909273343945323, -0.02975139169821508847 ) ) ; -#22259 = EDGE_CURVE ( 'NONE', #7826, #6999, #6645, .T. ) ; -#22260 = CARTESIAN_POINT ( 'NONE', ( 2.879337540444164567, 205.2605563912295850, 76.16820990527092761 ) ) ; -#22261 = FACE_OUTER_BOUND ( 'NONE', #23537, .T. ) ; -#22262 = AXIS2_PLACEMENT_3D ( 'NONE', #9522, #107, #24269 ) ; -#22263 = AXIS2_PLACEMENT_3D ( 'NONE', #21637, #9357, #34466 ) ; -#22264 = CARTESIAN_POINT ( 'NONE', ( -26.04096242281000073, 189.6189556054999912, 106.3534993234000012 ) ) ; -#22265 = ORIENTED_EDGE ( 'NONE', *, *, #9480, .F. ) ; -#22266 = VECTOR ( 'NONE', #35647, 1000.000000000000000 ) ; -#22267 = AXIS2_PLACEMENT_3D ( 'NONE', #35087, #7290, #7096 ) ; -#22268 = CARTESIAN_POINT ( 'NONE', ( 42.51832847222295442, 128.8459892653891075, 92.45259438658834483 ) ) ; -#22269 = CARTESIAN_POINT ( 'NONE', ( -12.63633278542094196, 136.6784457103040040, 94.29417180125015818 ) ) ; -#22270 = ORIENTED_EDGE ( 'NONE', *, *, #27854, .F. ) ; -#22271 = CARTESIAN_POINT ( 'NONE', ( 28.26067382423566698, 125.1347711400599110, 91.09124888412546284 ) ) ; -#22272 = CARTESIAN_POINT ( 'NONE', ( -22.49999922076901981, 174.5126133868815543, 99.95592377105238313 ) ) ; -#22273 = LINE ( 'NONE', #25142, #35883 ) ; -#22274 = CARTESIAN_POINT ( 'NONE', ( 37.96499314393000191, 190.9636352775000034, 106.2831835281999986 ) ) ; -#22275 = CARTESIAN_POINT ( 'NONE', ( 36.76977172392000170, 191.5398167378999972, 106.2267418912000068 ) ) ; -#22276 = EDGE_LOOP ( 'NONE', ( #10510, #22804, #26285, #16568, #33344, #30163 ) ) ; -#22277 = CARTESIAN_POINT ( 'NONE', ( -28.46737701140902033, 184.1209660424817400, 102.1777913196515755 ) ) ; -#22278 = EDGE_CURVE ( 'NONE', #315, #14670, #4661, .T. ) ; -#22279 = LINE ( 'NONE', #31472, #11844 ) ; -#22280 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#22281 = ORIENTED_EDGE ( 'NONE', *, *, #38976, .F. ) ; -#22282 = CARTESIAN_POINT ( 'NONE', ( -30.72295198953211326, 177.7251950676070749, 100.7025732852349762 ) ) ; -#22283 = ORIENTED_EDGE ( 'NONE', *, *, #21842, .T. ) ; -#22284 = CONICAL_SURFACE ( 'NONE', #35962, 6.000000000029579006, 0.7853981634430682313 ) ; -#22285 = VECTOR ( 'NONE', #40299, 1000.000000000000000 ) ; -#22286 = CARTESIAN_POINT ( 'NONE', ( 25.99904971602028425, 120.7769186021849066, 87.52076664421943519 ) ) ; -#22287 = CARTESIAN_POINT ( 'NONE', ( -36.70588856729196436, 191.6013385684930483, 104.3872917547991932 ) ) ; -#22288 = ORIENTED_EDGE ( 'NONE', *, *, #11539, .T. ) ; -#22289 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; -#22290 = EDGE_CURVE ( 'NONE', #26621, #1901, #30206, .T. ) ; -#22291 = AXIS2_PLACEMENT_3D ( 'NONE', #18930, #3392, #6461 ) ; -#22292 = AXIS2_PLACEMENT_3D ( 'NONE', #19348, #24718, #9360 ) ; -#22293 = LINE ( 'NONE', #16728, #20071 ) ; -#22294 = CARTESIAN_POINT ( 'NONE', ( -22.49952074149951997, 137.4671135675431515, 177.5661851824280291 ) ) ; -#22295 = LINE ( 'NONE', #15928, #25613 ) ; -#22296 = ORIENTED_EDGE ( 'NONE', *, *, #7686, .T. ) ; -#22297 = EDGE_CURVE ( 'NONE', #8771, #15381, #9902, .T. ) ; -#22298 = CARTESIAN_POINT ( 'NONE', ( -26.00898928064792059, 209.7096528057114710, 76.07444037909847623 ) ) ; -#22299 = LINE ( 'NONE', #18590, #944 ) ; -#22300 = LINE ( 'NONE', #4057, #18177 ) ; -#22301 = CARTESIAN_POINT ( 'NONE', ( -35.81913783262000095, 191.4997546378000095, 103.7576553867999962 ) ) ; -#22302 = EDGE_CURVE ( 'NONE', #3973, #15609, #6013, .T. ) ; -#22303 = ORIENTED_EDGE ( 'NONE', *, *, #36111, .F. ) ; -#22304 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#22305 = ORIENTED_EDGE ( 'NONE', *, *, #34996, .T. ) ; -#22306 = EDGE_CURVE ( 'NONE', #19810, #22776, #37691, .T. ) ; -#22307 = ADVANCED_FACE ( 'NONE', ( #18864 ), #11869, .F. ) ; -#22308 = CARTESIAN_POINT ( 'NONE', ( -28.53208073851174476, 125.2791694434640135, 88.59312828080875590 ) ) ; -#22309 = ADVANCED_FACE ( 'NONE', ( #678 ), #5956, .T. ) ; -#22310 = CARTESIAN_POINT ( 'NONE', ( 25.53747175047978857, 190.9172658757476313, 106.2799836673595024 ) ) ; -#22311 = CARTESIAN_POINT ( 'NONE', ( -13.36410657841409488, 181.7648119164822162, 101.6247081824262040 ) ) ; -#22312 = CARTESIAN_POINT ( 'NONE', ( -22.49967939491756752, 153.8038087509543743, 95.68807059495395606 ) ) ; -#22313 = CIRCLE ( 'NONE', #24927, 1.999999997455631284 ) ; -#22314 = CARTESIAN_POINT ( 'NONE', ( 15.50029467790899496, 185.7974155947267718, 103.0514270424844483 ) ) ; -#22315 = AXIS2_PLACEMENT_3D ( 'NONE', #34197, #2394, #37480 ) ; -#22316 = CARTESIAN_POINT ( 'NONE', ( -2.288621054235000063, 209.3634523597000054, 73.69906321377999348 ) ) ; -#22317 = CARTESIAN_POINT ( 'NONE', ( 38.48555382640000033, 118.5484835161000063, 89.80748669179000387 ) ) ; -#22318 = ORIENTED_EDGE ( 'NONE', *, *, #13693, .T. ) ; -#22319 = CARTESIAN_POINT ( 'NONE', ( -22.50000097842500679, 160.7375465425423897, 96.77263313290113445 ) ) ; -#22320 = CARTESIAN_POINT ( 'NONE', ( 24.63900929408691454, 117.2586415609094814, 170.8533154267458940 ) ) ; -#22321 = DIRECTION ( 'NONE', ( 1.397458901295144550E-11, 0.9743043966640304587, 0.2252353050503839715 ) ) ; -#22322 = CARTESIAN_POINT ( 'NONE', ( 16.28891463809603124, 132.2249801446032791, 155.9597679450893679 ) ) ; -#22323 = ORIENTED_EDGE ( 'NONE', *, *, #2690, .T. ) ; -#22324 = EDGE_LOOP ( 'NONE', ( #27997, #33336, #13820, #26675 ) ) ; -#22325 = EDGE_CURVE ( 'NONE', #2286, #36964, #16808, .T. ) ; -#22326 = ORIENTED_EDGE ( 'NONE', *, *, #21789, .T. ) ; -#22327 = CARTESIAN_POINT ( 'NONE', ( 23.68458193633980713, 135.2968916886795228, 91.38751720632359365 ) ) ; -#22328 = LINE ( 'NONE', #26803, #4293 ) ; -#22329 = DIRECTION ( 'NONE', ( -0.0004271987741244301384, 0.7071067811864831798, -0.7071066521404663074 ) ) ; -#22330 = ORIENTED_EDGE ( 'NONE', *, *, #33198, .F. ) ; -#22331 = ORIENTED_EDGE ( 'NONE', *, *, #18163, .T. ) ; -#22332 = FACE_OUTER_BOUND ( 'NONE', #4174, .T. ) ; -#22333 = CARTESIAN_POINT ( 'NONE', ( 12.31247077724877315, 134.4456542776592585, 93.59261989489698408 ) ) ; -#22334 = CARTESIAN_POINT ( 'NONE', ( 25.50773797008787369, 191.9759150222000130, 101.9060413058080030 ) ) ; -#22335 = CARTESIAN_POINT ( 'NONE', ( 29.40663682764231268, 130.8456206841377707, 89.84325200762386032 ) ) ; -#22336 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; -#22337 = ORIENTED_EDGE ( 'NONE', *, *, #37899, .F. ) ; -#22338 = CARTESIAN_POINT ( 'NONE', ( -19.21678146528146058, 125.2620815843974924, 178.3530915497297258 ) ) ; -#22339 = EDGE_CURVE ( 'NONE', #10264, #11480, #7614, .T. ) ; -#22340 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24173, #33540, #18198, #27649, #5946, #37033, #21703, #36625, #12477, #36421, #33749, #30504 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999995047295, 0.3749999999992678079, 0.4374999999991787680, 0.4687499999991626698, 0.4843749999991739386, 0.4999999999991850963, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22341 = VERTEX_POINT ( 'NONE', #25849 ) ; -#22342 = CARTESIAN_POINT ( 'NONE', ( -20.54149002962999049, 176.5964826137828254, 28.07869762585763240 ) ) ; -#22343 = DIRECTION ( 'NONE', ( -0.9999998176028267460, -3.062651553416717956E-09, 0.0006039820470873916896 ) ) ; -#22344 = AXIS2_PLACEMENT_3D ( 'NONE', #24212, #2323, #33380 ) ; -#22345 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; -#22346 = ORIENTED_EDGE ( 'NONE', *, *, #33159, .T. ) ; -#22347 = CONICAL_SURFACE ( 'NONE', #4687, 6.499999999933947947, 0.7853981634770059728 ) ; -#22348 = VERTEX_POINT ( 'NONE', #10309 ) ; -#22349 = ADVANCED_FACE ( 'NONE', ( #35205 ), #29103, .T. ) ; -#22350 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988408924259, 150.9961524914645850, 94.51313162284453995 ) ) ; -#22351 = CARTESIAN_POINT ( 'NONE', ( 2.922156723524788724, 190.2869223753070855, 103.5823562725477842 ) ) ; -#22352 = FACE_OUTER_BOUND ( 'NONE', #32967, .T. ) ; -#22353 = EDGE_CURVE ( 'NONE', #35918, #7067, #10505, .T. ) ; -#22354 = VERTEX_POINT ( 'NONE', #22308 ) ; -#22355 = DIRECTION ( 'NONE', ( -0.0005884949961266395689, 0.2249510543439048882, -0.9743698870671267942 ) ) ; -#22356 = CARTESIAN_POINT ( 'NONE', ( -25.50046849319145537, 118.1130939482222857, 89.11646148004645340 ) ) ; -#22357 = ORIENTED_EDGE ( 'NONE', *, *, #29121, .T. ) ; -#22358 = EDGE_CURVE ( 'NONE', #30585, #8959, #25778, .T. ) ; -#22359 = CARTESIAN_POINT ( 'NONE', ( 59.75594728249464538, 30.15273947196611815, 149.3573573250752133 ) ) ; -#22360 = CARTESIAN_POINT ( 'NONE', ( 36.13530173960303671, 191.5119209504615867, 103.8451096219701810 ) ) ; -#22361 = CARTESIAN_POINT ( 'NONE', ( -27.04885921334999921, 123.0440198693000013, 91.29407312176999767 ) ) ; -#22362 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29806, #1998, #14468, #21004, #7912, #36119, #33249, #2405, #1785, #5451 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.0008906419405732026156, 0.2506679814554299002, 0.5004453209702866001, 0.7502226604851433001, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22363 = VERTEX_POINT ( 'NONE', #18597 ) ; -#22364 = CARTESIAN_POINT ( 'NONE', ( -6.036264379393829316, 136.7917950106709100, 93.80320213086851311 ) ) ; -#22365 = LINE ( 'NONE', #21960, #34535 ) ; -#22366 = DIRECTION ( 'NONE', ( -0.0006039748319391913256, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#22367 = EDGE_LOOP ( 'NONE', ( #37923, #24761, #30421, #17831 ) ) ; -#22368 = FACE_OUTER_BOUND ( 'NONE', #16813, .T. ) ; -#22369 = CARTESIAN_POINT ( 'NONE', ( -22.49970497327230490, 184.8490926230421962, 102.8554404399357622 ) ) ; -#22370 = AXIS2_PLACEMENT_3D ( 'NONE', #4923, #23536, #14145 ) ; -#22372 = CARTESIAN_POINT ( 'NONE', ( -17.08965732320790920, 121.5613976340063118, 176.7749525043521146 ) ) ; -#22371 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825929013683355, 0.0005734119021813978553 ) ) ; -#22373 = AXIS2_PLACEMENT_3D ( 'NONE', #12382, #5646, #2786 ) ; -#22374 = ORIENTED_EDGE ( 'NONE', *, *, #8756, .F. ) ; -#22375 = LINE ( 'NONE', #21968, #18620 ) ; -#22376 = DIRECTION ( 'NONE', ( 0.0005884949961246576473, -0.2249510543439054155, 0.9743698870671265722 ) ) ; -#22377 = VERTEX_POINT ( 'NONE', #15937 ) ; -#22378 = EDGE_LOOP ( 'NONE', ( #20547, #3879, #36071, #13685 ) ) ; -#22379 = PLANE ( 'NONE', #20443 ) ; -#22380 = CARTESIAN_POINT ( 'NONE', ( -25.51388077191477066, 211.0902258580313742, 75.57405363378009611 ) ) ; -#22381 = CARTESIAN_POINT ( 'NONE', ( 13.51095425345201129, 187.6707999454940818, 106.0508869016509266 ) ) ; -#22382 = CARTESIAN_POINT ( 'NONE', ( 20.50147081996105314, 160.1804844985509817, 99.18687942156120130 ) ) ; -#22383 = ORIENTED_EDGE ( 'NONE', *, *, #5138, .F. ) ; -#22384 = EDGE_CURVE ( 'NONE', #13079, #17036, #20937, .T. ) ; -#22385 = VERTEX_POINT ( 'NONE', #28045 ) ; -#22386 = EDGE_CURVE ( 'NONE', #33385, #37452, #16995, .T. ) ; -#22387 = ORIENTED_EDGE ( 'NONE', *, *, #11824, .F. ) ; -#22388 = CYLINDRICAL_SURFACE ( 'NONE', #35635, 6.000000000000011546 ) ; -#22389 = EDGE_CURVE ( 'NONE', #9503, #734, #30128, .T. ) ; -#22390 = CARTESIAN_POINT ( 'NONE', ( -12.63767699504066577, 177.1899956602251507, 101.0812418388079834 ) ) ; -#22391 = CARTESIAN_POINT ( 'NONE', ( -23.36763934512021734, 134.2409834847225625, 93.73796057560730333 ) ) ; -#22392 = ADVANCED_FACE ( 'NONE', ( #34930 ), #6538, .T. ) ; -#22393 = CARTESIAN_POINT ( 'NONE', ( 18.99670475096374034, 148.1889770648965623, 184.7135872576050986 ) ) ; -#22394 = ORIENTED_EDGE ( 'NONE', *, *, #27339, .T. ) ; -#22395 = ORIENTED_EDGE ( 'NONE', *, *, #12285, .T. ) ; -#22396 = CARTESIAN_POINT ( 'NONE', ( -25.49121842733731569, 191.8361208170296379, 104.4329317390898950 ) ) ; -#22397 = ORIENTED_EDGE ( 'NONE', *, *, #23667, .F. ) ; -#22398 = AXIS2_PLACEMENT_3D ( 'NONE', #15962, #10047, #6757 ) ; -#22399 = EDGE_CURVE ( 'NONE', #7245, #39006, #11688, .T. ) ; -#22400 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; -#22401 = ORIENTED_EDGE ( 'NONE', *, *, #36264, .F. ) ; -#22402 = CARTESIAN_POINT ( 'NONE', ( -31.05248204746864005, 158.9539887611892652, 186.6368167519732424 ) ) ; -#22403 = EDGE_CURVE ( 'NONE', #26164, #8671, #26817, .T. ) ; -#22404 = AXIS2_PLACEMENT_3D ( 'NONE', #14914, #39835, #32897 ) ; -#22405 = CARTESIAN_POINT ( 'NONE', ( -2.813165966022999953, 190.9564557362000130, 106.6949844788999968 ) ) ; -#22406 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218859315, 87.27946979429613350, 297.5295786860743874 ) ) ; -#22407 = ORIENTED_EDGE ( 'NONE', *, *, #912, .F. ) ; -#22408 = DIRECTION ( 'NONE', ( -0.7072735235946167043, -0.6508952239913153859, -0.2758615054830065305 ) ) ; -#22409 = CARTESIAN_POINT ( 'NONE', ( 33.29944284160863077, 84.12354575840004145, 284.1448177430615374 ) ) ; -#22410 = CARTESIAN_POINT ( 'NONE', ( -25.66804413620193159, 118.1146252066666733, 87.61661746274521079 ) ) ; -#22411 = LINE ( 'NONE', #9529, #32041 ) ; -#22412 = EDGE_CURVE ( 'NONE', #23623, #20699, #1007, .T. ) ; -#22413 = LINE ( 'NONE', #3972, #3013 ) ; -#22414 = ORIENTED_EDGE ( 'NONE', *, *, #13872, .T. ) ; -#22415 = CARTESIAN_POINT ( 'NONE', ( -45.03708708209951084, 124.0713768683079081, 93.45577792510331960 ) ) ; -#22416 = LINE ( 'NONE', #19115, #32470 ) ; -#22417 = ORIENTED_EDGE ( 'NONE', *, *, #3386, .F. ) ; -#22418 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12027, #36966, #8968, #21443 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22419 = AXIS2_PLACEMENT_3D ( 'NONE', #37897, #25646, #22371 ) ; -#22420 = ORIENTED_EDGE ( 'NONE', *, *, #40087, .T. ) ; -#22421 = DIRECTION ( 'NONE', ( -0.0006039748319380815363, -1.388651635424563573E-14, -0.9999998176071845934 ) ) ; -#22422 = DIRECTION ( 'NONE', ( 0.0005121997063476214180, 0.5299192642332222203, 0.8480479414785353498 ) ) ; -#22423 = CARTESIAN_POINT ( 'NONE', ( -3.657007565168505003, 174.7046328845856920, 102.9436394089264155 ) ) ; -#22424 = VERTEX_POINT ( 'NONE', #8783 ) ; -#22425 = DIRECTION ( 'NONE', ( -1.214306433183758024E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#22426 = VERTEX_POINT ( 'NONE', #36378 ) ; -#22427 = ORIENTED_EDGE ( 'NONE', *, *, #26991, .F. ) ; -#22428 = CARTESIAN_POINT ( 'NONE', ( 39.73175645750271912, 182.5347700109205675, 106.6535420028259438 ) ) ; -#22429 = LINE ( 'NONE', #26102, #39350 ) ; -#22430 = AXIS2_PLACEMENT_3D ( 'NONE', #10283, #7790, #35568 ) ; -#22431 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#22432 = EDGE_CURVE ( 'NONE', #9285, #21583, #30042, .T. ) ; -#22433 = EDGE_LOOP ( 'NONE', ( #2934, #23995, #11375, #19393 ) ) ; -#22434 = CARTESIAN_POINT ( 'NONE', ( 8.046776635720599202, 151.4387294071806593, 94.61044745561473235 ) ) ; -#22435 = EDGE_CURVE ( 'NONE', #32876, #23127, #33596, .T. ) ; -#22436 = CARTESIAN_POINT ( 'NONE', ( 21.85504115049297980, 129.9621995019233225, 89.81490981051685196 ) ) ; -#22437 = EDGE_CURVE ( 'NONE', #3193, #3978, #17704, .T. ) ; -#22438 = ORIENTED_EDGE ( 'NONE', *, *, #8596, .F. ) ; -#22439 = DIRECTION ( 'NONE', ( 0.5988683521957592903, -0.8008474865655358377, 0.000000000000000000 ) ) ; -#22440 = CARTESIAN_POINT ( 'NONE', ( 30.07009376554507440, 174.7970070534087768, 102.5555909528905261 ) ) ; -#22441 = CARTESIAN_POINT ( 'NONE', ( 25.99332206926874278, 209.7096538831000032, 78.04280567916214295 ) ) ; -#22442 = ORIENTED_EDGE ( 'NONE', *, *, #25126, .T. ) ; -#22443 = CARTESIAN_POINT ( 'NONE', ( 28.20672708967000020, 125.3940403962999994, 88.92763624988999993 ) ) ; -#22444 = EDGE_CURVE ( 'NONE', #5073, #81, #15117, .T. ) ; -#22445 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#22446 = CARTESIAN_POINT ( 'NONE', ( -21.82845865523656315, 182.3067054805563316, 104.3206871860773504 ) ) ; -#22447 = CARTESIAN_POINT ( 'NONE', ( 3.755182731601074408, 175.3075123181448305, 100.3502401767937613 ) ) ; -#22448 = DIRECTION ( 'NONE', ( -0.0006039748319379876444, -1.544770086762009064E-14, -0.9999998176071845934 ) ) ; -#22449 = ORIENTED_EDGE ( 'NONE', *, *, #2888, .T. ) ; -#22451 = EDGE_CURVE ( 'NONE', #520, #20878, #15078, .T. ) ; -#22450 = CARTESIAN_POINT ( 'NONE', ( 22.49999736296386743, 160.7435420377399282, 96.74666379507640102 ) ) ; -#22452 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971519328 ) ) ; -#22453 = AXIS2_PLACEMENT_3D ( 'NONE', #5090, #2250, #30060 ) ; -#22454 = DIRECTION ( 'NONE', ( 0.5968393679912002980, 0.8023607473050164973, 0.000000000000000000 ) ) ; -#22455 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37855, #9054, #6170, #15768, #34372, #3488 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 4 ), - ( 0.000000000000000000, 0.3333281889657515595, 0.6666640818021849491, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22456 = CARTESIAN_POINT ( 'NONE', ( 12.63717152284372958, 130.1526461680852265, 92.50424807167719621 ) ) ; -#22457 = ORIENTED_EDGE ( 'NONE', *, *, #37909, .T. ) ; -#22458 = VECTOR ( 'NONE', #876, 1000.000000000000000 ) ; -#22459 = CARTESIAN_POINT ( 'NONE', ( 38.36940859710925622, 118.9353376627760071, 90.24631930852783057 ) ) ; -#22460 = DIRECTION ( 'NONE', ( 0.0005884949961264727102, -0.2249510543439039167, 0.9743698870671270162 ) ) ; -#22461 = PLANE ( 'NONE', #17621 ) ; -#22462 = EDGE_CURVE ( 'NONE', #30098, #23829, #37775, .T. ) ; -#22463 = AXIS2_PLACEMENT_3D ( 'NONE', #26707, #14022, #22832 ) ; -#22464 = CARTESIAN_POINT ( 'NONE', ( -26.00373707785711730, 190.8838294880926014, 106.8165467415037142 ) ) ; -#22465 = ORIENTED_EDGE ( 'NONE', *, *, #22614, .F. ) ; -#22466 = CARTESIAN_POINT ( 'NONE', ( 20.48791368134620683, 201.8041646541999796, 85.15356383073336133 ) ) ; -#22467 = CARTESIAN_POINT ( 'NONE', ( -12.63793912156016042, 182.0618459091404873, 102.2059974569859975 ) ) ; -#22468 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29227, #400, #25767, #10018 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22469 = CARTESIAN_POINT ( 'NONE', ( -43.75033814667176557, 185.4897723175090221, 107.5113483461213661 ) ) ; -#22470 = FACE_OUTER_BOUND ( 'NONE', #38561, .T. ) ; -#22471 = CARTESIAN_POINT ( 'NONE', ( -22.78255965921956161, 158.2257193261845316, 98.76172871125201880 ) ) ; -#22472 = CARTESIAN_POINT ( 'NONE', ( 0.5441254074100964067, 211.4999999999614602, 73.05817544432547095 ) ) ; -#22473 = CARTESIAN_POINT ( 'NONE', ( 35.09291703857000044, 217.7719116314000019, 152.4718672074000381 ) ) ; -#22474 = CARTESIAN_POINT ( 'NONE', ( 36.08518882432319685, 192.3722560605559977, 106.3999998832000102 ) ) ; -#22475 = CARTESIAN_POINT ( 'NONE', ( 3.820232418934266239, 143.6044667692935093, 95.59131969296058173 ) ) ; -#22476 = CARTESIAN_POINT ( 'NONE', ( 4.034499240732137615, 175.2435454650998850, 100.6217987443006194 ) ) ; -#22477 = EDGE_LOOP ( 'NONE', ( #35181, #40188 ) ) ; -#22478 = EDGE_LOOP ( 'NONE', ( #17870, #20844, #4227, #12674 ) ) ; -#22479 = CARTESIAN_POINT ( 'NONE', ( -2.946865378000000035, 209.3288521576999983, 76.09373086713999612 ) ) ; -#22480 = VECTOR ( 'NONE', #32937, 1000.000000000000000 ) ; -#22481 = CARTESIAN_POINT ( 'NONE', ( 20.50029254611199292, 184.8549113859068029, 102.8308091169877798 ) ) ; -#22482 = VECTOR ( 'NONE', #4835, 1000.000000000000227 ) ; -#22483 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 77.27946979429643193, 322.5967026918629017 ) ) ; -#22484 = CARTESIAN_POINT ( 'NONE', ( 39.05648265166797017, 127.5103312055594955, 92.14632397477382142 ) ) ; -#22485 = ORIENTED_EDGE ( 'NONE', *, *, #25991, .T. ) ; -#22486 = CARTESIAN_POINT ( 'NONE', ( -39.69261857620511336, 119.4152473592345842, 89.81183687744525912 ) ) ; -#22487 = EDGE_CURVE ( 'NONE', #39445, #7666, #13120, .T. ) ; -#22488 = CIRCLE ( 'NONE', #5501, 51.90509899263581417 ) ; -#22489 = EDGE_CURVE ( 'NONE', #39132, #33799, #31455, .T. ) ; -#22490 = ORIENTED_EDGE ( 'NONE', *, *, #19643, .F. ) ; -#22491 = VECTOR ( 'NONE', #25154, 1000.000000000000000 ) ; -#22492 = CARTESIAN_POINT ( 'NONE', ( -23.36013446842593666, 174.6767834003346138, 103.0763367099988415 ) ) ; -#22493 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#22494 = LINE ( 'NONE', #28417, #16471 ) ; -#22495 = LINE ( 'NONE', #18776, #12749 ) ; -#22496 = CARTESIAN_POINT ( 'NONE', ( -45.19483343799229402, 186.0262136949233138, 106.1956750743143090 ) ) ; -#22497 = ADVANCED_FACE ( 'NONE', ( #6292 ), #34295, .T. ) ; -#22498 = DIRECTION ( 'NONE', ( -0.7865509479255973213, -0.6175253892086901564, 0.000000000000000000 ) ) ; -#22499 = CARTESIAN_POINT ( 'NONE', ( 2.943104451508621544, 209.7096517725655644, 76.05672380837390278 ) ) ; -#22500 = ORIENTED_EDGE ( 'NONE', *, *, #4915, .F. ) ; -#22501 = ORIENTED_EDGE ( 'NONE', *, *, #34092, .T. ) ; -#22502 = FACE_OUTER_BOUND ( 'NONE', #17811, .T. ) ; -#22503 = CARTESIAN_POINT ( 'NONE', ( 92.50187971282166188, 221.8453154663451699, 201.2060978135920379 ) ) ; -#22504 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#22505 = FACE_OUTER_BOUND ( 'NONE', #3954, .T. ) ; -#22506 = EDGE_LOOP ( 'NONE', ( #33423, #24128, #32697, #36474 ) ) ; -#22507 = CARTESIAN_POINT ( 'NONE', ( 44.87746509354383306, 179.5854585350990362, 137.0276591108483331 ) ) ; -#22508 = VERTEX_POINT ( 'NONE', #7097 ) ; -#22509 = VECTOR ( 'NONE', #34885, 1000.000000000000000 ) ; -#22510 = EDGE_CURVE ( 'NONE', #39608, #9539, #13451, .T. ) ; -#22511 = CARTESIAN_POINT ( 'NONE', ( -20.00025820447960001, 138.1823733798348428, 91.56700283718186029 ) ) ; -#22512 = CARTESIAN_POINT ( 'NONE', ( 19.99933118494021755, 196.5785306413737601, 103.8628508136982731 ) ) ; -#22513 = VECTOR ( 'NONE', #7554, 1000.000000000000000 ) ; -#22514 = LINE ( 'NONE', #34932, #12980 ) ; -#22515 = DIRECTION ( 'NONE', ( -0.0006039748319384964604, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#22516 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999904787, 132.9679238121919980, 90.36185680185722902 ) ) ; -#22517 = CARTESIAN_POINT ( 'NONE', ( 20.48137660469177490, 206.5183323763784529, 74.84160177721973639 ) ) ; -#22518 = CARTESIAN_POINT ( 'NONE', ( -37.90890821973000158, 190.8183704905999889, 106.4200881177000184 ) ) ; -#22519 = EDGE_LOOP ( 'NONE', ( #18086, #1048, #27230, #11555 ) ) ; -#22520 = EDGE_CURVE ( 'NONE', #19730, #35236, #20166, .T. ) ; -#22521 = CARTESIAN_POINT ( 'NONE', ( 38.29593043767467719, 218.5902260770999987, 76.03537484722993156 ) ) ; -#22522 = CARTESIAN_POINT ( 'NONE', ( -36.54104006138566518, 191.4170194552398812, 106.3917187889346252 ) ) ; -#22523 = DIRECTION ( 'NONE', ( -0.0005884949961228156962, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#22524 = CARTESIAN_POINT ( 'NONE', ( -28.52494644200928064, 186.7521494213145559, 105.8641958179564568 ) ) ; -#22525 = VERTEX_POINT ( 'NONE', #4828 ) ; -#22526 = ORIENTED_EDGE ( 'NONE', *, *, #12787, .F. ) ; -#22527 = EDGE_CURVE ( 'NONE', #35660, #9503, #762, .T. ) ; -#22528 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #26053, #22782, #29315, #4142 ), - ( #38495, #9705, #10109, #7016 ), - ( #19489, #35216, #25252, #10514 ), - ( #37702, #28710, #879, #484 ), - ( #19686, #22982, #29113, #31983 ), - ( #19882, #19084, #1086, #22185 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 4 ), - ( 4, 4 ), - ( -0.01985735277108999913, 0.000000000000000000, 1.000000000000000000, 1.019994027157999916 ), - ( -2.955566845425000168E-05, 0.9999999395687999559 ), - .UNSPECIFIED. ) ; -#22529 = ORIENTED_EDGE ( 'NONE', *, *, #21130, .T. ) ; -#22530 = CARTESIAN_POINT ( 'NONE', ( 26.00081424259415641, 120.1020648120652510, 90.44388058125247198 ) ) ; -#22531 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#22532 = ADVANCED_FACE ( 'NONE', ( #22663 ), #32065, .F. ) ; -#22533 = ORIENTED_EDGE ( 'NONE', *, *, #39876, .T. ) ; -#22534 = ORIENTED_EDGE ( 'NONE', *, *, #6847, .T. ) ; -#22535 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; -#22536 = CARTESIAN_POINT ( 'NONE', ( -20.16352061881138980, 211.0884378490691802, 75.92576696064729447 ) ) ; -#22537 = CARTESIAN_POINT ( 'NONE', ( -3.669581222327467973, 184.0117732734406104, 102.6507570783573300 ) ) ; -#22538 = AXIS2_PLACEMENT_3D ( 'NONE', #12796, #19109, #31601 ) ; -#22539 = AXIS2_PLACEMENT_3D ( 'NONE', #18492, #39775, #34436 ) ; -#22540 = CYLINDRICAL_SURFACE ( 'NONE', #37359, 2.000000000000014655 ) ; -#22541 = ORIENTED_EDGE ( 'NONE', *, *, #35, .T. ) ; -#22542 = FACE_OUTER_BOUND ( 'NONE', #14695, .T. ) ; -#22543 = ORIENTED_EDGE ( 'NONE', *, *, #6944, .F. ) ; -#22544 = DIRECTION ( 'NONE', ( -0.0006039748319395907457, -1.314021223879979801E-14, -0.9999998176071847045 ) ) ; -#22545 = CIRCLE ( 'NONE', #4888, 7.499999999880614610 ) ; -#22546 = CARTESIAN_POINT ( 'NONE', ( -2.455126040769211038, 209.0000001767654965, 74.29847181561608238 ) ) ; -#22547 = ORIENTED_EDGE ( 'NONE', *, *, #36883, .T. ) ; -#22548 = CARTESIAN_POINT ( 'NONE', ( -19.99861762737637960, 193.7273908560958944, 106.6527233798307179 ) ) ; -#22549 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#22550 = LINE ( 'NONE', #28870, #1849 ) ; -#22551 = ORIENTED_EDGE ( 'NONE', *, *, #23458, .F. ) ; -#22552 = ORIENTED_EDGE ( 'NONE', *, *, #5745, .T. ) ; -#22553 = CYLINDRICAL_SURFACE ( 'NONE', #3501, 2.000000000000001332 ) ; -#22554 = CARTESIAN_POINT ( 'NONE', ( 24.53499375125008797, 104.1131156705585283, 90.25296631813145609 ) ) ; -#22555 = VERTEX_POINT ( 'NONE', #19959 ) ; -#22556 = CARTESIAN_POINT ( 'NONE', ( -24.42746480797000430, 103.6131156702000027, 87.78253795972000262 ) ) ; -#22557 = CARTESIAN_POINT ( 'NONE', ( -45.38028798438312350, 123.7560755211207351, 91.33058355487838753 ) ) ; -#22558 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#22559 = ORIENTED_EDGE ( 'NONE', *, *, #1013, .F. ) ; -#22560 = CARTESIAN_POINT ( 'NONE', ( -13.46995280217765156, 158.2275496627099756, 98.75652669741377565 ) ) ; -#22561 = CARTESIAN_POINT ( 'NONE', ( 3.882702609166361896, 148.9606115483820190, 129.9617790688332093 ) ) ; -#22562 = ORIENTED_EDGE ( 'NONE', *, *, #2682, .T. ) ; -#22563 = AXIS2_PLACEMENT_3D ( 'NONE', #30689, #30270, #2477 ) ; -#22564 = AXIS2_PLACEMENT_3D ( 'NONE', #3919, #25426, #10288 ) ; -#22565 = ORIENTED_EDGE ( 'NONE', *, *, #4320, .F. ) ; -#22566 = AXIS2_PLACEMENT_3D ( 'NONE', #24159, #24769, #9220 ) ; -#22567 = CARTESIAN_POINT ( 'NONE', ( 26.00644222260579852, 120.1782714929480136, 90.46828040459247688 ) ) ; -#22568 = CARTESIAN_POINT ( 'NONE', ( -28.46570037481142990, 129.9682353502039405, 92.24140578106545263 ) ) ; -#22569 = LINE ( 'NONE', #31971, #28342 ) ; -#22570 = AXIS2_PLACEMENT_3D ( 'NONE', #9412, #31698, #22088 ) ; -#22572 = CARTESIAN_POINT ( 'NONE', ( 75.33446582941786573, 196.6730905574605970, 189.2244420380926329 ) ) ; -#22571 = CARTESIAN_POINT ( 'NONE', ( 20.48191743768403228, 208.0778533060426412, 76.14482956145043602 ) ) ; -#22573 = EDGE_CURVE ( 'NONE', #3283, #15358, #29485, .T. ) ; -#22574 = ORIENTED_EDGE ( 'NONE', *, *, #10110, .T. ) ; -#22575 = CARTESIAN_POINT ( 'NONE', ( -1.212289009923044114, 143.4874838728126747, 158.5684238127680317 ) ) ; -#22576 = CARTESIAN_POINT ( 'NONE', ( -35.93776389612042976, 192.3429967070654811, 104.4165159352158696 ) ) ; -#22577 = CARTESIAN_POINT ( 'NONE', ( 1.222756636386816087, 143.4873526228519722, 158.5689915630758549 ) ) ; -#22578 = ORIENTED_EDGE ( 'NONE', *, *, #39679, .T. ) ; -#22579 = EDGE_CURVE ( 'NONE', #30603, #16409, #23251, .T. ) ; -#22580 = EDGE_CURVE ( 'NONE', #19924, #27113, #33045, .T. ) ; -#22581 = VERTEX_POINT ( 'NONE', #6394 ) ; -#22582 = EDGE_CURVE ( 'NONE', #30526, #11064, #15751, .T. ) ; -#22583 = CARTESIAN_POINT ( 'NONE', ( -25.02288988185319596, 182.0930031294805644, 101.7075183579726598 ) ) ; -#22584 = ADVANCED_FACE ( 'NONE', ( #9280 ), #5308, .F. ) ; -#22585 = CARTESIAN_POINT ( 'NONE', ( -20.24826303546999995, 118.4645066319000080, 90.03000659637000069 ) ) ; -#22586 = CARTESIAN_POINT ( 'NONE', ( 16.67763860462360981, 127.2204759592696917, 176.3528348589679524 ) ) ; -#22587 = LINE ( 'NONE', #38106, #6527 ) ; -#22588 = ORIENTED_EDGE ( 'NONE', *, *, #14387, .F. ) ; -#22589 = VERTEX_POINT ( 'NONE', #8116 ) ; -#22590 = DIRECTION ( 'NONE', ( 0.0006039748319392047697, 1.158053700410192562E-15, 0.9999998176071845934 ) ) ; -#22591 = CARTESIAN_POINT ( 'NONE', ( -1.208148773261155995, 135.9313244140174675, 177.2163779120750178 ) ) ; -#22592 = CARTESIAN_POINT ( 'NONE', ( -28.42925635489000413, 114.0103269030000064, 152.4718672074000381 ) ) ; -#22593 = CARTESIAN_POINT ( 'NONE', ( 37.31693588142861273, 172.3309151562380919, 164.9673944986862466 ) ) ; -#22594 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#22595 = ORIENTED_EDGE ( 'NONE', *, *, #31268, .T. ) ; -#22596 = CARTESIAN_POINT ( 'NONE', ( -3.334859686512663401, 127.9467318872441126, 92.10164337879916729 ) ) ; -#22597 = VERTEX_POINT ( 'NONE', #20576 ) ; -#22598 = AXIS2_PLACEMENT_3D ( 'NONE', #38747, #4805, #7472 ) ; -#22599 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38586, #13069, #25546, #7109 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999992929003319597 ), - .UNSPECIFIED. ) ; -#22600 = CIRCLE ( 'NONE', #16035, 5.499999999795470274 ) ; -#22601 = ORIENTED_EDGE ( 'NONE', *, *, #14997, .F. ) ; -#22602 = PLANE ( 'NONE', #7197 ) ; -#22603 = ORIENTED_EDGE ( 'NONE', *, *, #24909, .T. ) ; -#22604 = CARTESIAN_POINT ( 'NONE', ( -5.666787700381098247, 187.4723117046142988, 105.7482843246638282 ) ) ; -#22605 = CARTESIAN_POINT ( 'NONE', ( -3.069700939255000094, 190.9031832800000075, 106.9453286978999955 ) ) ; -#22606 = CARTESIAN_POINT ( 'NONE', ( -3.669581222364402873, 126.6894591277509221, 89.41685568663245931 ) ) ; -#22607 = ORIENTED_EDGE ( 'NONE', *, *, #11562, .T. ) ; -#22608 = CARTESIAN_POINT ( 'NONE', ( 12.63943526405000028, 181.6152899278259838, 104.1402435540826730 ) ) ; -#22609 = CARTESIAN_POINT ( 'NONE', ( -25.43620862700356966, 117.4588632744077898, 87.78297971315110715 ) ) ; -#22610 = CARTESIAN_POINT ( 'NONE', ( 22.78193024035000391, 158.2317512724935114, 98.73560148591467112 ) ) ; -#22611 = CARTESIAN_POINT ( 'NONE', ( 13.49868479949546618, 123.8375716773093984, 91.19048863502061408 ) ) ; -#22612 = CARTESIAN_POINT ( 'NONE', ( -42.34690063467109411, 120.8447378157120511, 90.65661607257399623 ) ) ; -#22613 = ORIENTED_EDGE ( 'NONE', *, *, #12208, .T. ) ; -#22614 = EDGE_CURVE ( 'NONE', #9290, #30211, #8186, .T. ) ; -#22616 = EDGE_CURVE ( 'NONE', #15817, #33167, #14056, .T. ) ; -#22615 = CARTESIAN_POINT ( 'NONE', ( 5.669508483227596152, 188.3446291069645611, 103.1322831256426866 ) ) ; -#22617 = VECTOR ( 'NONE', #12814, 1000.000000000000227 ) ; -#22618 = VECTOR ( 'NONE', #2975, 1000.000000000000000 ) ; -#22619 = CARTESIAN_POINT ( 'NONE', ( -35.56297588777000129, 113.0122100763999953, 90.16589942257002122 ) ) ; -#22621 = ORIENTED_EDGE ( 'NONE', *, *, #9351, .F. ) ; -#22620 = EDGE_CURVE ( 'NONE', #33611, #7238, #3727, .T. ) ; -#22622 = EDGE_LOOP ( 'NONE', ( #36695, #32709, #8697, #37340 ) ) ; -#22624 = AXIS2_PLACEMENT_3D ( 'NONE', #30977, #8909, #18075 ) ; -#22623 = CARTESIAN_POINT ( 'NONE', ( 9.448122968319339066, 159.6991011598222769, 96.51665850995770768 ) ) ; -#22625 = EDGE_CURVE ( 'NONE', #28895, #16043, #16918, .T. ) ; -#22626 = CARTESIAN_POINT ( 'NONE', ( -28.34217563707975174, 125.1610136493592762, 88.56573566053803859 ) ) ; -#22627 = CIRCLE ( 'NONE', #27872, 1.999999999928235628 ) ; -#22628 = CARTESIAN_POINT ( 'NONE', ( -3.769492941842434774, 174.7312905648006733, 102.8344854120291245 ) ) ; -#22629 = ORIENTED_EDGE ( 'NONE', *, *, #33466, .F. ) ; -#22630 = CARTESIAN_POINT ( 'NONE', ( -37.15110916248943340, 71.94901889567350395, 323.0119659613925478 ) ) ; -#22631 = EDGE_LOOP ( 'NONE', ( #21756, #34823, #25870, #2646 ) ) ; -#22632 = ORIENTED_EDGE ( 'NONE', *, *, #312, .T. ) ; -#22633 = EDGE_CURVE ( 'NONE', #11054, #5530, #20861, .T. ) ; -#22634 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323826078921479493, 0.0005734118987168501961 ) ) ; -#22635 = FACE_OUTER_BOUND ( 'NONE', #31264, .T. ) ; -#22636 = CARTESIAN_POINT ( 'NONE', ( 29.41435563321591218, 160.9614827452744237, 187.1157519457187561 ) ) ; -#22637 = EDGE_LOOP ( 'NONE', ( #12723, #19264, #6322, #18047 ) ) ; -#22638 = EDGE_LOOP ( 'NONE', ( #3688, #28044, #24547, #38908, #39780, #2941, #36531, #29560, #23120 ) ) ; -#22639 = DIRECTION ( 'NONE', ( -0.1305261967116597976, -0.9660514608154224803, -0.2229517594197838737 ) ) ; -#22640 = CARTESIAN_POINT ( 'NONE', ( 36.18171820146000073, 191.5958956560999980, 103.9695318283999939 ) ) ; -#22641 = DIRECTION ( 'NONE', ( 0.0006039748319379437342, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#22642 = DIRECTION ( 'NONE', ( 0.6087614883550945821, -0.7730004026499607273, -0.1785492307423600655 ) ) ; -#22643 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#22644 = LINE ( 'NONE', #1149, #28161 ) ; -#22645 = ORIENTED_EDGE ( 'NONE', *, *, #23912, .F. ) ; -#22646 = FACE_OUTER_BOUND ( 'NONE', #12756, .T. ) ; -#22647 = CARTESIAN_POINT ( 'NONE', ( -20.51779757010343985, 207.7035150799023882, 76.57867102927539804 ) ) ; -#22648 = CARTESIAN_POINT ( 'NONE', ( -20.00029466087617180, 160.7280592933503556, 96.77210435901376684 ) ) ; -#22649 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7850, #26678, #29741, #1724 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22650 = CARTESIAN_POINT ( 'NONE', ( 16.59040448417249891, 121.5622698803751121, 177.2309519810485767 ) ) ; -#22651 = CARTESIAN_POINT ( 'NONE', ( -18.76885123896627050, 125.8224625306723112, 175.1047239809785765 ) ) ; -#22652 = AXIS2_PLACEMENT_3D ( 'NONE', #19803, #7344, #10641 ) ; -#22653 = VERTEX_POINT ( 'NONE', #36006 ) ; -#22654 = CARTESIAN_POINT ( 'NONE', ( -23.36589107377781005, 134.9158523539519194, 90.81477344275025132 ) ) ; -#22655 = DIRECTION ( 'NONE', ( 0.0005884965073584763964, -0.2249510525036909903, 0.9743698874910607932 ) ) ; -#22656 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749903839, 135.0525466846722225, 91.33453887330247767 ) ) ; -#22657 = AXIS2_PLACEMENT_3D ( 'NONE', #25959, #38000, #16510 ) ; -#22658 = CARTESIAN_POINT ( 'NONE', ( 3.168077512235829563, 183.4518822370066289, 105.0831384053979036 ) ) ; -#22659 = VECTOR ( 'NONE', #7084, 1000.000000000000000 ) ; -#22660 = CARTESIAN_POINT ( 'NONE', ( 38.38896709011299180, 118.9510566342067506, 90.24663272979658757 ) ) ; -#22661 = DIRECTION ( 'NONE', ( -7.428452990058934869E-11, 0.9743700557754537694, 0.2249510933695120507 ) ) ; -#22662 = CARTESIAN_POINT ( 'NONE', ( -3.871848511230478351, 168.4194807666234794, 98.88106509990059578 ) ) ; -#22663 = FACE_OUTER_BOUND ( 'NONE', #31172, .T. ) ; -#22664 = CARTESIAN_POINT ( 'NONE', ( 25.50065687296894978, 121.1891575091324285, 90.18200499751846166 ) ) ; -#22665 = EDGE_CURVE ( 'NONE', #267, #10675, #20997, .T. ) ; -#22666 = VERTEX_POINT ( 'NONE', #21710 ) ; -#22667 = ADVANCED_FACE ( 'NONE', ( #40289 ), #30710, .T. ) ; -#22668 = EDGE_CURVE ( 'NONE', #9147, #16362, #37944, .T. ) ; -#22669 = ADVANCED_FACE ( 'NONE', ( #11900 ), #5338, .F. ) ; -#22670 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023851578 ) ) ; -#22671 = CARTESIAN_POINT ( 'NONE', ( -45.38741881364221342, 124.3872433421413177, 88.42275326155656501 ) ) ; -#22672 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#22673 = CARTESIAN_POINT ( 'NONE', ( 5.667731215173129833, 181.6143669964321248, 104.1442412133662998 ) ) ; -#22674 = EDGE_CURVE ( 'NONE', #5859, #19656, #12099, .T. ) ; -#22675 = AXIS2_PLACEMENT_3D ( 'NONE', #21394, #12981, #12771 ) ; -#22676 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772234801672, 136.6775772631780796, 180.9814965275865575 ) ) ; -#22677 = CARTESIAN_POINT ( 'NONE', ( 36.06506691458749714, 192.7090436111730014, 106.3601754007769813 ) ) ; -#22678 = CARTESIAN_POINT ( 'NONE', ( -10.44543797371702532, 134.9177046684737888, 90.80749218586807103 ) ) ; -#22679 = VECTOR ( 'NONE', #28608, 1000.000000000000114 ) ; -#22680 = CARTESIAN_POINT ( 'NONE', ( 21.00183496203274913, 175.6226406432039084, 103.0937819539236671 ) ) ; -#22681 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #36906, #13863, #17865, #19978 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.022641250864768203, 3.265663285694688334 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9950844102104468014, 0.9950844102104468014, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#22682 = CONICAL_SURFACE ( 'NONE', #472, 8.000002017059829384, 0.7853981633973110554 ) ; -#22683 = ORIENTED_EDGE ( 'NONE', *, *, #28570, .F. ) ; -#22684 = EDGE_CURVE ( 'NONE', #23777, #4523, #15503, .T. ) ; -#22685 = CARTESIAN_POINT ( 'NONE', ( -2.620903370884999806, 209.1091071886999941, 75.80136619622000183 ) ) ; -#22686 = CARTESIAN_POINT ( 'NONE', ( 35.59944106830731414, 113.9908721492990082, 87.24628312167284605 ) ) ; -#22687 = FACE_OUTER_BOUND ( 'NONE', #11881, .T. ) ; -#22688 = VERTEX_POINT ( 'NONE', #13101 ) ; -#22689 = DIRECTION ( 'NONE', ( -0.1305262373691798983, 0.9659583596717404852, 0.2233547598295697878 ) ) ; -#22690 = EDGE_LOOP ( 'NONE', ( #35774, #27533, #5006, #40146 ) ) ; -#22691 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; -#22692 = CARTESIAN_POINT ( 'NONE', ( 3.689590423171785094, 168.4639776339773221, 98.70304694460136830 ) ) ; -#22693 = PLANE ( 'NONE', #36660 ) ; -#22694 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#22695 = CARTESIAN_POINT ( 'NONE', ( 22.99270477044632344, 214.0899081099834689, 76.04459013870678064 ) ) ; -#22696 = CARTESIAN_POINT ( 'NONE', ( -30.06912398756719895, 176.8608841570483605, 103.2369763308513058 ) ) ; -#22697 = CARTESIAN_POINT ( 'NONE', ( -3.537750984983824232, 137.3463269818849426, 91.36396247942009552 ) ) ; -#22698 = VERTEX_POINT ( 'NONE', #16157 ) ; -#22699 = CARTESIAN_POINT ( 'NONE', ( 15.95616423589712340, 121.8747789553152785, 174.5819126748912709 ) ) ; -#22700 = CARTESIAN_POINT ( 'NONE', ( -5.407053729055359526, 177.7320116765900195, 100.6888568555215357 ) ) ; -#22701 = DIRECTION ( 'NONE', ( -0.0005884949961249829080, 0.2249510543439062205, -0.9743698870671264611 ) ) ; -#22702 = VERTEX_POINT ( 'NONE', #31304 ) ; -#22703 = AXIS2_PLACEMENT_3D ( 'NONE', #7222, #4148, #29322 ) ; -#22704 = CARTESIAN_POINT ( 'NONE', ( -36.71895117216000415, 191.7004588050999985, 104.5481094693000017 ) ) ; -#22705 = ORIENTED_EDGE ( 'NONE', *, *, #24582, .F. ) ; -#22706 = DIRECTION ( 'NONE', ( -0.5669487081581161547, -0.8237530954830113439, 0.000000000000000000 ) ) ; -#22707 = ORIENTED_EDGE ( 'NONE', *, *, #16137, .T. ) ; -#22708 = CARTESIAN_POINT ( 'NONE', ( -20.61224116156940411, 136.5556511042426280, 91.19172679136488568 ) ) ; -#22709 = EDGE_CURVE ( 'NONE', #11864, #7059, #4018, .T. ) ; -#22710 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422003068, 160.0671381723056754, 99.67809115075311865 ) ) ; -#22711 = EDGE_CURVE ( 'NONE', #1023, #33655, #15168, .T. ) ; -#22712 = FACE_OUTER_BOUND ( 'NONE', #3198, .T. ) ; -#22713 = DIRECTION ( 'NONE', ( 0.6087613186456907188, 0.7730177010543248795, 0.1784749023741044327 ) ) ; -#22714 = CARTESIAN_POINT ( 'NONE', ( -2.574763605953999779, 208.8764647145999902, 73.51762046848000409 ) ) ; -#22715 = CARTESIAN_POINT ( 'NONE', ( -37.29184647923000284, 190.5495719324999868, 106.6204670725000057 ) ) ; -#22716 = ORIENTED_EDGE ( 'NONE', *, *, #14390, .F. ) ; -#22717 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452350121, 0.1781166614240802804 ) ) ; -#22718 = CARTESIAN_POINT ( 'NONE', ( 42.97429946896744468, 67.83849343097567441, 322.0145824706445978 ) ) ; -#22719 = CARTESIAN_POINT ( 'NONE', ( 18.99767128196905830, 125.6058446513852118, 175.3475295528536151 ) ) ; -#22720 = LINE ( 'NONE', #16551, #1679 ) ; -#22721 = EDGE_LOOP ( 'NONE', ( #29116, #8030, #8526, #19612, #23456, #12561, #39244, #78, #6598, #27343, #14736 ) ) ; -#22722 = VERTEX_POINT ( 'NONE', #10241 ) ; -#22723 = ORIENTED_EDGE ( 'NONE', *, *, #1156, .T. ) ; -#22724 = CARTESIAN_POINT ( 'NONE', ( -43.94721011010098266, 112.7011882844193309, 88.77749572683383406 ) ) ; -#22725 = CONICAL_SURFACE ( 'NONE', #16171, 2.749999999892358549, 0.7853981634430725611 ) ; -#22726 = CARTESIAN_POINT ( 'NONE', ( 21.84918941357979705, 115.3422797856098185, 87.25458792911985029 ) ) ; -#22727 = CYLINDRICAL_SURFACE ( 'NONE', #39607, 1.999999999999989342 ) ; -#22728 = ORIENTED_EDGE ( 'NONE', *, *, #6864, .T. ) ; -#22729 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31098, #37427, #12092, #22098 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0005629175158857319377, 0.0007039624576953972413 ), - .UNSPECIFIED. ) ; -#22730 = AXIS2_PLACEMENT_3D ( 'NONE', #36739, #8750, #21212 ) ; -#22731 = ORIENTED_EDGE ( 'NONE', *, *, #14402, .T. ) ; -#22732 = DIRECTION ( 'NONE', ( 0.7075229215369458480, 9.360719863062603953E-05, 0.7066903895890456200 ) ) ; -#22733 = EDGE_CURVE ( 'NONE', #21947, #20205, #2326, .T. ) ; -#22734 = CARTESIAN_POINT ( 'NONE', ( -32.88044542039068574, 158.6959831765299214, 186.6567934753981888 ) ) ; -#22735 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971559574 ) ) ; -#22736 = CARTESIAN_POINT ( 'NONE', ( 25.50773797003102317, 191.9759150222000130, 101.9060413058080314 ) ) ; -#22737 = CARTESIAN_POINT ( 'NONE', ( 12.63493752644979118, 130.4235786262125032, 90.26909773778339741 ) ) ; -#22738 = CARTESIAN_POINT ( 'NONE', ( 19.98232544185748694, 209.7096131673859816, 76.04619115725449774 ) ) ; -#22739 = ORIENTED_EDGE ( 'NONE', *, *, #18771, .T. ) ; -#22740 = CARTESIAN_POINT ( 'NONE', ( -19.46367776224865409, 126.2483085376569250, 175.9816896695615753 ) ) ; -#22741 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28296, #3931, #21962, #16207 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0001033949579707245088, 0.0007867618316233762534 ), - .UNSPECIFIED. ) ; -#22742 = ORIENTED_EDGE ( 'NONE', *, *, #38840, .T. ) ; -#22743 = CARTESIAN_POINT ( 'NONE', ( -24.53639859075814300, 116.1139236424685208, 89.78257310409678382 ) ) ; -#22744 = CARTESIAN_POINT ( 'NONE', ( -6.316814198236529343, 180.2143825551339376, 27.02657698885747095 ) ) ; -#22745 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498900431, 132.2978364233248953, 93.26432363101957890 ) ) ; -#22746 = CYLINDRICAL_SURFACE ( 'NONE', #10575, 3.000000000000000888 ) ; -#22747 = ORIENTED_EDGE ( 'NONE', *, *, #33672, .F. ) ; -#22748 = FACE_OUTER_BOUND ( 'NONE', #39529, .T. ) ; -#22749 = FACE_OUTER_BOUND ( 'NONE', #8597, .T. ) ; -#22750 = FACE_OUTER_BOUND ( 'NONE', #8239, .T. ) ; -#22751 = CARTESIAN_POINT ( 'NONE', ( 8.470678308075262564, 161.4201748467667983, 97.42774225087779882 ) ) ; -#22752 = ORIENTED_EDGE ( 'NONE', *, *, #17567, .F. ) ; -#22753 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825926232611000, 0.0005734119022436430946 ) ) ; -#22754 = CARTESIAN_POINT ( 'NONE', ( 13.47018477901269051, 157.8313129290910695, 98.99086971718068639 ) ) ; -#22755 = ORIENTED_EDGE ( 'NONE', *, *, #10579, .F. ) ; -#22756 = CARTESIAN_POINT ( 'NONE', ( 41.04524146634799564, 219.5549399801000163, 73.53371387614997445 ) ) ; -#22757 = AXIS2_PLACEMENT_3D ( 'NONE', #8973, #17935, #8563 ) ; -#22758 = ORIENTED_EDGE ( 'NONE', *, *, #40274, .T. ) ; -#22759 = ADVANCED_FACE ( 'NONE', ( #19801 ), #29848, .F. ) ; -#22760 = EDGE_CURVE ( 'NONE', #30934, #23210, #28838, .T. ) ; -#22761 = DIRECTION ( 'NONE', ( 0.9999998268364571619, 0.0001323821501201892905, -0.0005734126106023100652 ) ) ; -#22762 = AXIS2_PLACEMENT_3D ( 'NONE', #2938, #40346, #34606 ) ; -#22763 = LINE ( 'NONE', #28100, #7799 ) ; -#22764 = VERTEX_POINT ( 'NONE', #16745 ) ; -#22765 = CARTESIAN_POINT ( 'NONE', ( 26.00448138516999919, 120.3035362655000000, 90.49060283839000363 ) ) ; -#22766 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#22767 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24732, #37185, #15695, #3221, #9781, #9578, #12629, #38184, #16101, #25735, #25129, #28780, #27998, #18743, #22660, #28196, #28385, #165, #22459, #22053, #34689, #31050 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999992953414, 0.1874999999989522270, 0.2187499999987793931, 0.2343749999986751154, 0.2421874999986851629, 0.2499999999986952104, 0.3749999999991081578, 0.4374999999992994493, 0.4687499999994137467, 0.4843749999994504396, 0.4999999999994870770, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22769 = CARTESIAN_POINT ( 'NONE', ( -37.29428432633125112, 118.1868522465356364, 122.8630558711557796 ) ) ; -#22768 = CARTESIAN_POINT ( 'NONE', ( 25.49183423580130636, 211.0903769678246817, 75.54322026927223988 ) ) ; -#22770 = ORIENTED_EDGE ( 'NONE', *, *, #40315, .T. ) ; -#22771 = ORIENTED_EDGE ( 'NONE', *, *, #27117, .T. ) ; -#22772 = DIRECTION ( 'NONE', ( -0.6087613186456907188, 0.7729176985478710682, 0.1789074850089337476 ) ) ; -#22773 = CARTESIAN_POINT ( 'NONE', ( 28.46393509008022349, 182.0672870871918576, 102.1824291507762865 ) ) ; -#22774 = CARTESIAN_POINT ( 'NONE', ( -35.94659742851874284, 109.6131156826799895, 89.78949559170979455 ) ) ; -#22775 = ORIENTED_EDGE ( 'NONE', *, *, #12540, .T. ) ; -#22776 = VERTEX_POINT ( 'NONE', #13897 ) ; -#22777 = CARTESIAN_POINT ( 'NONE', ( 38.57548057532000030, 119.2480769345999931, 90.41779171121000047 ) ) ; -#22778 = CARTESIAN_POINT ( 'NONE', ( -35.55125210787799972, 114.2871942515880335, 87.28925635746423950 ) ) ; -#22779 = AXIS2_PLACEMENT_3D ( 'NONE', #18580, #6324, #3250 ) ; -#22780 = ADVANCED_FACE ( 'NONE', ( #20634 ), #7955, .F. ) ; -#22781 = CARTESIAN_POINT ( 'NONE', ( 5.673401637569556399, 187.6316643536460731, 105.9943968491383970 ) ) ; -#22782 = CARTESIAN_POINT ( 'NONE', ( -2.813782933366999917, 190.8795050674000038, 106.6764022065000006 ) ) ; -#22783 = CARTESIAN_POINT ( 'NONE', ( 36.14124483135999810, 192.1045279321999999, 104.3956236366000212 ) ) ; -#22784 = ORIENTED_EDGE ( 'NONE', *, *, #28431, .T. ) ; -#22785 = ORIENTED_EDGE ( 'NONE', *, *, #34582, .T. ) ; -#22786 = AXIS2_PLACEMENT_3D ( 'NONE', #19793, #13682, #34729 ) ; -#22787 = VERTEX_POINT ( 'NONE', #35528 ) ; -#22788 = CARTESIAN_POINT ( 'NONE', ( -6.034872611388630403, 176.9126535083784688, 103.3009512934358582 ) ) ; -#22789 = VECTOR ( 'NONE', #30345, 1000.000000000000000 ) ; -#22790 = CARTESIAN_POINT ( 'NONE', ( -37.22290639677533619, 126.0669666328596321, 91.85916804901101784 ) ) ; -#22791 = CARTESIAN_POINT ( 'NONE', ( 22.49999745837402543, 174.5192442765713849, 99.92720223818444936 ) ) ; -#22792 = VERTEX_POINT ( 'NONE', #20014 ) ; -#22793 = ORIENTED_EDGE ( 'NONE', *, *, #22297, .F. ) ; -#22794 = CARTESIAN_POINT ( 'NONE', ( 20.33358726661999683, 174.4467126026231085, 100.2570000595842430 ) ) ; -#22795 = ORIENTED_EDGE ( 'NONE', *, *, #17871, .F. ) ; -#22796 = EDGE_CURVE ( 'NONE', #11205, #39755, #20214, .T. ) ; -#22797 = DIRECTION ( 'NONE', ( 2.893731969398355670E-13, -0.9743700559028483088, -0.2249510928177059499 ) ) ; -#22798 = ORIENTED_EDGE ( 'NONE', *, *, #26926, .F. ) ; -#22799 = CARTESIAN_POINT ( 'NONE', ( -30.07353167211553213, 135.0567859791754302, 91.04548219668697584 ) ) ; -#22800 = EDGE_CURVE ( 'NONE', #1699, #38902, #21390, .T. ) ; -#22801 = CARTESIAN_POINT ( 'NONE', ( -30.07185925050806574, 137.2385153804196705, 91.86824398011344783 ) ) ; -#22802 = CARTESIAN_POINT ( 'NONE', ( 34.29562917979933445, 218.5902260770999987, 75.53779083768952773 ) ) ; -#22803 = EDGE_LOOP ( 'NONE', ( #4046, #21507, #2153, #10405 ) ) ; -#22804 = ORIENTED_EDGE ( 'NONE', *, *, #14621, .F. ) ; -#22806 = EDGE_CURVE ( 'NONE', #24313, #13948, #9638, .T. ) ; -#22805 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#22807 = EDGE_CURVE ( 'NONE', #23218, #37942, #39850, .T. ) ; -#22808 = CARTESIAN_POINT ( 'NONE', ( 24.33241291692780806, 117.2920445016514748, 170.8609620625155117 ) ) ; -#22809 = CARTESIAN_POINT ( 'NONE', ( -20.49588020594338644, 118.8154963149322754, 94.28014888055585629 ) ) ; -#22810 = EDGE_CURVE ( 'NONE', #15150, #32498, #39636, .T. ) ; -#22811 = CIRCLE ( 'NONE', #30633, 2.500000000019892532 ) ; -#22812 = EDGE_CURVE ( 'NONE', #38645, #8802, #24287, .T. ) ; -#22813 = CYLINDRICAL_SURFACE ( 'NONE', #21977, 4.999999999999990230 ) ; -#22814 = ORIENTED_EDGE ( 'NONE', *, *, #38791, .T. ) ; -#22815 = VECTOR ( 'NONE', #39575, 1000.000000000000000 ) ; -#22816 = CARTESIAN_POINT ( 'NONE', ( 25.50043875868088961, 117.7861551627153744, 89.75251609159239763 ) ) ; -#22817 = CARTESIAN_POINT ( 'NONE', ( -37.21824319516999680, 117.1596748030000015, 89.86351461361999782 ) ) ; -#22818 = ORIENTED_EDGE ( 'NONE', *, *, #8255, .F. ) ; -#22819 = CARTESIAN_POINT ( 'NONE', ( -23.20480341064914498, 151.8084575254806339, 205.6165954981223081 ) ) ; -#22820 = EDGE_LOOP ( 'NONE', ( #22147, #28418, #26932, #23121 ) ) ; -#22821 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971564570 ) ) ; -#22822 = CARTESIAN_POINT ( 'NONE', ( 26.03550245107076933, 190.8511564191358900, 106.7775725292634945 ) ) ; -#22823 = DIRECTION ( 'NONE', ( 0.7855779781279682572, 0.6187626687837376460, 0.000000000000000000 ) ) ; -#22824 = ORIENTED_EDGE ( 'NONE', *, *, #30432, .T. ) ; -#22825 = CARTESIAN_POINT ( 'NONE', ( 30.07038983360635243, 136.6834034282913422, 94.27269756974730797 ) ) ; -#22826 = ORIENTED_EDGE ( 'NONE', *, *, #10656, .T. ) ; -#22827 = ORIENTED_EDGE ( 'NONE', *, *, #5577, .F. ) ; -#22828 = CARTESIAN_POINT ( 'NONE', ( 1.837866333389163609, 189.4578565298617718, 105.8682861792007373 ) ) ; -#22829 = CARTESIAN_POINT ( 'NONE', ( 36.05352243695643466, 118.8155708862894642, 87.24600886790115339 ) ) ; -#22830 = VERTEX_POINT ( 'NONE', #4433 ) ; -#22831 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178587041921E-05, -0.0002331579774917524482 ) ) ; -#22832 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319372081030 ) ) ; -#22833 = CARTESIAN_POINT ( 'NONE', ( -26.00152628985659575, 118.5828354757999961, 87.28353789566725141 ) ) ; -#22834 = CARTESIAN_POINT ( 'NONE', ( 36.36406131881000192, 191.7312092642999914, 104.2373321830999942 ) ) ; -#22835 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559296 ) ) ; -#22836 = AXIS2_PLACEMENT_3D ( 'NONE', #7377, #37513, #4509 ) ; -#22837 = CARTESIAN_POINT ( 'NONE', ( 37.28741399843698900, 124.9789241431960392, 93.24647550195996359 ) ) ; -#22838 = DIRECTION ( 'NONE', ( 0.0005884949961194453454, -0.2249510543439075527, 0.9743698870671261281 ) ) ; -#22839 = ORIENTED_EDGE ( 'NONE', *, *, #26416, .F. ) ; -#22840 = CARTESIAN_POINT ( 'NONE', ( 25.83247327863999843, 120.7394249123999970, 87.68326996205000512 ) ) ; -#22841 = EDGE_CURVE ( 'NONE', #16282, #28951, #10153, .T. ) ; -#22842 = VECTOR ( 'NONE', #6193, 1000.000000000000000 ) ; -#22843 = CARTESIAN_POINT ( 'NONE', ( -20.51745969899640087, 207.4083551867479116, 77.09396086730279762 ) ) ; -#22844 = VECTOR ( 'NONE', #24344, 1000.000000000000000 ) ; -#22845 = CARTESIAN_POINT ( 'NONE', ( -7.985938709523869861, 131.0204239720261512, 89.90626579571295451 ) ) ; -#22846 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#22847 = DIRECTION ( 'NONE', ( -0.7871416011357068587, 0.6167723240884886993, 0.000000000000000000 ) ) ; -#22848 = ORIENTED_EDGE ( 'NONE', *, *, #18916, .F. ) ; -#22849 = CARTESIAN_POINT ( 'NONE', ( 45.29398665750001385, 181.0941504656715608, 101.9475978871965651 ) ) ; -#22850 = ADVANCED_FACE ( 'NONE', ( #25940 ), #3825, .F. ) ; -#22851 = CARTESIAN_POINT ( 'NONE', ( 0.7809376719035407977, 189.0122013254281512, 103.6875910670326277 ) ) ; -#22852 = CARTESIAN_POINT ( 'NONE', ( -2.676356233750540881, 189.7677746538298607, 106.5447958017762176 ) ) ; -#22853 = EDGE_CURVE ( 'NONE', #16029, #36719, #37976, .T. ) ; -#22854 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; -#22855 = CARTESIAN_POINT ( 'NONE', ( -25.87511576118999912, 191.6567917961000092, 104.0339623576000179 ) ) ; -#22856 = LINE ( 'NONE', #7289, #2985 ) ; -#22857 = FACE_OUTER_BOUND ( 'NONE', #29568, .T. ) ; -#22858 = EDGE_CURVE ( 'NONE', #21490, #35342, #754, .T. ) ; -#22859 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #30447, #36149, #11418, #21037 ), - ( #36763, #5889, #20618, #17536 ), - ( #27190, #17736, #26978, #14899 ), - ( #40030, #39415, #5479, #8978 ), - ( #5694, #24520, #36978, #23903 ), - ( #20828, #33280, #5272, #30231 ), - ( #17939, #14708, #2437, #39620 ), - ( #24112, #27402, #39823, #8773 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.05582231594939000147, 0.000000000000000000, 0.3333333892231000184, 0.6666666942443999488, 1.000000000000000000, 1.059484521436000026 ), - ( -0.2890760154095999845, 1.289073967883000105 ), - .UNSPECIFIED. ) ; -#22860 = CARTESIAN_POINT ( 'NONE', ( 3.596286182869788295, 141.6796019413746706, 182.7901370451803587 ) ) ; -#22861 = LINE ( 'NONE', #7293, #30445 ) ; -#22862 = ORIENTED_EDGE ( 'NONE', *, *, #30002, .T. ) ; -#22863 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23716, #21060, #5299, #5498 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22864 = CARTESIAN_POINT ( 'NONE', ( -22.78329764787637046, 154.4034317766920310, 95.31352365236099899 ) ) ; -#22865 = AXIS2_PLACEMENT_3D ( 'NONE', #29426, #13677, #3856 ) ; -#22866 = VECTOR ( 'NONE', #17011, 1000.000000000000114 ) ; -#22867 = ORIENTED_EDGE ( 'NONE', *, *, #14007, .T. ) ; -#22868 = DIRECTION ( 'NONE', ( 0.0006039712449778905342, 0.000000000000000000, 0.9999998176093508606 ) ) ; -#22869 = CARTESIAN_POINT ( 'NONE', ( 5.666581507162372411, 181.3641253286114079, 104.3006101419990870 ) ) ; -#22870 = AXIS2_PLACEMENT_3D ( 'NONE', #20796, #39388, #39793 ) ; -#22871 = CARTESIAN_POINT ( 'NONE', ( -15.10535409822645647, 135.6520233040683934, 94.05869708244797778 ) ) ; -#22872 = CARTESIAN_POINT ( 'NONE', ( 36.06465037923999972, 192.5956917412999871, 105.6705187376000197 ) ) ; -#22873 = CIRCLE ( 'NONE', #26150, 2.500000000008382628 ) ; -#22874 = CARTESIAN_POINT ( 'NONE', ( -5.666930955406936476, 130.1424768347354188, 92.50234736738113384 ) ) ; -#22875 = CARTESIAN_POINT ( 'NONE', ( 35.68143157579000047, 192.6396356641000409, 106.7375437715000004 ) ) ; -#22876 = ORIENTED_EDGE ( 'NONE', *, *, #13824, .F. ) ; -#22877 = CARTESIAN_POINT ( 'NONE', ( -5.669593981664322158, 181.2570474460025309, 104.3730823857091394 ) ) ; -#22878 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#22879 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178582675974E-05, -0.0002331579774919535406 ) ) ; -#22880 = CARTESIAN_POINT ( 'NONE', ( 12.31735795870903161, 136.6817491452135016, 94.27986305550896873 ) ) ; -#22881 = ORIENTED_EDGE ( 'NONE', *, *, #1186, .F. ) ; -#22882 = PLANE ( 'NONE', #5022 ) ; -#22883 = VERTEX_POINT ( 'NONE', #13055 ) ; -#22884 = CARTESIAN_POINT ( 'NONE', ( -23.36043049209896694, 136.7895015923607787, 93.81313601547243763 ) ) ; -#22885 = ORIENTED_EDGE ( 'NONE', *, *, #13324, .T. ) ; -#22886 = DIRECTION ( 'NONE', ( 0.6983012566254244158, 0.000000000000000000, 0.7158039920225042207 ) ) ; -#22887 = ADVANCED_FACE ( 'NONE', ( #6900 ), #36333, .F. ) ; -#22888 = ADVANCED_FACE ( 'NONE', ( #17906 ), #26334, .F. ) ; -#22889 = CARTESIAN_POINT ( 'NONE', ( -45.58302259763831188, 185.8574834039084180, 105.8703329252015806 ) ) ; -#22890 = EDGE_CURVE ( 'NONE', #22006, #1429, #13044, .T. ) ; -#22891 = FACE_OUTER_BOUND ( 'NONE', #16650, .T. ) ; -#22892 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; -#22893 = ORIENTED_EDGE ( 'NONE', *, *, #23111, .T. ) ; -#22894 = AXIS2_PLACEMENT_3D ( 'NONE', #16287, #10773, #20983 ) ; -#22895 = DIRECTION ( 'NONE', ( -0.7855473026356900590, -0.6188014303620735790, 0.0004744508866335530478 ) ) ; -#22896 = AXIS2_PLACEMENT_3D ( 'NONE', #28765, #743, #22835 ) ; -#22897 = CARTESIAN_POINT ( 'NONE', ( -8.271967253109403728, 188.3426927931979264, 103.1403358607322360 ) ) ; -#22898 = CARTESIAN_POINT ( 'NONE', ( -3.419728389424999904, 127.6373404636000117, 89.37896439713999541 ) ) ; -#22899 = EDGE_CURVE ( 'NONE', #25549, #30903, #21682, .T. ) ; -#22900 = VECTOR ( 'NONE', #11453, 999.9999999999998863 ) ; -#22901 = CONICAL_SURFACE ( 'NONE', #1337, 2.502995680536484802, 0.7853981633384532479 ) ; -#22902 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#22903 = VERTEX_POINT ( 'NONE', #11601 ) ; -#22904 = ORIENTED_EDGE ( 'NONE', *, *, #11536, .F. ) ; -#22905 = CARTESIAN_POINT ( 'NONE', ( 13.55514511692094537, 147.5124591927943811, 96.26643020890679736 ) ) ; -#22906 = EDGE_CURVE ( 'NONE', #32161, #30285, #35903, .T. ) ; -#22907 = CARTESIAN_POINT ( 'NONE', ( -18.92878511345999826, 158.4511806311000157, 97.78514868614999500 ) ) ; -#22908 = CARTESIAN_POINT ( 'NONE', ( -12.64562993050861550, 181.6872450680611450, 101.6064063805796280 ) ) ; -#22909 = CARTESIAN_POINT ( 'NONE', ( 10.88293107966285334, 124.3679198336539571, 88.35892229760115413 ) ) ; -#22910 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #22203, #303, #6836, #35235 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.137875966956430229, 6.279468620546222901 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.3333333333333335369, 0.3333333333333335369, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#22911 = CARTESIAN_POINT ( 'NONE', ( 25.67924018176999823, 190.7157574210999940, 106.3544759560000017 ) ) ; -#22912 = ADVANCED_FACE ( 'NONE', ( #24286 ), #12584, .T. ) ; -#22913 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24127, #27207, #26792, #17757, #11653, #20425, #10846, #20219, #23315, #17150, #14727, #8588, #17957, #21059, #35744, #17343, #26999 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000044131, 0.1875000000000067446, 0.2500000000000090483, 0.3750000000000066058, 0.5000000000000042188, 0.6250000000000018874, 0.7499999999999993339, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22914 = CARTESIAN_POINT ( 'NONE', ( 20.48181612770335391, 206.0037509564070319, 75.48930600427006254 ) ) ; -#22915 = CARTESIAN_POINT ( 'NONE', ( -37.94564516765999684, 190.8198141665000094, 106.4202611438000048 ) ) ; -#22916 = ORIENTED_EDGE ( 'NONE', *, *, #29669, .T. ) ; -#22917 = CYLINDRICAL_SURFACE ( 'NONE', #1566, 4.999999999999990230 ) ; -#22918 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 77.27946979429611929, 297.5967072516830854 ) ) ; -#22919 = CARTESIAN_POINT ( 'NONE', ( 3.334663831449610871, 126.1666046699075281, 91.68664002808421287 ) ) ; -#22920 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#22921 = EDGE_LOOP ( 'NONE', ( #6094, #21495, #13808, #26111 ) ) ; -#22922 = AXIS2_PLACEMENT_3D ( 'NONE', #23853, #36309, #7690 ) ; -#22923 = AXIS2_PLACEMENT_3D ( 'NONE', #15635, #19093, #27735 ) ; -#22924 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37607, #18986, #36810, #21688, #6126, #33928 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.1624460549302637891, 0.5812230274651318807, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22925 = ORIENTED_EDGE ( 'NONE', *, *, #6295, .T. ) ; -#22926 = CARTESIAN_POINT ( 'NONE', ( -26.00760980898482799, 207.8686442861051376, 77.29275028086965449 ) ) ; -#22927 = VECTOR ( 'NONE', #38737, 1000.000000000000114 ) ; -#22928 = CIRCLE ( 'NONE', #22292, 29.99999999998092548 ) ; -#22929 = CARTESIAN_POINT ( 'NONE', ( -45.30371984282656683, 124.3227729409930618, 91.46136974178453727 ) ) ; -#22930 = ORIENTED_EDGE ( 'NONE', *, *, #4883, .F. ) ; -#22931 = CARTESIAN_POINT ( 'NONE', ( -25.91302099857000130, 130.1559280140999988, 92.53977237774999764 ) ) ; -#22932 = CARTESIAN_POINT ( 'NONE', ( -39.69437836998564251, 161.5619712970498085, 197.5056430804474985 ) ) ; -#22933 = CARTESIAN_POINT ( 'NONE', ( -38.39048845847000280, 118.6206116153999943, 89.90268112204999795 ) ) ; -#22934 = CARTESIAN_POINT ( 'NONE', ( -3.503019623547876993, 184.0485918194861767, 102.4881131396436444 ) ) ; -#22935 = CARTESIAN_POINT ( 'NONE', ( 28.47525309053320797, 130.3504702658399879, 92.80840815248680542 ) ) ; -#22936 = ORIENTED_EDGE ( 'NONE', *, *, #40229, .T. ) ; -#22937 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26248, #13562, #33157, #36232 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#22938 = FACE_OUTER_BOUND ( 'NONE', #21722, .T. ) ; -#22939 = ORIENTED_EDGE ( 'NONE', *, *, #26674, .F. ) ; -#22940 = EDGE_CURVE ( 'NONE', #38457, #34802, #27592, .T. ) ; -#22941 = CARTESIAN_POINT ( 'NONE', ( -3.169881913554984720, 185.9062129263137138, 102.5746722649703315 ) ) ; -#22942 = ADVANCED_FACE ( 'NONE', ( #5657 ), #6639, .F. ) ; -#22943 = DIRECTION ( 'NONE', ( -4.452505765293227325E-11, -0.9743700387726779155, -0.2249511670165995070 ) ) ; -#22944 = CARTESIAN_POINT ( 'NONE', ( 46.36049362162751919, 125.3570268543407167, 88.90797177416244779 ) ) ; -#22945 = ORIENTED_EDGE ( 'NONE', *, *, #38289, .T. ) ; -#22946 = ORIENTED_EDGE ( 'NONE', *, *, #34601, .F. ) ; -#22947 = CARTESIAN_POINT ( 'NONE', ( -0.4374722634361999929, 188.8708576324000035, 103.5226396815999976 ) ) ; -#22948 = CARTESIAN_POINT ( 'NONE', ( 25.50924790716773671, 191.9759150222000130, 104.4060408498541079 ) ) ; -#22949 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971577060 ) ) ; -#22950 = ORIENTED_EDGE ( 'NONE', *, *, #20945, .T. ) ; -#22951 = AXIS2_PLACEMENT_3D ( 'NONE', #3444, #34716, #3852 ) ; -#22952 = FACE_OUTER_BOUND ( 'NONE', #5163, .T. ) ; -#22953 = LINE ( 'NONE', #35382, #11523 ) ; -#22954 = VERTEX_POINT ( 'NONE', #8946 ) ; -#22955 = VECTOR ( 'NONE', #31802, 1000.000000000000000 ) ; -#22956 = VECTOR ( 'NONE', #31620, 1000.000000000000000 ) ; -#22957 = CARTESIAN_POINT ( 'NONE', ( 21.46414478492309996, 116.1138660754223508, 89.75506028734766062 ) ) ; -#22958 = EDGE_LOOP ( 'NONE', ( #2871, #24111, #33755, #3343 ) ) ; -#22959 = DIRECTION ( 'NONE', ( 0.7933530821293307556, 0.5932640870757668328, 0.1364866662427073885 ) ) ; -#22960 = CARTESIAN_POINT ( 'NONE', ( 2.544461030880475594, 209.0000001909309901, 73.61327617014224245 ) ) ; -#22961 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; -#22962 = LINE ( 'NONE', #32359, #3420 ) ; -#22963 = EDGE_CURVE ( 'NONE', #40341, #27102, #38626, .T. ) ; -#22964 = EDGE_LOOP ( 'NONE', ( #38339, #29236, #20870, #26626 ) ) ; -#22965 = CARTESIAN_POINT ( 'NONE', ( 25.66875014887000006, 120.3200521089000006, 90.15167757061000486 ) ) ; -#22966 = CARTESIAN_POINT ( 'NONE', ( -25.51388077191477066, 211.0902258580313742, 75.57405363378009611 ) ) ; -#22968 = LINE ( 'NONE', #13556, #30528 ) ; -#22967 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988445790169, 150.9961524914176607, 94.51313162276940716 ) ) ; -#22969 = CARTESIAN_POINT ( 'NONE', ( -14.13846548020544880, 164.5254833472192217, 152.7619685177316740 ) ) ; -#22970 = VERTEX_POINT ( 'NONE', #27757 ) ; -#22971 = DIRECTION ( 'NONE', ( 0.0005884949961249829080, -0.2249510543439062205, 0.9743698870671264611 ) ) ; -#22972 = FACE_OUTER_BOUND ( 'NONE', #5332, .T. ) ; -#22973 = CARTESIAN_POINT ( 'NONE', ( -8.473620771760185022, 151.0652496779955811, 95.04735290400581960 ) ) ; -#22974 = ORIENTED_EDGE ( 'NONE', *, *, #39996, .F. ) ; -#22975 = ORIENTED_EDGE ( 'NONE', *, *, #13794, .F. ) ; -#22976 = FACE_OUTER_BOUND ( 'NONE', #10291, .T. ) ; -#22978 = AXIS2_PLACEMENT_3D ( 'NONE', #39826, #21655, #17942 ) ; -#22977 = FACE_OUTER_BOUND ( 'NONE', #12357, .T. ) ; -#22979 = AXIS2_PLACEMENT_3D ( 'NONE', #22516, #31918, #19419 ) ; -#22980 = CYLINDRICAL_SURFACE ( 'NONE', #4971, 2.000000000000001332 ) ; -#22981 = CARTESIAN_POINT ( 'NONE', ( -45.41309877574845899, 123.7966584769246197, 93.36316325758346579 ) ) ; -#22982 = CARTESIAN_POINT ( 'NONE', ( -2.814039094922999862, 190.9184237906999897, 106.6856330288999999 ) ) ; -#22983 = ORIENTED_EDGE ( 'NONE', *, *, #39523, .F. ) ; -#22984 = ORIENTED_EDGE ( 'NONE', *, *, #13764, .T. ) ; -#22985 = ORIENTED_EDGE ( 'NONE', *, *, #11675, .T. ) ; -#22986 = EDGE_CURVE ( 'NONE', #32426, #206, #11213, .T. ) ; -#22987 = CARTESIAN_POINT ( 'NONE', ( -16.53460274203917635, 121.8354022778151204, 177.5673403339679055 ) ) ; -#22988 = ADVANCED_FACE ( 'NONE', ( #24891 ), #36001, .F. ) ; -#22989 = CYLINDRICAL_SURFACE ( 'NONE', #35935, 2.000000000000000000 ) ; -#22990 = ORIENTED_EDGE ( 'NONE', *, *, #21049, .T. ) ; -#22991 = ORIENTED_EDGE ( 'NONE', *, *, #39052, .T. ) ; -#22992 = CARTESIAN_POINT ( 'NONE', ( 29.05382570111806118, 110.6131156702000027, 87.75023660053001606 ) ) ; -#22993 = CARTESIAN_POINT ( 'NONE', ( -37.92915657618366509, 117.8950347885309498, 89.71597331060294778 ) ) ; -#22994 = ORIENTED_EDGE ( 'NONE', *, *, #4472, .F. ) ; -#22995 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#22996 = VERTEX_POINT ( 'NONE', #32014 ) ; -#22997 = FACE_OUTER_BOUND ( 'NONE', #25774, .T. ) ; -#22998 = CARTESIAN_POINT ( 'NONE', ( -2.752073334482000089, 190.2672676434999914, 106.5277000906000069 ) ) ; -#22999 = CARTESIAN_POINT ( 'NONE', ( 36.43736767128643095, 111.7645015433333384, 175.7443402496501790 ) ) ; -#23000 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391903498 ) ) ; -#23001 = ORIENTED_EDGE ( 'NONE', *, *, #32837, .T. ) ; -#23002 = CARTESIAN_POINT ( 'NONE', ( -13.49823529424112145, 160.0636115298041204, 99.69358428540749628 ) ) ; -#23003 = VECTOR ( 'NONE', #4252, 1000.000000000000114 ) ; -#23004 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12456, #15914, #37798, #6115, #9205, #18574, #31079, #15529, #12871, #25347, #3639 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998192557, 0.3749999999997322697, 0.4374999999996888045, 0.4687499999996911915, 0.4999999999996935784, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23005 = CARTESIAN_POINT ( 'NONE', ( 22.20627172700715590, 213.9926456290793908, 73.04509205071391875 ) ) ; -#23006 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 82.27946979429631824, 312.5857197240630967 ) ) ; -#23007 = VECTOR ( 'NONE', #5458, 1000.000000000000000 ) ; -#23008 = LINE ( 'NONE', #35242, #31110 ) ; -#23009 = EDGE_LOOP ( 'NONE', ( #21343, #14892, #24855, #37297, #24074, #31994, #6631 ) ) ; -#23010 = CARTESIAN_POINT ( 'NONE', ( 22.99212157941825296, 211.0902260771000272, 76.05077210604348181 ) ) ; -#23011 = CARTESIAN_POINT ( 'NONE', ( -36.71662452048000347, 115.6901090825000011, 89.59692734496999833 ) ) ; -#23012 = VERTEX_POINT ( 'NONE', #35040 ) ; -#23013 = ORIENTED_EDGE ( 'NONE', *, *, #7875, .T. ) ; -#23014 = PLANE ( 'NONE', #31680 ) ; -#23015 = EDGE_CURVE ( 'NONE', #24868, #35038, #4762, .T. ) ; -#23016 = CARTESIAN_POINT ( 'NONE', ( -4.076917671009580246, 159.1898768710711636, 28.07643227829938226 ) ) ; -#23017 = CARTESIAN_POINT ( 'NONE', ( 25.86949214255275820, 190.8731965187743356, 106.6117107760572082 ) ) ; -#23018 = LINE ( 'NONE', #19526, #19435 ) ; -#23019 = VERTEX_POINT ( 'NONE', #16250 ) ; -#23020 = ORIENTED_EDGE ( 'NONE', *, *, #7319, .T. ) ; -#23021 = CARTESIAN_POINT ( 'NONE', ( -2.935493006219376255, 190.8915656532114724, 106.8042233182557652 ) ) ; -#23022 = ORIENTED_EDGE ( 'NONE', *, *, #1139, .T. ) ; -#23023 = ORIENTED_EDGE ( 'NONE', *, *, #14443, .F. ) ; -#23024 = CARTESIAN_POINT ( 'NONE', ( -6.031620047117566052, 177.7903949882438042, 100.7027583919079063 ) ) ; -#23025 = EDGE_CURVE ( 'NONE', #11556, #14938, #3751, .T. ) ; -#23026 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#23027 = ORIENTED_EDGE ( 'NONE', *, *, #40327, .F. ) ; -#23028 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39505, #38689, #39098, #32962 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23029 = ORIENTED_EDGE ( 'NONE', *, *, #5337, .F. ) ; -#23030 = CARTESIAN_POINT ( 'NONE', ( -39.35358084013989810, 182.6251433340804624, 104.9179412529496176 ) ) ; -#23032 = EDGE_CURVE ( 'NONE', #12363, #20529, #36686, .T. ) ; -#23031 = CARTESIAN_POINT ( 'NONE', ( -18.98875009441257333, 125.3860450160050277, 176.2394239049030773 ) ) ; -#23033 = FACE_OUTER_BOUND ( 'NONE', #15723, .T. ) ; -#23035 = AXIS2_PLACEMENT_3D ( 'NONE', #2008, #26551, #7925 ) ; -#23034 = CARTESIAN_POINT ( 'NONE', ( 36.52937954486999672, 191.8776055557000007, 104.5091987639000166 ) ) ; -#23036 = ADVANCED_FACE ( 'NONE', ( #33355 ), #4853, .F. ) ; -#23037 = CARTESIAN_POINT ( 'NONE', ( 19.99998068445589894, 192.4505593463679531, 103.8661183637674696 ) ) ; -#23038 = EDGE_CURVE ( 'NONE', #5670, #18015, #6220, .T. ) ; -#23039 = AXIS2_PLACEMENT_3D ( 'NONE', #33595, #17441, #15005 ) ; -#23040 = DIRECTION ( 'NONE', ( 0.0002393071182782299474, 0.2252352986010034697, -0.9743043687658493601 ) ) ; -#23041 = FACE_OUTER_BOUND ( 'NONE', #27153, .T. ) ; -#23042 = CARTESIAN_POINT ( 'NONE', ( 13.76428958129024060, 149.7303430849056554, 179.8030703196882882 ) ) ; -#23043 = EDGE_LOOP ( 'NONE', ( #40372, #1657, #3864, #23703 ) ) ; -#23044 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501099214, 179.0628333271199892, 104.0826189413407548 ) ) ; -#23045 = CARTESIAN_POINT ( 'NONE', ( 25.43413852155488186, 117.4589139984525588, 87.75225533617421547 ) ) ; -#23046 = CARTESIAN_POINT ( 'NONE', ( 3.778874383621917854, 175.3021472085679591, 100.3732877819419684 ) ) ; -#23047 = CARTESIAN_POINT ( 'NONE', ( 45.75915549074260014, 185.6501889555703713, 105.6243901609633724 ) ) ; -#23048 = ORIENTED_EDGE ( 'NONE', *, *, #12349, .F. ) ; -#23049 = LINE ( 'NONE', #19948, #3686 ) ; -#23050 = CARTESIAN_POINT ( 'NONE', ( 1.081957969975081646, 189.0686000648533422, 103.7038781678739525 ) ) ; -#23051 = CARTESIAN_POINT ( 'NONE', ( 13.55514511693098889, 164.0767501412786942, 100.0905987950646931 ) ) ; -#23052 = CARTESIAN_POINT ( 'NONE', ( -21.44693694427656538, 176.9185168219783009, 100.5107344958116897 ) ) ; -#23053 = CARTESIAN_POINT ( 'NONE', ( -26.12919643628000088, 191.8854903158000127, 103.7978481772000094 ) ) ; -#23054 = CARTESIAN_POINT ( 'NONE', ( 77.66418106072950422, 192.0495531737880697, 194.3144031859467020 ) ) ; -#23055 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#23056 = ADVANCED_FACE ( 'NONE', ( #39484 ), #3466, .F. ) ; -#23057 = CARTESIAN_POINT ( 'NONE', ( 13.50147201673213893, 151.4095814229721668, 97.16618435358425643 ) ) ; -#23058 = ORIENTED_EDGE ( 'NONE', *, *, #37153, .T. ) ; -#23059 = AXIS2_PLACEMENT_3D ( 'NONE', #2566, #30577, #24657 ) ; -#23060 = CARTESIAN_POINT ( 'NONE', ( -3.589080270976114040, 149.3464402625973548, 130.0539584792211940 ) ) ; -#23061 = VECTOR ( 'NONE', #7669, 1000.000000000000114 ) ; -#23062 = ORIENTED_EDGE ( 'NONE', *, *, #29580, .F. ) ; -#23063 = CARTESIAN_POINT ( 'NONE', ( 22.34487381648171933, 115.6781641173579374, 87.75408369845331435 ) ) ; -#23064 = CARTESIAN_POINT ( 'NONE', ( 46.36186659599525228, 124.8321406060005216, 91.18150140577510854 ) ) ; -#23065 = ADVANCED_FACE ( 'NONE', ( #2884 ), #40293, .F. ) ; -#23066 = CARTESIAN_POINT ( 'NONE', ( -25.49061850948251262, 191.6070706629876668, 105.4250562708838004 ) ) ; -#23067 = CARTESIAN_POINT ( 'NONE', ( 36.06505478249000163, 192.7057421003999877, 106.3400883135000043 ) ) ; -#23068 = CARTESIAN_POINT ( 'NONE', ( -39.68966533330124946, 159.7604222978274322, 205.3090076836404876 ) ) ; -#23069 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26081, #6844, #2097, #5131, #22612, #25692 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.0006561535229017134967, 0.001312307045803426993 ), - .UNSPECIFIED. ) ; -#23070 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672435848, 137.9484336565874116, 94.05843294792771303 ) ) ; -#23071 = CARTESIAN_POINT ( 'NONE', ( 13.50718655633492382, 188.3455032986072979, 103.1278069412195748 ) ) ; -#23072 = VERTEX_POINT ( 'NONE', #18602 ) ; -#23073 = CARTESIAN_POINT ( 'NONE', ( -2.954012872169000214, 209.1419319052000105, 76.14255845111000554 ) ) ; -#23074 = ADVANCED_FACE ( 'NONE', ( #12486 ), #2735, .T. ) ; -#23075 = CARTESIAN_POINT ( 'NONE', ( -16.40936930839530916, 122.6519308020210985, 174.4724684896352187 ) ) ; -#23076 = CARTESIAN_POINT ( 'NONE', ( 4.035676232316198764, 143.6517845923164600, 95.38087260498555509 ) ) ; -#23077 = ORIENTED_EDGE ( 'NONE', *, *, #21233, .T. ) ; -#23078 = LINE ( 'NONE', #28808, #6249 ) ; -#23079 = CARTESIAN_POINT ( 'NONE', ( 25.50040748627628773, 118.8155663766999481, 89.75240507814876878 ) ) ; -#23080 = EDGE_CURVE ( 'NONE', #6360, #6247, #24987, .T. ) ; -#23081 = ORIENTED_EDGE ( 'NONE', *, *, #40041, .F. ) ; -#23082 = ADVANCED_FACE ( 'NONE', ( #10445 ), #7151, .F. ) ; -#23083 = EDGE_CURVE ( 'NONE', #20264, #8681, #2091, .T. ) ; -#23084 = CARTESIAN_POINT ( 'NONE', ( -38.54565956053704667, 119.1564759897554211, 90.30561907418552892 ) ) ; -#23085 = CARTESIAN_POINT ( 'NONE', ( 23.39706652104787565, 115.1133789070304090, 87.25365305013352213 ) ) ; -#23086 = ORIENTED_EDGE ( 'NONE', *, *, #26544, .F. ) ; -#23087 = CARTESIAN_POINT ( 'NONE', ( 36.25669640222992030, 191.9251549171964655, 106.3935000725031728 ) ) ; -#23088 = VECTOR ( 'NONE', #6054, 1000.000000000000000 ) ; -#23089 = CARTESIAN_POINT ( 'NONE', ( -37.20408499833268223, 118.8543451041053629, 123.0175147492476100 ) ) ; -#23090 = VECTOR ( 'NONE', #26860, 1000.000000000000227 ) ; -#23091 = CARTESIAN_POINT ( 'NONE', ( -19.40198027091592081, 124.9165765156423760, 177.8474014814652264 ) ) ; -#23092 = CARTESIAN_POINT ( 'NONE', ( -36.06983547239383370, 77.73424611234590031, 291.5803292120234573 ) ) ; -#23093 = EDGE_LOOP ( 'NONE', ( #26696, #3112, #7837, #39360 ) ) ; -#23094 = CARTESIAN_POINT ( 'NONE', ( 15.94070853784563013, 152.8278484770639523, 181.6213642978358109 ) ) ; -#23095 = VECTOR ( 'NONE', #9554, 1000.000000000000114 ) ; -#23096 = CARTESIAN_POINT ( 'NONE', ( -30.07125580757959682, 177.2369646589789056, 101.0604468351817928 ) ) ; -#23097 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927789794472, 0.0005734119022071577400 ) ) ; -#23098 = CARTESIAN_POINT ( 'NONE', ( -20.51815631801374096, 205.9571214413596181, 75.54984696095283425 ) ) ; -#23099 = ORIENTED_EDGE ( 'NONE', *, *, #18103, .F. ) ; -#23100 = DIRECTION ( 'NONE', ( 0.0005884949961259727845, -0.2249510543439064703, 0.9743698870671262391 ) ) ; -#23101 = CARTESIAN_POINT ( 'NONE', ( 37.88844529860523380, 117.7436133799949403, 89.67204850642481517 ) ) ; -#23102 = CARTESIAN_POINT ( 'NONE', ( 32.37225758321823577, 137.6347993665977185, 94.48777941942033465 ) ) ; -#23103 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13928, #10061, #26012, #16776 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23104 = DIRECTION ( 'NONE', ( -0.0006039748319344481579, 1.110223022795018804E-14, -0.9999998176071845934 ) ) ; -#23105 = CARTESIAN_POINT ( 'NONE', ( 20.00171108015191024, 119.7153632178993377, 90.35824133875276232 ) ) ; -#23106 = CARTESIAN_POINT ( 'NONE', ( -3.535970564801350857, 118.9425530769304515, 90.19402121340442591 ) ) ; -#23107 = DIRECTION ( 'NONE', ( -0.7933535594326887042, 0.5932204071694016090, 0.1366736194488628042 ) ) ; -#23108 = CARTESIAN_POINT ( 'NONE', ( 38.13650326794999756, 118.9089952261000036, 90.39651201712000272 ) ) ; -#23109 = CIRCLE ( 'NONE', #33546, 5.500000000058693495 ) ; -#23110 = ORIENTED_EDGE ( 'NONE', *, *, #4929, .T. ) ; -#23111 = EDGE_CURVE ( 'NONE', #11548, #22377, #26254, .T. ) ; -#23112 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#23113 = EDGE_CURVE ( 'NONE', #25308, #32551, #817, .T. ) ; -#23114 = LINE ( 'NONE', #38432, #27430 ) ; -#23115 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24790, #15175, #15368, #33557 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23116 = CARTESIAN_POINT ( 'NONE', ( -16.11981483100024448, 123.6845644636535582, 173.7931095965155635 ) ) ; -#23117 = ADVANCED_FACE ( 'NONE', ( #29038 ), #1634, .F. ) ; -#23118 = AXIS2_PLACEMENT_3D ( 'NONE', #13306, #16355, #3683 ) ; -#23120 = ORIENTED_EDGE ( 'NONE', *, *, #20051, .T. ) ; -#23119 = CARTESIAN_POINT ( 'NONE', ( -13.46215051151162889, 153.7291600434821532, 98.23113887026609348 ) ) ; -#23121 = ORIENTED_EDGE ( 'NONE', *, *, #4499, .F. ) ; -#23122 = EDGE_CURVE ( 'NONE', #20440, #31162, #14725, .T. ) ; -#23123 = EDGE_LOOP ( 'NONE', ( #32960, #32955, #25274, #14447 ) ) ; -#23124 = CARTESIAN_POINT ( 'NONE', ( -26.00789644338852469, 208.0210118655040787, 76.93397401140359193 ) ) ; -#23125 = EDGE_CURVE ( 'NONE', #20950, #29253, #21469, .T. ) ; -#23126 = DIRECTION ( 'NONE', ( 0.0005884949961251158311, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#23127 = VERTEX_POINT ( 'NONE', #37781 ) ; -#23128 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825857840055654, 0.0005734119038270033821 ) ) ; -#23129 = ADVANCED_FACE ( 'NONE', ( #3033 ), #9792, .T. ) ; -#23130 = CARTESIAN_POINT ( 'NONE', ( -20.45366101552173532, 211.0901972962080322, 75.63591788811629613 ) ) ; -#23131 = CARTESIAN_POINT ( 'NONE', ( -38.09076243749999691, 119.2798029714000023, 87.30615167818000089 ) ) ; -#23132 = FACE_OUTER_BOUND ( 'NONE', #3519, .T. ) ; -#23133 = VERTEX_POINT ( 'NONE', #34303 ) ; -#23134 = CARTESIAN_POINT ( 'NONE', ( 19.54487014920338339, 148.9873530275860958, 183.1261089886357638 ) ) ; -#23135 = DIRECTION ( 'NONE', ( 0.0005884949961260158274, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#23136 = DIRECTION ( 'NONE', ( 0.0006039748319392047697, 1.154386647790520729E-15, 0.9999998176071845934 ) ) ; -#23137 = CARTESIAN_POINT ( 'NONE', ( 39.01778814463001055, 209.7096538831000032, 28.07991271570000080 ) ) ; -#23138 = VECTOR ( 'NONE', #35951, 1000.000000000000227 ) ; -#23139 = ADVANCED_FACE ( 'NONE', ( #18968 ), #6298, .T. ) ; -#23140 = ORIENTED_EDGE ( 'NONE', *, *, #23260, .T. ) ; -#23141 = CARTESIAN_POINT ( 'NONE', ( -1.852762058314000093, 189.5547784236999860, 103.8460018853999998 ) ) ; -#23142 = PLANE ( 'NONE', #9456 ) ; -#23143 = VECTOR ( 'NONE', #17542, 1000.000000000000114 ) ; -#23144 = AXIS2_PLACEMENT_3D ( 'NONE', #11218, #23692, #4860 ) ; -#23145 = CARTESIAN_POINT ( 'NONE', ( -5.668107859749786925, 185.2316718754979377, 105.5024628770674866 ) ) ; -#23146 = CIRCLE ( 'NONE', #39441, 1.650000000000002798 ) ; -#23147 = VERTEX_POINT ( 'NONE', #40239 ) ; -#23148 = CARTESIAN_POINT ( 'NONE', ( -40.55516615315095663, 184.2569486434040869, 105.2953989892096445 ) ) ; -#23149 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319417801836 ) ) ; -#23150 = VERTEX_POINT ( 'NONE', #28204 ) ; -#23151 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #22808, #32209, #4165, #16643 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.6245186104307177688, 0.8013624142894875124 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973955533075615776, 0.9973955533075615776, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#23152 = ORIENTED_EDGE ( 'NONE', *, *, #2682, .F. ) ; -#23153 = VERTEX_POINT ( 'NONE', #9584 ) ; -#23154 = CARTESIAN_POINT ( 'NONE', ( 39.81119971704559646, 75.02554102933939362, 323.6757538848392528 ) ) ; -#23155 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048996748, 130.3419545077892678, 92.84535593381433216 ) ) ; -#23156 = ORIENTED_EDGE ( 'NONE', *, *, #9047, .F. ) ; -#23157 = DIRECTION ( 'NONE', ( -0.0005884949961212082581, 0.2249510543439042498, -0.9743698870671267942 ) ) ; -#23158 = VERTEX_POINT ( 'NONE', #22064 ) ; -#23159 = CARTESIAN_POINT ( 'NONE', ( 26.01546616514680466, 120.4365795122199927, 90.52613441020730534 ) ) ; -#23160 = ADVANCED_FACE ( 'NONE', ( #24742 ), #34706, .F. ) ; -#23161 = CARTESIAN_POINT ( 'NONE', ( 77.76841782105992706, 192.2294772166672772, 194.3560228188070766 ) ) ; -#23162 = EDGE_CURVE ( 'NONE', #3220, #6135, #860, .T. ) ; -#23163 = EDGE_CURVE ( 'NONE', #28309, #35551, #24311, .T. ) ; -#23165 = DIRECTION ( 'NONE', ( -0.5989082241854613020, 0.8008175873178838833, 0.0003617255600147346959 ) ) ; -#23164 = FACE_OUTER_BOUND ( 'NONE', #5215, .T. ) ; -#23166 = ORGANIZATION ( '未', '未', '' ) ; -#23167 = CARTESIAN_POINT ( 'NONE', ( 76.10777906859902942, 155.6827192487123455, 98.62805563715404844 ) ) ; -#23168 = VECTOR ( 'NONE', #31452, 1000.000000000000227 ) ; -#23169 = CONICAL_SURFACE ( 'NONE', #34871, 2.499987184277071339, 0.7853981634084753471 ) ; -#23170 = VERTEX_POINT ( 'NONE', #13651 ) ; -#23171 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971567345 ) ) ; -#23172 = EDGE_CURVE ( 'NONE', #19831, #8063, #24794, .T. ) ; -#23173 = LINE ( 'NONE', #7617, #16856 ) ; -#23174 = ORIENTED_EDGE ( 'NONE', *, *, #18399, .T. ) ; -#23175 = DIRECTION ( 'NONE', ( 0.0004161288024526961808, 0.5299192578740949955, 0.8480479980348919478 ) ) ; -#23176 = EDGE_CURVE ( 'NONE', #16772, #25128, #33951, .T. ) ; -#23177 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923101038, 127.7447309815698873, 89.13696229017300254 ) ) ; -#23178 = CARTESIAN_POINT ( 'NONE', ( -45.37018052505393939, 124.2011127489164153, 91.76099384493524269 ) ) ; -#23179 = CARTESIAN_POINT ( 'NONE', ( 3.534232527368997623, 141.9351730801645033, 92.41913181349261208 ) ) ; -#23180 = EDGE_LOOP ( 'NONE', ( #22731, #33258, #29216, #36451 ) ) ; -#23181 = VERTEX_POINT ( 'NONE', #28792 ) ; -#23182 = CYLINDRICAL_SURFACE ( 'NONE', #20013, 2.000000000000001332 ) ; -#23183 = VERTEX_POINT ( 'NONE', #38579 ) ; -#23184 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #16162, #819, #29246, #32506 ), - ( #25986, #16944, #19618, #28640 ), - ( #23108, #615, #22317, #28840 ), - ( #19211, #13303, #35341, #3680 ), - ( #31721, #4071, #4481, #13106 ), - ( #16543, #29445, #25591, #29040 ), - ( #1016, #38033, #19421, #31920 ), - ( #7551, #3878, #16352, #26190 ), - ( #4278, #25789, #38236, #10447 ), - ( #35534, #7346, #10247, #19807 ), - ( #16752, #1218, #13700, #38628 ), - ( #8385, #23714, #29854, #36169 ), - ( #35952, #38823, #30462, #30248 ), - ( #14314, #20843, #7962, #36586 ), - ( #17554, #7750, #30058, #11441 ), - ( #39431, #2457, #5298, #5088 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.001700366337021999965, 0.000000000000000000, 0.005170675847449000308, 0.01037958123234999919, 0.02079739200211999997, 0.04163301354170000079, 0.06246863508127999814, 0.08330425662085999550, 0.1249754996999000028, 0.1666467427790999933, 0.3333317150958000075, 0.6666652572568999569, 1.000000000000000000, 1.177776354664000102 ), - ( -0.2624929596591999981, 1.257088294254000038 ), - .UNSPECIFIED. ) ; -#23185 = CYLINDRICAL_SURFACE ( 'NONE', #33693, 2.000000000000001332 ) ; -#23186 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27238, #10655, #36726, #36107, #5443, #20578, #33046, #8325, #15069, #1992 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23187 = EDGE_LOOP ( 'NONE', ( #17764, #29911, #37086, #2062, #11202, #40221, #30269 ) ) ; -#23188 = CARTESIAN_POINT ( 'NONE', ( -28.94629671773198965, 110.6131156702000027, 90.28526767713175616 ) ) ; -#23189 = CARTESIAN_POINT ( 'NONE', ( 3.081029741328818794, 190.8867177225405669, 106.8190053092809819 ) ) ; -#23190 = VERTEX_POINT ( 'NONE', #26141 ) ; -#23191 = LINE ( 'NONE', #35622, #27566 ) ; -#23192 = AXIS2_PLACEMENT_3D ( 'NONE', #26030, #34588, #13158 ) ; -#23193 = AXIS2_PLACEMENT_3D ( 'NONE', #9979, #16096, #22452 ) ; -#23194 = CARTESIAN_POINT ( 'NONE', ( -41.39426888469423460, 120.3350051359701638, 90.19625819200398098 ) ) ; -#23195 = CARTESIAN_POINT ( 'NONE', ( 43.23122282123772919, 179.1331515733938886, 148.2643789950020619 ) ) ; -#23196 = EDGE_LOOP ( 'NONE', ( #10813, #8369, #15787, #29732 ) ) ; -#23197 = AXIS2_PLACEMENT_3D ( 'NONE', #37209, #24548, #6505 ) ; -#23198 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#23199 = CARTESIAN_POINT ( 'NONE', ( -3.668404232393724929, 183.5617789225002809, 104.5994755552988096 ) ) ; -#23200 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425197144, 137.5181437524809667, 94.48855197221574542 ) ) ; -#23201 = ORIENTED_EDGE ( 'NONE', *, *, #10574, .T. ) ; -#23202 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825928107556782, 0.0005734119021999202568 ) ) ; -#23203 = EDGE_CURVE ( 'NONE', #14712, #22688, #1369, .T. ) ; -#23204 = EDGE_CURVE ( 'NONE', #33391, #28841, #36716, .T. ) ; -#23206 = CARTESIAN_POINT ( 'NONE', ( -38.08615123650999834, 118.2522031968999983, 89.85284521143999825 ) ) ; -#23205 = CARTESIAN_POINT ( 'NONE', ( -15.49970618492638508, 127.6313525092815411, 89.64145404642985682 ) ) ; -#23207 = ORIENTED_EDGE ( 'NONE', *, *, #1928, .F. ) ; -#23208 = CARTESIAN_POINT ( 'NONE', ( 31.79421365038999880, 226.4002260771000010, 73.53930126516999621 ) ) ; -#23209 = CARTESIAN_POINT ( 'NONE', ( 38.57409235987329055, 118.4658207127237688, 89.66260175151403189 ) ) ; -#23210 = VERTEX_POINT ( 'NONE', #10997 ) ; -#23211 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825852464688619, 0.0005734119039458779104 ) ) ; -#23212 = CARTESIAN_POINT ( 'NONE', ( 46.08267618988084280, 184.7865884867546242, 107.4179575081553253 ) ) ; -#23213 = CARTESIAN_POINT ( 'NONE', ( 45.33187901993595403, 106.2369563754977122, 169.3368253429517836 ) ) ; -#23214 = PLANE ( 'NONE', #8011 ) ; -#23215 = CARTESIAN_POINT ( 'NONE', ( 3.168112933839599688, 185.2356858264948301, 105.4949491227606870 ) ) ; -#23216 = ORIENTED_EDGE ( 'NONE', *, *, #36784, .T. ) ; -#23217 = CIRCLE ( 'NONE', #38874, 6.000000000000007994 ) ; -#23218 = VERTEX_POINT ( 'NONE', #2404 ) ; -#23219 = CARTESIAN_POINT ( 'NONE', ( -42.72426501338485849, 120.8886262355579220, 91.39497110141761027 ) ) ; -#23220 = ORIENTED_EDGE ( 'NONE', *, *, #8420, .F. ) ; -#23221 = VERTEX_POINT ( 'NONE', #36534 ) ; -#23222 = CARTESIAN_POINT ( 'NONE', ( -8.048542123008331828, 160.5967930229313367, 99.81338747665230926 ) ) ; -#23223 = VECTOR ( 'NONE', #19015, 1000.000000000000114 ) ; -#23224 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510153906202348, 0.9743700737782995391 ) ) ; -#23225 = AXIS2_PLACEMENT_3D ( 'NONE', #32891, #33288, #33495 ) ; -#23226 = AXIS2_PLACEMENT_3D ( 'NONE', #12608, #31640, #25512 ) ; -#23227 = ORIENTED_EDGE ( 'NONE', *, *, #17729, .F. ) ; -#23228 = CARTESIAN_POINT ( 'NONE', ( 25.50040748627628773, 118.8155663766999481, 89.75240507814876878 ) ) ; -#23229 = CARTESIAN_POINT ( 'NONE', ( -2.480274637552000172, 211.0000000000000000, 32.65999473746001058 ) ) ; -#23230 = CARTESIAN_POINT ( 'NONE', ( 44.87323697063200001, 186.3386389082236860, 107.7764265916358113 ) ) ; -#23231 = CARTESIAN_POINT ( 'NONE', ( 19.99963753331764593, 193.2798873410197871, 103.4435829895760577 ) ) ; -#23232 = ORIENTED_EDGE ( 'NONE', *, *, #5904, .F. ) ; -#23233 = DIRECTION ( 'NONE', ( 0.0005884949961270922233, -0.2249510543439054433, 0.9743698870671265722 ) ) ; -#23234 = CARTESIAN_POINT ( 'NONE', ( -23.36030038340052428, 176.7386739072689181, 103.0361307674479150 ) ) ; -#23235 = ORIENTED_EDGE ( 'NONE', *, *, #25080, .F. ) ; -#23236 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 77.27946979429631824, 312.5857197240631535 ) ) ; -#23237 = CARTESIAN_POINT ( 'NONE', ( 14.29930377595062652, 176.1145857943713793, 103.0403539068457235 ) ) ; -#23238 = FACE_OUTER_BOUND ( 'NONE', #33314, .T. ) ; -#23239 = CARTESIAN_POINT ( 'NONE', ( 36.04796026496615724, 209.7096538831000032, 78.03673292965207509 ) ) ; -#23240 = VERTEX_POINT ( 'NONE', #35906 ) ; -#23241 = CARTESIAN_POINT ( 'NONE', ( -22.99592550276514658, 134.9153278805555090, 90.81446795239106962 ) ) ; -#23242 = DIRECTION ( 'NONE', ( -0.1305262304084799929, 0.9659442311576372786, 0.2234158576928528539 ) ) ; -#23243 = CARTESIAN_POINT ( 'NONE', ( 31.32891649726831673, 135.2306215998971481, 90.85444841302377483 ) ) ; -#23244 = EDGE_CURVE ( 'NONE', #24812, #13325, #21003, .T. ) ; -#23245 = CARTESIAN_POINT ( 'NONE', ( 23.68470177377144381, 137.2456318144843976, 91.83741932284023335 ) ) ; -#23246 = CARTESIAN_POINT ( 'NONE', ( -25.63353067346999836, 191.3682931014000133, 104.2390837140000031 ) ) ; -#23247 = AXIS2_PLACEMENT_3D ( 'NONE', #6455, #2613, #18515 ) ; -#23248 = CARTESIAN_POINT ( 'NONE', ( 19.70863784699480448, 149.1560517737245561, 182.9541186021026817 ) ) ; -#23249 = CIRCLE ( 'NONE', #5584, 2.000000003652215419 ) ; -#23250 = CARTESIAN_POINT ( 'NONE', ( 25.67500669693000503, 191.2493216073000042, 104.1755163559000010 ) ) ; -#23251 = LINE ( 'NONE', #14258, #17047 ) ; -#23252 = CARTESIAN_POINT ( 'NONE', ( -28.46728868143000213, 182.0597503762595579, 102.2150741956516384 ) ) ; -#23253 = ORIENTED_EDGE ( 'NONE', *, *, #17357, .F. ) ; -#23254 = CONICAL_SURFACE ( 'NONE', #2988, 6.500001087336274352, 0.7853982191638021471 ) ; -#23255 = EDGE_CURVE ( 'NONE', #1872, #10112, #4641, .T. ) ; -#23256 = ADVANCED_FACE ( 'NONE', ( #20377 ), #27368, .T. ) ; -#23257 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178587041921E-05, 0.0002331579774917524482 ) ) ; -#23258 = DIRECTION ( 'NONE', ( -0.1305262373691799260, -0.9659798014921964215, -0.2232620085624539286 ) ) ; -#23259 = CARTESIAN_POINT ( 'NONE', ( 19.98483764167631094, 211.0849390754169974, 73.04592155476974824 ) ) ; -#23260 = EDGE_CURVE ( 'NONE', #30446, #21872, #24290, .T. ) ; -#23261 = FACE_OUTER_BOUND ( 'NONE', #24205, .T. ) ; -#23262 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#23263 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1988, #11996, #2787, #11377 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23264 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971530430 ) ) ; -#23265 = CARTESIAN_POINT ( 'NONE', ( 22.81058210632548366, 115.1133384263758472, 90.25400781920090765 ) ) ; -#23266 = ORIENTED_EDGE ( 'NONE', *, *, #24197, .F. ) ; -#23267 = ORIENTED_EDGE ( 'NONE', *, *, #31288, .F. ) ; -#23268 = CARTESIAN_POINT ( 'NONE', ( 25.49921019565536184, 118.1133140256443426, 87.75227232668940758 ) ) ; -#23269 = DIRECTION ( 'NONE', ( -0.1706442583057901363, -1.252691005673331975E-14, -0.9853327037641991248 ) ) ; -#23270 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596097999, 128.5887768395806177, 89.32567453967637050 ) ) ; -#23271 = FACE_OUTER_BOUND ( 'NONE', #35863, .T. ) ; -#23272 = CIRCLE ( 'NONE', #16744, 4.500000000010161649 ) ; -#23273 = ORIENTED_EDGE ( 'NONE', *, *, #20085, .F. ) ; -#23274 = CARTESIAN_POINT ( 'NONE', ( 6.035686183114718162, 177.4040666397187067, 100.9383125970363864 ) ) ; -#23275 = CARTESIAN_POINT ( 'NONE', ( 3.535839194698592980, 136.6870853775678825, 94.28644726325400427 ) ) ; -#23276 = VECTOR ( 'NONE', #14837, 1000.000000000000114 ) ; -#23277 = EDGE_LOOP ( 'NONE', ( #36277, #2341, #26409, #1190 ) ) ; -#23278 = VECTOR ( 'NONE', #12801, 1000.000000000000000 ) ; -#23279 = CARTESIAN_POINT ( 'NONE', ( 25.99332526491797069, 209.7096538831000032, 78.04280567724204332 ) ) ; -#23280 = VERTEX_POINT ( 'NONE', #12209 ) ; -#23281 = CYLINDRICAL_SURFACE ( 'NONE', #1387, 2.000000000000014655 ) ; -#23282 = VECTOR ( 'NONE', #29483, 999.9999999999998863 ) ; -#23283 = CARTESIAN_POINT ( 'NONE', ( -5.668109638568584074, 127.9100376797824907, 92.26561629879442705 ) ) ; -#23284 = CARTESIAN_POINT ( 'NONE', ( -13.49823340920320724, 160.0628909777703655, 99.69670533858855777 ) ) ; -#23285 = DIRECTION ( 'NONE', ( -0.0005884949961232824453, 0.2249510543439075805, -0.9743698870671260170 ) ) ; -#23286 = AXIS2_PLACEMENT_3D ( 'NONE', #13489, #20000, #38416 ) ; -#23287 = CYLINDRICAL_SURFACE ( 'NONE', #21561, 2.000000000000011546 ) ; -#23288 = CARTESIAN_POINT ( 'NONE', ( -25.49994355703909932, 120.2054709989172778, 89.98570258340846806 ) ) ; -#23289 = ORIENTED_EDGE ( 'NONE', *, *, #26264, .F. ) ; -#23290 = ORIENTED_EDGE ( 'NONE', *, *, #23083, .F. ) ; -#23291 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971546806 ) ) ; -#23292 = CARTESIAN_POINT ( 'NONE', ( -30.07072815488413653, 177.4736756012406431, 100.9125331478477676 ) ) ; -#23293 = CARTESIAN_POINT ( 'NONE', ( 28.34940426444671147, 125.4854830354149300, 88.94851520771482001 ) ) ; -#23294 = ADVANCED_FACE ( 'NONE', ( #30616 ), #8659, .F. ) ; -#23295 = CARTESIAN_POINT ( 'NONE', ( -13.46391575659845685, 154.4039982810205629, 95.30803284751881677 ) ) ; -#23296 = EDGE_LOOP ( 'NONE', ( #21453, #164, #39762, #8365 ) ) ; -#23297 = CARTESIAN_POINT ( 'NONE', ( 30.06878009202964463, 135.2977368468020813, 91.38385643107594092 ) ) ; -#23298 = CARTESIAN_POINT ( 'NONE', ( -20.49970531958900821, 174.4001369415014437, 100.4419005551936834 ) ) ; -#23299 = CARTESIAN_POINT ( 'NONE', ( 37.71311666782268190, 212.3970731212147598, 75.53572676091057758 ) ) ; -#23300 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#23301 = EDGE_CURVE ( 'NONE', #5782, #15583, #30568, .T. ) ; -#23302 = CARTESIAN_POINT ( 'NONE', ( -20.49970532896238495, 138.0793279496801631, 92.05657955325195019 ) ) ; -#23303 = CARTESIAN_POINT ( 'NONE', ( -21.21320613303312541, 183.0566203626299284, 103.8092442496014485 ) ) ; -#23304 = CARTESIAN_POINT ( 'NONE', ( 5.696483686681999892, 174.3879284816999871, 152.4718672074000381 ) ) ; -#23305 = EDGE_CURVE ( 'NONE', #20475, #23972, #36426, .T. ) ; -#23306 = CIRCLE ( 'NONE', #30505, 16.50000000000598277 ) ; -#23307 = EDGE_CURVE ( 'NONE', #32767, #133, #13860, .T. ) ; -#23308 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15685, #2432, #21231, #3009, #24516, #21032, #39818, #15496, #11834, #27784 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.002297953239941401965, 0.2517230612339881879, 0.5011481692280349565, 0.7505732772220816695, 0.9999983852161284936 ), - .UNSPECIFIED. ) ; -#23309 = DIRECTION ( 'NONE', ( 0.0006039748319377573598, 1.390293078070570268E-14, 0.9999998176071845934 ) ) ; -#23310 = AXIS2_PLACEMENT_3D ( 'NONE', #28395, #12856, #25335 ) ; -#23311 = EDGE_CURVE ( 'NONE', #15935, #12175, #37871, .T. ) ; -#23312 = CARTESIAN_POINT ( 'NONE', ( 26.14898090114000340, 191.6041293664000023, 107.0269310404000151 ) ) ; -#23313 = EDGE_CURVE ( 'NONE', #25599, #14004, #9538, .T. ) ; -#23314 = LINE ( 'NONE', #7961, #38779 ) ; -#23315 = CARTESIAN_POINT ( 'NONE', ( 26.45759199812077611, 122.9297683075388079, 88.01751430407519194 ) ) ; -#23316 = ORIENTED_EDGE ( 'NONE', *, *, #23872, .T. ) ; -#23317 = VECTOR ( 'NONE', #7015, 1000.000000000000114 ) ; -#23318 = DIRECTION ( 'NONE', ( 7.677760455955688654E-18, -1.000000000000000000, 1.271205131337280331E-14 ) ) ; -#23319 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7071067167009886800, 0.7071068456721004702 ) ) ; -#23320 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29536, #23403, #20318, #4576 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.003244958643172611134 ), - .UNSPECIFIED. ) ; -#23321 = CARTESIAN_POINT ( 'NONE', ( -21.10693792752578801, 183.2696801607907844, 102.3189169904713509 ) ) ; -#23322 = CARTESIAN_POINT ( 'NONE', ( -28.47139460624499208, 181.8099728549552481, 101.8153497139206962 ) ) ; -#23324 = ORIENTED_EDGE ( 'NONE', *, *, #22510, .F. ) ; -#23323 = DIRECTION ( 'NONE', ( -0.7066795771589046149, 3.237673907669277066E-09, 0.7075337272713659864 ) ) ; -#23325 = VERTEX_POINT ( 'NONE', #38148 ) ; -#23326 = ORIENTED_EDGE ( 'NONE', *, *, #19543, .F. ) ; -#23327 = ORIENTED_EDGE ( 'NONE', *, *, #25414, .F. ) ; -#23328 = CYLINDRICAL_SURFACE ( 'NONE', #23530, 6.000000000000001776 ) ; -#23329 = CARTESIAN_POINT ( 'NONE', ( -21.21399091017794802, 175.8930158889867528, 100.7869902896899816 ) ) ; -#23330 = ORIENTED_EDGE ( 'NONE', *, *, #36386, .T. ) ; -#23331 = FACE_BOUND ( 'NONE', #34421, .T. ) ; -#23332 = EDGE_CURVE ( 'NONE', #8868, #25286, #35046, .T. ) ; -#23333 = CARTESIAN_POINT ( 'NONE', ( -38.64958770352021844, 161.8984352577749348, 192.4743989663406012 ) ) ; -#23334 = CARTESIAN_POINT ( 'NONE', ( -24.42595486541198824, 109.6131156702000027, 90.28253750392424593 ) ) ; -#23335 = DIRECTION ( 'NONE', ( -0.0002393071182782278061, -0.2252352986010052738, 0.9743043687658489160 ) ) ; -#23336 = CARTESIAN_POINT ( 'NONE', ( -36.18523557502999921, 114.4326857091000136, 87.90963942732001613 ) ) ; -#23337 = ORIENTED_EDGE ( 'NONE', *, *, #34942, .F. ) ; -#23338 = CARTESIAN_POINT ( 'NONE', ( 17.92694799460988975, 127.4246020651061997, 177.6516979807273628 ) ) ; -#23339 = CONICAL_SURFACE ( 'NONE', #3096, 5.003076031389202427, 0.7853570728742632623 ) ; -#23340 = CARTESIAN_POINT ( 'NONE', ( 16.56083148683698170, 121.8447191377824907, 177.5628756867482423 ) ) ; -#23341 = CARTESIAN_POINT ( 'NONE', ( 38.29593043761780535, 218.5902260770999987, 76.03537484717311656 ) ) ; -#23342 = CARTESIAN_POINT ( 'NONE', ( -25.98973257537553749, 191.3166157958662836, 106.8934875062374203 ) ) ; -#23343 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561239 ) ) ; -#23344 = CARTESIAN_POINT ( 'NONE', ( -5.668109638568660458, 185.2323518255123815, 105.4995176905214294 ) ) ; -#23345 = ORIENTED_EDGE ( 'NONE', *, *, #2888, .F. ) ; -#23346 = VERTEX_POINT ( 'NONE', #29350 ) ; -#23347 = CARTESIAN_POINT ( 'NONE', ( -2.325334792972999942, 189.9234775223999918, 103.8041889634999961 ) ) ; -#23348 = CARTESIAN_POINT ( 'NONE', ( 22.50176470574469079, 160.0679787287287752, 99.67284943499184635 ) ) ; -#23349 = CARTESIAN_POINT ( 'NONE', ( 28.47525309053320797, 130.3504702658399879, 92.80840815248680542 ) ) ; -#23350 = CARTESIAN_POINT ( 'NONE', ( 26.00081424259415641, 120.1020648120652510, 90.44388058125247198 ) ) ; -#23351 = EDGE_CURVE ( 'NONE', #34249, #26229, #28868, .T. ) ; -#23352 = ORIENTED_EDGE ( 'NONE', *, *, #16427, .T. ) ; -#23353 = VERTEX_POINT ( 'NONE', #22819 ) ; -#23354 = CARTESIAN_POINT ( 'NONE', ( -2.448596876244000242, 209.1869211169000096, 75.60179039185000249 ) ) ; -#23355 = DIRECTION ( 'NONE', ( 1.249000902710531491E-14, -1.000000000000000000, 0.000000000000000000 ) ) ; -#23356 = ORIENTED_EDGE ( 'NONE', *, *, #34317, .T. ) ; -#23357 = ORIENTED_EDGE ( 'NONE', *, *, #39821, .F. ) ; -#23358 = EDGE_CURVE ( 'NONE', #32563, #24177, #4175, .T. ) ; -#23359 = ADVANCED_FACE ( 'NONE', ( #31619 ), #16062, .F. ) ; -#23360 = ORIENTED_EDGE ( 'NONE', *, *, #7098, .F. ) ; -#23361 = EDGE_LOOP ( 'NONE', ( #34712, #40279, #9476, #26234 ) ) ; -#23362 = CARTESIAN_POINT ( 'NONE', ( -28.16705420941000071, 186.9743051542000103, 105.9152683551999985 ) ) ; -#23363 = CARTESIAN_POINT ( 'NONE', ( -6.037441369385896373, 137.2416971194969335, 91.85446235641137491 ) ) ; -#23364 = EDGE_CURVE ( 'NONE', #315, #27892, #36061, .T. ) ; -#23365 = EDGE_LOOP ( 'NONE', ( #18191, #26575, #36629, #8451 ) ) ; -#23366 = CARTESIAN_POINT ( 'NONE', ( -5.670680073181483039, 181.8822695513912322, 101.9131439626678883 ) ) ; -#23367 = ORIENTED_EDGE ( 'NONE', *, *, #5666, .T. ) ; -#23368 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19764, #10794, #26144, #25943 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.01233348531029615849, 0.01329655828663948471 ), - .UNSPECIFIED. ) ; -#23369 = CARTESIAN_POINT ( 'NONE', ( 26.00143615033000088, 120.1794630026000021, 90.46342538870999306 ) ) ; -#23370 = AXIS2_PLACEMENT_3D ( 'NONE', #5267, #23285, #26364 ) ; -#23371 = CARTESIAN_POINT ( 'NONE', ( 30.05202369937001805, 184.7526529595380964, 104.8540442476633956 ) ) ; -#23372 = VECTOR ( 'NONE', #27667, 1000.000000000000227 ) ; -#23374 = FACE_OUTER_BOUND ( 'NONE', #17239, .T. ) ; -#23373 = CARTESIAN_POINT ( 'NONE', ( 25.49182901039327831, 209.7089661076149127, 75.54314178666862745 ) ) ; -#23375 = VERTEX_POINT ( 'NONE', #17244 ) ; -#23376 = VERTEX_POINT ( 'NONE', #39140 ) ; -#23377 = CARTESIAN_POINT ( 'NONE', ( -36.14255531305040137, 191.9341410994068156, 104.4181006106035738 ) ) ; -#23378 = VERTEX_POINT ( 'NONE', #35850 ) ; -#23379 = CARTESIAN_POINT ( 'NONE', ( -36.63447688325992857, 117.3726060988748827, 87.28991059808527098 ) ) ; -#23380 = DIRECTION ( 'NONE', ( 0.1632030863883311977, -0.3417424275059330885, 0.9255143790539803739 ) ) ; -#23381 = LINE ( 'NONE', #39100, #9793 ) ; -#23382 = VERTEX_POINT ( 'NONE', #17453 ) ; -#23383 = ORIENTED_EDGE ( 'NONE', *, *, #36111, .T. ) ; -#23384 = LINE ( 'NONE', #35821, #27941 ) ; -#23385 = ORIENTED_EDGE ( 'NONE', *, *, #29539, .F. ) ; -#23386 = CARTESIAN_POINT ( 'NONE', ( -35.46684749371900836, 192.2358989730090286, 106.9510738220610051 ) ) ; -#23387 = EDGE_CURVE ( 'NONE', #21784, #40324, #783, .T. ) ; -#23388 = ADVANCED_FACE ( 'NONE', ( #7857 ), #8064, .F. ) ; -#23389 = CIRCLE ( 'NONE', #14261, 55.00273826250365516 ) ; -#23390 = EDGE_CURVE ( 'NONE', #18545, #4424, #21057, .T. ) ; -#23391 = ORIENTED_EDGE ( 'NONE', *, *, #27586, .T. ) ; -#23392 = ADVANCED_FACE ( 'NONE', ( #20528 ), #2347, .F. ) ; -#23393 = CARTESIAN_POINT ( 'NONE', ( 2.897488417982000186, 190.8910880237999947, 106.6291566765000169 ) ) ; -#23394 = ORIENTED_EDGE ( 'NONE', *, *, #25585, .F. ) ; -#23395 = CARTESIAN_POINT ( 'NONE', ( 39.51558108783103762, 119.2344049514255317, 89.72500211528681291 ) ) ; -#23396 = DIRECTION ( 'NONE', ( 0.0005884949961209496759, -0.2249510543439030841, 0.9743698870671270162 ) ) ; -#23397 = CARTESIAN_POINT ( 'NONE', ( 31.79177573931936962, 115.2378407561303391, 176.5461501322318725 ) ) ; -#23398 = CARTESIAN_POINT ( 'NONE', ( 10.03596943924900486, 143.5399299914239180, 95.86457705213388181 ) ) ; -#23399 = EDGE_CURVE ( 'NONE', #18000, #3485, #17347, .T. ) ; -#23400 = ORIENTED_EDGE ( 'NONE', *, *, #18608, .T. ) ; -#23401 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31327, #13319, #22934, #22537 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23402 = CARTESIAN_POINT ( 'NONE', ( 44.90853464007773965, 181.5172347420035237, 101.5323552624301016 ) ) ; -#23403 = CARTESIAN_POINT ( 'NONE', ( -12.63329150945545365, 131.0198790336825141, 89.90887378819283526 ) ) ; -#23404 = EDGE_CURVE ( 'NONE', #36508, #25569, #11511, .T. ) ; -#23405 = ORIENTED_EDGE ( 'NONE', *, *, #3840, .T. ) ; -#23406 = CARTESIAN_POINT ( 'NONE', ( 33.32721009243029897, 80.97613274184595866, 288.9672004084912373 ) ) ; -#23408 = CARTESIAN_POINT ( 'NONE', ( -36.62475089482000357, 116.6800463140000090, 90.15487809088000404 ) ) ; -#23407 = CARTESIAN_POINT ( 'NONE', ( -40.80866763255103535, 127.3612606829378535, 89.59438440199370746 ) ) ; -#23409 = EDGE_CURVE ( 'NONE', #1228, #32479, #10607, .T. ) ; -#23410 = VECTOR ( 'NONE', #2269, 1000.000000000000000 ) ; -#23411 = EDGE_LOOP ( 'NONE', ( #30888, #1264, #34125, #24004 ) ) ; -#23412 = VERTEX_POINT ( 'NONE', #5602 ) ; -#23413 = CARTESIAN_POINT ( 'NONE', ( 14.70300188629267168, 151.6530204554825048, 27.72645225616384934 ) ) ; -#23414 = CARTESIAN_POINT ( 'NONE', ( 37.28954786541507360, 191.0747319291052975, 106.2969461956769095 ) ) ; -#23415 = AXIS2_PLACEMENT_3D ( 'NONE', #5183, #1937, #36470 ) ; -#23416 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082098698, 139.6633459290210055, 297.5876476292032180 ) ) ; -#23417 = ORIENTED_EDGE ( 'NONE', *, *, #4129, .T. ) ; -#23418 = ORIENTED_EDGE ( 'NONE', *, *, #31125, .F. ) ; -#23419 = FACE_OUTER_BOUND ( 'NONE', #27851, .T. ) ; -#23420 = EDGE_LOOP ( 'NONE', ( #7585, #37284, #40123, #11060, #21936, #8976, #28289, #40063, #30772, #26901, #16979, #38072, #22094 ) ) ; -#23421 = ORIENTED_EDGE ( 'NONE', *, *, #22384, .T. ) ; -#23422 = CARTESIAN_POINT ( 'NONE', ( -13.46973633630999956, 173.3942358358999911, 152.4718672074000381 ) ) ; -#23423 = FACE_OUTER_BOUND ( 'NONE', #27605, .T. ) ; -#23424 = FACE_OUTER_BOUND ( 'NONE', #35187, .T. ) ; -#23425 = ORIENTED_EDGE ( 'NONE', *, *, #21342, .F. ) ; -#23426 = EDGE_LOOP ( 'NONE', ( #13889, #32125, #23597, #1141 ) ) ; -#23427 = CARTESIAN_POINT ( 'NONE', ( 14.31745512424952516, 177.1967911514969956, 100.5533783294099663 ) ) ; -#23428 = CARTESIAN_POINT ( 'NONE', ( 3.062765380279557359, 191.9759150222000130, 103.9195978716434610 ) ) ; -#23429 = CARTESIAN_POINT ( 'NONE', ( 26.00024017384605557, 120.0658609975274231, 90.40786069970178573 ) ) ; -#23430 = CARTESIAN_POINT ( 'NONE', ( -25.66867234669999931, 120.7997677173000000, 87.89940608527000165 ) ) ; -#23431 = ORIENTED_EDGE ( 'NONE', *, *, #11032, .F. ) ; -#23432 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971560961 ) ) ; -#23433 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#23434 = ORIENTED_EDGE ( 'NONE', *, *, #23244, .F. ) ; -#23435 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1209, #16934, #23101, #10437, #7543, #32702, #10237, #35523, #20010, #35129, #38027, #7143, #4473, #29029, #19798, #1413, #14302, #39832, #1826, #5288 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 1, 1, 1, 1, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999978351, 0.3749999999999983902, 0.4374999999999962252, 0.4687499999999926170, 0.4843749999999907296, 0.4921874999999897859, 0.4960937499999917843, 0.4980468749999927280, 0.4999999999999937272, 0.7499999999999967804, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23436 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825968346491471, 0.0005734119012694825638 ) ) ; -#23437 = CARTESIAN_POINT ( 'NONE', ( 25.49918375113658087, 117.7860527769602470, 87.75221892551610381 ) ) ; -#23438 = ADVANCED_FACE ( 'NONE', ( #35204 ), #6669, .F. ) ; -#23439 = EDGE_CURVE ( 'NONE', #13145, #34776, #28501, .T. ) ; -#23440 = FACE_OUTER_BOUND ( 'NONE', #2974, .T. ) ; -#23441 = PLANE ( 'NONE', #13114 ) ; -#23442 = ORIENTED_EDGE ( 'NONE', *, *, #5392, .T. ) ; -#23443 = FACE_OUTER_BOUND ( 'NONE', #29876, .T. ) ; -#23444 = VECTOR ( 'NONE', #33271, 1000.000000000000000 ) ; -#23445 = CARTESIAN_POINT ( 'NONE', ( -15.99798258269242623, 173.8482551488953050, 102.8774467584792802 ) ) ; -#23446 = PLANE ( 'NONE', #3841 ) ; -#23447 = VECTOR ( 'NONE', #32836, 1000.000000000000114 ) ; -#23448 = ORIENTED_EDGE ( 'NONE', *, *, #9148, .F. ) ; -#23449 = CARTESIAN_POINT ( 'NONE', ( 5.666342389540173663, 185.9093800082626160, 102.5669869859405026 ) ) ; -#23450 = VECTOR ( 'NONE', #22167, 1000.000000000000000 ) ; -#23451 = CARTESIAN_POINT ( 'NONE', ( -26.00800983458967508, 191.5260122442129216, 103.8858970416150385 ) ) ; -#23452 = CARTESIAN_POINT ( 'NONE', ( 17.31813039954455036, 152.9213809402095023, 180.9051047961254142 ) ) ; -#23453 = AXIS2_PLACEMENT_3D ( 'NONE', #22907, #29032, #7341 ) ; -#23454 = CARTESIAN_POINT ( 'NONE', ( -2.453916141853501820, 205.5673811402000126, 76.30169882352981858 ) ) ; -#23455 = LINE ( 'NONE', #32066, #31084 ) ; -#23456 = ORIENTED_EDGE ( 'NONE', *, *, #32310, .T. ) ; -#23457 = CARTESIAN_POINT ( 'NONE', ( 1.447658035571013802, 152.0519508787176335, 130.6788418760813784 ) ) ; -#23458 = EDGE_CURVE ( 'NONE', #16326, #13844, #2115, .T. ) ; -#23459 = CARTESIAN_POINT ( 'NONE', ( -35.94504593274000825, 192.5960943757999928, 104.9593749602999964 ) ) ; -#23460 = DIRECTION ( 'NONE', ( -0.0005559617608505201727, 0.3907311284922885264, -0.9205046855576908271 ) ) ; -#23461 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#23462 = CARTESIAN_POINT ( 'NONE', ( -23.35635573182313607, 131.0183818788550241, 89.91503395410319399 ) ) ; -#23463 = DIRECTION ( 'NONE', ( 0.6087613505916590340, -0.7729391287937367183, -0.1788147678616013314 ) ) ; -#23464 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988446460639, 156.3551877982853000, 95.75036263590625651 ) ) ; -#23465 = CARTESIAN_POINT ( 'NONE', ( -38.37333053086418744, 118.8333496579262487, 87.72072121845931747 ) ) ; -#23466 = ORIENTED_EDGE ( 'NONE', *, *, #4929, .F. ) ; -#23467 = CARTESIAN_POINT ( 'NONE', ( 5.659893952243699289, 181.0147214850249782, 104.5189528120545646 ) ) ; -#23468 = PLANE ( 'NONE', #17021 ) ; -#23469 = CIRCLE ( 'NONE', #7145, 8.999999999999998224 ) ; -#23470 = CARTESIAN_POINT ( 'NONE', ( 12.31694666161969387, 134.8454845476107096, 93.34277599105703871 ) ) ; -#23471 = ORIENTED_EDGE ( 'NONE', *, *, #30924, .F. ) ; -#23472 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490506714044, 156.2427122712157086, 96.23754757944949745 ) ) ; -#23473 = AXIS2_PLACEMENT_3D ( 'NONE', #26437, #32560, #20281 ) ; -#23474 = CARTESIAN_POINT ( 'NONE', ( 3.725419649892127261, 136.7247895207366355, 94.10044209311497809 ) ) ; -#23475 = AXIS2_PLACEMENT_3D ( 'NONE', #20271, #11090, #1681 ) ; -#23476 = ORIENTED_EDGE ( 'NONE', *, *, #6613, .F. ) ; -#23477 = LINE ( 'NONE', #20817, #23444 ) ; -#23478 = ORIENTED_EDGE ( 'NONE', *, *, #5294, .F. ) ; -#23479 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; -#23480 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#23481 = CARTESIAN_POINT ( 'NONE', ( -12.63532332570012073, 130.1618938156200613, 92.53889310033923721 ) ) ; -#23482 = ADVANCED_FACE ( 'NONE', ( #16602 ), #35376, .F. ) ; -#23483 = EDGE_CURVE ( 'NONE', #326, #36696, #20391, .T. ) ; -#23484 = CARTESIAN_POINT ( 'NONE', ( 37.39851594842701132, 107.7137877614669179, 168.6499130571439196 ) ) ; -#23485 = CARTESIAN_POINT ( 'NONE', ( -5.670177853320987893, 124.7093853677813513, 88.91838017179868814 ) ) ; -#23486 = ORIENTED_EDGE ( 'NONE', *, *, #18512, .F. ) ; -#23487 = CARTESIAN_POINT ( 'NONE', ( 39.04493984371202941, 209.7096538830999748, 73.03492191715572801 ) ) ; -#23488 = DIRECTION ( 'NONE', ( 0.7933533416835718555, -0.5930537051408170113, -0.1373964266575322390 ) ) ; -#23489 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#23490 = ORIENTED_EDGE ( 'NONE', *, *, #28837, .T. ) ; -#23491 = CARTESIAN_POINT ( 'NONE', ( -45.39809028288159709, 124.1809289841894213, 92.62646527380597661 ) ) ; -#23492 = ORIENTED_EDGE ( 'NONE', *, *, #31520, .F. ) ; -#23493 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#23494 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18006, #21518, #2499, #11491, #27655, #18601, #40292, #36837, #31111, #30515, #15172, #14776, #8842, #40092 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999997961075, 0.3749999999997057354, 0.4374999999996544986, 0.4687499999996283528, 0.4843749999996272981, 0.4999999999996261879, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23495 = FACE_OUTER_BOUND ( 'NONE', #28415, .T. ) ; -#23496 = CARTESIAN_POINT ( 'NONE', ( -28.68341338983000455, 124.5116353150000066, 91.63388613658000281 ) ) ; -#23497 = CIRCLE ( 'NONE', #35232, 7.999999999999992895 ) ; -#23498 = CARTESIAN_POINT ( 'NONE', ( -25.84608708632153551, 211.0902257898999892, 73.23808610911966355 ) ) ; -#23499 = CARTESIAN_POINT ( 'NONE', ( -21.21281380558005125, 182.9066539643694966, 104.4588199671594850 ) ) ; -#23500 = VECTOR ( 'NONE', #30252, 1000.000000000000000 ) ; -#23501 = AXIS2_PLACEMENT_3D ( 'NONE', #33703, #14723, #20635 ) ; -#23502 = CARTESIAN_POINT ( 'NONE', ( -28.46708276391288450, 184.0084905153442492, 102.6649762630933651 ) ) ; -#23503 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971552357 ) ) ; -#23504 = ADVANCED_FACE ( 'NONE', ( #39498 ), #17208, .F. ) ; -#23505 = CARTESIAN_POINT ( 'NONE', ( 37.58195705592999758, 118.7990928048999990, 87.12052553435999869 ) ) ; -#23506 = LINE ( 'NONE', #1834, #23138 ) ; -#23507 = CARTESIAN_POINT ( 'NONE', ( 3.188030641335061421, 183.7439365961982674, 102.0716281244637145 ) ) ; -#23508 = ORIENTED_EDGE ( 'NONE', *, *, #34130, .T. ) ; -#23509 = CARTESIAN_POINT ( 'NONE', ( 39.01961099994073123, 121.1792603210347608, 123.5275808920352603 ) ) ; -#23510 = CARTESIAN_POINT ( 'NONE', ( -14.78424370841450042, 128.6742020487672278, 91.93439134535178425 ) ) ; -#23511 = CARTESIAN_POINT ( 'NONE', ( -36.35641993181373266, 191.5958320935953623, 106.4146220668809377 ) ) ; -#23512 = CARTESIAN_POINT ( 'NONE', ( 35.40748609300000282, 112.8223810538000009, 87.09901120572000366 ) ) ; -#23513 = CARTESIAN_POINT ( 'NONE', ( 39.01510395514510776, 128.3961366480688184, 92.35085356743662999 ) ) ; -#23514 = ORIENTED_EDGE ( 'NONE', *, *, #3666, .F. ) ; -#23515 = ORIENTED_EDGE ( 'NONE', *, *, #21338, .T. ) ; -#23516 = EDGE_LOOP ( 'NONE', ( #20463, #35722, #8666, #32007 ) ) ; -#23517 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#23518 = EDGE_CURVE ( 'NONE', #40179, #32617, #20359, .T. ) ; -#23519 = DIRECTION ( 'NONE', ( 0.0005884965073590145944, -0.2249510525036911290, 0.9743698874910607932 ) ) ; -#23520 = CARTESIAN_POINT ( 'NONE', ( 5.664340955981074011, 123.7792148246779078, 91.23079828286975612 ) ) ; -#23521 = EDGE_LOOP ( 'NONE', ( #15742, #10041, #21204, #20617 ) ) ; -#23522 = EDGE_LOOP ( 'NONE', ( #34953, #25604, #28967, #32335 ) ) ; -#23523 = FACE_BOUND ( 'NONE', #2100, .T. ) ; -#23524 = CIRCLE ( 'NONE', #30073, 6.000000000043544723 ) ; -#23525 = ADVANCED_FACE ( 'NONE', ( #29711 ), #1693, .F. ) ; -#23526 = CIRCLE ( 'NONE', #37890, 2.749999999927908334 ) ; -#23527 = CARTESIAN_POINT ( 'NONE', ( -13.49083856689536987, 187.6673735495426740, 106.0664666259349644 ) ) ; -#23528 = ORIENTED_EDGE ( 'NONE', *, *, #25536, .T. ) ; -#23529 = CARTESIAN_POINT ( 'NONE', ( -19.40383092080755745, 125.3891650183175841, 175.7828678101702167 ) ) ; -#23530 = AXIS2_PLACEMENT_3D ( 'NONE', #25998, #13914, #10459 ) ; -#23531 = EDGE_LOOP ( 'NONE', ( #5699, #24354, #36298, #13488 ) ) ; -#23532 = CYLINDRICAL_SURFACE ( 'NONE', #16826, 10.00000000000000533 ) ; -#23533 = EDGE_CURVE ( 'NONE', #26865, #3241, #25221, .T. ) ; -#23534 = ADVANCED_FACE ( 'NONE', ( #18221 ), #39701, .T. ) ; -#23535 = LINE ( 'NONE', #7988, #31325 ) ; -#23536 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 1.005820108796730516E-17, 0.0006039748319389842430 ) ) ; -#23537 = EDGE_LOOP ( 'NONE', ( #38278, #14215, #24186, #40210 ) ) ; -#23538 = CARTESIAN_POINT ( 'NONE', ( -0.4376709669680989845, 188.6085996256109922, 103.1929362358850142 ) ) ; -#23539 = EDGE_CURVE ( 'NONE', #17164, #29960, #28636, .T. ) ; -#23540 = CARTESIAN_POINT ( 'NONE', ( 0.9451061190988069294, 189.0447137624019831, 103.7056411191770025 ) ) ; -#23541 = DIRECTION ( 'NONE', ( 0.5988683521957626210, -0.8008474865655332842, 0.000000000000000000 ) ) ; -#23542 = ORIENTED_EDGE ( 'NONE', *, *, #21570, .T. ) ; -#23543 = CARTESIAN_POINT ( 'NONE', ( -22.19951751066730239, 122.8658642608983484, 176.1889355587336752 ) ) ; -#23544 = ORIENTED_EDGE ( 'NONE', *, *, #27221, .F. ) ; -#23545 = EDGE_LOOP ( 'NONE', ( #14331, #2912, #4902, #25402 ) ) ; -#23546 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37364, #33476, #40419, #33273, #24314, #33885, #5263, #9165, #8763, #27782, #34084, #2429, #17728, #27182, #30221, #39614, #12230, #24720, #11626, #21229 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000069666, 0.1875000000000091038, 0.2187500000000237033, 0.2500000000000383027, 0.3750000000000381362, 0.5000000000000378586, 0.6250000000000376366, 0.7500000000000373035, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23547 = ORIENTED_EDGE ( 'NONE', *, *, #34529, .F. ) ; -#23548 = CARTESIAN_POINT ( 'NONE', ( -38.46044104337040181, 118.4609804511839286, 89.70916240556151422 ) ) ; -#23549 = VERTEX_POINT ( 'NONE', #5773 ) ; -#23550 = CARTESIAN_POINT ( 'NONE', ( -28.17025018105144341, 187.6480004385370819, 102.9918920620223730 ) ) ; -#23551 = CARTESIAN_POINT ( 'NONE', ( -27.38562835820999908, 187.4256067411000117, 105.8479368917000158 ) ) ; -#23552 = FACE_OUTER_BOUND ( 'NONE', #4583, .T. ) ; -#23553 = AXIS2_PLACEMENT_3D ( 'NONE', #15642, #25471, #34234 ) ; -#23554 = ADVANCED_FACE ( 'NONE', ( #28995 ), #4647, .T. ) ; -#23555 = ORIENTED_EDGE ( 'NONE', *, *, #1459, .T. ) ; -#23556 = CARTESIAN_POINT ( 'NONE', ( -20.49839850487972726, 118.3474708296278664, 89.78013583511243212 ) ) ; -#23557 = ORIENTED_EDGE ( 'NONE', *, *, #19851, .T. ) ; -#23558 = CIRCLE ( 'NONE', #14398, 5.499999999656736804 ) ; -#23559 = CARTESIAN_POINT ( 'NONE', ( 27.41836671908999890, 124.2890015699999964, 91.06748153460000594 ) ) ; -#23560 = CONICAL_SURFACE ( 'NONE', #38549, 5.999999999815444518, 0.7853981633778843729 ) ; -#23561 = DIRECTION ( 'NONE', ( -0.0005884949961187637075, 0.2249510543439065258, -0.9743698870671262391 ) ) ; -#23563 = CARTESIAN_POINT ( 'NONE', ( 22.50029346826671173, 138.3995272081080259, 92.10453246904701530 ) ) ; -#23562 = CARTESIAN_POINT ( 'NONE', ( 17.03084806954877095, 121.4891440001390492, 177.4761730266376105 ) ) ; -#23564 = ORIENTED_EDGE ( 'NONE', *, *, #17746, .T. ) ; -#23565 = ORIENTED_EDGE ( 'NONE', *, *, #36480, .T. ) ; -#23566 = CARTESIAN_POINT ( 'NONE', ( -36.19139248826387245, 191.8884328938771944, 104.4137272565322831 ) ) ; -#23567 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17498, #5655, #29801, #2604, #33453, #24489 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23568 = EDGE_LOOP ( 'NONE', ( #24480, #38730, #24513, #2111 ) ) ; -#23569 = CARTESIAN_POINT ( 'NONE', ( 39.15547825205999999, 119.6286442269999952, 90.46801798868999356 ) ) ; -#23570 = DIRECTION ( 'NONE', ( 0.6068735732728635091, 0.7743428331745977333, 0.1791581501750993122 ) ) ; -#23571 = EDGE_CURVE ( 'NONE', #29762, #39475, #32150, .T. ) ; -#23572 = CARTESIAN_POINT ( 'NONE', ( 40.93334977941019304, 181.3867412422068526, 104.5835422556928052 ) ) ; -#23573 = CARTESIAN_POINT ( 'NONE', ( -37.46426832607435387, 111.9935766244044117, 150.7713156516942945 ) ) ; -#23574 = ORIENTED_EDGE ( 'NONE', *, *, #1047, .F. ) ; -#23575 = EDGE_CURVE ( 'NONE', #37873, #19980, #11004, .T. ) ; -#23576 = EDGE_LOOP ( 'NONE', ( #33563, #2513, #24349, #3099 ) ) ; -#23577 = ORIENTED_EDGE ( 'NONE', *, *, #3338, .F. ) ; -#23578 = CARTESIAN_POINT ( 'NONE', ( -12.63691346781947722, 177.4392416099184686, 100.9254952946230901 ) ) ; -#23579 = CARTESIAN_POINT ( 'NONE', ( -2.771263523205826029, 193.9703421779226176, 102.7697054433951678 ) ) ; -#23580 = VECTOR ( 'NONE', #2222, 999.9999999999998863 ) ; -#23581 = ADVANCED_FACE ( 'NONE', ( #10403 ), #29411, .T. ) ; -#23582 = CARTESIAN_POINT ( 'NONE', ( 27.36069733113999902, 124.7149260091999992, 88.77129815678000568 ) ) ; -#23583 = EDGE_CURVE ( 'NONE', #23937, #22722, #13853, .T. ) ; -#23584 = ORIENTED_EDGE ( 'NONE', *, *, #20245, .T. ) ; -#23585 = CARTESIAN_POINT ( 'NONE', ( -35.96364602615999928, 192.3236677699999859, 106.4340467460000212 ) ) ; -#23586 = CONICAL_SURFACE ( 'NONE', #7905, 6.000000000067895023, 0.7853981634347139140 ) ; -#23587 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3322, #28682, #28285, #21753, #22360, #34194, #6990, #15994, #6192, #25228, #461, #65, #28486, #13149, #19462, #18644, #37677, #31151, #3124, #25027, #37476, #6387, #18848, #31350, #13345, #25832, #32700, #17138, #39228 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 1, 2, 2, 1, 1, 2, 2, 1, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.03125000000016738694, 0.04687500000023392399, 0.06250000000030046798, 0.09375000000043354209, 0.1093750000005237893, 0.1250000000006140366, 0.1875000000007510381, 0.2187500000008107681, 0.2343750000008530954, 0.2500000000008953949, 0.3750000000012715939, 0.4375000000014597212, 0.4687500000015364376, 0.4843750000015764612, 0.4921875000015817347, 0.4960937500015843993, 0.5000000000015870638, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23588 = AXIS2_PLACEMENT_3D ( 'NONE', #23270, #13665, #20181 ) ; -#23589 = CONICAL_SURFACE ( 'NONE', #3326, 2.503100863752302896, 0.7853981633869029366 ) ; -#23590 = CARTESIAN_POINT ( 'NONE', ( 3.075358835610300101, 190.8616699574176039, 106.8060003944983833 ) ) ; -#23591 = VERTEX_POINT ( 'NONE', #14682 ) ; -#23592 = FACE_OUTER_BOUND ( 'NONE', #486, .T. ) ; -#23593 = CARTESIAN_POINT ( 'NONE', ( -2.851221542150457200, 209.7096659646922774, 76.06022685436926167 ) ) ; -#23594 = CARTESIAN_POINT ( 'NONE', ( 22.50147045824727599, 137.9496250995102855, 94.05327224295773192 ) ) ; -#23595 = CARTESIAN_POINT ( 'NONE', ( -15.03362232203068771, 151.2943605774707407, 177.4366870137986609 ) ) ; -#23596 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23071, #19972, #35303, #38777, #19169, #34702, #977, #13660, #4444, #19771, #10210 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000003837486, 0.3750000000005756506, 0.4375000000006891709, 0.4687500000006858403, 0.5000000000006824541, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23597 = ORIENTED_EDGE ( 'NONE', *, *, #13981, .F. ) ; -#23598 = DIRECTION ( 'NONE', ( -0.0005884949961238158727, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#23599 = CARTESIAN_POINT ( 'NONE', ( 22.66453919972767039, 213.5901743387830152, 75.54496024088506090 ) ) ; -#23600 = ORIENTED_EDGE ( 'NONE', *, *, #7268, .T. ) ; -#23601 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14489, #11412, #23898, #8359, #15253, #106, #12987, #18687, #10123, #9518, #3552, #7028, #28921, #15833, #9924, #892, #28722, #25875, #38318, #34431, #28526, #700, #13188, #10329, #29518, #35826, #4970, #22993, #7631, #26067, #8040, #38701, #14198, #7835, #20306, #39112, #20499, #35417 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 1, 1, 1, 1, 2, 2, 2, 2, 1, 1, 1, 1, 2, 2, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999995608790, 0.1874999999993424704, 0.2187499999992332522, 0.2343749999991789901, 0.2421874999991508737, 0.2460937499991381339, 0.2480468749991304178, 0.2490234374991269484, 0.2499999999991234789, 0.3749999999991580069, 0.4374999999991762700, 0.4687499999991853739, 0.4843749999991859845, 0.4921874999991874278, 0.4960937499991910360, 0.4980468749991939781, 0.4999999999991968647, 0.6249999999993025579, 0.6874999999993643973, 0.7187499999993987032, 0.7343749999994065858, 0.7421874999994167998, 0.7499999999994269029, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23602 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#23603 = AXIS2_PLACEMENT_3D ( 'NONE', #12512, #25215, #31338 ) ; -#23605 = DIRECTION ( 'NONE', ( 0.0005884949961214528541, -0.2249510543439078303, 0.9743698870671260170 ) ) ; -#23604 = CARTESIAN_POINT ( 'NONE', ( 2.463364856792551905, 209.5677208948551993, 75.55701285043443249 ) ) ; -#23606 = AXIS2_PLACEMENT_3D ( 'NONE', #21848, #34288, #37573 ) ; -#23607 = ORIENTED_EDGE ( 'NONE', *, *, #15506, .F. ) ; -#23608 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749390117, 179.6299767372342160, 101.6260513916748920 ) ) ; -#23609 = AXIS2_PLACEMENT_3D ( 'NONE', #20581, #10991, #30401 ) ; -#23610 = ORIENTED_EDGE ( 'NONE', *, *, #138, .F. ) ; -#23611 = EDGE_CURVE ( 'NONE', #33199, #20733, #7960, .T. ) ; -#23612 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319380788258 ) ) ; -#23613 = EDGE_CURVE ( 'NONE', #34462, #23591, #21612, .T. ) ; -#23614 = DIRECTION ( 'NONE', ( -0.0005884949961279498272, 0.2249510543439066645, -0.9743698870671262391 ) ) ; -#23615 = CARTESIAN_POINT ( 'NONE', ( -24.42625685282789405, 109.6131156702000027, 89.78253759522658584 ) ) ; -#23616 = ADVANCED_BREP_SHAPE_REPRESENTATION ( 'MID360+\X2\76f8673a652f67b6\X0\6.24', ( #1957, #11396 ), #2275 ) ; -#23617 = EDGE_CURVE ( 'NONE', #9198, #36415, #13204, .T. ) ; -#23618 = DIRECTION ( 'NONE', ( -2.530387804365254516E-14, -0.9743700557921585181, -0.2249510932971561239 ) ) ; -#23619 = ORIENTED_EDGE ( 'NONE', *, *, #23518, .T. ) ; -#23620 = EDGE_CURVE ( 'NONE', #27747, #14927, #32857, .T. ) ; -#23621 = VERTEX_POINT ( 'NONE', #36126 ) ; -#23622 = CARTESIAN_POINT ( 'NONE', ( -3.233962871607205081, 183.4879531415897418, 102.0164083997212146 ) ) ; -#23623 = VERTEX_POINT ( 'NONE', #20593 ) ; -#23624 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #39429, #36993, #12057, #11439 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.016443151784193422, 3.056089401325539079 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9998690188640146914, 0.9998690188640146914, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#23625 = ORIENTED_EDGE ( 'NONE', *, *, #6042, .F. ) ; -#23626 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455648834120, -31.54510897440487938, 136.4474729010643159 ) ) ; -#23627 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25477, #709, #3770, #16438 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23628 = CARTESIAN_POINT ( 'NONE', ( 2.877595496360000116, 208.9474331168999868, 73.28391261951000502 ) ) ; -#23629 = ORIENTED_EDGE ( 'NONE', *, *, #32407, .T. ) ; -#23630 = EDGE_CURVE ( 'NONE', #37866, #15089, #33057, .T. ) ; -#23631 = ORIENTED_EDGE ( 'NONE', *, *, #25585, .T. ) ; -#23632 = CARTESIAN_POINT ( 'NONE', ( -0.4361371085228029076, 189.0000000148081654, 105.7376017109280184 ) ) ; -#23633 = FACE_OUTER_BOUND ( 'NONE', #39737, .T. ) ; -#23634 = CARTESIAN_POINT ( 'NONE', ( -35.54692679333999905, 192.3064933894999911, 104.0386506509999975 ) ) ; -#23635 = CARTESIAN_POINT ( 'NONE', ( 37.09773084145999889, 191.6304407382999955, 104.5058401963000136 ) ) ; -#23636 = CARTESIAN_POINT ( 'NONE', ( -25.66777027296999947, 120.6958994388000121, 87.87614527869999392 ) ) ; -#23637 = EDGE_CURVE ( 'NONE', #7336, #17805, #19710, .T. ) ; -#23638 = ORIENTED_EDGE ( 'NONE', *, *, #687, .T. ) ; -#23639 = CARTESIAN_POINT ( 'NONE', ( 1.752039179668189783, 151.6655327357930219, 130.5892088565730091 ) ) ; -#23640 = CYLINDRICAL_SURFACE ( 'NONE', #35202, 2.500000000000003997 ) ; -#23641 = ORIENTED_EDGE ( 'NONE', *, *, #33196, .F. ) ; -#23642 = CARTESIAN_POINT ( 'NONE', ( -20.51827374288739847, 208.4342764294943606, 75.91696062898481046 ) ) ; -#23643 = CARTESIAN_POINT ( 'NONE', ( 25.49921019565536184, 118.1133140256443426, 87.75227232668940758 ) ) ; -#23644 = VECTOR ( 'NONE', #19788, 999.9999999999998863 ) ; -#23645 = CARTESIAN_POINT ( 'NONE', ( 3.046672840563001472, 207.8686389444187341, 77.27521480613795291 ) ) ; -#23646 = ORIENTED_EDGE ( 'NONE', *, *, #33311, .T. ) ; -#23647 = CONICAL_SURFACE ( 'NONE', #33404, 2.499999999873558476, 0.7853981633651732075 ) ; -#23648 = ADVANCED_FACE ( 'NONE', ( #3190 ), #24702, .F. ) ; -#23649 = CARTESIAN_POINT ( 'NONE', ( 14.24259403095196319, 124.1280741090887574, 175.6403682132716426 ) ) ; -#23650 = AXIS2_PLACEMENT_3D ( 'NONE', #30564, #36685, #8698 ) ; -#23651 = FACE_OUTER_BOUND ( 'NONE', #16843, .T. ) ; -#23652 = FACE_OUTER_BOUND ( 'NONE', #3352, .T. ) ; -#23653 = ORIENTED_EDGE ( 'NONE', *, *, #14137, .T. ) ; -#23654 = CARTESIAN_POINT ( 'NONE', ( 20.00004282447493864, 191.5259056233101091, 103.8580927373495371 ) ) ; -#23655 = ORIENTED_EDGE ( 'NONE', *, *, #28982, .T. ) ; -#23656 = CARTESIAN_POINT ( 'NONE', ( -26.12791299326000072, 191.8330791879999992, 103.7958756749000031 ) ) ; -#23657 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31814, #3970, #19512, #23005, #6841, #38137, #7240, #4374, #16245, #7437, #19110, #13201, #26276, #25689, #16443, #1112, #31603, #10539 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999893419, 0.2499999999999786837, 0.3749999999999680256, 0.4374999999999676370, 0.4999999999999672484, 0.6249999999999790168, 0.6874999999999849010, 0.7499999999999907851, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23658 = CARTESIAN_POINT ( 'NONE', ( -9.584790827646999745, 188.0427815642999860, 103.3283854050000201 ) ) ; -#23659 = CARTESIAN_POINT ( 'NONE', ( 25.43225731411000012, 191.0569328349000102, 104.3863169934000013 ) ) ; -#23660 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#23661 = FACE_OUTER_BOUND ( 'NONE', #9692, .T. ) ; -#23662 = ORIENTED_EDGE ( 'NONE', *, *, #38392, .T. ) ; -#23663 = DIRECTION ( 'NONE', ( -0.0002393071182776102175, -0.2252352986010028590, 0.9743043687658493601 ) ) ; -#23664 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#23665 = CARTESIAN_POINT ( 'NONE', ( 20.00025828646017345, 174.5279639952516106, 99.93388581131628712 ) ) ; -#23666 = CARTESIAN_POINT ( 'NONE', ( 22.50034184233011914, 153.8097659799650501, 95.66226703669086362 ) ) ; -#23667 = EDGE_CURVE ( 'NONE', #20961, #5945, #24373, .T. ) ; -#23668 = CARTESIAN_POINT ( 'NONE', ( 19.46082156961019294, 125.9120791161117410, 177.4132114498032422 ) ) ; -#23669 = CARTESIAN_POINT ( 'NONE', ( 32.48294317935824438, 176.0008788113808009, 100.2663086607479244 ) ) ; -#23670 = LINE ( 'NONE', #20589, #33487 ) ; -#23671 = EDGE_CURVE ( 'NONE', #36559, #29017, #15844, .T. ) ; -#23672 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418800025, 218.5902260770999987, 73.08022052563953253 ) ) ; -#23673 = AXIS2_PLACEMENT_3D ( 'NONE', #40407, #9149, #40205 ) ; -#23674 = EDGE_CURVE ( 'NONE', #23190, #18594, #6454, .T. ) ; -#23675 = CARTESIAN_POINT ( 'NONE', ( -1.458415328219441198, 152.0517121881307503, 130.6798743971081365 ) ) ; -#23676 = CARTESIAN_POINT ( 'NONE', ( -38.80490438818794274, 119.2275004425862335, 87.75208274189962765 ) ) ; -#23677 = VERTEX_POINT ( 'NONE', #20510 ) ; -#23678 = EDGE_LOOP ( 'NONE', ( #39418, #7264, #16945, #15104 ) ) ; -#23679 = AXIS2_PLACEMENT_3D ( 'NONE', #10133, #12573, #37527 ) ; -#23680 = CARTESIAN_POINT ( 'NONE', ( 25.99207700458055825, 210.6299893049999810, 76.04276577997849529 ) ) ; -#23681 = CARTESIAN_POINT ( 'NONE', ( -38.87088589341672673, 169.4517328299331780, 182.9034801424807029 ) ) ; -#23682 = EDGE_CURVE ( 'NONE', #16249, #4337, #34938, .T. ) ; -#23683 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12750, #19068, #3736, #34598 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23684 = ORIENTED_EDGE ( 'NONE', *, *, #21383, .F. ) ; -#23685 = LINE ( 'NONE', #8138, #20609 ) ; -#23686 = ORIENTED_EDGE ( 'NONE', *, *, #4685, .T. ) ; -#23687 = EDGE_CURVE ( 'NONE', #33799, #17057, #9992, .T. ) ; -#23688 = CARTESIAN_POINT ( 'NONE', ( -16.89653939414543871, 151.9703269149406424, 184.0152534838730958 ) ) ; -#23689 = CARTESIAN_POINT ( 'NONE', ( 25.61835187867219688, 116.5980403540922765, 87.25231144943825257 ) ) ; -#23690 = VERTEX_POINT ( 'NONE', #27297 ) ; -#23691 = CARTESIAN_POINT ( 'NONE', ( 36.06505478217123795, 192.7057421143160525, 106.3400883098223915 ) ) ; -#23692 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; -#23693 = LINE ( 'NONE', #32685, #8370 ) ; -#23694 = CARTESIAN_POINT ( 'NONE', ( -15.49970618492638508, 127.6313525092815411, 89.64145404642985682 ) ) ; -#23695 = CARTESIAN_POINT ( 'NONE', ( 21.70190315701263017, 123.1837599801819465, 176.5257127422096914 ) ) ; -#23696 = ORIENTED_EDGE ( 'NONE', *, *, #19041, .T. ) ; -#23697 = ADVANCED_FACE ( 'NONE', ( #5591 ), #2536, .T. ) ; -#23698 = CARTESIAN_POINT ( 'NONE', ( -39.71429903588311561, 169.1766066404292985, 164.5230398149320763 ) ) ; -#23699 = CARTESIAN_POINT ( 'NONE', ( 12.63704034694744571, 181.8935201937362933, 101.9167722821602098 ) ) ; -#23700 = AXIS2_PLACEMENT_3D ( 'NONE', #31319, #20976, #36300 ) ; -#23701 = DIRECTION ( 'NONE', ( -0.7066903926851150208, 0.000000000000000000, 0.7075229246367624736 ) ) ; -#23702 = CARTESIAN_POINT ( 'NONE', ( 23.69388335781209776, 131.0246890999723632, 89.88804818403849595 ) ) ; -#23703 = ORIENTED_EDGE ( 'NONE', *, *, #26396, .F. ) ; -#23704 = VECTOR ( 'NONE', #36904, 1000.000000000000000 ) ; -#23705 = CARTESIAN_POINT ( 'NONE', ( -43.00650784327562093, 120.7113638011818750, 92.29910861957030477 ) ) ; -#23706 = CARTESIAN_POINT ( 'NONE', ( -2.436970328474767467, 191.4135392062999870, 104.3588452339995882 ) ) ; -#23707 = CARTESIAN_POINT ( 'NONE', ( -28.27925241266000000, 125.3242495368999982, 91.03020751606000260 ) ) ; -#23708 = AXIS2_PLACEMENT_3D ( 'NONE', #10750, #35257, #19532 ) ; -#23709 = CARTESIAN_POINT ( 'NONE', ( -25.77711092217260358, 212.2744629154549045, 73.07407281147119704 ) ) ; -#23710 = CARTESIAN_POINT ( 'NONE', ( -25.90152905792492177, 209.7106500049521003, 73.18271116922589670 ) ) ; -#23711 = CARTESIAN_POINT ( 'NONE', ( 25.89011449699999901, 191.5660806957999966, 106.7678315448000035 ) ) ; -#23712 = CARTESIAN_POINT ( 'NONE', ( 37.73510322196000288, 118.9927959184999935, 87.11919898040000021 ) ) ; -#23713 = CARTESIAN_POINT ( 'NONE', ( 39.06517727473992352, 190.5638640950986655, 106.5323238486747073 ) ) ; -#23714 = CARTESIAN_POINT ( 'NONE', ( 38.47096800405999772, 118.8680569848000061, 90.10415460253000219 ) ) ; -#23715 = VERTEX_POINT ( 'NONE', #12740 ) ; -#23716 = CARTESIAN_POINT ( 'NONE', ( 25.51044001015309703, 191.4790671403759745, 106.3785283636754855 ) ) ; -#23717 = CARTESIAN_POINT ( 'NONE', ( -6.035968311314003465, 136.6786235697017844, 94.29340140767534706 ) ) ; -#23718 = DIRECTION ( 'NONE', ( -0.9914447795421099663, -0.1272537940605282525, -0.02904687618140097335 ) ) ; -#23719 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971537369 ) ) ; -#23720 = EDGE_CURVE ( 'NONE', #1984, #34777, #28490, .T. ) ; -#23721 = EDGE_CURVE ( 'NONE', #14927, #3624, #15215, .T. ) ; -#23723 = EDGE_LOOP ( 'NONE', ( #36651, #1378, #15050, #38477 ) ) ; -#23722 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971580945 ) ) ; -#23724 = ORIENTED_EDGE ( 'NONE', *, *, #25133, .T. ) ; -#23725 = ORIENTED_EDGE ( 'NONE', *, *, #35422, .T. ) ; -#23726 = ORIENTED_EDGE ( 'NONE', *, *, #1177, .T. ) ; -#23727 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421684034, 185.2348895838669591, 105.4885254536207100 ) ) ; -#23728 = VECTOR ( 'NONE', #4335, 1000.000000000000000 ) ; -#23729 = CARTESIAN_POINT ( 'NONE', ( 19.99941580399983110, 118.1025156334579265, 87.25545403306659864 ) ) ; -#23730 = LINE ( 'NONE', #29869, #13530 ) ; -#23731 = CIRCLE ( 'NONE', #32873, 9.999999999987895904 ) ; -#23732 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21801, #12378, #31193, #27346 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23733 = VERTEX_POINT ( 'NONE', #663 ) ; -#23734 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561239 ) ) ; -#23735 = AXIS2_PLACEMENT_3D ( 'NONE', #14590, #11514, #31335 ) ; -#23736 = CARTESIAN_POINT ( 'NONE', ( -39.64444090039871327, 161.8176364200976707, 196.2252754037533293 ) ) ; -#23737 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 183.4515543678114966, 105.0773313099630855 ) ) ; -#23738 = CARTESIAN_POINT ( 'NONE', ( -35.56060160276999937, 113.4209612089999979, 87.40543740024000385 ) ) ; -#23739 = ORIENTED_EDGE ( 'NONE', *, *, #36822, .T. ) ; -#23740 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; -#23741 = CARTESIAN_POINT ( 'NONE', ( 3.665000663723704477, 187.4035791409591809, 102.9162352551000339 ) ) ; -#23742 = CARTESIAN_POINT ( 'NONE', ( -20.50629817461280169, 199.8811588058565007, 94.82707092103487412 ) ) ; -#23743 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#23744 = CARTESIAN_POINT ( 'NONE', ( 28.18739088310087482, 186.6040837889091506, 105.2826068624289064 ) ) ; -#23745 = CARTESIAN_POINT ( 'NONE', ( -19.37711623718722009, 148.6588772883655736, 183.3364165269119042 ) ) ; -#23746 = ORIENTED_EDGE ( 'NONE', *, *, #10455, .F. ) ; -#23747 = ORIENTED_EDGE ( 'NONE', *, *, #18898, .F. ) ; -#23748 = EDGE_CURVE ( 'NONE', #32876, #6189, #13471, .T. ) ; -#23749 = CARTESIAN_POINT ( 'NONE', ( -1.067684965441970002, 188.6609290045259968, 103.2053738198000019 ) ) ; -#23750 = CARTESIAN_POINT ( 'NONE', ( 0.5998483646439000117, 188.7533020767000096, 103.3645834587000110 ) ) ; -#23751 = CARTESIAN_POINT ( 'NONE', ( 21.70855119580487269, 123.2009557436313401, 176.5136632602473981 ) ) ; -#23752 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4686, #10640, #29442, #17143 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.006242663039495804055, 0.006951143884268293910 ), - .UNSPECIFIED. ) ; -#23753 = ORIENTED_EDGE ( 'NONE', *, *, #14997, .T. ) ; -#23754 = VERTEX_POINT ( 'NONE', #37081 ) ; -#23755 = CARTESIAN_POINT ( 'NONE', ( 1.447658035571013802, 152.0519508787176335, 130.6788418760813784 ) ) ; -#23756 = EDGE_LOOP ( 'NONE', ( #9751, #26169, #30290, #38746 ) ) ; -#23757 = VERTEX_POINT ( 'NONE', #9477 ) ; -#23758 = CIRCLE ( 'NONE', #13974, 5.499999999852380306 ) ; -#23759 = CIRCLE ( 'NONE', #15266, 9.500000000017017499 ) ; -#23760 = EDGE_CURVE ( 'NONE', #23378, #37138, #20778, .T. ) ; -#23761 = ORIENTED_EDGE ( 'NONE', *, *, #22711, .T. ) ; -#23762 = VERTEX_POINT ( 'NONE', #18448 ) ; -#23763 = AXIS2_PLACEMENT_3D ( 'NONE', #32328, #35976, #23128 ) ; -#23764 = CARTESIAN_POINT ( 'NONE', ( 20.80638670441944527, 212.3488676199132783, 73.54615486076477282 ) ) ; -#23765 = FACE_OUTER_BOUND ( 'NONE', #1884, .T. ) ; -#23766 = LINE ( 'NONE', #36219, #38907 ) ; -#23767 = ORIENTED_EDGE ( 'NONE', *, *, #31292, .F. ) ; -#23768 = LINE ( 'NONE', #7807, #37578 ) ; -#23769 = ORIENTED_EDGE ( 'NONE', *, *, #18563, .T. ) ; -#23770 = CARTESIAN_POINT ( 'NONE', ( 26.49585351857600202, 122.3650666170340031, 90.96953248081020149 ) ) ; -#23771 = CARTESIAN_POINT ( 'NONE', ( 40.11622567341476753, 89.23467188456967847, 291.5343147401541160 ) ) ; -#23772 = EDGE_CURVE ( 'NONE', #23677, #29062, #35791, .T. ) ; -#23773 = EDGE_CURVE ( 'NONE', #31566, #26136, #25636, .T. ) ; -#23775 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#23774 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672095143, 184.4039562885918713, 104.7835373820076939 ) ) ; -#23776 = EDGE_CURVE ( 'NONE', #32811, #6019, #36053, .T. ) ; -#23777 = VERTEX_POINT ( 'NONE', #10491 ) ; -#23778 = VERTEX_POINT ( 'NONE', #26233 ) ; -#23779 = VERTEX_POINT ( 'NONE', #16985 ) ; -#23780 = CARTESIAN_POINT ( 'NONE', ( 39.13448785807999997, 118.7961619415000030, 89.51920029467000006 ) ) ; -#23781 = CARTESIAN_POINT ( 'NONE', ( -36.51709733199022168, 117.1641781026797275, 87.28983970377757373 ) ) ; -#23782 = CARTESIAN_POINT ( 'NONE', ( -15.94449010895081642, 152.1461032928982036, 184.5535245782780294 ) ) ; -#23783 = CARTESIAN_POINT ( 'NONE', ( -27.47748879306896086, 186.9397151897404683, 105.3937141543796230 ) ) ; -#23784 = CARTESIAN_POINT ( 'NONE', ( 36.42566904746000489, 191.8206917416999886, 104.3689174806000040 ) ) ; -#23785 = CIRCLE ( 'NONE', #32930, 5.999999999963008257 ) ; -#23786 = VECTOR ( 'NONE', #20610, 1000.000000000000114 ) ; -#23787 = ORIENTED_EDGE ( 'NONE', *, *, #28113, .T. ) ; -#23788 = ORIENTED_EDGE ( 'NONE', *, *, #13646, .F. ) ; -#23789 = CARTESIAN_POINT ( 'NONE', ( -0.9403779577023761993, 189.0417799565218218, 103.6973547697631659 ) ) ; -#23790 = CARTESIAN_POINT ( 'NONE', ( -2.937969491697683733, 193.8169247291332340, 102.7046841998142241 ) ) ; -#23791 = CIRCLE ( 'NONE', #17899, 2.500000000100818021 ) ; -#23792 = CARTESIAN_POINT ( 'NONE', ( 27.59710228827999856, 124.5605221792999941, 88.39323889937000445 ) ) ; -#23793 = ORIENTED_EDGE ( 'NONE', *, *, #32762, .F. ) ; -#23794 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 3.370379598151327408E-34, -0.0006039748319386880390 ) ) ; -#23795 = CARTESIAN_POINT ( 'NONE', ( 3.062734419220130455, 191.5259964270285025, 103.8683342040099831 ) ) ; -#23796 = CARTESIAN_POINT ( 'NONE', ( 2.730912326449253413, 190.9537264196661113, 106.4728235569722585 ) ) ; -#23797 = ORIENTED_EDGE ( 'NONE', *, *, #24400, .T. ) ; -#23798 = CARTESIAN_POINT ( 'NONE', ( -20.51922277227172131, 207.6016423443957422, 74.06967515246797973 ) ) ; -#23799 = CARTESIAN_POINT ( 'NONE', ( 28.70699186420280569, 148.4355579229025750, 96.47039304610791532 ) ) ; -#23800 = CARTESIAN_POINT ( 'NONE', ( 20.18580386471265697, 152.8943896618027338, 94.93918149854322053 ) ) ; -#23801 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#23802 = EDGE_CURVE ( 'NONE', #30783, #15846, #1675, .T. ) ; -#23803 = ORIENTED_EDGE ( 'NONE', *, *, #19147, .T. ) ; -#23804 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38460, #38864, #1451, #32151, #32346, #35778 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23805 = DIRECTION ( 'NONE', ( 0.6087611434179115433, -0.7728348325624404547, -0.1792657018023851023 ) ) ; -#23806 = CARTESIAN_POINT ( 'NONE', ( 40.95827073235999904, 112.8424141243000065, 152.4718672074000381 ) ) ; -#23807 = EDGE_CURVE ( 'NONE', #39104, #28131, #20268, .T. ) ; -#23808 = AXIS2_PLACEMENT_3D ( 'NONE', #3566, #16045, #19313 ) ; -#23809 = AXIS2_PLACEMENT_3D ( 'NONE', #8775, #30848, #15501 ) ; -#23810 = ORIENTED_EDGE ( 'NONE', *, *, #24059, .F. ) ; -#23811 = CARTESIAN_POINT ( 'NONE', ( 31.79629795468130027, 77.14301703112144537, 291.5393397680163616 ) ) ; -#23812 = AXIS2_PLACEMENT_3D ( 'NONE', #15856, #28352, #321 ) ; -#23813 = EDGE_CURVE ( 'NONE', #10234, #13401, #9321, .T. ) ; -#23814 = EDGE_CURVE ( 'NONE', #9576, #3624, #9136, .T. ) ; -#23816 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250907130, 179.1753088543010222, 103.5954339977679126 ) ) ; -#23815 = CARTESIAN_POINT ( 'NONE', ( 13.80919085533496116, 135.4028283656384986, 90.90478696006167070 ) ) ; -#23817 = EDGE_CURVE ( 'NONE', #33081, #7841, #39476, .T. ) ; -#23818 = ORIENTED_EDGE ( 'NONE', *, *, #1179, .F. ) ; -#23819 = ORIENTED_EDGE ( 'NONE', *, *, #9836, .T. ) ; -#23820 = EDGE_CURVE ( 'NONE', #14260, #9552, #18808, .T. ) ; -#23821 = VERTEX_POINT ( 'NONE', #32941 ) ; -#23822 = CARTESIAN_POINT ( 'NONE', ( -1.208357120606557533, 136.1559913323450246, 176.2419420377342760 ) ) ; -#23823 = LINE ( 'NONE', #5192, #17644 ) ; -#23824 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568733 ) ) ; -#23825 = ORIENTED_EDGE ( 'NONE', *, *, #7366, .T. ) ; -#23826 = ORIENTED_EDGE ( 'NONE', *, *, #8732, .F. ) ; -#23827 = DIRECTION ( 'NONE', ( -1.001359783477163956E-17, 0.9743043966640315690, 0.2252353050503800580 ) ) ; -#23828 = ORIENTED_EDGE ( 'NONE', *, *, #21751, .F. ) ; -#23829 = VERTEX_POINT ( 'NONE', #14357 ) ; -#23830 = FACE_OUTER_BOUND ( 'NONE', #29749, .T. ) ; -#23831 = CARTESIAN_POINT ( 'NONE', ( 3.044162729732000194, 208.9211496470000213, 73.11923083157999770 ) ) ; -#23832 = CARTESIAN_POINT ( 'NONE', ( -2.851224489384554861, 209.7096574326964458, 76.06022722088786736 ) ) ; -#23833 = ORIENTED_EDGE ( 'NONE', *, *, #28034, .T. ) ; -#23834 = ORIENTED_EDGE ( 'NONE', *, *, #31018, .T. ) ; -#23835 = DIRECTION ( 'NONE', ( 0.7072262180194089920, 0.6509452856072081017, 0.2758646619118033660 ) ) ; -#23836 = CARTESIAN_POINT ( 'NONE', ( -40.80866763254666552, 127.3612606828822891, 89.59438440209265764 ) ) ; -#23837 = CARTESIAN_POINT ( 'NONE', ( -35.65792458881000471, 191.9570647582000049, 104.0584178364000110 ) ) ; -#23838 = CARTESIAN_POINT ( 'NONE', ( 36.58238559271000412, 191.1514690895999991, 103.6232305048999933 ) ) ; -#23839 = VERTEX_POINT ( 'NONE', #18202 ) ; -#23840 = DIRECTION ( 'NONE', ( -0.0005884949961261976481, 0.2255194585872562218, -0.9742384859325514679 ) ) ; -#23841 = AXIS2_PLACEMENT_3D ( 'NONE', #12576, #37531, #27564 ) ; -#23842 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319394906738 ) ) ; -#23843 = ORIENTED_EDGE ( 'NONE', *, *, #13946, .F. ) ; -#23844 = CARTESIAN_POINT ( 'NONE', ( -20.49973909911777881, 191.9757886370473443, 104.4339460251406706 ) ) ; -#23845 = CARTESIAN_POINT ( 'NONE', ( -76.10925030609094222, 156.2249461908077421, 96.27941314734424338 ) ) ; -#23846 = CARTESIAN_POINT ( 'NONE', ( -15.49892152445502269, 185.4935632634996807, 104.3684056661689397 ) ) ; -#23847 = ORIENTED_EDGE ( 'NONE', *, *, #9641, .F. ) ; -#23848 = VECTOR ( 'NONE', #19644, 1000.000000000000114 ) ; -#23849 = DIRECTION ( 'NONE', ( -0.0005884949961209497843, 0.2249510543439031118, -0.9743698870671271273 ) ) ; -#23850 = DIRECTION ( 'NONE', ( 0.9999998268369121313, 0.0001323825517318003638, -0.0005734117245120936733 ) ) ; -#23851 = VECTOR ( 'NONE', #8396, 1000.000000000000000 ) ; -#23852 = CARTESIAN_POINT ( 'NONE', ( 24.12246166080794652, 148.1961369715741341, 202.2538559978290493 ) ) ; -#23853 = CARTESIAN_POINT ( 'NONE', ( 30.07038801304316777, 174.6845315262252143, 103.0427758964743816 ) ) ; -#23854 = ORIENTED_EDGE ( 'NONE', *, *, #14824, .T. ) ; -#23855 = LINE ( 'NONE', #30189, #25730 ) ; -#23856 = LINE ( 'NONE', #33442, #1650 ) ; -#23857 = CARTESIAN_POINT ( 'NONE', ( -15.99970515225999179, 151.9770228117144484, 94.74935186622352035 ) ) ; -#23858 = EDGE_CURVE ( 'NONE', #11457, #13536, #33754, .T. ) ; -#23859 = ORIENTED_EDGE ( 'NONE', *, *, #24909, .F. ) ; -#23860 = CARTESIAN_POINT ( 'NONE', ( 20.48555995111231809, 211.0898943587194481, 73.54694346759191603 ) ) ; -#23861 = CARTESIAN_POINT ( 'NONE', ( -12.60649365401999944, 165.2216646563843199, 152.9217693939943388 ) ) ; -#23862 = CARTESIAN_POINT ( 'NONE', ( 36.11364262193256280, 191.5260145455536929, 103.8483746271915322 ) ) ; -#23863 = CARTESIAN_POINT ( 'NONE', ( -24.55651442736381895, 213.0895335167360543, 73.57320146239435132 ) ) ; -#23864 = EDGE_CURVE ( 'NONE', #14925, #17057, #36004, .T. ) ; -#23865 = CARTESIAN_POINT ( 'NONE', ( 5.674687014606257129, 130.3475820607916660, 92.82156578849662765 ) ) ; -#23866 = DIRECTION ( 'NONE', ( -0.0006039748319388143485, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#23867 = ORIENTED_EDGE ( 'NONE', *, *, #38295, .F. ) ; -#23868 = EDGE_CURVE ( 'NONE', #24000, #28951, #27652, .T. ) ; -#23869 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2117, #20916, #23179, #5569 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23870 = CIRCLE ( 'NONE', #6225, 2.250000000025557778 ) ; -#23871 = DIRECTION ( 'NONE', ( -0.0005884949961229519804, 0.2249510543439058041, -0.9743698870671265722 ) ) ; -#23872 = EDGE_CURVE ( 'NONE', #32617, #8891, #37828, .T. ) ; -#23873 = AXIS2_PLACEMENT_3D ( 'NONE', #34484, #25326, #15310 ) ; -#23874 = CARTESIAN_POINT ( 'NONE', ( 23.39351881373000097, 163.2729245447999915, 152.4718672074000381 ) ) ; -#23876 = AXIS2_PLACEMENT_3D ( 'NONE', #592, #12671, #793 ) ; -#23875 = CARTESIAN_POINT ( 'NONE', ( 20.31643133402063128, 211.0882409943167204, 73.38274506984599554 ) ) ; -#23877 = CARTESIAN_POINT ( 'NONE', ( 13.50046316317049566, 187.7460073498711495, 103.5025028263219014 ) ) ; -#23878 = DIRECTION ( 'NONE', ( 0.7856637149787866203, -0.6186538021912836305, 0.000000000000000000 ) ) ; -#23879 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#23880 = VECTOR ( 'NONE', #6601, 1000.000000000000000 ) ; -#23881 = CARTESIAN_POINT ( 'NONE', ( 28.70581487418796129, 148.8854600315911796, 94.52165327196804867 ) ) ; -#23882 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39913, #11714, #30730, #8862 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23883 = DIRECTION ( 'NONE', ( 0.0005884949961246697904, -0.2249510543439056376, 0.9743698870671265722 ) ) ; -#23884 = ORIENTED_EDGE ( 'NONE', *, *, #31664, .T. ) ; -#23885 = ORIENTED_EDGE ( 'NONE', *, *, #21797, .F. ) ; -#23886 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971570121 ) ) ; -#23887 = CARTESIAN_POINT ( 'NONE', ( 3.755190925667593937, 144.1654378765031765, 93.16053287089553692 ) ) ; -#23888 = FACE_BOUND ( 'NONE', #31684, .T. ) ; -#23889 = EDGE_LOOP ( 'NONE', ( #38914, #5634, #26775, #30644 ) ) ; -#23890 = LINE ( 'NONE', #17722, #1763 ) ; -#23891 = CARTESIAN_POINT ( 'NONE', ( -6.272775217941449988, 148.2033965809511074, 96.43792127017829330 ) ) ; -#23892 = VERTEX_POINT ( 'NONE', #21709 ) ; -#23893 = CARTESIAN_POINT ( 'NONE', ( 0.04503145192458000295, 271.9029643395999756, 74.55847715811999876 ) ) ; -#23894 = LINE ( 'NONE', #33883, #13155 ) ; -#23895 = ORIENTED_EDGE ( 'NONE', *, *, #13788, .T. ) ; -#23896 = DIRECTION ( 'NONE', ( 0.0006039748319382907873, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#23897 = CARTESIAN_POINT ( 'NONE', ( 3.535852102820259191, 167.8277681301466941, 101.4758341492079410 ) ) ; -#23898 = CARTESIAN_POINT ( 'NONE', ( -36.07906380798383594, 114.1210279025020640, 89.76624208691289653 ) ) ; -#23899 = CARTESIAN_POINT ( 'NONE', ( -77.80691370946981067, 191.9356020547612900, 194.2498739115223145 ) ) ; -#23900 = CONICAL_SURFACE ( 'NONE', #9536, 6.000002063501014504, 0.7853981633766364823 ) ; -#23901 = DIRECTION ( 'NONE', ( -0.6087614115774880874, -0.7729348350621346730, -0.1788331191967951483 ) ) ; -#23902 = ORIENTED_EDGE ( 'NONE', *, *, #16273, .T. ) ; -#23903 = CARTESIAN_POINT ( 'NONE', ( 38.96275200744000244, 119.0759358096000113, 87.81759083996999493 ) ) ; -#23904 = DIRECTION ( 'NONE', ( -9.819286345289026293E-14, -0.9743700557546187691, -0.2249510934597585554 ) ) ; -#23905 = DIRECTION ( 'NONE', ( 0.0005884949961232365835, -0.2249510543439025012, 0.9743698870671272383 ) ) ; -#23906 = ADVANCED_FACE ( 'NONE', ( #27855 ), #17140, .F. ) ; -#23907 = VECTOR ( 'NONE', #30157, 1000.000000000000114 ) ; -#23909 = ORIENTED_EDGE ( 'NONE', *, *, #19418, .F. ) ; -#23908 = EDGE_CURVE ( 'NONE', #5720, #13097, #30907, .T. ) ; -#23910 = CARTESIAN_POINT ( 'NONE', ( 16.56210604780206097, 152.2139753621886200, 181.5173256375959454 ) ) ; -#23911 = VERTEX_POINT ( 'NONE', #15745 ) ; -#23912 = EDGE_CURVE ( 'NONE', #4266, #39205, #2141, .T. ) ; -#23913 = CONICAL_SURFACE ( 'NONE', #6258, 59.40509992922268623, 0.7853981633972876297 ) ; -#23914 = ORIENTED_EDGE ( 'NONE', *, *, #15038, .F. ) ; -#23915 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#23916 = EDGE_CURVE ( 'NONE', #36914, #8, #12690, .T. ) ; -#23917 = CARTESIAN_POINT ( 'NONE', ( -42.90458491324071133, 121.0778554138752696, 91.06191244779695637 ) ) ; -#23918 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#23919 = CARTESIAN_POINT ( 'NONE', ( -38.93661188361225811, 190.9636370701329042, 106.3296290494274814 ) ) ; -#23920 = CARTESIAN_POINT ( 'NONE', ( -26.01494426630450008, 211.0902259182902014, 73.07465174665132679 ) ) ; -#23921 = ADVANCED_FACE ( 'NONE', ( #29440 ), #29033, .T. ) ; -#23922 = FACE_OUTER_BOUND ( 'NONE', #36068, .T. ) ; -#23923 = CARTESIAN_POINT ( 'NONE', ( -20.89285664280696864, 129.6089482465050366, 89.58812326051432251 ) ) ; -#23924 = CARTESIAN_POINT ( 'NONE', ( 19.98232544185748694, 209.7096131673859816, 76.04619115725449774 ) ) ; -#23925 = EDGE_CURVE ( 'NONE', #7306, #11263, #38818, .T. ) ; -#23926 = CARTESIAN_POINT ( 'NONE', ( 38.31866179960999830, 118.8458981293999983, 87.57078246666000609 ) ) ; -#23927 = CARTESIAN_POINT ( 'NONE', ( 37.43095215650283336, 132.6072067203139966, 336.9709689194860402 ) ) ; -#23928 = DIRECTION ( 'NONE', ( 0.9999998355993788834, 0.000000000000000000, -0.0005734119072321743841 ) ) ; -#23929 = ORIENTED_EDGE ( 'NONE', *, *, #8601, .T. ) ; -#23930 = CARTESIAN_POINT ( 'NONE', ( -19.99823416869160653, 118.9403737594142854, 90.20346087292679726 ) ) ; -#23931 = CARTESIAN_POINT ( 'NONE', ( -34.02805798185369213, 127.1714145380894934, 297.5790971239380269 ) ) ; -#23932 = AXIS2_PLACEMENT_3D ( 'NONE', #10168, #19733, #34862 ) ; -#23933 = CARTESIAN_POINT ( 'NONE', ( 35.67229871239999994, 112.8254580524999966, 87.36424608503999423 ) ) ; -#23934 = CIRCLE ( 'NONE', #18033, 22.00000000001089973 ) ; -#23936 = ORIENTED_EDGE ( 'NONE', *, *, #18850, .F. ) ; -#23935 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178587041921E-05, 0.0002331579774917524482 ) ) ; -#23937 = VERTEX_POINT ( 'NONE', #13100 ) ; -#23938 = ORIENTED_EDGE ( 'NONE', *, *, #11278, .F. ) ; -#23939 = DIRECTION ( 'NONE', ( -3.469446951775313086E-15, 0.9743700557921582961, 0.2249510932971566790 ) ) ; -#23940 = ORIENTED_EDGE ( 'NONE', *, *, #4323, .F. ) ; -#23941 = CARTESIAN_POINT ( 'NONE', ( 26.80352412410122653, 110.6131156702000027, 87.25159563508790939 ) ) ; -#23942 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971541810 ) ) ; -#23943 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2525, #17829, #21344, #24416 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23944 = AXIS2_PLACEMENT_3D ( 'NONE', #9922, #19298, #3359 ) ; -#23945 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37345, #31616, #37538, #12806 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999992928476323373 ), - .UNSPECIFIED. ) ; -#23946 = VERTEX_POINT ( 'NONE', #20012 ) ; -#23947 = CARTESIAN_POINT ( 'NONE', ( 41.04524146633079340, 217.7719116456999870, 73.53371387620883581 ) ) ; -#23948 = LINE ( 'NONE', #8612, #31917 ) ; -#23949 = CARTESIAN_POINT ( 'NONE', ( -20.35105629446761810, 205.4136997713417827, 76.24793642633174784 ) ) ; -#23950 = CARTESIAN_POINT ( 'NONE', ( -37.98047323488999893, 118.5895443490000076, 87.61478617256000234 ) ) ; -#23951 = ORIENTED_EDGE ( 'NONE', *, *, #32216, .T. ) ; -#23952 = LINE ( 'NONE', #11882, #17297 ) ; -#23953 = ORIENTED_EDGE ( 'NONE', *, *, #7348, .T. ) ; -#23954 = LINE ( 'NONE', #11067, #18777 ) ; -#23955 = CARTESIAN_POINT ( 'NONE', ( -6.678738644527168193E-14, 150.3212993284946606, 97.43624128390267458 ) ) ; -#23956 = FACE_OUTER_BOUND ( 'NONE', #10553, .T. ) ; -#23957 = ORIENTED_EDGE ( 'NONE', *, *, #36264, .T. ) ; -#23958 = CARTESIAN_POINT ( 'NONE', ( -45.30254285283432836, 123.8728708323052530, 93.41010951591879063 ) ) ; -#23959 = CARTESIAN_POINT ( 'NONE', ( 0.6024761863935000905, 188.6227430405999996, 103.2008371842000116 ) ) ; -#23960 = DIRECTION ( 'NONE', ( 0.7730662169443226484, 0.5272861007345267526, 0.3526159273084130130 ) ) ; -#23961 = CARTESIAN_POINT ( 'NONE', ( -36.15565225323541654, 190.9881546654719955, 106.8454183269966933 ) ) ; -#23962 = AXIS2_PLACEMENT_3D ( 'NONE', #12179, #6028, #30583 ) ; -#23963 = EDGE_CURVE ( 'NONE', #18635, #36684, #35396, .T. ) ; -#23964 = ORIENTED_EDGE ( 'NONE', *, *, #12189, .F. ) ; -#23965 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319697732, 89.77447388934736239, 291.5295797804315612 ) ) ; -#23966 = EDGE_CURVE ( 'NONE', #35463, #17707, #3424, .T. ) ; -#23967 = VECTOR ( 'NONE', #33518, 1000.000000000000000 ) ; -#23968 = EDGE_LOOP ( 'NONE', ( #19877, #15138, #26985, #18783 ) ) ; -#23969 = AXIS2_PLACEMENT_3D ( 'NONE', #23457, #22670, #17295 ) ; -#23970 = AXIS2_PLACEMENT_3D ( 'NONE', #28312, #28120, #10918 ) ; -#23971 = EDGE_LOOP ( 'NONE', ( #36611, #1590, #2759 ) ) ; -#23972 = VERTEX_POINT ( 'NONE', #4475 ) ; -#23973 = CARTESIAN_POINT ( 'NONE', ( -28.52670407937950969, 187.4270078119665754, 102.9410870260050928 ) ) ; -#23974 = DIRECTION ( 'NONE', ( -0.0004161288024659176468, -0.5299192578491020988, -0.8480479980505092330 ) ) ; -#23975 = DIRECTION ( 'NONE', ( -0.1305262051638081122, -0.9660383184132187440, -0.2230086929312311284 ) ) ; -#23976 = CARTESIAN_POINT ( 'NONE', ( -25.50905134446982814, 211.0902258593999932, 74.90585137389213344 ) ) ; -#23977 = ORIENTED_EDGE ( 'NONE', *, *, #19678, .F. ) ; -#23978 = LINE ( 'NONE', #26434, #10829 ) ; -#23979 = ORIENTED_EDGE ( 'NONE', *, *, #18634, .F. ) ; -#23980 = CARTESIAN_POINT ( 'NONE', ( 27.65543316470899526, 123.9742713734289907, 91.34205566895781203 ) ) ; -#23981 = CARTESIAN_POINT ( 'NONE', ( -35.46040159328508423, 192.0851836084571573, 103.9436889710039509 ) ) ; -#23983 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#23982 = LINE ( 'NONE', #23562, #30402 ) ; -#23984 = VERTEX_POINT ( 'NONE', #1010 ) ; -#23985 = ADVANCED_FACE ( 'NONE', ( #13497 ), #32109, .F. ) ; -#23986 = ORIENTED_EDGE ( 'NONE', *, *, #34992, .F. ) ; -#23987 = AXIS2_PLACEMENT_3D ( 'NONE', #27367, #33861, #15272 ) ; -#23988 = ORIENTED_EDGE ( 'NONE', *, *, #13200, .F. ) ; -#23989 = CARTESIAN_POINT ( 'NONE', ( 39.08959358783000226, 118.7615907617999937, 89.51972163240000668 ) ) ; -#23990 = CARTESIAN_POINT ( 'NONE', ( 12.50955560414800338, 154.7292631241200809, 156.6833918255910874 ) ) ; -#23991 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19240, #35171, #25413, #7183 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 1.364025899357880227E-07, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#23992 = CARTESIAN_POINT ( 'NONE', ( 25.99211731546482795, 209.7096512574500480, 76.04280604205342797 ) ) ; -#23993 = CARTESIAN_POINT ( 'NONE', ( 19.99976926757112849, 160.7481248081381295, 96.75239270071580222 ) ) ; -#23994 = ORIENTED_EDGE ( 'NONE', *, *, #14905, .F. ) ; -#23995 = ORIENTED_EDGE ( 'NONE', *, *, #1816, .T. ) ; -#23996 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319388572829 ) ) ; -#23997 = CARTESIAN_POINT ( 'NONE', ( 15.69892041351113932, 187.1166384466105796, 102.8427215779686605 ) ) ; -#23998 = ORIENTED_EDGE ( 'NONE', *, *, #14355, .T. ) ; -#23999 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#24000 = VERTEX_POINT ( 'NONE', #39027 ) ; -#24001 = ADVANCED_FACE ( 'NONE', ( #23922 ), #8023, .F. ) ; -#24002 = CARTESIAN_POINT ( 'NONE', ( 2.633415369384000115, 190.2731404274000226, 106.2916909573000055 ) ) ; -#24003 = EDGE_CURVE ( 'NONE', #28125, #33123, #19103, .T. ) ; -#24004 = ORIENTED_EDGE ( 'NONE', *, *, #7077, .F. ) ; -#24005 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049171541, 157.6243160761467266, 99.14398654756077178 ) ) ; -#24006 = CARTESIAN_POINT ( 'NONE', ( -22.99922046160000022, 115.1130721137993191, 90.28167579205376114 ) ) ; -#24007 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971550137 ) ) ; -#24008 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825940092507032, 0.0005734119019213044762 ) ) ; -#24009 = AXIS2_PLACEMENT_3D ( 'NONE', #31336, #3495, #8869 ) ; -#24010 = ORIENTED_EDGE ( 'NONE', *, *, #34309, .T. ) ; -#24011 = CARTESIAN_POINT ( 'NONE', ( 25.99161516108275904, 205.5538991746897750, 75.22020848238861390 ) ) ; -#24012 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#24013 = AXIS2_PLACEMENT_3D ( 'NONE', #10600, #32856, #26543 ) ; -#24014 = CARTESIAN_POINT ( 'NONE', ( 58.66975477332916711, 246.4867810014529823, 202.1076182964096120 ) ) ; -#24015 = VERTEX_POINT ( 'NONE', #26787 ) ; -#24016 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#24017 = ORIENTED_EDGE ( 'NONE', *, *, #22063, .T. ) ; -#24019 = CARTESIAN_POINT ( 'NONE', ( 2.546554931011165923, 207.4083916550792424, 77.08013917139633975 ) ) ; -#24018 = CARTESIAN_POINT ( 'NONE', ( 24.01770307888959621, 118.3486789263952517, 189.6358675532988229 ) ) ; -#24020 = VERTEX_POINT ( 'NONE', #8379 ) ; -#24021 = ORIENTED_EDGE ( 'NONE', *, *, #12194, .T. ) ; -#24022 = ADVANCED_FACE ( 'NONE', ( #17953 ), #14553, .F. ) ; -#24023 = ORIENTED_EDGE ( 'NONE', *, *, #29904, .T. ) ; -#24024 = CARTESIAN_POINT ( 'NONE', ( 2.923530179117999950, 209.0467129328000055, 76.04238949198999364 ) ) ; -#24025 = LINE ( 'NONE', #14623, #38546 ) ; -#24026 = CARTESIAN_POINT ( 'NONE', ( 44.18542131443735599, 185.8340086539333527, 107.6130707359650671 ) ) ; -#24027 = CARTESIAN_POINT ( 'NONE', ( 12.64087841763192976, 177.6494266093880583, 100.7817535531127220 ) ) ; -#24028 = ORIENTED_EDGE ( 'NONE', *, *, #26538, .T. ) ; -#24029 = VERTEX_POINT ( 'NONE', #39232 ) ; -#24030 = CARTESIAN_POINT ( 'NONE', ( -14.16859886990510731, 176.0439122282943458, 102.8701808096547126 ) ) ; -#24031 = ORIENTED_EDGE ( 'NONE', *, *, #24145, .F. ) ; -#24032 = ORIENTED_EDGE ( 'NONE', *, *, #39168, .F. ) ; -#24033 = DIRECTION ( 'NONE', ( -0.0006039748319385906776, -1.894780628693970208E-14, -0.9999998176071844824 ) ) ; -#24034 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498896523, 176.3880814481161678, 103.4433606027125876 ) ) ; -#24035 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319697732, 89.77447388934736239, 291.5295797804315612 ) ) ; -#24036 = VERTEX_POINT ( 'NONE', #8169 ) ; -#24037 = EDGE_CURVE ( 'NONE', #39966, #8486, #30861, .T. ) ; -#24038 = CONICAL_SURFACE ( 'NONE', #9677, 10.00000000001786482, 0.7853981633973029508 ) ; -#24039 = EDGE_LOOP ( 'NONE', ( #22824, #5348, #32212, #15507 ) ) ; -#24040 = FACE_OUTER_BOUND ( 'NONE', #35745, .T. ) ; -#24041 = CARTESIAN_POINT ( 'NONE', ( 22.99270477044632344, 214.0899081099834689, 76.04459013870678064 ) ) ; -#24042 = CARTESIAN_POINT ( 'NONE', ( -35.89237578347999857, 192.0714260180999986, 104.3144186237000213 ) ) ; -#24043 = FACE_OUTER_BOUND ( 'NONE', #2419, .T. ) ; -#24044 = ORIENTED_EDGE ( 'NONE', *, *, #37060, .F. ) ; -#24045 = LINE ( 'NONE', #8089, #15049 ) ; -#24046 = AXIS2_PLACEMENT_3D ( 'NONE', #6858, #16068, #31421 ) ; -#24047 = ADVANCED_FACE ( 'NONE', ( #15703 ), #6043, .F. ) ; -#24048 = VERTEX_POINT ( 'NONE', #6102 ) ; -#24049 = FACE_OUTER_BOUND ( 'NONE', #12968, .T. ) ; -#24050 = CYLINDRICAL_SURFACE ( 'NONE', #38250, 4.000000000000000000 ) ; -#24051 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; -#24052 = ORIENTED_EDGE ( 'NONE', *, *, #19999, .F. ) ; -#24053 = CARTESIAN_POINT ( 'NONE', ( 0.8403833798046884684, 188.6282387687823530, 103.2006762577494499 ) ) ; -#24054 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39908, #5359, #8653, #18017, #18223, #30727, #27878, #2719, #27671, #33970, #5971, #22125, #829, #3097, #34368, #22726, #19026, #15961, #31517, #38046 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999693301, 0.1874999999999585332, 0.2187499999999572564, 0.2343749999999562295, 0.2499999999999552025, 0.4999999999999809042, 0.6249999999999945599, 0.6875000000000004441, 0.7187500000000023315, 0.7343750000000032196, 0.7500000000000041078, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24055 = EDGE_CURVE ( 'NONE', #19089, #9253, #10083, .T. ) ; -#24056 = CARTESIAN_POINT ( 'NONE', ( -14.42530073247155720, 176.7775577408967536, 100.6450012727129604 ) ) ; -#24057 = ADVANCED_FACE ( 'NONE', ( #10140 ), #34758, .T. ) ; -#24058 = LINE ( 'NONE', #27342, #36632 ) ; -#24059 = EDGE_CURVE ( 'NONE', #40319, #24779, #7048, .T. ) ; -#24060 = ORIENTED_EDGE ( 'NONE', *, *, #25588, .F. ) ; -#24061 = CARTESIAN_POINT ( 'NONE', ( -21.09366915965894052, 182.9316659667568672, 101.8987661775678646 ) ) ; -#24062 = EDGE_CURVE ( 'NONE', #37119, #3824, #14934, .T. ) ; -#24063 = CARTESIAN_POINT ( 'NONE', ( 2.243807508789410932, 189.9164095999701942, 103.9478535516479525 ) ) ; -#24064 = CARTESIAN_POINT ( 'NONE', ( 27.20828230392673319, 188.6004222997412967, 103.1783301543543558 ) ) ; -#24065 = ORIENTED_EDGE ( 'NONE', *, *, #8155, .F. ) ; -#24066 = CARTESIAN_POINT ( 'NONE', ( -38.36106832263448752, 118.8212171802660606, 87.72011982685570786 ) ) ; -#24067 = VERTEX_POINT ( 'NONE', #16052 ) ; -#24068 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #12722, #2732, #34568, #31538 ), - .UNSPECIFIED., .F., .F. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.944787670326749243E-14, 1.570060973614819666 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8049111466635345824, 0.8049111466635345824, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#24069 = CARTESIAN_POINT ( 'NONE', ( -5.668109638568818553, 183.4491308723886789, 105.0878286196073645 ) ) ; -#24070 = CARTESIAN_POINT ( 'NONE', ( -12.63810009328765815, 175.3544237672228121, 100.1411543447596983 ) ) ; -#24071 = CARTESIAN_POINT ( 'NONE', ( 25.37978428000000264, 192.2113631761999955, 104.5397008112999941 ) ) ; -#24072 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #40067, #34128, #37415, #30487 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 1.247272850135699217E-05, 0.0003357035447835687012 ), - .UNSPECIFIED. ) ; -#24073 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474974874276943, 155.7928101624827946, 98.18628735359691007 ) ) ; -#24074 = ORIENTED_EDGE ( 'NONE', *, *, #3760, .T. ) ; -#24075 = VECTOR ( 'NONE', #1552, 1000.000000000000000 ) ; -#24076 = VECTOR ( 'NONE', #35210, 1000.000000000000114 ) ; -#24077 = DIRECTION ( 'NONE', ( -0.6087614810001763521, 0.7729390313185928729, 0.1788147452386053549 ) ) ; -#24078 = CARTESIAN_POINT ( 'NONE', ( 19.99866638146631104, 191.9758059840616227, 106.9124836309507884 ) ) ; -#24079 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971574562 ) ) ; -#24080 = CARTESIAN_POINT ( 'NONE', ( -3.763919581963022676, 137.3023230737443896, 91.58620352610245163 ) ) ; -#24081 = CARTESIAN_POINT ( 'NONE', ( -19.99970941558080284, 118.1131156714892114, 90.27986793006986943 ) ) ; -#24082 = CARTESIAN_POINT ( 'NONE', ( -25.99970180910912632, 119.7153706046975543, 90.38600776144058102 ) ) ; -#24083 = CARTESIAN_POINT ( 'NONE', ( -25.49004383460846057, 191.2291505275362340, 106.3759092483763737 ) ) ; -#24084 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#24085 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#24086 = ORIENTED_EDGE ( 'NONE', *, *, #6659, .T. ) ; -#24087 = FACE_OUTER_BOUND ( 'NONE', #21021, .T. ) ; -#24088 = CARTESIAN_POINT ( 'NONE', ( -32.08517628747592454, 135.8679722276884263, 91.03989294943069410 ) ) ; -#24089 = EDGE_CURVE ( 'NONE', #726, #21825, #19317, .T. ) ; -#24090 = ORIENTED_EDGE ( 'NONE', *, *, #1269, .F. ) ; -#24091 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684796025, 217.7719116314000019, 75.57961659102821272 ) ) ; -#24092 = CARTESIAN_POINT ( 'NONE', ( 22.95436083522999837, 211.0902260770999987, 13.53038997162000001 ) ) ; -#24093 = EDGE_LOOP ( 'NONE', ( #5194, #3986 ) ) ; -#24094 = LINE ( 'NONE', #2218, #38544 ) ; -#24095 = VECTOR ( 'NONE', #14940, 1000.000000000000114 ) ; -#24096 = EDGE_CURVE ( 'NONE', #25840, #20231, #18313, .T. ) ; -#24097 = CARTESIAN_POINT ( 'NONE', ( 16.23669227365375178, 152.0555296727118559, 181.0551735875241093 ) ) ; -#24098 = DIRECTION ( 'NONE', ( 0.0006039748319390980842, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#24099 = FACE_OUTER_BOUND ( 'NONE', #4547, .T. ) ; -#24100 = VERTEX_POINT ( 'NONE', #3174 ) ; -#24101 = CARTESIAN_POINT ( 'NONE', ( 30.77384432821773075, 154.8931025985799863, 195.9769581536852741 ) ) ; -#24102 = EDGE_CURVE ( 'NONE', #34936, #28826, #6155, .T. ) ; -#24103 = AXIS2_PLACEMENT_3D ( 'NONE', #5275, #23489, #11420 ) ; -#24104 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#24105 = CONICAL_SURFACE ( 'NONE', #19494, 2.999999999919165550, 0.7853981633921003347 ) ; -#24106 = CARTESIAN_POINT ( 'NONE', ( -46.25578703409212267, 126.0671570396426659, 91.86466764140388364 ) ) ; -#24107 = DIRECTION ( 'NONE', ( -0.7856637153356348380, 0.6186538017381019161, 0.000000000000000000 ) ) ; -#24108 = VECTOR ( 'NONE', #810, 1000.000000000000227 ) ; -#24109 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142367503004439, 137.4659008082804519, 177.5714312369109393 ) ) ; -#24110 = EDGE_CURVE ( 'NONE', #30170, #711, #18160, .T. ) ; -#24111 = ORIENTED_EDGE ( 'NONE', *, *, #39031, .F. ) ; -#24112 = CARTESIAN_POINT ( 'NONE', ( 37.94196629854999969, 119.2238566698000000, 87.13002152622999574 ) ) ; -#24113 = CARTESIAN_POINT ( 'NONE', ( 17.99676327751970106, 132.8602135917551266, 90.82840093810243332 ) ) ; -#24114 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#24115 = ORIENTED_EDGE ( 'NONE', *, *, #13162, .F. ) ; -#24116 = CARTESIAN_POINT ( 'NONE', ( 32.66389061773956826, 141.7118122376935219, 282.5421777876526335 ) ) ; -#24117 = CARTESIAN_POINT ( 'NONE', ( -42.69612883678725268, 120.9011579166986223, 92.53537271405176057 ) ) ; -#24118 = DIRECTION ( 'NONE', ( -0.0009686424659220636531, 0.2252351993847904188, -0.9743039395844949047 ) ) ; -#24119 = CARTESIAN_POINT ( 'NONE', ( 16.16561595000348817, 152.0060889837787386, 180.9382316808850533 ) ) ; -#24120 = LINE ( 'NONE', #17950, #38721 ) ; -#24121 = CARTESIAN_POINT ( 'NONE', ( 33.53687168153876996, 218.5902260770998282, 61.03824646354980388 ) ) ; -#24122 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927769952488, 0.0005734119022077144778 ) ) ; -#24123 = FACE_OUTER_BOUND ( 'NONE', #2476, .T. ) ; -#24124 = VECTOR ( 'NONE', #17524, 1000.000000000000000 ) ; -#24125 = CARTESIAN_POINT ( 'NONE', ( 37.92873555815999964, 118.8137886041999991, 87.34311561645002087 ) ) ; -#24126 = PERSON_AND_ORGANIZATION_ROLE ( 'creator' ) ; -#24127 = CARTESIAN_POINT ( 'NONE', ( 25.99904971602028425, 120.7769186021849066, 87.52076664421943519 ) ) ; -#24128 = ORIENTED_EDGE ( 'NONE', *, *, #34145, .F. ) ; -#24129 = CARTESIAN_POINT ( 'NONE', ( 36.06237287903013566, 191.9759150222000130, 101.8996665707920073 ) ) ; -#24130 = DIRECTION ( 'NONE', ( -0.0006039748319386903158, 0.000000000000000000, -0.9999998176071845934 ) ) ; -#24131 = VECTOR ( 'NONE', #3414, 1000.000000000000114 ) ; -#24132 = CARTESIAN_POINT ( 'NONE', ( -25.67411030247916415, 190.9010662205137692, 106.4782255816775347 ) ) ; -#24133 = CARTESIAN_POINT ( 'NONE', ( 35.93711133181000150, 112.8285350512999941, 87.62948096434999457 ) ) ; -#24134 = AXIS2_PLACEMENT_3D ( 'NONE', #8848, #14974, #9039 ) ; -#24135 = ORIENTED_EDGE ( 'NONE', *, *, #9842, .T. ) ; -#24136 = CONICAL_SURFACE ( 'NONE', #28051, 48.00000000001370637, 0.7853981633973088350 ) ; -#24137 = CARTESIAN_POINT ( 'NONE', ( 23.72254622402000024, 114.0103269029000188, 152.4718672074000381 ) ) ; -#24138 = EDGE_LOOP ( 'NONE', ( #34148, #22414, #36933, #2564 ) ) ; -#24139 = EDGE_LOOP ( 'NONE', ( #27326, #31180, #9795, #11329 ) ) ; -#24140 = ORIENTED_EDGE ( 'NONE', *, *, #1500, .F. ) ; -#24141 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#24142 = ORIENTED_EDGE ( 'NONE', *, *, #3690, .F. ) ; -#24143 = CARTESIAN_POINT ( 'NONE', ( 47.95581608532123141, 138.8991522261716227, 291.4101743701981491 ) ) ; -#24144 = ADVANCED_FACE ( 'NONE', ( #27616 ), #27424, .F. ) ; -#24145 = EDGE_CURVE ( 'NONE', #18171, #11951, #37393, .T. ) ; -#24146 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37043, #37239, #9241, #6151 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24147 = CARTESIAN_POINT ( 'NONE', ( -31.65770855151000518, 220.4002260771000010, 152.4718672074000381 ) ) ; -#24148 = EDGE_CURVE ( 'NONE', #36888, #23778, #38310, .T. ) ; -#24149 = EDGE_CURVE ( 'NONE', #2542, #9013, #17361, .T. ) ; -#24150 = ORIENTED_EDGE ( 'NONE', *, *, #15459, .F. ) ; -#24151 = CARTESIAN_POINT ( 'NONE', ( -39.81773669046000208, 119.3672490520999929, 89.66199800214000959 ) ) ; -#24152 = CARTESIAN_POINT ( 'NONE', ( -37.62184588523724926, 212.3970731564136543, 75.58122719057897143 ) ) ; -#24153 = CARTESIAN_POINT ( 'NONE', ( 0.03597117087481289943, -13.74990928990362882, 59.55738949995932785 ) ) ; -#24154 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386905326 ) ) ; -#24155 = VERTEX_POINT ( 'NONE', #26624 ) ; -#24156 = EDGE_CURVE ( 'NONE', #31711, #32274, #40013, .T. ) ; -#24157 = DIRECTION ( 'NONE', ( 0.0005559617637900415204, -0.3907311284895835235, 0.9205046855588372434 ) ) ; -#24158 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971560961 ) ) ; -#24159 = CARTESIAN_POINT ( 'NONE', ( 76.10748482110098223, 155.7951947758797644, 98.14087069364009608 ) ) ; -#24160 = CARTESIAN_POINT ( 'NONE', ( 35.90288022432931569, 114.9671451721747388, 90.24610039920314364 ) ) ; -#24161 = CARTESIAN_POINT ( 'NONE', ( -4.472258755436127942, 188.0486996950087644, 103.0700877984231454 ) ) ; -#24162 = CARTESIAN_POINT ( 'NONE', ( -19.44498994767157996, 147.7083494500389236, 183.5267648320292437 ) ) ; -#24163 = EDGE_CURVE ( 'NONE', #711, #14055, #4748, .T. ) ; -#24164 = ORIENTED_EDGE ( 'NONE', *, *, #2807, .T. ) ; -#24165 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24166 = CARTESIAN_POINT ( 'NONE', ( 0.5626196048780000014, 189.0076182214000369, 103.6939729820999929 ) ) ; -#24167 = DIRECTION ( 'NONE', ( -0.6087614115774880874, -0.7729348350621346730, -0.1788331191967949541 ) ) ; -#24168 = CARTESIAN_POINT ( 'NONE', ( -35.47623439677231261, 192.3170613116924983, 106.9314473276327959 ) ) ; -#24169 = CIRCLE ( 'NONE', #33264, 2.499999996677015446 ) ; -#24170 = AXIS2_PLACEMENT_3D ( 'NONE', #17232, #17027, #38707 ) ; -#24171 = ORIENTED_EDGE ( 'NONE', *, *, #3811, .F. ) ; -#24172 = ORIENTED_EDGE ( 'NONE', *, *, #32675, .T. ) ; -#24173 = CARTESIAN_POINT ( 'NONE', ( -4.036264725700203115, 136.7920597759830628, 93.80205530682346193 ) ) ; -#24174 = VERTEX_POINT ( 'NONE', #7588 ) ; -#24175 = VECTOR ( 'NONE', #21052, 1000.000000000000000 ) ; -#24176 = ADVANCED_FACE ( 'NONE', ( #22750 ), #35991, .F. ) ; -#24177 = VERTEX_POINT ( 'NONE', #32152 ) ; -#24178 = CARTESIAN_POINT ( 'NONE', ( -25.49994349231765867, 120.2054710424039712, 89.98570239460282494 ) ) ; -#24179 = ORIENTED_EDGE ( 'NONE', *, *, #11828, .T. ) ; -#24180 = CARTESIAN_POINT ( 'NONE', ( 22.64037623556000156, 154.1096148157000130, 95.47483195632999298 ) ) ; -#24181 = CARTESIAN_POINT ( 'NONE', ( -42.17438498177038042, 189.1974161214382377, 108.4895825446868827 ) ) ; -#24182 = CARTESIAN_POINT ( 'NONE', ( -43.55091172764321072, 114.1088728472908542, 121.9228533734347906 ) ) ; -#24183 = CARTESIAN_POINT ( 'NONE', ( 38.86524458869443066, 78.89674437744240265, 287.2041492525814874 ) ) ; -#24184 = ORIENTED_EDGE ( 'NONE', *, *, #9933, .T. ) ; -#24185 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700561807847604, -0.2249510916138314776 ) ) ; -#24186 = ORIENTED_EDGE ( 'NONE', *, *, #32627, .T. ) ; -#24187 = CARTESIAN_POINT ( 'NONE', ( 28.53099798254000063, 124.6121974830000028, 91.48367005413001607 ) ) ; -#24188 = CARTESIAN_POINT ( 'NONE', ( -35.95482889959664163, 191.5453567879722527, 103.8962766636049651 ) ) ; -#24189 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21407, #8728, #21606, #5846 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24191 = CARTESIAN_POINT ( 'NONE', ( -25.59112167743846911, 177.7878761659546569, 100.7140007254543121 ) ) ; -#24190 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24192 = ORIENTED_EDGE ( 'NONE', *, *, #8651, .F. ) ; -#24193 = VECTOR ( 'NONE', #32874, 1000.000000000000114 ) ; -#24194 = AXIS2_PLACEMENT_3D ( 'NONE', #13573, #13179, #32186 ) ; -#24195 = VERTEX_POINT ( 'NONE', #16386 ) ; -#24196 = VECTOR ( 'NONE', #23262, 1000.000000000000000 ) ; -#24197 = EDGE_CURVE ( 'NONE', #3422, #31634, #29548, .T. ) ; -#24198 = EDGE_CURVE ( 'NONE', #28275, #844, #4104, .T. ) ; -#24199 = EDGE_LOOP ( 'NONE', ( #6705, #40214, #22541, #33617 ) ) ; -#24200 = CARTESIAN_POINT ( 'NONE', ( 38.81343184944000058, 119.1356832321999946, 90.12174961364000580 ) ) ; -#24201 = DIRECTION ( 'NONE', ( 0.0005559617453743673698, -0.3907311284892681091, 0.9205046855589822385 ) ) ; -#24202 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597321 ) ) ; -#24203 = DIRECTION ( 'NONE', ( 0.0005884949961199763876, -0.2249510543439082189, 0.9743698870671259060 ) ) ; -#24204 = CARTESIAN_POINT ( 'NONE', ( 12.63559769525019760, 130.7554039043622538, 90.06174994595149030 ) ) ; -#24205 = EDGE_LOOP ( 'NONE', ( #18331, #29373, #28482, #850 ) ) ; -#24206 = EDGE_CURVE ( 'NONE', #30170, #36211, #24375, .T. ) ; -#24207 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3621, #26134, #32457, #32652, #33452, #14053 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.005654176964698274729, 0.006914021989763599434, 0.008173867014828924138 ), - .UNSPECIFIED. ) ; -#24208 = ORIENTED_EDGE ( 'NONE', *, *, #7816, .T. ) ; -#24209 = FACE_OUTER_BOUND ( 'NONE', #21272, .T. ) ; -#24210 = CARTESIAN_POINT ( 'NONE', ( 6.035675884397954327, 136.7933931256889650, 93.79627993537543773 ) ) ; -#24211 = FACE_OUTER_BOUND ( 'NONE', #14615, .T. ) ; -#24212 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250102911, 179.6252109630355562, 101.6466942236733502 ) ) ; -#24213 = ORIENTED_EDGE ( 'NONE', *, *, #27348, .F. ) ; -#24214 = EDGE_CURVE ( 'NONE', #34239, #4201, #16498, .T. ) ; -#24215 = ORIENTED_EDGE ( 'NONE', *, *, #2167, .T. ) ; -#24216 = CARTESIAN_POINT ( 'NONE', ( 36.04645032798080706, 209.7096537570166390, 75.53673338561257822 ) ) ; -#24217 = CARTESIAN_POINT ( 'NONE', ( 1.805080888245589099, 188.6616185568467188, 106.3070958968081925 ) ) ; -#24218 = DIRECTION ( 'NONE', ( 0.0005884949961248703678, -0.2249510543439058319, 0.9743698870671263501 ) ) ; -#24219 = CIRCLE ( 'NONE', #7843, 30.49999999999569411 ) ; -#24220 = EDGE_CURVE ( 'NONE', #33804, #24048, #39356, .T. ) ; -#24221 = CIRCLE ( 'NONE', #7199, 4.500000040450174765 ) ; -#24222 = CARTESIAN_POINT ( 'NONE', ( 39.72066838923261400, 121.2692008855572539, 123.5482992136137597 ) ) ; -#24223 = CARTESIAN_POINT ( 'NONE', ( -19.28798288393075921, 116.9568857464341960, 189.5000423914045484 ) ) ; -#24224 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386880390 ) ) ; -#24225 = VECTOR ( 'NONE', #31932, 1000.000000000000114 ) ; -#24226 = ORIENTED_EDGE ( 'NONE', *, *, #21053, .T. ) ; -#24227 = AXIS2_PLACEMENT_3D ( 'NONE', #24281, #8941, #21613 ) ; -#24228 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #12095, #34147 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 0.9772821279367359670 ), - .UNSPECIFIED. ) ; -#24229 = CARTESIAN_POINT ( 'NONE', ( 45.36643772893244630, 116.4348306688925589, 122.4284095013975815 ) ) ; -#24230 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319390483193 ) ) ; -#24231 = ORIENTED_EDGE ( 'NONE', *, *, #28609, .T. ) ; -#24232 = CARTESIAN_POINT ( 'NONE', ( -13.50000076883903510, 154.4042507776735818, 95.30811371979322644 ) ) ; -#24233 = ORIENTED_EDGE ( 'NONE', *, *, #3498, .F. ) ; -#24234 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #16832, #35624, #20933, #2740 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.589500645051687755, 4.589514308577216539 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999844423337, 0.9999999999844423337, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#24236 = LINE ( 'NONE', #27520, #26587 ) ; -#24235 = CARTESIAN_POINT ( 'NONE', ( 1.447658035601137039, 144.9407251426815719, 129.0349007182437049 ) ) ; -#24237 = ORIENTED_EDGE ( 'NONE', *, *, #22810, .F. ) ; -#24238 = EDGE_LOOP ( 'NONE', ( #690, #10119, #30981, #6405 ) ) ; -#24239 = ORIENTED_EDGE ( 'NONE', *, *, #28787, .F. ) ; -#24240 = CARTESIAN_POINT ( 'NONE', ( 2.892746630442000200, 209.4404812580999931, 75.94847571316999790 ) ) ; -#24241 = FACE_OUTER_BOUND ( 'NONE', #15627, .T. ) ; -#24242 = FACE_OUTER_BOUND ( 'NONE', #11899, .T. ) ; -#24243 = ORIENTED_EDGE ( 'NONE', *, *, #10483, .T. ) ; -#24244 = ADVANCED_FACE ( 'NONE', ( #11272 ), #36205, .F. ) ; -#24245 = ORIENTED_EDGE ( 'NONE', *, *, #9599, .T. ) ; -#24246 = CARTESIAN_POINT ( 'NONE', ( -19.46367937371129742, 126.2449231135791052, 175.9963188856066267 ) ) ; -#24247 = ORIENTED_EDGE ( 'NONE', *, *, #24102, .T. ) ; -#24248 = ORIENTED_EDGE ( 'NONE', *, *, #39169, .F. ) ; -#24250 = AXIS2_PLACEMENT_3D ( 'NONE', #28137, #29132, #26265 ) ; -#24249 = CARTESIAN_POINT ( 'NONE', ( -19.46394794124172023, 125.6806896231740751, 178.4345049239138064 ) ) ; -#24251 = AXIS2_PLACEMENT_3D ( 'NONE', #12110, #24598, #12303 ) ; -#24252 = CARTESIAN_POINT ( 'NONE', ( -20.16658013707266761, 191.4887187421555836, 104.0448208598989339 ) ) ; -#24253 = DIRECTION ( 'NONE', ( -0.0005884949961217841863, 0.2249510543439059707, -0.9743698870671263501 ) ) ; -#24254 = ORIENTED_EDGE ( 'NONE', *, *, #11636, .T. ) ; -#24255 = ORIENTED_EDGE ( 'NONE', *, *, #3997, .T. ) ; -#24256 = AXIS2_PLACEMENT_3D ( 'NONE', #7926, #8346, #8553 ) ; -#24257 = ORIENTED_EDGE ( 'NONE', *, *, #23358, .T. ) ; -#24258 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#24259 = AXIS2_PLACEMENT_3D ( 'NONE', #14799, #27283, #11725 ) ; -#24260 = CARTESIAN_POINT ( 'NONE', ( -8.608366704199914565, 290.9053179400343083, 213.0407505633107803 ) ) ; -#24261 = CARTESIAN_POINT ( 'NONE', ( -35.86721096416999899, 191.4607620390000022, 103.7475147376000137 ) ) ; -#24262 = ORIENTED_EDGE ( 'NONE', *, *, #5493, .F. ) ; -#24263 = CARTESIAN_POINT ( 'NONE', ( -25.67606946964000159, 121.0254811276000027, 87.95152064859000518 ) ) ; -#24264 = ORIENTED_EDGE ( 'NONE', *, *, #13873, .T. ) ; -#24265 = CARTESIAN_POINT ( 'NONE', ( -24.95545957861278197, 159.0476773995373208, 180.5017353223074110 ) ) ; -#24266 = CARTESIAN_POINT ( 'NONE', ( 39.75749670546768044, 190.3327792175265074, 106.6496084232941683 ) ) ; -#24267 = ORIENTED_EDGE ( 'NONE', *, *, #38380, .T. ) ; -#24268 = CARTESIAN_POINT ( 'NONE', ( 2.923899559741844456, 190.2918927302490317, 103.5835027169823377 ) ) ; -#24269 = DIRECTION ( 'NONE', ( 2.610758831345079531E-13, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#24270 = CARTESIAN_POINT ( 'NONE', ( -16.00004089843094590, 126.6464682493123917, 88.90122559946476599 ) ) ; -#24271 = CARTESIAN_POINT ( 'NONE', ( 15.89469151744206421, 128.5927809666073927, 173.0004654942144384 ) ) ; -#24272 = EDGE_CURVE ( 'NONE', #37342, #27638, #10805, .T. ) ; -#24273 = FACE_OUTER_BOUND ( 'NONE', #13374, .T. ) ; -#24274 = CARTESIAN_POINT ( 'NONE', ( 39.60379206711759537, 77.57075965540369111, 291.0398443752740718 ) ) ; -#24275 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #13159, #16001 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24276 = VERTEX_POINT ( 'NONE', #23268 ) ; -#24277 = CARTESIAN_POINT ( 'NONE', ( -10.43102010142666636, 177.7899709888353073, 100.7052528220414445 ) ) ; -#24278 = ORIENTED_EDGE ( 'NONE', *, *, #35605, .T. ) ; -#24279 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#24280 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24281 = CARTESIAN_POINT ( 'NONE', ( 1.447658035571013802, 152.0519508787176335, 130.6788418760813784 ) ) ; -#24282 = VECTOR ( 'NONE', #2836, 1000.000000000000114 ) ; -#24283 = LINE ( 'NONE', #20579, #31759 ) ; -#24284 = ORIENTED_EDGE ( 'NONE', *, *, #38013, .T. ) ; -#24285 = EDGE_CURVE ( 'NONE', #34119, #2177, #11525, .T. ) ; -#24286 = FACE_OUTER_BOUND ( 'NONE', #26697, .T. ) ; -#24287 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5708, #18110, #22466, #7498 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24288 = LINE ( 'NONE', #24491, #13534 ) ; -#24289 = EDGE_CURVE ( 'NONE', #36914, #7388, #16713, .T. ) ; -#24290 = LINE ( 'NONE', #1575, #38657 ) ; -#24291 = DIRECTION ( 'NONE', ( 0.0005884949961258157921, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24292 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#24293 = LINE ( 'NONE', #20795, #21544 ) ; -#24294 = DIRECTION ( 'NONE', ( 0.0005884949961260158274, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24295 = LINE ( 'NONE', #14472, #32520 ) ; -#24296 = EDGE_CURVE ( 'NONE', #32946, #14369, #37375, .T. ) ; -#24297 = ADVANCED_FACE ( 'NONE', ( #1183 ), #19762, .F. ) ; -#24298 = PLANE ( 'NONE', #5614 ) ; -#24299 = ORIENTED_EDGE ( 'NONE', *, *, #1638, .F. ) ; -#24300 = ADVANCED_FACE ( 'NONE', ( #21631 ), #30899, .F. ) ; -#24301 = CARTESIAN_POINT ( 'NONE', ( -18.25047883358543643, 148.8013935164445058, 179.6016233685625707 ) ) ; -#24302 = PLANE ( 'NONE', #2778 ) ; -#24303 = FACE_OUTER_BOUND ( 'NONE', #16760, .T. ) ; -#24304 = ORIENTED_EDGE ( 'NONE', *, *, #38211, .T. ) ; -#24305 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501101346, 132.2930706491314936, 93.28496646302122031 ) ) ; -#24306 = CARTESIAN_POINT ( 'NONE', ( -17.34531841451655509, 148.6239897228831239, 177.2780028082611068 ) ) ; -#24307 = AXIS2_PLACEMENT_3D ( 'NONE', #11934, #18633, #30738 ) ; -#24308 = ORIENTED_EDGE ( 'NONE', *, *, #25037, .T. ) ; -#24309 = CARTESIAN_POINT ( 'NONE', ( -38.06878942637000307, 119.2569487920000029, 87.30466660982000349 ) ) ; -#24310 = AXIS2_PLACEMENT_3D ( 'NONE', #2388, #15457, #27951 ) ; -#24311 = CIRCLE ( 'NONE', #39947, 40.00000000000000000 ) ; -#24312 = CARTESIAN_POINT ( 'NONE', ( -3.868308320181239601, 143.6108898970049950, 95.54847815645690901 ) ) ; -#24313 = VERTEX_POINT ( 'NONE', #11613 ) ; -#24314 = CARTESIAN_POINT ( 'NONE', ( 36.19426920368436384, 191.0813240488200790, 106.8190525720156359 ) ) ; -#24315 = CARTESIAN_POINT ( 'NONE', ( -44.78361369234769285, 123.5315818933150638, 88.22160218664450326 ) ) ; -#24316 = FACE_OUTER_BOUND ( 'NONE', #38110, .T. ) ; -#24317 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8770, #40028, #24724, #6279 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 6.123799525086606188, 7.674909438896238001 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8093550745305059246, 0.8093550745305059246, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#24318 = CARTESIAN_POINT ( 'NONE', ( 30.07151994636415893, 176.9016356171800055, 103.2549657627566262 ) ) ; -#24319 = CARTESIAN_POINT ( 'NONE', ( 13.47345847663963880, 153.8080446478709575, 95.66732164731912746 ) ) ; -#24320 = VERTEX_POINT ( 'NONE', #5254 ) ; -#24321 = ORIENTED_EDGE ( 'NONE', *, *, #17228, .F. ) ; -#24322 = CARTESIAN_POINT ( 'NONE', ( 15.10888617544567047, 175.7086446263182609, 103.2882499569403336 ) ) ; -#24323 = LINE ( 'NONE', #7737, #39467 ) ; -#24324 = CARTESIAN_POINT ( 'NONE', ( 40.77345084030530842, 111.1478968208657818, 141.5557280835205631 ) ) ; -#24325 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23897, #7728, #20194, #4667, #39008, #6082, #34471, #30639, #2633, #21837, #22042, #28184, #31039, #18731, #3008, #3205, #37365 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999997805367, 0.1874999999996615485, 0.2187499999996115052, 0.2343749999996013744, 0.2421874999995963229, 0.2499999999995912714, 0.3749999999996251332, 0.4374999999996631583, 0.4999999999997011280, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24326 = VERTEX_POINT ( 'NONE', #8551 ) ; -#24327 = DIRECTION ( 'NONE', ( 0.0008702530711002103318, -0.2253087760482092305, 0.9742870203873447155 ) ) ; -#24328 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16947, #1424, #20025, #16164 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24329 = CARTESIAN_POINT ( 'NONE', ( -43.76721067839228141, 120.3817750124939323, 91.13402268011530794 ) ) ; -#24330 = CARTESIAN_POINT ( 'NONE', ( 25.88694336884159242, 211.8813746531136815, 73.04286901727219572 ) ) ; -#24331 = CARTESIAN_POINT ( 'NONE', ( -13.84340190164384232, 129.1309658598411829, 155.2542762368457261 ) ) ; -#24332 = LINE ( 'NONE', #36381, #36488 ) ; -#24333 = EDGE_CURVE ( 'NONE', #39651, #14192, #21014, .T. ) ; -#24334 = CARTESIAN_POINT ( 'NONE', ( -2.436970329118646639, 191.4135392062368908, 104.3588452342733603 ) ) ; -#24335 = VECTOR ( 'NONE', #38258, 1000.000000000000000 ) ; -#24336 = LINE ( 'NONE', #18157, #12201 ) ; -#24337 = EDGE_CURVE ( 'NONE', #24627, #30524, #31559, .T. ) ; -#24338 = VECTOR ( 'NONE', #27105, 1000.000000000000000 ) ; -#24339 = CARTESIAN_POINT ( 'NONE', ( 37.94419046432000187, 119.2344160205999941, 87.12639605929000197 ) ) ; -#24340 = DATE_TIME_ROLE ( 'classification_date' ) ; -#24341 = CARTESIAN_POINT ( 'NONE', ( 20.50145991744662055, 186.5915574767782061, 105.2843683661653102 ) ) ; -#24342 = EDGE_CURVE ( 'NONE', #29960, #22046, #32800, .T. ) ; -#24343 = CARTESIAN_POINT ( 'NONE', ( 20.00201742172724551, 173.8530216436687965, 102.8568040933565300 ) ) ; -#24344 = DIRECTION ( 'NONE', ( 1.447458112927613770E-19, 1.000000000000000000, -1.271205603797056623E-14 ) ) ; -#24345 = LINE ( 'NONE', #36392, #37860 ) ; -#24346 = ADVANCED_FACE ( 'NONE', ( #37745 ), #3790, .T. ) ; -#24348 = ORIENTED_EDGE ( 'NONE', *, *, #8399, .F. ) ; -#24347 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178662923876E-05, -0.0002331579774918193435 ) ) ; -#24349 = ORIENTED_EDGE ( 'NONE', *, *, #27585, .T. ) ; -#24350 = EDGE_LOOP ( 'NONE', ( #36220, #36823, #2136, #11360, #15113, #9612, #31030 ) ) ; -#24351 = EDGE_CURVE ( 'NONE', #37430, #33415, #37003, .T. ) ; -#24352 = CARTESIAN_POINT ( 'NONE', ( -2.384008221771502622, 189.5405707719284010, 103.4132521871697747 ) ) ; -#24353 = EDGE_CURVE ( 'NONE', #14192, #23280, #284, .T. ) ; -#24354 = ORIENTED_EDGE ( 'NONE', *, *, #6295, .F. ) ; -#24355 = CARTESIAN_POINT ( 'NONE', ( 16.14434960479602310, 151.5098951869622965, 180.2135683096460639 ) ) ; -#24356 = DIRECTION ( 'NONE', ( 0.7855473026356902810, 0.6188014303620730239, -0.0004744508866335444284 ) ) ; -#24357 = ORIENTED_EDGE ( 'NONE', *, *, #3115, .T. ) ; -#24358 = CARTESIAN_POINT ( 'NONE', ( 40.54493957013273331, 217.7719115632999944, 73.03401595487400755 ) ) ; -#24359 = CARTESIAN_POINT ( 'NONE', ( -23.36173672920000044, 135.2906635721360828, 91.41449412993499379 ) ) ; -#24360 = DIRECTION ( 'NONE', ( 1.766515445929712010E-15, 0.9743043966640313469, 0.2252353050503801690 ) ) ; -#24361 = DIRECTION ( 'NONE', ( -0.0005884949961244972938, 0.2249510543439076637, -0.9743698870671260170 ) ) ; -#24362 = CARTESIAN_POINT ( 'NONE', ( 17.33255171641533110, 121.2645175805946138, 177.4250592562015925 ) ) ; -#24363 = CIRCLE ( 'NONE', #33456, 1.749999999939591433 ) ; -#24364 = VERTEX_POINT ( 'NONE', #4596 ) ; -#24365 = DIRECTION ( 'NONE', ( 0.5634794340701355653, -0.8261300910752492621, 0.000000000000000000 ) ) ; -#24366 = FACE_OUTER_BOUND ( 'NONE', #6160, .T. ) ; -#24367 = VECTOR ( 'NONE', #7082, 1000.000000000000000 ) ; -#24368 = CARTESIAN_POINT ( 'NONE', ( 13.50000077932746834, 151.9719590241109870, 94.73025978658517943 ) ) ; -#24369 = FACE_OUTER_BOUND ( 'NONE', #29930, .T. ) ; -#24370 = VERTEX_POINT ( 'NONE', #38542 ) ; -#24371 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173120816, 138.0805213879916664, 92.05262725620852393 ) ) ; -#24372 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33076, #5063, #29830, #39408 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24373 = CIRCLE ( 'NONE', #5393, 3.000000000000005773 ) ; -#24374 = CARTESIAN_POINT ( 'NONE', ( 1.111562947836880255, 189.0855455024050400, 103.7202029498749880 ) ) ; -#24375 = LINE ( 'NONE', #4927, #32203 ) ; -#24376 = CARTESIAN_POINT ( 'NONE', ( -42.83084823883022807, 121.2593020781266659, 90.75261808358531823 ) ) ; -#24377 = EDGE_LOOP ( 'NONE', ( #27310, #11450, #30392, #7442 ) ) ; -#24378 = ORIENTED_EDGE ( 'NONE', *, *, #35132, .F. ) ; -#24379 = CARTESIAN_POINT ( 'NONE', ( 20.49908935505346719, 194.2769733015968541, 102.8866291927022303 ) ) ; -#24380 = ORIENTED_EDGE ( 'NONE', *, *, #4265, .T. ) ; -#24381 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9585, #24341, #18363, #3426 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24382 = EDGE_CURVE ( 'NONE', #36231, #38065, #11150, .T. ) ; -#24383 = EDGE_CURVE ( 'NONE', #39292, #38824, #35423, .T. ) ; -#24384 = EDGE_LOOP ( 'NONE', ( #5556, #10142, #39912, #8024 ) ) ; -#24385 = CARTESIAN_POINT ( 'NONE', ( -25.50098454281350158, 121.6303684359623389, 88.26205429894362453 ) ) ; -#24386 = EDGE_CURVE ( 'NONE', #37113, #25434, #12904, .T. ) ; -#24387 = ORIENTED_EDGE ( 'NONE', *, *, #28442, .F. ) ; -#24388 = CARTESIAN_POINT ( 'NONE', ( -35.93912355882999776, 192.8585610955000220, 106.5512944815999958 ) ) ; -#24389 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927765820594, 0.0005734119022078099960 ) ) ; -#24390 = CARTESIAN_POINT ( 'NONE', ( 21.17088928811812920, 192.5990385700442573, 28.42526875025830435 ) ) ; -#24391 = EDGE_CURVE ( 'NONE', #13040, #3283, #20130, .T. ) ; -#24392 = VERTEX_POINT ( 'NONE', #1954 ) ; -#24393 = CARTESIAN_POINT ( 'NONE', ( -5.671868782401078946, 181.7830489082147380, 101.7543586301373040 ) ) ; -#24394 = AXIS2_PLACEMENT_3D ( 'NONE', #19271, #31168, #31775 ) ; -#24395 = ORIENTED_EDGE ( 'NONE', *, *, #36164, .T. ) ; -#24396 = CARTESIAN_POINT ( 'NONE', ( 26.49433430397300171, 122.3661283948670047, 90.96806730438009936 ) ) ; -#24397 = CARTESIAN_POINT ( 'NONE', ( -21.70206937734006303, 182.6897195680310233, 102.1853773300410779 ) ) ; -#24399 = CARTESIAN_POINT ( 'NONE', ( 38.15045221970718359, 118.4868570840783377, 87.66883015867043127 ) ) ; -#24398 = PLANE ( 'NONE', #27828 ) ; -#24400 = EDGE_CURVE ( 'NONE', #7852, #10957, #40157, .T. ) ; -#24401 = CONICAL_SURFACE ( 'NONE', #13920, 2.500000073598442896, 0.7853981634226060438 ) ; -#24402 = EDGE_LOOP ( 'NONE', ( #13856, #32936, #17461, #36139 ) ) ; -#24403 = ORIENTED_EDGE ( 'NONE', *, *, #37203, .F. ) ; -#24404 = CARTESIAN_POINT ( 'NONE', ( -13.46279686986694202, 157.6279356061011185, 99.13124279942860539 ) ) ; -#24405 = ADVANCED_FACE ( 'NONE', ( #8708 ), #8046, .F. ) ; -#24406 = LINE ( 'NONE', #8863, #35680 ) ; -#24407 = CARTESIAN_POINT ( 'NONE', ( -45.27486310239934397, 116.8517531720308540, 123.7677792994715560 ) ) ; -#24408 = CARTESIAN_POINT ( 'NONE', ( 12.63563601333813224, 130.7300475903418544, 90.07759431230093128 ) ) ; -#24409 = CARTESIAN_POINT ( 'NONE', ( -12.63881457583079992, 135.0847523732418836, 91.07654686071646211 ) ) ; -#24410 = ORIENTED_EDGE ( 'NONE', *, *, #24296, .T. ) ; -#24411 = ORIENTED_EDGE ( 'NONE', *, *, #22160, .T. ) ; -#24412 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; -#24413 = DIRECTION ( 'NONE', ( -0.0005884949961247568518, 0.2249510543439060262, -0.9743698870671264611 ) ) ; -#24414 = VERTEX_POINT ( 'NONE', #36074 ) ; -#24415 = EDGE_LOOP ( 'NONE', ( #12028, #5722, #32080, #35449 ) ) ; -#24416 = CARTESIAN_POINT ( 'NONE', ( -3.537737212824113353, 144.2088358181959222, 92.94829169108382416 ) ) ; -#24417 = AXIS2_PLACEMENT_3D ( 'NONE', #38198, #13653, #22672 ) ; -#24418 = CARTESIAN_POINT ( 'NONE', ( -17.00047812746342402, 136.5658759208817230, 181.4646850263357010 ) ) ; -#24419 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39705, #30314, #39914, #33572 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24420 = CIRCLE ( 'NONE', #10039, 2.500000000000002220 ) ; -#24421 = CARTESIAN_POINT ( 'NONE', ( 3.068920026728427786, 190.7403886567750817, 106.7700806275786647 ) ) ; -#24422 = DIRECTION ( 'NONE', ( 0.0005884949961219227473, -0.2249510543439028620, 0.9743698870671272383 ) ) ; -#24423 = AXIS2_PLACEMENT_3D ( 'NONE', #39457, #20873, #11469 ) ; -#24424 = CARTESIAN_POINT ( 'NONE', ( -36.45697978980704335, 190.7486664167910249, 106.7916551997199690 ) ) ; -#24425 = CARTESIAN_POINT ( 'NONE', ( -4.036264725720115187, 167.9338357148002387, 100.9917020970990791 ) ) ; -#24426 = CARTESIAN_POINT ( 'NONE', ( 19.70863784699480448, 149.1560517737245561, 182.9541186021026817 ) ) ; -#24427 = EDGE_CURVE ( 'NONE', #34118, #21532, #5411, .T. ) ; -#24428 = EDGE_CURVE ( 'NONE', #10727, #18757, #24454, .T. ) ; -#24429 = ORIENTED_EDGE ( 'NONE', *, *, #27848, .F. ) ; -#24430 = EDGE_CURVE ( 'NONE', #33123, #40304, #14420, .T. ) ; -#24431 = ADVANCED_FACE ( 'NONE', ( #36491 ), #8499, .F. ) ; -#24432 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748613964, 179.1800746285507842, 103.5747911657901170 ) ) ; -#24433 = CARTESIAN_POINT ( 'NONE', ( -20.23142761837597803, 127.1194786501865508, 91.85271049129865162 ) ) ; -#24434 = ORIENTED_EDGE ( 'NONE', *, *, #39588, .F. ) ; -#24435 = EDGE_CURVE ( 'NONE', #32839, #9483, #40350, .T. ) ; -#24436 = CARTESIAN_POINT ( 'NONE', ( 37.96380763661293400, 191.4135383555317844, 104.3344495138068595 ) ) ; -#24437 = ORIENTED_EDGE ( 'NONE', *, *, #2582, .F. ) ; -#24438 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24439 = EDGE_LOOP ( 'NONE', ( #18953, #30581, #30631, #24645 ) ) ; -#24440 = ADVANCED_FACE ( 'NONE', ( #31371 ), #22379, .F. ) ; -#24441 = EDGE_LOOP ( 'NONE', ( #7571, #36920, #31155, #20700 ) ) ; -#24442 = AXIS2_PLACEMENT_3D ( 'NONE', #23755, #26831, #20680 ) ; -#24443 = ORIENTED_EDGE ( 'NONE', *, *, #11535, .T. ) ; -#24444 = CARTESIAN_POINT ( 'NONE', ( 2.618453597419999834, 209.4619370535999963, 75.68410014526000396 ) ) ; -#24445 = CARTESIAN_POINT ( 'NONE', ( -25.66662714986091132, 118.1127751917333200, 89.94994881093153083 ) ) ; -#24446 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24447 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#24449 = ORIENTED_EDGE ( 'NONE', *, *, #4639, .T. ) ; -#24448 = VECTOR ( 'NONE', #11669, 1000.000000000000000 ) ; -#24450 = ORIENTED_EDGE ( 'NONE', *, *, #9688, .F. ) ; -#24451 = FACE_OUTER_BOUND ( 'NONE', #30351, .T. ) ; -#24452 = EDGE_LOOP ( 'NONE', ( #37270, #34645, #16622, #11337 ) ) ; -#24453 = VERTEX_POINT ( 'NONE', #24656 ) ; -#24454 = LINE ( 'NONE', #30165, #17168 ) ; -#24455 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#24456 = AXIS2_PLACEMENT_3D ( 'NONE', #34714, #18772, #28025 ) ; -#24457 = CARTESIAN_POINT ( 'NONE', ( 22.95436083522999837, 118.1131156702000169, 13.53038997162000001 ) ) ; -#24458 = CYLINDRICAL_SURFACE ( 'NONE', #18676, 6.000000000000008882 ) ; -#24459 = CARTESIAN_POINT ( 'NONE', ( 22.25482580366933405, 135.3257585116184032, 90.88189302714953044 ) ) ; -#24460 = ORIENTED_EDGE ( 'NONE', *, *, #13788, .F. ) ; -#24461 = EDGE_LOOP ( 'NONE', ( #9420, #9076, #3725, #30825 ) ) ; -#24462 = DIRECTION ( 'NONE', ( 0.0005884949961247620560, -0.2249510543439075527, 0.9743698870671261281 ) ) ; -#24463 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7833, #8252, #26872, #4969, #20718, #33171, #19889, #2127, #14596, #5164, #29326, #29517 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999992246202, 0.3749999999988369304, 0.4374999999986430854, 0.4687499999985523247, 0.4843749999985315080, 0.4999999999985107468, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24464 = CARTESIAN_POINT ( 'NONE', ( -36.34981164026000044, 191.9154030711000019, 104.5556768045999974 ) ) ; -#24465 = ORIENTED_EDGE ( 'NONE', *, *, #5577, .T. ) ; -#24466 = CARTESIAN_POINT ( 'NONE', ( 15.38986074322405706, 183.3318898957821546, 101.9691300310993682 ) ) ; -#24467 = ORIENTED_EDGE ( 'NONE', *, *, #2107, .T. ) ; -#24468 = CARTESIAN_POINT ( 'NONE', ( -3.168142195203446754, 126.1261981506732468, 91.85226338672082136 ) ) ; -#24469 = FACE_OUTER_BOUND ( 'NONE', #509, .T. ) ; -#24470 = ORIENTED_EDGE ( 'NONE', *, *, #21291, .F. ) ; -#24471 = CARTESIAN_POINT ( 'NONE', ( 3.858347067253080187, 174.7549553854443332, 102.7438146759574522 ) ) ; -#24472 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31515, #3481, #828, #4494 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24473 = CARTESIAN_POINT ( 'NONE', ( 12.31735976862525561, 136.6810573082978806, 94.28285972987136176 ) ) ; -#24474 = AXIS2_PLACEMENT_3D ( 'NONE', #4218, #1162, #26131 ) ; -#24475 = CARTESIAN_POINT ( 'NONE', ( -46.29694876502865952, 80.51358819988081450, 287.6592691764436154 ) ) ; -#24476 = CARTESIAN_POINT ( 'NONE', ( 41.73867405848197620, 189.2432962648855721, 106.9167062554396068 ) ) ; -#24477 = AXIS2_PLACEMENT_3D ( 'NONE', #35521, #14298, #32699 ) ; -#24478 = VECTOR ( 'NONE', #33083, 1000.000000000000227 ) ; -#24479 = CARTESIAN_POINT ( 'NONE', ( -45.17721186414367907, 180.6407286098181544, 103.9501681112560192 ) ) ; -#24480 = ORIENTED_EDGE ( 'NONE', *, *, #27918, .T. ) ; -#24481 = CARTESIAN_POINT ( 'NONE', ( -15.49852918059724693, 160.1761146120170736, 99.20761365264185372 ) ) ; -#24482 = ADVANCED_FACE ( 'NONE', ( #12551 ), #9101, .T. ) ; -#24483 = AXIS2_PLACEMENT_3D ( 'NONE', #23717, #35955, #8389 ) ; -#24484 = FACE_OUTER_BOUND ( 'NONE', #8412, .T. ) ; -#24485 = EDGE_CURVE ( 'NONE', #22, #13543, #1503, .T. ) ; -#24486 = CARTESIAN_POINT ( 'NONE', ( -38.05885084466000023, 119.4654426599000203, 87.18889340133002008 ) ) ; -#24487 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #17961, #21263, #24748, #14922 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.712388980384485393, 6.509724810461453792 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7484352496336041938, 0.7484352496336041938, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#24488 = PLANE ( 'NONE', #28789 ) ; -#24489 = CARTESIAN_POINT ( 'NONE', ( -25.49994355703909932, 120.2054709989172778, 89.98570258340846806 ) ) ; -#24490 = ORIENTED_EDGE ( 'NONE', *, *, #6085, .T. ) ; -#24491 = CARTESIAN_POINT ( 'NONE', ( -45.56069752896866731, 133.9656849080258496, 337.3347232553839490 ) ) ; -#24492 = VERTEX_POINT ( 'NONE', #22182 ) ; -#24493 = CARTESIAN_POINT ( 'NONE', ( 32.45263285945821252, 152.9980946676346889, 291.5389433581793242 ) ) ; -#24494 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24495 = DIRECTION ( 'NONE', ( -0.0005884949961226037347, 0.2249510543439047494, -0.9743698870671267942 ) ) ; -#24496 = CARTESIAN_POINT ( 'NONE', ( -36.03785673918448396, 115.6782689564399931, 90.28955080164526237 ) ) ; -#24497 = ORIENTED_EDGE ( 'NONE', *, *, #1257, .F. ) ; -#24498 = CONICAL_SURFACE ( 'NONE', #19226, 2.503061127006177777, 0.7853981634091529163 ) ; -#24499 = AXIS2_PLACEMENT_3D ( 'NONE', #32793, #23805, #20514 ) ; -#24500 = EDGE_LOOP ( 'NONE', ( #30610, #22449, #11658, #5752 ) ) ; -#24501 = CARTESIAN_POINT ( 'NONE', ( 8.046776639317595681, 161.2737771581006996, 96.88104755365348808 ) ) ; -#24502 = ADVANCED_FACE ( 'NONE', ( #25658 ), #26251, .F. ) ; -#24503 = AXIS2_PLACEMENT_3D ( 'NONE', #34483, #6685, #25324 ) ; -#24504 = CARTESIAN_POINT ( 'NONE', ( 37.34715196620786060, 164.6396645750260745, 198.2231758344085506 ) ) ; -#24505 = AXIS2_PLACEMENT_3D ( 'NONE', #18298, #30997, #18896 ) ; -#24506 = ORIENTED_EDGE ( 'NONE', *, *, #12936, .T. ) ; -#24507 = CARTESIAN_POINT ( 'NONE', ( -23.36259834854143591, 135.1300385911131627, 91.15744102916718816 ) ) ; -#24508 = AXIS2_PLACEMENT_3D ( 'NONE', #38724, #14006, #36063 ) ; -#24509 = FACE_OUTER_BOUND ( 'NONE', #15924, .T. ) ; -#24510 = ORIENTED_EDGE ( 'NONE', *, *, #30297, .T. ) ; -#24511 = CARTESIAN_POINT ( 'NONE', ( -38.18399642279999995, 119.1291464787000081, 87.44400818926999364 ) ) ; -#24512 = CARTESIAN_POINT ( 'NONE', ( 37.96521291183479008, 190.3639829187772250, 106.6578906949923464 ) ) ; -#24513 = ORIENTED_EDGE ( 'NONE', *, *, #16417, .T. ) ; -#24514 = DIRECTION ( 'NONE', ( 0.0005884949961240085355, -0.2249510543439064425, 0.9743698870671262391 ) ) ; -#24515 = CARTESIAN_POINT ( 'NONE', ( 19.46059643144436535, 126.3442427331793141, 175.5385488862945635 ) ) ; -#24516 = CARTESIAN_POINT ( 'NONE', ( 16.81893173097259009, 122.1576077111467669, 174.6474910666977394 ) ) ; -#24517 = CARTESIAN_POINT ( 'NONE', ( -23.18986705890396394, 115.1130375555242011, 90.28179093782202358 ) ) ; -#24518 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319351123402 ) ) ; -#24519 = ORIENTED_EDGE ( 'NONE', *, *, #9599, .F. ) ; -#24520 = CARTESIAN_POINT ( 'NONE', ( 38.62156013492000284, 119.5280236665000047, 87.38525354376000109 ) ) ; -#24521 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#24522 = CARTESIAN_POINT ( 'NONE', ( 36.53325801408829676, 191.7380623391987058, 104.3522437978620303 ) ) ; -#24523 = PLANE ( 'NONE', #22978 ) ; -#24524 = ADVANCED_FACE ( 'NONE', ( #22976 ), #1290, .F. ) ; -#24525 = ORIENTED_EDGE ( 'NONE', *, *, #19909, .T. ) ; -#24526 = FACE_OUTER_BOUND ( 'NONE', #23411, .T. ) ; -#24527 = EDGE_CURVE ( 'NONE', #6854, #17839, #37300, .T. ) ; -#24528 = CARTESIAN_POINT ( 'NONE', ( 16.14434960479181669, 123.6872145152307922, 173.7816462226733449 ) ) ; -#24529 = CARTESIAN_POINT ( 'NONE', ( 24.96542012578290226, 213.3574743203983530, 73.04342559421955627 ) ) ; -#24530 = AXIS2_PLACEMENT_3D ( 'NONE', #10059, #25209, #3702 ) ; -#24531 = CONICAL_SURFACE ( 'NONE', #25839, 2.503000005691713437, 0.7853981633624692593 ) ; -#24532 = CARTESIAN_POINT ( 'NONE', ( 5.668109638569122311, 127.9115383981770435, 92.25911597461721669 ) ) ; -#24533 = VECTOR ( 'NONE', #36567, 1000.000000000000000 ) ; -#24534 = EDGE_CURVE ( 'NONE', #29659, #20818, #229, .T. ) ; -#24535 = CARTESIAN_POINT ( 'NONE', ( -30.82037056355595084, 183.2973804097868822, 101.9890727088156979 ) ) ; -#24536 = CIRCLE ( 'NONE', #2962, 2.000000000000011546 ) ; -#24537 = CARTESIAN_POINT ( 'NONE', ( -25.84889468334661800, 209.7109668267897007, 73.23528207987367011 ) ) ; -#24538 = CARTESIAN_POINT ( 'NONE', ( 6.040442610973922655, 177.0788152924815506, 103.5573834436911369 ) ) ; -#24539 = SHAPE_DEFINITION_REPRESENTATION ( #10456, #23616 ) ; -#24540 = LINE ( 'NONE', #18756, #20678 ) ; -#24541 = CARTESIAN_POINT ( 'NONE', ( -2.437379602309801996, 196.1181861109790532, 103.6812116298660129 ) ) ; -#24542 = CARTESIAN_POINT ( 'NONE', ( 13.76428958104859746, 149.7303430849865720, 179.8030703197069897 ) ) ; -#24543 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#24544 = CARTESIAN_POINT ( 'NONE', ( 37.18342958457959924, 191.4796220198800256, 104.3003503982839959 ) ) ; -#24545 = CARTESIAN_POINT ( 'NONE', ( 36.51380830376000830, 190.9776620762999926, 106.6665925439999967 ) ) ; -#24546 = ORIENTED_EDGE ( 'NONE', *, *, #27459, .F. ) ; -#24547 = ORIENTED_EDGE ( 'NONE', *, *, #32881, .F. ) ; -#24548 = DIRECTION ( 'NONE', ( 3.092411411307044243E-16, -0.9743043966640313469, -0.2252353050503803911 ) ) ; -#24549 = EDGE_CURVE ( 'NONE', #16868, #34038, #21931, .T. ) ; -#24550 = FACE_OUTER_BOUND ( 'NONE', #6755, .T. ) ; -#24551 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #38981, #10988 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24552 = CYLINDRICAL_SURFACE ( 'NONE', #15408, 59.40509898897002472 ) ; -#24553 = CONICAL_SURFACE ( 'NONE', #19289, 5.003058809538631024, 0.7854316141403709928 ) ; -#24554 = CARTESIAN_POINT ( 'NONE', ( 16.16915973785429372, 151.9784250564231343, 184.4864535658479383 ) ) ; -#24555 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; -#24556 = AXIS2_PLACEMENT_3D ( 'NONE', #34746, #18613, #12304 ) ; -#24557 = ORIENTED_EDGE ( 'NONE', *, *, #24163, .F. ) ; -#24558 = CIRCLE ( 'NONE', #14775, 1.999999999727680722 ) ; -#24559 = CARTESIAN_POINT ( 'NONE', ( 15.50068700820734335, 127.4824608105999744, 90.27255908592694311 ) ) ; -#24560 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971562072 ) ) ; -#24561 = VECTOR ( 'NONE', #13148, 1000.000000000000000 ) ; -#24562 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#24563 = ORIENTED_EDGE ( 'NONE', *, *, #39640, .T. ) ; -#24564 = AXIS2_PLACEMENT_3D ( 'NONE', #20397, #4854, #32480 ) ; -#24565 = CARTESIAN_POINT ( 'NONE', ( -53.48535521792690872, 68.11573456465821153, 284.1968697250433706 ) ) ; -#24566 = EDGE_CURVE ( 'NONE', #16069, #40361, #13403, .T. ) ; -#24567 = CARTESIAN_POINT ( 'NONE', ( 20.25158342518999888, 118.4641756243000117, 90.00571388583000498 ) ) ; -#24568 = VECTOR ( 'NONE', #37919, 1000.000000000000114 ) ; -#24569 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559296 ) ) ; -#24570 = CARTESIAN_POINT ( 'NONE', ( -5.662686464640452222, 188.3429660633563287, 103.1387990589197869 ) ) ; -#24571 = CARTESIAN_POINT ( 'NONE', ( -22.23345940463643444, 214.0123076496562078, 76.07197583563208809 ) ) ; -#24572 = ORIENTED_EDGE ( 'NONE', *, *, #21201, .T. ) ; -#24573 = ADVANCED_FACE ( 'NONE', ( #35710 ), #10021, .F. ) ; -#24574 = LINE ( 'NONE', #37029, #25257 ) ; -#24575 = CARTESIAN_POINT ( 'NONE', ( 2.894932050292999826, 190.8748715014000084, 103.8886708489000057 ) ) ; -#24576 = CARTESIAN_POINT ( 'NONE', ( -33.70586835455132046, 218.5902260770999987, 73.07886158226766327 ) ) ; -#24577 = EDGE_CURVE ( 'NONE', #20818, #5436, #32851, .T. ) ; -#24578 = VERTEX_POINT ( 'NONE', #33066 ) ; -#24579 = CYLINDRICAL_SURFACE ( 'NONE', #31607, 2.000000000000000000 ) ; -#24580 = EDGE_LOOP ( 'NONE', ( #8655, #3491, #39748, #36859 ) ) ; -#24581 = EDGE_CURVE ( 'NONE', #21600, #38636, #34389, .T. ) ; -#24582 = EDGE_CURVE ( 'NONE', #18145, #629, #17797, .T. ) ; -#24583 = EDGE_CURVE ( 'NONE', #12315, #30815, #34142, .T. ) ; -#24584 = AXIS2_PLACEMENT_3D ( 'NONE', #29770, #17061, #39758 ) ; -#24585 = CARTESIAN_POINT ( 'NONE', ( -39.61054748937312553, 129.5177821288435780, 336.3042500576304974 ) ) ; -#24586 = VECTOR ( 'NONE', #778, 999.9999999999998863 ) ; -#24587 = LINE ( 'NONE', #12294, #29002 ) ; -#24588 = CARTESIAN_POINT ( 'NONE', ( -8.607980242643897384, 290.0045490278850480, 216.9380081958158826 ) ) ; -#24589 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; -#24590 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #503, #22206, #3968, #12996 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24591 = CARTESIAN_POINT ( 'NONE', ( 28.45310815370287472, 181.6925917411357148, 101.5827842051393617 ) ) ; -#24592 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; -#24593 = CARTESIAN_POINT ( 'NONE', ( -36.65000432357000193, 191.5328112857000065, 106.2711270500000040 ) ) ; -#24594 = ORIENTED_EDGE ( 'NONE', *, *, #32302, .F. ) ; -#24595 = AXIS2_PLACEMENT_3D ( 'NONE', #37299, #27314, #3141 ) ; -#24596 = CARTESIAN_POINT ( 'NONE', ( 37.42082609156221906, 71.98986935621209682, 322.9763574547569647 ) ) ; -#24597 = CYLINDRICAL_SURFACE ( 'NONE', #13670, 2.000000000000014655 ) ; -#24598 = DIRECTION ( 'NONE', ( 0.0005884949961236470625, -0.2249510543439058041, 0.9743698870671265722 ) ) ; -#24600 = CARTESIAN_POINT ( 'NONE', ( 16.21976467472907757, 122.6436220881636814, 172.0961230653717564 ) ) ; -#24599 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394468885165, 153.0051697192222093, 297.5584364845166760 ) ) ; -#24601 = ORIENTED_EDGE ( 'NONE', *, *, #16411, .T. ) ; -#24602 = EDGE_CURVE ( 'NONE', #17839, #28078, #25038, .T. ) ; -#24603 = EDGE_LOOP ( 'NONE', ( #15978, #36351, #26837, #7320 ) ) ; -#24604 = ORIENTED_EDGE ( 'NONE', *, *, #5547, .F. ) ; -#24605 = CARTESIAN_POINT ( 'NONE', ( -35.45414161168002920, 207.8686442570738677, 77.29845581748402594 ) ) ; -#24606 = CARTESIAN_POINT ( 'NONE', ( 13.35510997216094609, 181.7652417701797276, 101.6086696847208657 ) ) ; -#24607 = CARTESIAN_POINT ( 'NONE', ( -20.16727645646760436, 196.4248145870187443, 103.8226647487338283 ) ) ; -#24608 = CARTESIAN_POINT ( 'NONE', ( 39.70674893776387648, 114.9516458920610660, 150.7368254606779772 ) ) ; -#24609 = CARTESIAN_POINT ( 'NONE', ( 12.64144988264126646, 130.9981868284926918, 89.91003945015222598 ) ) ; -#24610 = DIRECTION ( 'NONE', ( 0.1305262373691799260, 0.9659798014921964215, 0.2232620085624539286 ) ) ; -#24611 = ORIENTED_EDGE ( 'NONE', *, *, #17597, .T. ) ; -#24612 = EDGE_CURVE ( 'NONE', #20537, #19373, #8032, .T. ) ; -#24613 = EDGE_LOOP ( 'NONE', ( #7521, #30511, #34022, #34290 ) ) ; -#24614 = CIRCLE ( 'NONE', #36346, 4.999999999999990230 ) ; -#24615 = CARTESIAN_POINT ( 'NONE', ( -5.668235839012205624, 187.2935674832718007, 105.4622348357629136 ) ) ; -#24616 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33394, #36266, #2335, #30142, #38712, #10729 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24617 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971583443 ) ) ; -#24618 = ORIENTED_EDGE ( 'NONE', *, *, #858, .T. ) ; -#24619 = EDGE_CURVE ( 'NONE', #15583, #35994, #13906, .T. ) ; -#24620 = CARTESIAN_POINT ( 'NONE', ( -36.19285314463999725, 191.4786645193000254, 106.5770535557000045 ) ) ; -#24621 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, -1.298960938811000068E-14 ) ) ; -#24622 = CIRCLE ( 'NONE', #33074, 2.500000000054189098 ) ; -#24623 = EDGE_CURVE ( 'NONE', #9539, #2007, #35310, .T. ) ; -#24624 = AXIS2_PLACEMENT_3D ( 'NONE', #19790, #7332, #13882 ) ; -#24625 = CARTESIAN_POINT ( 'NONE', ( 1.190304246311000069, 188.4394388974999970, 106.2357951811000021 ) ) ; -#24626 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32401, #26272, #32983, #1506 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.003686124984095357545, 0.004393344450578582673 ), - .UNSPECIFIED. ) ; -#24627 = VERTEX_POINT ( 'NONE', #24306 ) ; -#24628 = LINE ( 'NONE', #30948, #3977 ) ; -#24629 = EDGE_CURVE ( 'NONE', #328, #26074, #6577, .T. ) ; -#24630 = CARTESIAN_POINT ( 'NONE', ( 13.49774948664089536, 124.4632236369325113, 88.50938697307681480 ) ) ; -#24631 = CARTESIAN_POINT ( 'NONE', ( 24.86285456769096669, 182.2983400162870851, 101.7247947455283992 ) ) ; -#24632 = CARTESIAN_POINT ( 'NONE', ( 4.644859472722845162, 147.7869572978819406, 93.76942395331053604 ) ) ; -#24633 = ORIENTED_EDGE ( 'NONE', *, *, #15360, .T. ) ; -#24634 = CARTESIAN_POINT ( 'NONE', ( 25.99116264712915125, 206.1770306668426258, 74.47098211211711316 ) ) ; -#24635 = FACE_OUTER_BOUND ( 'NONE', #15959, .T. ) ; -#24636 = CARTESIAN_POINT ( 'NONE', ( -20.49852830656245928, 127.1805961887959029, 91.59301651814030265 ) ) ; -#24637 = ORIENTED_EDGE ( 'NONE', *, *, #39821, .T. ) ; -#24638 = AXIS2_PLACEMENT_3D ( 'NONE', #6617, #9714, #21786 ) ; -#24639 = CARTESIAN_POINT ( 'NONE', ( 16.48384946166832421, 121.5382711781017520, 177.2995345887800624 ) ) ; -#24640 = ORIENTED_EDGE ( 'NONE', *, *, #3475, .T. ) ; -#24641 = AXIS2_PLACEMENT_3D ( 'NONE', #23816, #2343, #39534 ) ; -#24643 = CARTESIAN_POINT ( 'NONE', ( -16.89042424569320389, 121.5869331581628785, 176.9809332940324111 ) ) ; -#24642 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24644 = ORIENTED_EDGE ( 'NONE', *, *, #34586, .F. ) ; -#24645 = ORIENTED_EDGE ( 'NONE', *, *, #27831, .F. ) ; -#24646 = ORIENTED_EDGE ( 'NONE', *, *, #7485, .F. ) ; -#24647 = CARTESIAN_POINT ( 'NONE', ( 2.358838354253999903, 209.4281692024999870, 75.42491224581000608 ) ) ; -#24648 = DIRECTION ( 'NONE', ( -2.486577296501327517E-19, -1.000000000000000000, 1.222202472776332422E-14 ) ) ; -#24649 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #6663, #34464 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24650 = CARTESIAN_POINT ( 'NONE', ( 44.93984957629947274, 145.3877245808612031, 285.0133094889154677 ) ) ; -#24651 = LINE ( 'NONE', #19278, #26031 ) ; -#24652 = EDGE_LOOP ( 'NONE', ( #17565, #21066, #30739, #8076 ) ) ; -#24653 = ORIENTED_EDGE ( 'NONE', *, *, #11383, .T. ) ; -#24654 = ORIENTED_EDGE ( 'NONE', *, *, #40460, .F. ) ; -#24655 = ORIENTED_EDGE ( 'NONE', *, *, #40376, .T. ) ; -#24656 = CARTESIAN_POINT ( 'NONE', ( 41.04644941598475327, 220.4002260660249988, 75.53371351150769897 ) ) ; -#24657 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178582662422E-05, 0.0002331579774919529443 ) ) ; -#24658 = CYLINDRICAL_SURFACE ( 'NONE', #33753, 17.00000000000406430 ) ; -#24659 = CARTESIAN_POINT ( 'NONE', ( 35.89873956569999791, 192.3079086021000137, 104.2139990170999937 ) ) ; -#24660 = ADVANCED_FACE ( 'NONE', ( #34077 ), #33267, .F. ) ; -#24661 = ORIENTED_EDGE ( 'NONE', *, *, #32532, .F. ) ; -#24662 = ADVANCED_FACE ( 'NONE', ( #2421 ), #24401, .F. ) ; -#24663 = ORIENTED_EDGE ( 'NONE', *, *, #13597, .F. ) ; -#24664 = CARTESIAN_POINT ( 'NONE', ( -35.44810745642832472, 111.2706431035999941, 87.28919406043203821 ) ) ; -#24665 = ADVANCED_FACE ( 'NONE', ( #15485 ), #36775, .T. ) ; -#24666 = PLANE ( 'NONE', #24638 ) ; -#24667 = EDGE_CURVE ( 'NONE', #10753, #14963, #2623, .T. ) ; -#24668 = CARTESIAN_POINT ( 'NONE', ( 15.99983399408007934, 184.6056815932580832, 102.2628396612452661 ) ) ; -#24669 = ORIENTED_EDGE ( 'NONE', *, *, #19643, .T. ) ; -#24670 = PLANE ( 'NONE', #26499 ) ; -#24671 = FACE_OUTER_BOUND ( 'NONE', #39702, .T. ) ; -#24672 = CARTESIAN_POINT ( 'NONE', ( 40.85748915988408925, 189.7900928382927361, 106.8264131337932525 ) ) ; -#24673 = ORIENTED_EDGE ( 'NONE', *, *, #37448, .T. ) ; -#24674 = ADVANCED_FACE ( 'NONE', ( #24509 ), #21439, .T. ) ; -#24675 = VECTOR ( 'NONE', #1914, 1000.000000000000227 ) ; -#24676 = CARTESIAN_POINT ( 'NONE', ( -28.25689436368393714, 186.9042180597057836, 103.3333805992548093 ) ) ; -#24677 = CARTESIAN_POINT ( 'NONE', ( -3.789621669352976951, 167.8773217199183136, 101.2314878384422627 ) ) ; -#24678 = CONICAL_SURFACE ( 'NONE', #9018, 4.999996804348348256, 0.7853981633997131340 ) ; -#24679 = ADVANCED_FACE ( 'NONE', ( #35064 ), #6754, .T. ) ; -#24680 = CARTESIAN_POINT ( 'NONE', ( -19.31979924309097996, 124.8061162773214079, 177.8324071844828893 ) ) ; -#24681 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24682 = ORIENTED_EDGE ( 'NONE', *, *, #811, .T. ) ; -#24683 = CARTESIAN_POINT ( 'NONE', ( -25.50888515336086471, 210.1678456467333262, 75.57414870955754793 ) ) ; -#24684 = ORIENTED_EDGE ( 'NONE', *, *, #14361, .F. ) ; -#24685 = DIRECTION ( 'NONE', ( 0.0005884949961242131244, -0.2249510543439063315, 0.9743698870671262391 ) ) ; -#24686 = CARTESIAN_POINT ( 'NONE', ( -38.41865702959000117, 119.0471156571999956, 87.62986678990000655 ) ) ; -#24687 = DIRECTION ( 'NONE', ( -0.9999998176078294110, -4.624125832697041071E-09, 0.0006039737643754598991 ) ) ; -#24688 = EDGE_CURVE ( 'NONE', #22702, #16794, #29479, .T. ) ; -#24689 = ORIENTED_EDGE ( 'NONE', *, *, #8450, .F. ) ; -#24690 = LINE ( 'NONE', #9736, #22618 ) ; -#24691 = ORIENTED_EDGE ( 'NONE', *, *, #5514, .T. ) ; -#24692 = CARTESIAN_POINT ( 'NONE', ( -25.49272541574507756, 191.9759150222000130, 101.9368443076606781 ) ) ; -#24693 = CARTESIAN_POINT ( 'NONE', ( -27.47868548835393554, 187.3896051497354165, 103.4449709403760664 ) ) ; -#24694 = CARTESIAN_POINT ( 'NONE', ( 15.99999293039724257, 151.9655111556795362, 94.72726368743165892 ) ) ; -#24695 = EDGE_LOOP ( 'NONE', ( #24021, #27320, #36769, #32689 ) ) ; -#24696 = CARTESIAN_POINT ( 'NONE', ( 20.00178331300101320, 191.9758063960465790, 106.9093738487591736 ) ) ; -#24697 = AXIS2_PLACEMENT_3D ( 'NONE', #4714, #20874, #24158 ) ; -#24698 = FACE_OUTER_BOUND ( 'NONE', #19796, .T. ) ; -#24699 = LINE ( 'NONE', #40200, #9153 ) ; -#24700 = CARTESIAN_POINT ( 'NONE', ( -35.69752021810370479, 164.7755956597675890, 192.0310054951918062 ) ) ; -#24701 = PLANE ( 'NONE', #3787 ) ; -#24702 = CYLINDRICAL_SURFACE ( 'NONE', #25649, 2.000000000000011546 ) ; -#24703 = CARTESIAN_POINT ( 'NONE', ( -37.30738829746174900, 117.9206417508360119, 90.29031756689468580 ) ) ; -#24704 = AXIS2_PLACEMENT_3D ( 'NONE', #18714, #34849, #31213 ) ; -#24705 = ORIENTED_EDGE ( 'NONE', *, *, #5493, .T. ) ; -#24706 = ORIENTED_EDGE ( 'NONE', *, *, #6492, .T. ) ; -#24707 = CARTESIAN_POINT ( 'NONE', ( 14.29931438863112092, 182.1696114513096632, 104.4382672223416222 ) ) ; -#24708 = CARTESIAN_POINT ( 'NONE', ( 0.5638618802117814077, 189.0000000030334490, 105.7369977366696219 ) ) ; -#24709 = CARTESIAN_POINT ( 'NONE', ( 26.00076108762728211, 119.7153706401760758, 90.35460073770548206 ) ) ; -#24710 = ORIENTED_EDGE ( 'NONE', *, *, #13157, .T. ) ; -#24711 = CARTESIAN_POINT ( 'NONE', ( 30.06995708078038376, 134.8478347390543490, 93.33259620325232220 ) ) ; -#24712 = EDGE_CURVE ( 'NONE', #43, #22159, #1531, .T. ) ; -#24713 = EDGE_CURVE ( 'NONE', #5306, #16662, #338, .T. ) ; -#24714 = ORIENTED_EDGE ( 'NONE', *, *, #3432, .F. ) ; -#24715 = FACE_OUTER_BOUND ( 'NONE', #18977, .T. ) ; -#24716 = CARTESIAN_POINT ( 'NONE', ( -29.30068297576036329, 112.1827979207552204, 175.8248936460288689 ) ) ; -#24717 = CARTESIAN_POINT ( 'NONE', ( -3.773828854691173795, 143.5900193873110595, 95.64051042385062829 ) ) ; -#24718 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#24719 = EDGE_LOOP ( 'NONE', ( #19498, #1087, #4184, #20503 ) ) ; -#24720 = CARTESIAN_POINT ( 'NONE', ( 35.58419356007505030, 192.4129442132274903, 106.8842446272596760 ) ) ; -#24721 = CARTESIAN_POINT ( 'NONE', ( -44.17354594865898321, 122.7351850097861217, 88.13690480915462899 ) ) ; -#24722 = CARTESIAN_POINT ( 'NONE', ( -25.90186315104000059, 190.6817704679999963, 106.6412877755000181 ) ) ; -#24723 = CARTESIAN_POINT ( 'NONE', ( -25.46031050648948835, 116.3743324429477752, 90.28316222877178632 ) ) ; -#24724 = CARTESIAN_POINT ( 'NONE', ( -37.94542170312856655, 145.9448510932590466, 287.7682489638611401 ) ) ; -#24725 = ORIENTED_EDGE ( 'NONE', *, *, #13200, .T. ) ; -#24726 = DIRECTION ( 'NONE', ( 0.7933530821293327540, 0.5932640870757643903, 0.1364866662427079991 ) ) ; -#24727 = LINE ( 'NONE', #24930, #10793 ) ; -#24728 = CARTESIAN_POINT ( 'NONE', ( 37.44995078656224763, 191.4485665340594096, 104.3357062982521200 ) ) ; -#24729 = VECTOR ( 'NONE', #1249, 1000.000000000000114 ) ; -#24730 = CARTESIAN_POINT ( 'NONE', ( -46.04337971101557514, 125.2490563996582722, 91.73451529294362672 ) ) ; -#24731 = ORIENTED_EDGE ( 'NONE', *, *, #22582, .F. ) ; -#24732 = CARTESIAN_POINT ( 'NONE', ( 38.65471576631835404, 119.1564763279458816, 90.25899222980254422 ) ) ; -#24733 = FACE_OUTER_BOUND ( 'NONE', #15571, .T. ) ; -#24734 = CARTESIAN_POINT ( 'NONE', ( 24.72869410855758687, 213.5506750203912816, 73.04356857080210830 ) ) ; -#24735 = CARTESIAN_POINT ( 'NONE', ( 19.98316611204134929, 210.6265419835666819, 73.04643475079905102 ) ) ; -#24736 = EDGE_CURVE ( 'NONE', #35055, #22424, #2861, .T. ) ; -#24737 = CARTESIAN_POINT ( 'NONE', ( -17.94609826159735633, 149.1879437480716035, 179.6906816993563041 ) ) ; -#24738 = CARTESIAN_POINT ( 'NONE', ( -25.50804370222000372, 190.9259865639999987, 106.3128279799000069 ) ) ; -#24739 = CARTESIAN_POINT ( 'NONE', ( -30.80024147420870051, 183.2447159666111816, 101.9769020043998751 ) ) ; -#24740 = CARTESIAN_POINT ( 'NONE', ( 10.31965884734673722, 131.0228646151953456, 89.89575833596944676 ) ) ; -#24741 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455649311516, -31.54510897440487938, 136.4474729010643159 ) ) ; -#24742 = FACE_OUTER_BOUND ( 'NONE', #3606, .T. ) ; -#24743 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35467, #17485, #20773, #19946, #38754, #20562, #1556, #38560, #16873, #33033, #29382, #4813, #5024, #23047, #7891, #4618 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.0003877968441633214782, 0.0007755936883266429565, 0.001163390532489964272, 0.001551187376653285913, 0.001938984220816607337, 0.002326781064979928544, 0.003102374753306582668 ), - .UNSPECIFIED. ) ; -#24744 = CARTESIAN_POINT ( 'NONE', ( 23.35435660873492125, 181.0170614477807476, 104.5088077577469221 ) ) ; -#24745 = VERTEX_POINT ( 'NONE', #6269 ) ; -#24746 = DIRECTION ( 'NONE', ( 2.489096615839555607E-14, -0.9743700558016280544, -0.2249510932561391563 ) ) ; -#24747 = CARTESIAN_POINT ( 'NONE', ( -20.15558927018948765, 184.3214773799085435, 105.1365765294155921 ) ) ; -#24748 = CARTESIAN_POINT ( 'NONE', ( -21.48817384324611979, 118.0722736972649898, 177.1883150436515280 ) ) ; -#24749 = CARTESIAN_POINT ( 'NONE', ( 36.36654068213999835, 191.7219889394999939, 106.3953969253999929 ) ) ; -#24750 = CARTESIAN_POINT ( 'NONE', ( 36.36211810150999924, 190.7161817749000079, 106.8880682140000005 ) ) ; -#24751 = ORIENTED_EDGE ( 'NONE', *, *, #1360, .F. ) ; -#24752 = ORIENTED_EDGE ( 'NONE', *, *, #29239, .F. ) ; -#24754 = AXIS2_PLACEMENT_3D ( 'NONE', #192, #21493, #39865 ) ; -#24753 = DIRECTION ( 'NONE', ( 0.1943643238945209628, -0.07321898756438961764, 0.9781929714821464561 ) ) ; -#24755 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319114355331 ) ) ; -#24756 = VECTOR ( 'NONE', #5748, 999.9999999999998863 ) ; -#24757 = CARTESIAN_POINT ( 'NONE', ( 25.83391288418735598, 118.1142945796899255, 90.08549593924796284 ) ) ; -#24758 = VECTOR ( 'NONE', #1314, 1000.000000000000114 ) ; -#24759 = EDGE_CURVE ( 'NONE', #4954, #19471, #18723, .T. ) ; -#24760 = EDGE_CURVE ( 'NONE', #18814, #25255, #24649, .T. ) ; -#24761 = ORIENTED_EDGE ( 'NONE', *, *, #12820, .T. ) ; -#24762 = CARTESIAN_POINT ( 'NONE', ( -38.90251905809999755, 119.2803178473000116, 90.18438403657999913 ) ) ; -#24763 = DIRECTION ( 'NONE', ( 0.0005884949961279498272, -0.2249510543439066645, 0.9743698870671262391 ) ) ; -#24764 = DIRECTION ( 'NONE', ( 3.469446951933831529E-16, -1.000000000000000000, -2.775557561547065224E-15 ) ) ; -#24765 = ORIENTED_EDGE ( 'NONE', *, *, #9688, .T. ) ; -#24766 = DIRECTION ( 'NONE', ( -0.7066795775160008564, -0.000000000000000000, 0.7075337269147008445 ) ) ; -#24767 = LINE ( 'NONE', #37614, #32878 ) ; -#24768 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971567068 ) ) ; -#24769 = DIRECTION ( 'NONE', ( -0.0005884949961246437695, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#24770 = CARTESIAN_POINT ( 'NONE', ( 24.86462005268900910, 181.6234868533236693, 104.6479044067249333 ) ) ; -#24771 = CARTESIAN_POINT ( 'NONE', ( -20.01839443158612397, 211.4829603436011780, 76.07060235661742809 ) ) ; -#24772 = ORIENTED_EDGE ( 'NONE', *, *, #6316, .F. ) ; -#24773 = CARTESIAN_POINT ( 'NONE', ( -28.12454816702999949, 187.5040379097000027, 103.0833663594000029 ) ) ; -#24774 = CARTESIAN_POINT ( 'NONE', ( 2.029765967374830282, 189.6354671328150232, 103.8765996616880045 ) ) ; -#24775 = FACE_OUTER_BOUND ( 'NONE', #29658, .T. ) ; -#24776 = EDGE_LOOP ( 'NONE', ( #14589, #34947, #2302, #31467 ) ) ; -#24777 = ORIENTED_EDGE ( 'NONE', *, *, #23358, .F. ) ; -#24778 = CARTESIAN_POINT ( 'NONE', ( 3.534206243108678702, 168.5015396740323581, 98.55243403413919623 ) ) ; -#24779 = VERTEX_POINT ( 'NONE', #18935 ) ; -#24780 = AXIS2_PLACEMENT_3D ( 'NONE', #31694, #38408, #13673 ) ; -#24781 = EDGE_CURVE ( 'NONE', #34802, #23158, #32230, .T. ) ; -#24782 = CIRCLE ( 'NONE', #5818, 22.00000000001092815 ) ; -#24783 = CONICAL_SURFACE ( 'NONE', #11051, 5.000000000100801145, 0.7853981634448925497 ) ; -#24784 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825598724, 151.4111237538535022, 97.16110465179032474 ) ) ; -#24785 = CARTESIAN_POINT ( 'NONE', ( -35.95747480195999657, 192.2464068831000077, 105.0133062726000190 ) ) ; -#24786 = VECTOR ( 'NONE', #2446, 1000.000000000000000 ) ; -#24787 = FACE_OUTER_BOUND ( 'NONE', #25939, .T. ) ; -#24788 = DIRECTION ( 'NONE', ( -0.6087614115774877543, 0.7730004600455410158, 0.1785492440296698458 ) ) ; -#24789 = CARTESIAN_POINT ( 'NONE', ( 36.06517739910999865, 192.1776130000999956, 106.5431043960000039 ) ) ; -#24790 = CARTESIAN_POINT ( 'NONE', ( -25.50127375672713725, 118.8155664721400058, 87.78318651355773738 ) ) ; -#24791 = CARTESIAN_POINT ( 'NONE', ( -36.63236904341999889, 191.1666167420000022, 106.4755554933000070 ) ) ; -#24792 = ORIENTED_EDGE ( 'NONE', *, *, #15755, .T. ) ; -#24793 = EDGE_CURVE ( 'NONE', #27115, #13672, #39239, .T. ) ; -#24794 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7503, #16499, #22469, #16304 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.003194535362460158325, 0.003705816747171950844 ), - .UNSPECIFIED. ) ; -#24795 = CARTESIAN_POINT ( 'NONE', ( -30.04055490880000079, 163.2729245447999915, 152.4718672074000381 ) ) ; -#24796 = DIRECTION ( 'NONE', ( -0.9999998176071864808, 0.000000000000000000, 0.0006039748286988863828 ) ) ; -#24798 = CARTESIAN_POINT ( 'NONE', ( -15.94475171933955693, 152.3708470875648686, 183.5791127486476171 ) ) ; -#24797 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24799 = VERTEX_POINT ( 'NONE', #3595 ) ; -#24800 = ORIENTED_EDGE ( 'NONE', *, *, #11877, .T. ) ; -#24801 = ADVANCED_FACE ( 'NONE', ( #28762 ), #38164, .F. ) ; -#24802 = ORIENTED_EDGE ( 'NONE', *, *, #34057, .F. ) ; -#24803 = EDGE_CURVE ( 'NONE', #16205, #1321, #447, .T. ) ; -#24804 = ORIENTED_EDGE ( 'NONE', *, *, #3305, .F. ) ; -#24805 = CARTESIAN_POINT ( 'NONE', ( 39.66605737025999900, 119.4471712140000079, 89.89566567319000967 ) ) ; -#24806 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -2.074124140377000483E-15, -0.0006039748319395083463 ) ) ; -#24807 = AXIS2_PLACEMENT_3D ( 'NONE', #24368, #36815, #8201 ) ; -#24808 = EDGE_CURVE ( 'NONE', #37651, #3915, #35869, .T. ) ; -#24809 = PLANE ( 'NONE', #31267 ) ; -#24810 = CARTESIAN_POINT ( 'NONE', ( -20.25903087670999980, 201.9933824238000000, 90.49061847330999342 ) ) ; -#24811 = CARTESIAN_POINT ( 'NONE', ( -12.64073606257721494, 135.0070896801547633, 90.95226204523241620 ) ) ; -#24812 = VERTEX_POINT ( 'NONE', #4607 ) ; -#24813 = VECTOR ( 'NONE', #10758, 1000.000000000000227 ) ; -#24814 = ORIENTED_EDGE ( 'NONE', *, *, #30184, .F. ) ; -#24815 = AXIS2_PLACEMENT_3D ( 'NONE', #22676, #973, #35911 ) ; -#24816 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22849, #953, #17077, #32247 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 3.918369104575206286E-11, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24817 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#24818 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901852, 132.2978364233190689, 93.26432363104480316 ) ) ; -#24819 = CIRCLE ( 'NONE', #1256, 6.000000000000007994 ) ; -#24820 = CARTESIAN_POINT ( 'NONE', ( 13.49999896020854528, 126.8049029696502430, 88.91681356176201234 ) ) ; -#24821 = LINE ( 'NONE', #40318, #11894 ) ; -#24822 = ORIENTED_EDGE ( 'NONE', *, *, #32262, .F. ) ; -#24823 = DIRECTION ( 'NONE', ( -0.7066795775298632121, -2.488830132209913689E-16, 0.7075337269008552532 ) ) ; -#24824 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11578, #20980, #15638, #17881, #30991, #2957, #18685, #39976, #11986, #37121, #15251, #30591, #6228, #6034, #9116, #39567, #27939, #21399 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.0009489744502343151061, 0.001423461675351503017, 0.001897948900468690928, 0.002372436125585878838, 0.002609679738144433762, 0.002846923350702988253, 0.003321410575820165322, 0.003795897800937342390 ), - .UNSPECIFIED. ) ; -#24825 = CARTESIAN_POINT ( 'NONE', ( 2.685831556720999824, 190.9742776067000136, 106.4315507416000059 ) ) ; -#24826 = VERTEX_POINT ( 'NONE', #10757 ) ; -#24827 = CARTESIAN_POINT ( 'NONE', ( 1.802356818792059556, 188.6677323499311569, 106.3017207989387884 ) ) ; -#24828 = VERTEX_POINT ( 'NONE', #38358 ) ; -#24829 = EDGE_CURVE ( 'NONE', #27587, #11205, #12009, .T. ) ; -#24830 = CARTESIAN_POINT ( 'NONE', ( -0.01811060958565999940, 181.5011387225000021, 104.6346866557999959 ) ) ; -#24831 = CARTESIAN_POINT ( 'NONE', ( 2.814369781637076962, 190.9457800965926708, 106.5567121617033166 ) ) ; -#24832 = LINE ( 'NONE', #11738, #28077 ) ; -#24833 = VERTEX_POINT ( 'NONE', #11162 ) ; -#24834 = CARTESIAN_POINT ( 'NONE', ( 25.99899579567804864, 120.3902236066977025, 87.43149108636995948 ) ) ; -#24835 = CARTESIAN_POINT ( 'NONE', ( -33.70405643004532692, 218.5902260770999987, 76.07886103513565956 ) ) ; -#24836 = CARTESIAN_POINT ( 'NONE', ( 0.5456353355600667143, 208.9999999999988916, 75.55817498829235035 ) ) ; -#24837 = AXIS2_PLACEMENT_3D ( 'NONE', #32055, #347, #29183 ) ; -#24838 = AXIS2_PLACEMENT_3D ( 'NONE', #21538, #27883, #12503 ) ; -#24839 = ORIENTED_EDGE ( 'NONE', *, *, #2816, .T. ) ; -#24840 = ADVANCED_FACE ( 'NONE', ( #23633 ), #17836, .T. ) ; -#24841 = AXIS2_PLACEMENT_3D ( 'NONE', #37349, #12592, #31419 ) ; -#24842 = VECTOR ( 'NONE', #36574, 1000.000000000000114 ) ; -#24843 = CARTESIAN_POINT ( 'NONE', ( -23.36150835703034190, 130.4188133218702319, 90.28973853220963974 ) ) ; -#24844 = ORIENTED_EDGE ( 'NONE', *, *, #30615, .T. ) ; -#24846 = CARTESIAN_POINT ( 'NONE', ( -3.169906973602109712, 126.7999172216492099, 88.92891361563410157 ) ) ; -#24845 = CARTESIAN_POINT ( 'NONE', ( -13.50718409113456886, 124.3648481134796242, 88.37302201493642428 ) ) ; -#24847 = ORIENTED_EDGE ( 'NONE', *, *, #2634, .T. ) ; -#24849 = ORIENTED_EDGE ( 'NONE', *, *, #23162, .F. ) ; -#24848 = ADVANCED_FACE ( 'NONE', ( #36082 ), #17062, .T. ) ; -#24850 = ORIENTED_EDGE ( 'NONE', *, *, #29730, .F. ) ; -#24851 = CARTESIAN_POINT ( 'NONE', ( 2.600535225549999829, 209.5323685392000073, 75.67987893369000574 ) ) ; -#24852 = EDGE_CURVE ( 'NONE', #20460, #25549, #35457, .T. ) ; -#24853 = CARTESIAN_POINT ( 'NONE', ( 3.166355817006013318, 184.7209557258482562, 102.2972154149039170 ) ) ; -#24854 = EDGE_LOOP ( 'NONE', ( #28283, #31662, #14494, #20563, #33967, #37842 ) ) ; -#24855 = ORIENTED_EDGE ( 'NONE', *, *, #25799, .T. ) ; -#24856 = ADVANCED_FACE ( 'NONE', ( #8084 ), #27696, .F. ) ; -#24857 = ORIENTED_EDGE ( 'NONE', *, *, #3716, .F. ) ; -#24858 = CARTESIAN_POINT ( 'NONE', ( -30.69720236079256992, 110.6131156702000027, 88.78632490663589749 ) ) ; -#24859 = DIRECTION ( 'NONE', ( 0.7933533411653264089, -0.5930537057989665461, -0.1373964268091649732 ) ) ; -#24860 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; -#24861 = ORIENTED_EDGE ( 'NONE', *, *, #17228, .T. ) ; -#24862 = ORIENTED_EDGE ( 'NONE', *, *, #35972, .T. ) ; -#24863 = ORIENTED_EDGE ( 'NONE', *, *, #24941, .F. ) ; -#24864 = CARTESIAN_POINT ( 'NONE', ( -5.670012814440080540, 124.0935331432966535, 91.03995203424359772 ) ) ; -#24865 = CARTESIAN_POINT ( 'NONE', ( 20.94615154526903567, 129.3425601203839221, 89.50137061379278691 ) ) ; -#24866 = CARTESIAN_POINT ( 'NONE', ( -25.73111875745999910, 121.5455867069999982, 88.07164025260999551 ) ) ; -#24867 = AXIS2_PLACEMENT_3D ( 'NONE', #3761, #16630, #31394 ) ; -#24868 = VERTEX_POINT ( 'NONE', #24041 ) ; -#24869 = CARTESIAN_POINT ( 'NONE', ( -14.46467930928257495, 149.8570382443049596, 184.5378989473168758 ) ) ; -#24870 = LINE ( 'NONE', #11784, #3868 ) ; -#24871 = AXIS2_PLACEMENT_3D ( 'NONE', #5975, #18027, #34174 ) ; -#24872 = EDGE_LOOP ( 'NONE', ( #25601, #26115, #1067, #32914 ) ) ; -#24873 = CIRCLE ( 'NONE', #33330, 2.000000000000000000 ) ; -#24874 = CIRCLE ( 'NONE', #18321, 2.499999999953833374 ) ; -#24875 = CARTESIAN_POINT ( 'NONE', ( 3.691301857067404324, 174.7169919634399662, 102.9066912158349254 ) ) ; -#24876 = CARTESIAN_POINT ( 'NONE', ( 14.29793062126701386, 176.6394715875823920, 100.7668241702324963 ) ) ; -#24877 = FACE_OUTER_BOUND ( 'NONE', #15458, .T. ) ; -#24878 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250611660, 132.8554482850399836, 90.84904174544993793 ) ) ; -#24879 = DIRECTION ( 'NONE', ( -0.5989082241854613020, 0.8008175873178837723, 0.0003617255600150170764 ) ) ; -#24880 = EDGE_LOOP ( 'NONE', ( #27409, #14972 ) ) ; -#24881 = LINE ( 'NONE', #5437, #3400 ) ; -#24882 = CARTESIAN_POINT ( 'NONE', ( 37.50072579531459382, 80.67056815341622666, 284.7731742817271652 ) ) ; -#24883 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#24884 = CARTESIAN_POINT ( 'NONE', ( 37.71625730213000338, 118.5106538418999946, 90.40116625531000238 ) ) ; -#24885 = CARTESIAN_POINT ( 'NONE', ( 45.20175636960371435, 116.0874664461612014, 126.6159648105440709 ) ) ; -#24886 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5761, #30717, #2710, #25 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 2.257925450127345695E-06, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24887 = EDGE_LOOP ( 'NONE', ( #2035, #5762, #25459, #36060 ) ) ; -#24888 = CARTESIAN_POINT ( 'NONE', ( 20.79492132475692401, 105.5805168949505486, 90.25522522787177593 ) ) ; -#24889 = ADVANCED_FACE ( 'NONE', ( #11773 ), #15243, .F. ) ; -#24890 = ORIENTED_EDGE ( 'NONE', *, *, #7353, .T. ) ; -#24891 = FACE_OUTER_BOUND ( 'NONE', #34408, .T. ) ; -#24892 = EDGE_CURVE ( 'NONE', #25997, #28271, #11569, .T. ) ; -#24893 = ADVANCED_FACE ( 'NONE', ( #21173 ), #225, .F. ) ; -#24894 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21428, #27765, #27168, #30209 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24895 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24896 = AXIS2_PLACEMENT_3D ( 'NONE', #26516, #7479, #1347 ) ; -#24897 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14746, #21076, #33523, #32730, #1647, #31481 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24898 = VERTEX_POINT ( 'NONE', #5628 ) ; -#24899 = FACE_OUTER_BOUND ( 'NONE', #31433, .T. ) ; -#24900 = EDGE_CURVE ( 'NONE', #35520, #23170, #21393, .T. ) ; -#24901 = AXIS2_PLACEMENT_3D ( 'NONE', #27975, #12602, #15087 ) ; -#24902 = CARTESIAN_POINT ( 'NONE', ( -39.72145289206626018, 121.0205764120224785, 124.6541090863944561 ) ) ; -#24903 = DIRECTION ( 'NONE', ( 0.1632030863883311977, -0.3417424275059330885, 0.9255143790539803739 ) ) ; -#24904 = CARTESIAN_POINT ( 'NONE', ( -35.36713754167588064, 164.6438278936635129, 191.4737616427881051 ) ) ; -#24905 = CARTESIAN_POINT ( 'NONE', ( 23.36311786012575453, 177.3181033220963911, 100.9835260450758767 ) ) ; -#24906 = CARTESIAN_POINT ( 'NONE', ( -35.64357260033455077, 114.3379716377514228, 90.28931266390532073 ) ) ; -#24907 = ORIENTED_EDGE ( 'NONE', *, *, #11018, .F. ) ; -#24908 = VERTEX_POINT ( 'NONE', #11350 ) ; -#24909 = EDGE_CURVE ( 'NONE', #28309, #21459, #33522, .T. ) ; -#24910 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 3.781471998463680422E-12, 291.5876487235622108 ) ) ; -#24911 = DIRECTION ( 'NONE', ( 0.7072735235945206700, 0.6508952239914190807, 0.2758615054830080293 ) ) ; -#24912 = EDGE_LOOP ( 'NONE', ( #9805, #30311, #37671, #3527 ) ) ; -#24913 = PLANE ( 'NONE', #33750 ) ; -#24914 = ORIENTED_EDGE ( 'NONE', *, *, #7688, .T. ) ; -#24915 = CARTESIAN_POINT ( 'NONE', ( -20.50418741012917678, 191.9757880780653068, 101.9338467359436322 ) ) ; -#24916 = ADVANCED_FACE ( 'NONE', ( #40364 ), #9918, .F. ) ; -#24917 = CARTESIAN_POINT ( 'NONE', ( -5.667172181233267381, 130.8762171797660869, 89.99523841397406443 ) ) ; -#24918 = FACE_OUTER_BOUND ( 'NONE', #28938, .T. ) ; -#24919 = ORIENTED_EDGE ( 'NONE', *, *, #38018, .F. ) ; -#24920 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#24921 = CARTESIAN_POINT ( 'NONE', ( -43.57128771414367918, 121.9172130293124212, 88.19101713714755419 ) ) ; -#24922 = FACE_OUTER_BOUND ( 'NONE', #32527, .T. ) ; -#24923 = AXIS2_PLACEMENT_3D ( 'NONE', #21641, #21030, #2630 ) ; -#24924 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971597321 ) ) ; -#24925 = CARTESIAN_POINT ( 'NONE', ( 3.333016505657594220, 125.9281135555316240, 88.72370363824984452 ) ) ; -#24926 = VERTEX_POINT ( 'NONE', #25258 ) ; -#24927 = AXIS2_PLACEMENT_3D ( 'NONE', #7033, #3363, #18689 ) ; -#24928 = CARTESIAN_POINT ( 'NONE', ( -14.55306118018871508, 176.9194272080598296, 100.5067835523781667 ) ) ; -#24929 = VECTOR ( 'NONE', #12479, 1000.000000000000114 ) ; -#24930 = CARTESIAN_POINT ( 'NONE', ( 15.46162228069872313, 153.1807904976651571, 28.07870763888208998 ) ) ; -#24931 = FACE_OUTER_BOUND ( 'NONE', #27767, .T. ) ; -#24932 = CARTESIAN_POINT ( 'NONE', ( -46.02961742942664358, 125.2286349362630204, 91.74328517761594526 ) ) ; -#24933 = ORIENTED_EDGE ( 'NONE', *, *, #8961, .T. ) ; -#24934 = ORIENTED_EDGE ( 'NONE', *, *, #11487, .F. ) ; -#24935 = PLANE ( 'NONE', #27094 ) ; -#24936 = DIRECTION ( 'NONE', ( -0.0005884949961219227473, 0.2249510543439028620, -0.9743698870671272383 ) ) ; -#24937 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#24938 = CARTESIAN_POINT ( 'NONE', ( -25.54227450396999899, 190.4807502401999955, 106.2100577384999980 ) ) ; -#24939 = EDGE_CURVE ( 'NONE', #30873, #22764, #9713, .T. ) ; -#24940 = EDGE_CURVE ( 'NONE', #7275, #35342, #16789, .T. ) ; -#24941 = EDGE_CURVE ( 'NONE', #27328, #8100, #11445, .T. ) ; -#24942 = CARTESIAN_POINT ( 'NONE', ( -12.63887418211175095, 181.8702697237338839, 101.8994121222765159 ) ) ; -#24943 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971581778 ) ) ; -#24944 = CARTESIAN_POINT ( 'NONE', ( -2.604006908027095779, 196.2716038095343265, 103.7464336095590340 ) ) ; -#24945 = CARTESIAN_POINT ( 'NONE', ( -37.52245665281768794, 145.6118553205347439, 282.0399067415914374 ) ) ; -#24946 = EDGE_CURVE ( 'NONE', #3689, #7666, #18732, .T. ) ; -#24947 = CARTESIAN_POINT ( 'NONE', ( -19.99825438583805237, 190.8509747501094580, 106.8052823956111013 ) ) ; -#24948 = CARTESIAN_POINT ( 'NONE', ( 36.19014522556999935, 192.0260854207000136, 105.7241431756999930 ) ) ; -#24949 = AXIS2_PLACEMENT_3D ( 'NONE', #27891, #21548, #6180 ) ; -#24950 = CARTESIAN_POINT ( 'NONE', ( 36.41168230344000278, 191.0646043602000077, 106.6848967381999955 ) ) ; -#24951 = ORIENTED_EDGE ( 'NONE', *, *, #20370, .F. ) ; -#24952 = ORIENTED_EDGE ( 'NONE', *, *, #6810, .F. ) ; -#24953 = ORIENTED_EDGE ( 'NONE', *, *, #39523, .T. ) ; -#24954 = VECTOR ( 'NONE', #20159, 999.9999999999998863 ) ; -#24955 = ADVANCED_FACE ( 'NONE', ( #13577 ), #31591, .F. ) ; -#24956 = CARTESIAN_POINT ( 'NONE', ( -5.255239607819333969, 135.0401204062967508, 90.83256365259357779 ) ) ; -#24957 = AXIS2_PLACEMENT_3D ( 'NONE', #36834, #8839, #21307 ) ; -#24958 = CARTESIAN_POINT ( 'NONE', ( 32.43759465430078137, 141.7182063835813324, 280.9329271823174281 ) ) ; -#24959 = CARTESIAN_POINT ( 'NONE', ( -30.07215349727681541, 177.7873460224360542, 100.7165300549321643 ) ) ; -#24960 = ORIENTED_EDGE ( 'NONE', *, *, #5041, .T. ) ; -#24961 = CARTESIAN_POINT ( 'NONE', ( 36.50162370931000311, 191.8959790318999978, 104.5103187171999934 ) ) ; -#24962 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971545418 ) ) ; -#24963 = CARTESIAN_POINT ( 'NONE', ( -15.10714331244187214, 129.6097141051087362, 89.58480571958619976 ) ) ; -#24964 = CYLINDRICAL_SURFACE ( 'NONE', #3975, 9.000000000000001776 ) ; -#24965 = ORIENTED_EDGE ( 'NONE', *, *, #33014, .T. ) ; -#24966 = CARTESIAN_POINT ( 'NONE', ( -21.57450327001340540, 130.0068484170668341, 89.85144842513163610 ) ) ; -#24967 = PLANE ( 'NONE', #28958 ) ; -#24968 = CARTESIAN_POINT ( 'NONE', ( 41.39749877257511201, 121.2433985891848067, 87.61916177723681187 ) ) ; -#24969 = CARTESIAN_POINT ( 'NONE', ( 37.02554508276092804, 117.3704043342096952, 90.24542233776027444 ) ) ; -#24970 = CARTESIAN_POINT ( 'NONE', ( -13.49823346095841714, 185.2306144803302459, 105.5070429579131144 ) ) ; -#24971 = ORIENTED_EDGE ( 'NONE', *, *, #8062, .T. ) ; -#24972 = CARTESIAN_POINT ( 'NONE', ( 13.43345251867550516, 169.1002433633066744, 29.42954392776661976 ) ) ; -#24973 = CARTESIAN_POINT ( 'NONE', ( 2.508104382811000121, 190.4796221226000057, 104.1196928475000050 ) ) ; -#24974 = CARTESIAN_POINT ( 'NONE', ( -28.46737701140902033, 184.1209660424817400, 102.1777913196515755 ) ) ; -#24975 = ORIENTED_EDGE ( 'NONE', *, *, #19721, .T. ) ; -#24976 = CARTESIAN_POINT ( 'NONE', ( 31.79629795468130027, 77.14301703112144537, 291.5393397680163616 ) ) ; -#24977 = ORIENTED_EDGE ( 'NONE', *, *, #19274, .F. ) ; -#24978 = CONICAL_SURFACE ( 'NONE', #6668, 2.499999999971520115, 0.7853981634347277918 ) ; -#24979 = AXIS2_PLACEMENT_3D ( 'NONE', #9346, #34259, #28166 ) ; -#24980 = CARTESIAN_POINT ( 'NONE', ( -16.56460900707709882, 121.8134807487768398, 177.5599358238133618 ) ) ; -#24981 = DIRECTION ( 'NONE', ( -0.7075229215369458480, -9.360719862668606239E-05, -0.7066903895890456200 ) ) ; -#24982 = CARTESIAN_POINT ( 'NONE', ( 13.49999901409649361, 138.5114860101464558, 91.61958570690872250 ) ) ; -#24983 = EDGE_CURVE ( 'NONE', #32940, #20118, #39709, .T. ) ; -#24984 = EDGE_CURVE ( 'NONE', #28078, #10631, #9493, .T. ) ; -#24985 = DIRECTION ( 'NONE', ( 0.7730662169443226484, 0.5272861007345267526, 0.3526159273084130130 ) ) ; -#24986 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#24987 = LINE ( 'NONE', #21911, #34059 ) ; -#24988 = CARTESIAN_POINT ( 'NONE', ( -13.46442671968396709, 158.3027909046028583, 96.20813345690331175 ) ) ; -#24989 = CARTESIAN_POINT ( 'NONE', ( -36.48805020081999828, 191.2769265263999898, 106.4956810465999979 ) ) ; -#24990 = ORIENTED_EDGE ( 'NONE', *, *, #16815, .T. ) ; -#24991 = DIRECTION ( 'NONE', ( 0.0005884949961183550717, -0.2249510543439067201, 0.9743698870671262391 ) ) ; -#24992 = CARTESIAN_POINT ( 'NONE', ( 19.71670726246199123, 125.1288345936551423, 175.0446023669997260 ) ) ; -#24993 = FACE_OUTER_BOUND ( 'NONE', #12497, .T. ) ; -#24995 = DIRECTION ( 'NONE', ( 0.0004161288024472093046, 0.5299192578742120130, 0.8480479980348188951 ) ) ; -#24994 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2255194953558363191, 0.9742386449830560124 ) ) ; -#24996 = ORIENTED_EDGE ( 'NONE', *, *, #39996, .T. ) ; -#24997 = VERTEX_POINT ( 'NONE', #2122 ) ; -#24998 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19647, #30989, #7181, #7376, #32141, #13932, #20450, #27029, #17375, #36412, #8416 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998875899, 0.3749999999998465672, 0.4374999999998260836, 0.4687499999998270828, 0.4999999999998280265, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#24999 = DIRECTION ( 'NONE', ( -0.5987319967475925875, -0.8009494341533932582, 0.000000000000000000 ) ) ; -#25000 = CONICAL_SURFACE ( 'NONE', #8683, 2.503023047069385942, 0.7853981633776393467 ) ; -#25001 = VERTEX_POINT ( 'NONE', #27493 ) ; -#25002 = CARTESIAN_POINT ( 'NONE', ( 39.81878037047000163, 119.5363919051000039, 89.91683048606999762 ) ) ; -#25004 = AXIS2_PLACEMENT_3D ( 'NONE', #26007, #15974, #28463 ) ; -#25003 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#25005 = EDGE_CURVE ( 'NONE', #33342, #38719, #33376, .T. ) ; -#25006 = VECTOR ( 'NONE', #37883, 1000.000000000000114 ) ; -#25007 = DIRECTION ( 'NONE', ( -0.6087614115774880874, 0.7730004600455407937, 0.1785492440296698458 ) ) ; -#25008 = CARTESIAN_POINT ( 'NONE', ( -3.168110071453226873, 118.9426017752647766, 90.19381027778267423 ) ) ; -#25009 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; -#25010 = ORIENTED_EDGE ( 'NONE', *, *, #3219, .F. ) ; -#25011 = CARTESIAN_POINT ( 'NONE', ( 15.95593686717950277, 122.0690666329238638, 173.7395398366195991 ) ) ; -#25012 = ORIENTED_EDGE ( 'NONE', *, *, #25640, .F. ) ; -#25013 = CARTESIAN_POINT ( 'NONE', ( -20.01758686034237655, 208.0209483956256804, 76.93031517792222473 ) ) ; -#25014 = CARTESIAN_POINT ( 'NONE', ( 19.98271301993268523, 207.8686081833218111, 77.26500776042075813 ) ) ; -#25015 = DIRECTION ( 'NONE', ( 0.0005884949961189402156, -0.2249510543439089960, 0.9743698870671257950 ) ) ; -#25016 = ORIENTED_EDGE ( 'NONE', *, *, #37474, .T. ) ; -#25017 = ORIENTED_EDGE ( 'NONE', *, *, #27359, .F. ) ; -#25018 = CARTESIAN_POINT ( 'NONE', ( 20.48231950984458649, 205.5677633305384120, 76.28703242847967658 ) ) ; -#25019 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8812, #27236, #15149, #27834, #33930, #5735 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.003244958643172611134, 0.5016224793215863231, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25020 = CARTESIAN_POINT ( 'NONE', ( 0.7856033910142913301, 188.6233245537923437, 103.1995748073575498 ) ) ; -#25021 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.298960938811000068E-14, 1.000000000000000000 ) ) ; -#25022 = ADVANCED_FACE ( 'NONE', ( #24209 ), #27020, .F. ) ; -#25023 = ORIENTED_EDGE ( 'NONE', *, *, #13782, .F. ) ; -#25024 = ORIENTED_EDGE ( 'NONE', *, *, #28305, .F. ) ; -#25025 = CARTESIAN_POINT ( 'NONE', ( -43.55091174308670787, 114.1088787615119600, 121.9228278241811125 ) ) ; -#25026 = LINE ( 'NONE', #14808, #32981 ) ; -#25027 = CARTESIAN_POINT ( 'NONE', ( 36.42022666025140865, 191.3502071219474772, 103.8076029485790883 ) ) ; -#25028 = CARTESIAN_POINT ( 'NONE', ( 41.55515210090072742, 120.2182341932538776, 89.94814927363270840 ) ) ; -#25029 = CIRCLE ( 'NONE', #12588, 48.00000000000002132 ) ; -#25030 = ORIENTED_EDGE ( 'NONE', *, *, #9053, .F. ) ; -#25031 = EDGE_CURVE ( 'NONE', #36967, #31566, #14602, .T. ) ; -#25032 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#25033 = AXIS2_PLACEMENT_3D ( 'NONE', #11764, #37104, #6022 ) ; -#25034 = EDGE_CURVE ( 'NONE', #6177, #1951, #9868, .T. ) ; -#25035 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#25036 = CARTESIAN_POINT ( 'NONE', ( 47.96253192634829077, 87.27946979429619034, 302.5295777741103507 ) ) ; -#25037 = EDGE_CURVE ( 'NONE', #33368, #2967, #2619, .T. ) ; -#25038 = CIRCLE ( 'NONE', #33498, 9.999999999999667821 ) ; -#25039 = ORIENTED_EDGE ( 'NONE', *, *, #7150, .T. ) ; -#25040 = EDGE_CURVE ( 'NONE', #27937, #7297, #27559, .T. ) ; -#25041 = CARTESIAN_POINT ( 'NONE', ( -28.46561152641095660, 183.4461128795074956, 105.1009009807951884 ) ) ; -#25042 = PLANE ( 'NONE', #12657 ) ; -#25043 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #10352, #7252 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 0.9999992929077466952 ), - .UNSPECIFIED. ) ; -#25045 = LINE ( 'NONE', #31363, #10277 ) ; -#25044 = DIRECTION ( 'NONE', ( 5.828670879282083197E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#25046 = VERTEX_POINT ( 'NONE', #13326 ) ; -#25047 = ORIENTED_EDGE ( 'NONE', *, *, #4530, .T. ) ; -#25048 = CARTESIAN_POINT ( 'NONE', ( 30.02141571457803337, 185.4797026207797899, 105.5350675521475381 ) ) ; -#25049 = LINE ( 'NONE', #35401, #31245 ) ; -#25050 = EDGE_LOOP ( 'NONE', ( #22087, #20153, #39897, #33454 ) ) ; -#25051 = EDGE_LOOP ( 'NONE', ( #38504, #24914, #15822, #7481 ) ) ; -#25052 = DIRECTION ( 'NONE', ( -3.006854025019484316E-14, -0.9743700557921584071, -0.2249510932971569566 ) ) ; -#25053 = FACE_OUTER_BOUND ( 'NONE', #40418, .T. ) ; -#25054 = CARTESIAN_POINT ( 'NONE', ( 8.329377690075951080, 151.1912382591438870, 94.89524035922103451 ) ) ; -#25055 = PLANE ( 'NONE', #39802 ) ; -#25056 = VECTOR ( 'NONE', #17409, 1000.000000000000000 ) ; -#25057 = ORIENTED_EDGE ( 'NONE', *, *, #35229, .T. ) ; -#25058 = ORIENTED_EDGE ( 'NONE', *, *, #15423, .T. ) ; -#25059 = CARTESIAN_POINT ( 'NONE', ( -5.669680444114638007, 123.9805980431854948, 91.11052156128529589 ) ) ; -#25060 = CARTESIAN_POINT ( 'NONE', ( 20.20873812859954555, 128.4129448192833820, 89.28717972900743405 ) ) ; -#25061 = AXIS2_PLACEMENT_3D ( 'NONE', #31935, #22732, #16372 ) ; -#25062 = CARTESIAN_POINT ( 'NONE', ( -41.95974523811950263, 77.14301703112136011, 284.1899085454229521 ) ) ; -#25063 = ORIENTED_EDGE ( 'NONE', *, *, #10349, .F. ) ; -#25064 = AXIS2_PLACEMENT_3D ( 'NONE', #28715, #37505, #15443 ) ; -#25065 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749095712, 132.4103119505919892, 92.77713868751720838 ) ) ; -#25066 = LINE ( 'NONE', #20252, #5178 ) ; -#25067 = ORIENTED_EDGE ( 'NONE', *, *, #13617, .T. ) ; -#25068 = EDGE_CURVE ( 'NONE', #33719, #7971, #28323, .T. ) ; -#25069 = FACE_OUTER_BOUND ( 'NONE', #16225, .T. ) ; -#25070 = CARTESIAN_POINT ( 'NONE', ( -21.44517133422852240, 176.2436636369649534, 103.4338440792942890 ) ) ; -#25071 = EDGE_CURVE ( 'NONE', #7877, #31651, #23103, .T. ) ; -#25072 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971577060 ) ) ; -#25073 = LINE ( 'NONE', #28331, #3204 ) ; -#25074 = VERTEX_POINT ( 'NONE', #26410 ) ; -#25075 = CARTESIAN_POINT ( 'NONE', ( -27.18627669408000003, 103.8631156702000027, 90.03420462350000264 ) ) ; -#25076 = ORIENTED_EDGE ( 'NONE', *, *, #14137, .F. ) ; -#25077 = VERTEX_POINT ( 'NONE', #35166 ) ; -#25079 = EDGE_CURVE ( 'NONE', #10320, #4933, #30426, .T. ) ; -#25078 = CARTESIAN_POINT ( 'NONE', ( 40.75388439505659477, 77.63890577630509426, 286.8133149076603559 ) ) ; -#25080 = EDGE_CURVE ( 'NONE', #38370, #16282, #36271, .T. ) ; -#25081 = CARTESIAN_POINT ( 'NONE', ( 19.73921667059327234, 149.8473492619755802, 180.1939462582248836 ) ) ; -#25082 = CYLINDRICAL_SURFACE ( 'NONE', #24227, 51.40509898897000340 ) ; -#25083 = EDGE_CURVE ( 'NONE', #16053, #22424, #33737, .T. ) ; -#25084 = EDGE_CURVE ( 'NONE', #34146, #37846, #37449, .T. ) ; -#25085 = CARTESIAN_POINT ( 'NONE', ( 15.99998378901094576, 184.9656665294078266, 102.3459542884652365 ) ) ; -#25086 = ORIENTED_EDGE ( 'NONE', *, *, #5668, .T. ) ; -#25087 = AXIS2_PLACEMENT_3D ( 'NONE', #21092, #11686, #27850 ) ; -#25088 = VECTOR ( 'NONE', #26794, 1000.000000000000000 ) ; -#25089 = CYLINDRICAL_SURFACE ( 'NONE', #6280, 6.000000000000008882 ) ; -#25090 = EDGE_LOOP ( 'NONE', ( #22930, #21354, #28732, #30160 ) ) ; -#25091 = VECTOR ( 'NONE', #10646, 1000.000000000000114 ) ; -#25092 = CARTESIAN_POINT ( 'NONE', ( -26.81810550607417554, 188.0528084918596221, 103.5976845505095554 ) ) ; -#25093 = VECTOR ( 'NONE', #10266, 1000.000000000000114 ) ; -#25094 = ORIENTED_EDGE ( 'NONE', *, *, #27299, .F. ) ; -#25095 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971565125 ) ) ; -#25096 = LINE ( 'NONE', #9542, #25199 ) ; -#25097 = CARTESIAN_POINT ( 'NONE', ( -49.98529739233697455, 137.2549075708836313, 297.5887348966869013 ) ) ; -#25098 = CARTESIAN_POINT ( 'NONE', ( -22.10847448091438139, 158.3221973905858704, 96.21783456353770703 ) ) ; -#25099 = CARTESIAN_POINT ( 'NONE', ( -35.50523995327358051, 113.6628431183386709, 90.28922911445282296 ) ) ; -#25100 = VERTEX_POINT ( 'NONE', #27447 ) ; -#25101 = EDGE_LOOP ( 'NONE', ( #839, #20769, #4655, #13545 ) ) ; -#25102 = CARTESIAN_POINT ( 'NONE', ( -38.95487693986197542, 209.7096538831000316, 76.08203239919926375 ) ) ; -#25103 = EDGE_CURVE ( 'NONE', #10007, #38150, #17778, .T. ) ; -#25104 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250907130, 179.1753088544017487, 103.5954339977648857 ) ) ; -#25105 = EDGE_LOOP ( 'NONE', ( #22490, #22230, #21400, #25671 ) ) ; -#25106 = CARTESIAN_POINT ( 'NONE', ( 30.06907600959092264, 134.5278394841953684, 93.53255188149118737 ) ) ; -#25107 = ORIENTED_EDGE ( 'NONE', *, *, #34005, .T. ) ; -#25108 = CARTESIAN_POINT ( 'NONE', ( -46.39481885264477512, 125.2269168869080431, 89.10500611615424305 ) ) ; -#25109 = CARTESIAN_POINT ( 'NONE', ( -3.761126252317481100, 143.5871800388951840, 95.65287630653199358 ) ) ; -#25110 = CARTESIAN_POINT ( 'NONE', ( -30.07186420872989530, 134.5903996172291102, 93.52297053483064815 ) ) ; -#25111 = ORIENTED_EDGE ( 'NONE', *, *, #7931, .F. ) ; -#25112 = CARTESIAN_POINT ( 'NONE', ( 28.34935775597000074, 125.4855392668000036, 88.94861811456999590 ) ) ; -#25113 = AXIS2_PLACEMENT_3D ( 'NONE', #18546, #14713, #9177 ) ; -#25114 = AXIS2_PLACEMENT_3D ( 'NONE', #37758, #345, #945 ) ; -#25115 = EDGE_CURVE ( 'NONE', #72, #34749, #17987, .T. ) ; -#25116 = FACE_OUTER_BOUND ( 'NONE', #22820, .T. ) ; -#25117 = LINE ( 'NONE', #19354, #35756 ) ; -#25118 = AXIS2_PLACEMENT_3D ( 'NONE', #8177, #8592, #23319 ) ; -#25119 = CARTESIAN_POINT ( 'NONE', ( -24.05908733069920302, 115.3062187369053788, 90.28231592508538483 ) ) ; -#25120 = CARTESIAN_POINT ( 'NONE', ( 20.06217115067450152, 160.1130821803652111, 96.60582295762662852 ) ) ; -#25121 = ORIENTED_EDGE ( 'NONE', *, *, #35352, .F. ) ; -#25122 = DIRECTION ( 'NONE', ( -0.0006039748319379876444, -1.544770086762009064E-14, -0.9999998176071845934 ) ) ; -#25123 = ADVANCED_FACE ( 'NONE', ( #33933 ), #24967, .F. ) ; -#25124 = CARTESIAN_POINT ( 'NONE', ( 42.44241944724925730, 182.6774603752619441, 137.7418560869625708 ) ) ; -#25125 = CARTESIAN_POINT ( 'NONE', ( 42.85442617173308832, 113.6598254356972149, 123.5406245648973993 ) ) ; -#25126 = EDGE_CURVE ( 'NONE', #29325, #31175, #5934, .T. ) ; -#25127 = DIRECTION ( 'NONE', ( 0.7933533411653097556, -0.5930537057989896388, -0.1373964268091597829 ) ) ; -#25128 = VERTEX_POINT ( 'NONE', #30891 ) ; -#25129 = CARTESIAN_POINT ( 'NONE', ( 38.47871008559464201, 119.0226701210926024, 90.24978937670915968 ) ) ; -#25130 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17692, #1771, #13835, #23243, #4819, #32644, #33038, #17285, #35679, #19950 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25131 = FACE_OUTER_BOUND ( 'NONE', #22187, .T. ) ; -#25132 = DIRECTION ( 'NONE', ( 0.0005884949961239157278, -0.2249510543439051935, 0.9743698870671265722 ) ) ; -#25133 = EDGE_CURVE ( 'NONE', #39586, #27000, #24767, .T. ) ; -#25134 = CARTESIAN_POINT ( 'NONE', ( -25.67278038845593713, 190.9183653190244172, 106.4822186747260275 ) ) ; -#25135 = ORIENTED_EDGE ( 'NONE', *, *, #11859, .T. ) ; -#25136 = CARTESIAN_POINT ( 'NONE', ( 37.96340687623389698, 191.0388351520254560, 103.7347888148996446 ) ) ; -#25137 = CARTESIAN_POINT ( 'NONE', ( 5.666787590609001946, 130.4226561650734766, 90.27309335910574362 ) ) ; -#25138 = AXIS2_PLACEMENT_3D ( 'NONE', #652, #9268, #3114 ) ; -#25139 = ORIENTED_EDGE ( 'NONE', *, *, #14354, .T. ) ; -#25140 = CYLINDRICAL_SURFACE ( 'NONE', #34186, 2.250000000000011102 ) ; -#25141 = LINE ( 'NONE', #28597, #37494 ) ; -#25142 = CARTESIAN_POINT ( 'NONE', ( -75.39652672445234316, 196.3653591838614147, 189.1162797731339822 ) ) ; -#25143 = CARTESIAN_POINT ( 'NONE', ( 37.68864880440000320, 190.9636362356999939, 106.2833514884000010 ) ) ; -#25144 = VECTOR ( 'NONE', #37348, 1000.000000000000114 ) ; -#25146 = ORIENTED_EDGE ( 'NONE', *, *, #4314, .T. ) ; -#25145 = CARTESIAN_POINT ( 'NONE', ( 36.20133086596000282, 190.8593587157999991, 106.9219863341999996 ) ) ; -#25147 = ORIENTED_EDGE ( 'NONE', *, *, #25950, .T. ) ; -#25148 = VERTEX_POINT ( 'NONE', #12669 ) ; -#25149 = CARTESIAN_POINT ( 'NONE', ( -3.893460978919630389, 148.9599728421477494, 129.9645419189286883 ) ) ; -#25150 = CARTESIAN_POINT ( 'NONE', ( 20.48673967653602901, 211.0896571907997554, 75.54495990469186495 ) ) ; -#25151 = CARTESIAN_POINT ( 'NONE', ( -28.94720267997999841, 110.6131156702000027, 88.78526795067999444 ) ) ; -#25152 = EDGE_LOOP ( 'NONE', ( #31593, #15265, #15399, #23638, #31825 ) ) ; -#25153 = CARTESIAN_POINT ( 'NONE', ( 36.28650120326999939, 114.3988653761000052, 87.86647717035999960 ) ) ; -#25154 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25155 = CARTESIAN_POINT ( 'NONE', ( 31.79542160255000027, 226.4002260771029285, 75.53930090045706436 ) ) ; -#25156 = DIRECTION ( 'NONE', ( 0.7066795775160008564, -1.024537656994001489E-14, -0.7075337269147008445 ) ) ; -#25157 = ADVANCED_FACE ( 'NONE', ( #6520 ), #3448, .T. ) ; -#25158 = VERTEX_POINT ( 'NONE', #16136 ) ; -#25159 = DIRECTION ( 'NONE', ( 5.677692444543882716E-15, 0.9743700557921585181, 0.2249510932971561239 ) ) ; -#25160 = EDGE_CURVE ( 'NONE', #23757, #20371, #10421, .T. ) ; -#25161 = EDGE_CURVE ( 'NONE', #13070, #24276, #6003, .T. ) ; -#25162 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#25163 = EDGE_CURVE ( 'NONE', #650, #33804, #4797, .T. ) ; -#25164 = CARTESIAN_POINT ( 'NONE', ( -6.831231556254691917, 155.4618032185357492, 100.6797548176731993 ) ) ; -#25165 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971552357 ) ) ; -#25166 = DIRECTION ( 'NONE', ( -0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; -#25167 = AXIS2_PLACEMENT_3D ( 'NONE', #21413, #6051, #15650 ) ; -#25168 = VERTEX_POINT ( 'NONE', #26363 ) ; -#25169 = FACE_OUTER_BOUND ( 'NONE', #32918, .T. ) ; -#25170 = CARTESIAN_POINT ( 'NONE', ( 1.551058168003000004, 189.2638696655000103, 103.7676963477999976 ) ) ; -#25171 = VECTOR ( 'NONE', #5320, 1000.000000000000114 ) ; -#25172 = CIRCLE ( 'NONE', #12745, 2.000000000000011546 ) ; -#25173 = CARTESIAN_POINT ( 'NONE', ( -42.84346822158022405, 121.2532099058262531, 90.73602644257893246 ) ) ; -#25174 = ADVANCED_FACE ( 'NONE', ( #25564 ), #7395, .F. ) ; -#25175 = ORIENTED_EDGE ( 'NONE', *, *, #11288, .F. ) ; -#25176 = VECTOR ( 'NONE', #26045, 1000.000000000000000 ) ; -#25177 = VERTEX_POINT ( 'NONE', #12374 ) ; -#25178 = CARTESIAN_POINT ( 'NONE', ( 13.51165246697000022, 180.7017300104000128, 28.07991271570000080 ) ) ; -#25179 = EDGE_LOOP ( 'NONE', ( #16194, #1943, #10258, #10644 ) ) ; -#25180 = ADVANCED_FACE ( 'NONE', ( #21601 ), #2960, .T. ) ; -#25181 = CARTESIAN_POINT ( 'NONE', ( -17.26178683907535927, 121.7484489831825130, 175.4673707433541949 ) ) ; -#25182 = CARTESIAN_POINT ( 'NONE', ( -20.51984876312966222, 210.1697757641009900, 73.57088085165091229 ) ) ; -#25183 = CARTESIAN_POINT ( 'NONE', ( 24.52812286584232382, 213.0894194010092519, 75.54387266846563875 ) ) ; -#25184 = CARTESIAN_POINT ( 'NONE', ( -12.63559448522873652, 176.9615553361401510, 103.3843939381521864 ) ) ; -#25185 = LINE ( 'NONE', #3465, #12868 ) ; -#25186 = ORIENTED_EDGE ( 'NONE', *, *, #28006, .T. ) ; -#25187 = PLANE ( 'NONE', #7533 ) ; -#25188 = DIRECTION ( 'NONE', ( -4.086237521180584978E-14, -0.9743700557921587402, -0.2249510932971558463 ) ) ; -#25189 = ORIENTED_EDGE ( 'NONE', *, *, #38131, .F. ) ; -#25190 = FACE_OUTER_BOUND ( 'NONE', #600, .T. ) ; -#25191 = DIRECTION ( 'NONE', ( -3.469446951953620894E-15, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#25192 = CARTESIAN_POINT ( 'NONE', ( -0.02805196447938418727, 127.1761617620222893, 297.5585619722723436 ) ) ; -#25193 = CARTESIAN_POINT ( 'NONE', ( 15.10764778216198323, 128.9370057249701063, 92.49016256005407399 ) ) ; -#25194 = VERTEX_POINT ( 'NONE', #20611 ) ; -#25195 = ORIENTED_EDGE ( 'NONE', *, *, #18512, .T. ) ; -#25196 = AXIS2_PLACEMENT_3D ( 'NONE', #9844, #32114, #31720 ) ; -#25197 = AXIS2_PLACEMENT_3D ( 'NONE', #21752, #21138, #36875 ) ; -#25198 = ORIENTED_EDGE ( 'NONE', *, *, #12537, .F. ) ; -#25199 = VECTOR ( 'NONE', #37149, 1000.000000000000114 ) ; -#25200 = CARTESIAN_POINT ( 'NONE', ( -20.16654258404202693, 118.8155352270249381, 87.44669327667693892 ) ) ; -#25201 = CIRCLE ( 'NONE', #14102, 7.999999999999992895 ) ; -#25202 = ORIENTED_EDGE ( 'NONE', *, *, #6307, .F. ) ; -#25203 = CARTESIAN_POINT ( 'NONE', ( 37.34003727481168511, 163.4882490151146328, 203.2693681478919245 ) ) ; -#25204 = LINE ( 'NONE', #634, #15890 ) ; -#25205 = CARTESIAN_POINT ( 'NONE', ( 23.68142001710316791, 134.4472197773023368, 93.58606303061318954 ) ) ; -#25206 = CARTESIAN_POINT ( 'NONE', ( 28.78718856440784180, 131.0245789305321011, 89.88494191302055469 ) ) ; -#25207 = CARTESIAN_POINT ( 'NONE', ( 13.50000077932746834, 154.4078840096753424, 95.29263748429374914 ) ) ; -#25208 = VERTEX_POINT ( 'NONE', #17731 ) ; -#25209 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25210 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17653, #39324, #39134, #8480 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25211 = ORIENTED_EDGE ( 'NONE', *, *, #17871, .T. ) ; -#25212 = ADVANCED_FACE ( 'NONE', ( #4861 ), #1602, .F. ) ; -#25213 = CARTESIAN_POINT ( 'NONE', ( 15.53487489549969247, 138.6412351325426755, 152.4706544089839326 ) ) ; -#25214 = EDGE_CURVE ( 'NONE', #24997, #9552, #23601, .T. ) ; -#25215 = DIRECTION ( 'NONE', ( -0.0005884949961221202890, 0.2249510543439054433, -0.9743698870671265722 ) ) ; -#25216 = ORIENTED_EDGE ( 'NONE', *, *, #9879, .T. ) ; -#25217 = CARTESIAN_POINT ( 'NONE', ( -19.99824965358324036, 191.4178399844840612, 106.9362295233956814 ) ) ; -#25218 = CARTESIAN_POINT ( 'NONE', ( 0.8185733436017654796, 188.6262843215965290, 103.2002382106960710 ) ) ; -#25219 = CARTESIAN_POINT ( 'NONE', ( -20.24985248663000093, 188.1876851508999948, 103.3682804701000038 ) ) ; -#25220 = APPROVAL ( #27814, '未' ) ; -#25221 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #377, #2896, #570, #25545, #22475, #21113, #33771, #39905, #27268, #31681, #5356 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000604516, 0.3750000000000907052, 0.4375000000000858202, 0.4687500000000547895, 0.5000000000000237588, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25222 = AXIS2_PLACEMENT_3D ( 'NONE', #39560, #11568, #27329 ) ; -#25223 = VERTEX_POINT ( 'NONE', #4562 ) ; -#25224 = CARTESIAN_POINT ( 'NONE', ( 5.667815391070724296, 126.2407929722768074, 91.36024196040290235 ) ) ; -#25225 = CARTESIAN_POINT ( 'NONE', ( -25.50087116340131743, 118.1131725775237413, 88.44976037191148066 ) ) ; -#25226 = ORIENTED_EDGE ( 'NONE', *, *, #39490, .T. ) ; -#25227 = CARTESIAN_POINT ( 'NONE', ( 20.56554265872798837, 117.4584777523052423, 89.75564615045188077 ) ) ; -#25228 = CARTESIAN_POINT ( 'NONE', ( 36.16093536340260783, 191.4947098609792988, 103.8411206460829277 ) ) ; -#25229 = CARTESIAN_POINT ( 'NONE', ( -25.81413844371000010, 122.5880832094999988, 90.39702476309000190 ) ) ; -#25230 = ORIENTED_EDGE ( 'NONE', *, *, #27895, .T. ) ; -#25231 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37785, #23064, #7507, #26145 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 1.217094566236478452E-11, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25232 = AXIS2_PLACEMENT_3D ( 'NONE', #37710, #494, #13381 ) ; -#25233 = CARTESIAN_POINT ( 'NONE', ( 0.8930066394032586397, 188.4030556334941195, 106.2275697269554655 ) ) ; -#25234 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; -#25235 = CARTESIAN_POINT ( 'NONE', ( 39.17918664236205473, 77.03152903297159071, 290.9156096052041676 ) ) ; -#25236 = EDGE_CURVE ( 'NONE', #8100, #26238, #26513, .T. ) ; -#25237 = VERTEX_POINT ( 'NONE', #19696 ) ; -#25238 = DIRECTION ( 'NONE', ( 0.0005884949961241158715, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25239 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23451, #19753, #7697, #7901 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25240 = CYLINDRICAL_SURFACE ( 'NONE', #13304, 2.000000000000014655 ) ; -#25242 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25241 = CARTESIAN_POINT ( 'NONE', ( 36.06891294252045554, 192.2247015031095714, 104.3873542762104449 ) ) ; -#25243 = ORIENTED_EDGE ( 'NONE', *, *, #28102, .T. ) ; -#25244 = VERTEX_POINT ( 'NONE', #27287 ) ; -#25245 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; -#25246 = AXIS2_PLACEMENT_3D ( 'NONE', #9917, #22590, #35012 ) ; -#25247 = DIRECTION ( 'NONE', ( -0.7066905299392122197, -0.1591580245907027458, 0.6893890179736117396 ) ) ; -#25248 = VERTEX_POINT ( 'NONE', #5166 ) ; -#25249 = ORIENTED_EDGE ( 'NONE', *, *, #35785, .T. ) ; -#25250 = CARTESIAN_POINT ( 'NONE', ( 2.783189324004925247, 209.6623415042751617, 75.89015708242718006 ) ) ; -#25251 = CARTESIAN_POINT ( 'NONE', ( 2.547144908305676747, 209.7096538831000032, 78.05696658266772658 ) ) ; -#25252 = CARTESIAN_POINT ( 'NONE', ( -2.557186615398999940, 190.9521776356999965, 106.4289101426000030 ) ) ; -#25253 = AXIS2_PLACEMENT_3D ( 'NONE', #5151, #33975, #5567 ) ; -#25254 = ORIENTED_EDGE ( 'NONE', *, *, #35485, .F. ) ; -#25255 = VERTEX_POINT ( 'NONE', #11730 ) ; -#25256 = CARTESIAN_POINT ( 'NONE', ( -6.032834300266884497, 177.0616227066033730, 103.5393503116357579 ) ) ; -#25257 = VECTOR ( 'NONE', #27845, 1000.000000000000114 ) ; -#25259 = EDGE_CURVE ( 'NONE', #6456, #33719, #8997, .T. ) ; -#25258 = CARTESIAN_POINT ( 'NONE', ( -5.658908186421000686, 187.6682623620686172, 106.0618792668577015 ) ) ; -#25260 = PLANE ( 'NONE', #5019 ) ; -#25261 = EDGE_CURVE ( 'NONE', #1494, #27517, #1570, .T. ) ; -#25262 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#25263 = ORIENTED_EDGE ( 'NONE', *, *, #12101, .T. ) ; -#25264 = CARTESIAN_POINT ( 'NONE', ( -29.42789445533455961, 116.9990604785378423, 176.9382643005241107 ) ) ; -#25265 = CARTESIAN_POINT ( 'NONE', ( 37.18882002358459715, 126.0768346319694189, 91.81650343837480932 ) ) ; -#25266 = ORIENTED_EDGE ( 'NONE', *, *, #536, .F. ) ; -#25267 = EDGE_CURVE ( 'NONE', #9107, #7260, #20927, .T. ) ; -#25268 = CARTESIAN_POINT ( 'NONE', ( 14.55306318046054592, 176.9232825744718411, 100.4900915860747403 ) ) ; -#25269 = ORIENTED_EDGE ( 'NONE', *, *, #15515, .T. ) ; -#25270 = CARTESIAN_POINT ( 'NONE', ( -39.71326994697852086, 161.5379849440253395, 197.5000934441027880 ) ) ; -#25271 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#25272 = LINE ( 'NONE', #31805, #1250 ) ; -#25273 = CIRCLE ( 'NONE', #7616, 2.500000000036972203 ) ; -#25274 = ORIENTED_EDGE ( 'NONE', *, *, #37884, .F. ) ; -#25275 = DIRECTION ( 'NONE', ( 0.9999998268366975251, 0.0001323826338100946118, -0.0005734120799280602960 ) ) ; -#25276 = ORIENTED_EDGE ( 'NONE', *, *, #18103, .T. ) ; -#25277 = CYLINDRICAL_SURFACE ( 'NONE', #23808, 2.000000000000000000 ) ; -#25278 = AXIS2_PLACEMENT_3D ( 'NONE', #1744, #26698, #33004 ) ; -#25279 = DIRECTION ( 'NONE', ( -0.7691761624280200049, -0.6302414090841089722, 0.1056588729268925636 ) ) ; -#25280 = CONICAL_SURFACE ( 'NONE', #38969, 40.50000000000950706, 0.7853981633972851872 ) ; -#25281 = CARTESIAN_POINT ( 'NONE', ( 13.49436806345008399, 123.6932719124138345, 91.28058047958029420 ) ) ; -#25282 = ADVANCED_FACE ( 'NONE', ( #15202 ), #27051, .T. ) ; -#25283 = DIRECTION ( 'NONE', ( 0.0002083763306416868528, -0.2252353001604435467, 0.9743043755115440296 ) ) ; -#25284 = ORIENTED_EDGE ( 'NONE', *, *, #39213, .F. ) ; -#25285 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25286 = VERTEX_POINT ( 'NONE', #23795 ) ; -#25287 = VECTOR ( 'NONE', #37499, 1000.000000000000114 ) ; -#25288 = CARTESIAN_POINT ( 'NONE', ( -37.83635444431042316, 190.3639788717852923, 106.7036751988638912 ) ) ; -#25289 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; -#25290 = ORIENTED_EDGE ( 'NONE', *, *, #90, .F. ) ; -#25291 = ORIENTED_EDGE ( 'NONE', *, *, #21047, .F. ) ; -#25292 = CARTESIAN_POINT ( 'NONE', ( -37.70435768791065101, 218.5902260770999987, 75.58127702559525574 ) ) ; -#25293 = ADVANCED_FACE ( 'NONE', ( #36249 ), #57, .T. ) ; -#25294 = CARTESIAN_POINT ( 'NONE', ( -26.30564657185992417, 122.5409679533868257, 87.95962032719154422 ) ) ; -#25295 = CARTESIAN_POINT ( 'NONE', ( -20.21161457727598076, 159.7565362432869165, 96.54783218446964099 ) ) ; -#25296 = ORIENTED_EDGE ( 'NONE', *, *, #8017, .T. ) ; -#25297 = CARTESIAN_POINT ( 'NONE', ( -15.49970617362840919, 138.0805224087925751, 92.05383544148693886 ) ) ; -#25298 = EDGE_LOOP ( 'NONE', ( #7100, #4874, #29065, #25249 ) ) ; -#25299 = VERTEX_POINT ( 'NONE', #6778 ) ; -#25300 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606776115838874, 137.3532831589803322, 178.0585834212922123 ) ) ; -#25301 = EDGE_CURVE ( 'NONE', #7897, #23733, #21746, .T. ) ; -#25302 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; -#25303 = CONICAL_SURFACE ( 'NONE', #10936, 5.000000517016990109, 0.7853981634346335339 ) ; -#25304 = ORIENTED_EDGE ( 'NONE', *, *, #34449, .T. ) ; -#25305 = CARTESIAN_POINT ( 'NONE', ( 5.957091369052168517, 163.5651307542015900, 97.41131042763848313 ) ) ; -#25306 = EDGE_CURVE ( 'NONE', #21532, #24320, #20633, .T. ) ; -#25307 = EDGE_CURVE ( 'NONE', #22348, #10007, #21673, .T. ) ; -#25308 = VERTEX_POINT ( 'NONE', #232 ) ; -#25309 = FACE_OUTER_BOUND ( 'NONE', #15977, .T. ) ; -#25310 = VECTOR ( 'NONE', #37689, 1000.000000000000000 ) ; -#25311 = EDGE_CURVE ( 'NONE', #2629, #26268, #22129, .T. ) ; -#25312 = ADVANCED_FACE ( 'NONE', ( #9452 ), #34558, .F. ) ; -#25313 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971564292 ) ) ; -#25314 = VERTEX_POINT ( 'NONE', #18820 ) ; -#25315 = CARTESIAN_POINT ( 'NONE', ( 27.72966693972999863, 125.2145490558000063, 89.05755400422999912 ) ) ; -#25316 = CARTESIAN_POINT ( 'NONE', ( -13.49823529425102109, 184.2879064305327574, 105.2862044504857266 ) ) ; -#25317 = FACE_OUTER_BOUND ( 'NONE', #5358, .T. ) ; -#25318 = DIRECTION ( 'NONE', ( -0.0006039748319391919761, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#25319 = CARTESIAN_POINT ( 'NONE', ( 4.700715882528976763, 124.5561775271440581, 88.40614113511351491 ) ) ; -#25320 = ORIENTED_EDGE ( 'NONE', *, *, #2771, .F. ) ; -#25321 = CARTESIAN_POINT ( 'NONE', ( 20.00174647213199108, 119.1180879114202611, 90.25575134532356003 ) ) ; -#25322 = CARTESIAN_POINT ( 'NONE', ( 0.5911775542440182996, 189.0001913861286766, 103.6867748575926242 ) ) ; -#25323 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363196006660E-14, -0.9999998176071844824 ) ) ; -#25324 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; -#25325 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8029, #26862, #17627, #39301 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25326 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25327 = CARTESIAN_POINT ( 'NONE', ( 24.53469179845209780, 109.6131156702000027, 89.75296640909391499 ) ) ; -#25328 = CARTESIAN_POINT ( 'NONE', ( 12.63943526405010154, 181.6152899300451509, 104.1402435546899170 ) ) ; -#25329 = CARTESIAN_POINT ( 'NONE', ( 14.29788517226990585, 182.6944325685452952, 102.1647223417331816 ) ) ; -#25330 = ORIENTED_EDGE ( 'NONE', *, *, #22674, .T. ) ; -#25331 = CARTESIAN_POINT ( 'NONE', ( -25.67144920672187425, 190.9356798558488322, 106.4862152470520584 ) ) ; -#25332 = ORIENTED_EDGE ( 'NONE', *, *, #2076, .T. ) ; -#25333 = VECTOR ( 'NONE', #13279, 1000.000000000000227 ) ; -#25334 = VECTOR ( 'NONE', #6159, 1000.000000000000000 ) ; -#25335 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971570121 ) ) ; -#25336 = CARTESIAN_POINT ( 'NONE', ( -75.98858757284095589, 155.6702750673102287, 98.71704506522313238 ) ) ; -#25337 = ORIENTED_EDGE ( 'NONE', *, *, #26866, .F. ) ; -#25338 = DIRECTION ( 'NONE', ( 0.0006039748319341030564, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#25339 = DIRECTION ( 'NONE', ( -0.0004161288024615436500, 0.8480480897848248212, -0.5299191110434963159 ) ) ; -#25340 = EDGE_CURVE ( 'NONE', #37514, #19656, #39677, .T. ) ; -#25341 = CARTESIAN_POINT ( 'NONE', ( -22.78187663633837801, 153.7285825244628086, 98.23663543168041201 ) ) ; -#25342 = CARTESIAN_POINT ( 'NONE', ( -20.01841854128525711, 211.0875725380936103, 76.07063535483980843 ) ) ; -#25343 = CARTESIAN_POINT ( 'NONE', ( 36.82399100351999977, 191.4977938263000397, 106.2215044991999946 ) ) ; -#25344 = ORIENTED_EDGE ( 'NONE', *, *, #28798, .F. ) ; -#25345 = CARTESIAN_POINT ( 'NONE', ( -3.732613411896025912, 136.4113666306057269, 91.14822121766043495 ) ) ; -#25346 = ADVANCED_FACE ( 'NONE', ( #35360 ), #19824, .T. ) ; -#25347 = CARTESIAN_POINT ( 'NONE', ( -20.41894654420494959, 184.8665439626683735, 102.7752807765683798 ) ) ; -#25348 = EDGE_CURVE ( 'NONE', #6048, #12157, #21147, .T. ) ; -#25349 = CARTESIAN_POINT ( 'NONE', ( -32.37225756500890839, 173.7258698620904340, 102.8591651650622936 ) ) ; -#25350 = CARTESIAN_POINT ( 'NONE', ( 20.66773077360686983, 151.6559761831365734, 197.7415732814573630 ) ) ; -#25351 = ORIENTED_EDGE ( 'NONE', *, *, #6460, .T. ) ; -#25352 = CARTESIAN_POINT ( 'NONE', ( 13.50718655633492382, 188.3455032986072979, 103.1278069412195748 ) ) ; -#25353 = VERTEX_POINT ( 'NONE', #11878 ) ; -#25354 = EDGE_CURVE ( 'NONE', #5203, #20872, #21492, .T. ) ; -#25355 = CARTESIAN_POINT ( 'NONE', ( -3.330163502441660928, 129.4435835497653784, 89.53933837856635591 ) ) ; -#25356 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971553190 ) ) ; -#25357 = ORIENTED_EDGE ( 'NONE', *, *, #21700, .T. ) ; -#25358 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319379466615 ) ) ; -#25359 = AXIS2_PLACEMENT_3D ( 'NONE', #33989, #28091, #28473 ) ; -#25360 = CARTESIAN_POINT ( 'NONE', ( -15.83167302941029853, 126.1635038823812351, 91.69749185279336245 ) ) ; -#25361 = CARTESIAN_POINT ( 'NONE', ( -32.71652505805614197, 141.8894161721785849, 281.5012411679362003 ) ) ; -#25362 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052565999616 ) ) ; -#25363 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540971401, 126.6879451654999116, 89.42365126072036219 ) ) ; -#25364 = VERTEX_POINT ( 'NONE', #6125 ) ; -#25365 = ORIENTED_EDGE ( 'NONE', *, *, #12879, .T. ) ; -#25366 = CARTESIAN_POINT ( 'NONE', ( 21.72426698684031976, 130.1004708904147265, 89.67586055015539159 ) ) ; -#25367 = CARTESIAN_POINT ( 'NONE', ( -10.03773492422904035, 144.2121259786891585, 92.95297688159946858 ) ) ; -#25368 = DIRECTION ( 'NONE', ( -0.0001408393175929667886, 0.2255194967740913881, -0.9742386446549157197 ) ) ; -#25369 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11981, #24466, #36915, #98, #24668, #9112 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25370 = CARTESIAN_POINT ( 'NONE', ( -36.16377129200999718, 191.5154754321000041, 103.9966361450999983 ) ) ; -#25371 = EDGE_LOOP ( 'NONE', ( #28257, #25057, #22346, #19660 ) ) ; -#25372 = DIRECTION ( 'NONE', ( 0.0005464070472052447603, -0.2249510597163257852, 0.9743699103378761217 ) ) ; -#25373 = ORIENTED_EDGE ( 'NONE', *, *, #33244, .F. ) ; -#25374 = CARTESIAN_POINT ( 'NONE', ( -3.669581222327467973, 184.0117732734406104, 102.6507570783573300 ) ) ; -#25375 = CARTESIAN_POINT ( 'NONE', ( -14.03390129455813273, 182.0709040599587922, 101.6957796740224609 ) ) ; -#25376 = CARTESIAN_POINT ( 'NONE', ( -12.63563447629612035, 176.9474841518645860, 103.3618753611535936 ) ) ; -#25377 = CARTESIAN_POINT ( 'NONE', ( 26.87813338839999844, 134.5475818962999881, 93.52178121608000083 ) ) ; -#25378 = AXIS2_PLACEMENT_3D ( 'NONE', #22334, #29056, #34759 ) ; -#25379 = CARTESIAN_POINT ( 'NONE', ( -2.321500140915000010, 209.0507070170999953, 73.74245843209999407 ) ) ; -#25380 = CARTESIAN_POINT ( 'NONE', ( -0.4361371085228029076, 189.0000000148081654, 105.7376017109280184 ) ) ; -#25381 = ORIENTED_EDGE ( 'NONE', *, *, #35152, .F. ) ; -#25382 = ADVANCED_FACE ( 'NONE', ( #36402 ), #20867, .F. ) ; -#25383 = CARTESIAN_POINT ( 'NONE', ( -12.64562993050861550, 181.6872450680611450, 101.6064063805796280 ) ) ; -#25384 = EDGE_CURVE ( 'NONE', #31175, #978, #33729, .T. ) ; -#25385 = CIRCLE ( 'NONE', #22145, 7.999999999973976372 ) ; -#25386 = FACE_OUTER_BOUND ( 'NONE', #21993, .T. ) ; -#25387 = DIRECTION ( 'NONE', ( -0.5988683521957608447, 0.8008474865655346164, 0.000000000000000000 ) ) ; -#25388 = AXIS2_PLACEMENT_3D ( 'NONE', #19416, #19207, #16349 ) ; -#25389 = ADVANCED_FACE ( 'NONE', ( #27233 ), #30684, .T. ) ; -#25390 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18487, #33839, #5840, #8721 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25392 = ADVANCED_FACE ( 'NONE', ( #16129 ), #19178, .F. ) ; -#25391 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1732, #14214, #8273, #26684, #39137, #39325, #36058, #20735, #33186, #20526 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25393 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#25394 = ORIENTED_EDGE ( 'NONE', *, *, #33393, .T. ) ; -#25395 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15292, #3200, #11830, #27780, #150, #40212, #27388, #34081, #6078, #30634, #33474, #15491, #25109, #24717, #24312, #27982, #2627 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000001012246, 0.1875000000001414979, 0.2187500000001616485, 0.2343750000001933453, 0.2421875000002091938, 0.2500000000002250422, 0.3750000000001751932, 0.4375000000001502687, 0.5000000000001253442, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25396 = VERTEX_POINT ( 'NONE', #3053 ) ; -#25397 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#25398 = ADVANCED_FACE ( 'NONE', ( #37806 ), #28612, .T. ) ; -#25399 = DIRECTION ( 'NONE', ( -0.5276053854356862471, 0.5676772811992385481, -0.6319612817803805793 ) ) ; -#25400 = FACE_BOUND ( 'NONE', #22238, .T. ) ; -#25401 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1333, #28560, #13813, #528, #17866, #26497, #20541, #14842, #5004, #11768 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.0004318883629631480991, 0.0008637767259262961982, 0.001295665088889418710, 0.001727553451852541005 ), - .UNSPECIFIED. ) ; -#25402 = ORIENTED_EDGE ( 'NONE', *, *, #617, .T. ) ; -#25403 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#25404 = EDGE_CURVE ( 'NONE', #29199, #37303, #31275, .T. ) ; -#25405 = CARTESIAN_POINT ( 'NONE', ( -31.84898476996059813, 157.9423125112969331, 186.4027463543498584 ) ) ; -#25406 = DIRECTION ( 'NONE', ( 0.6771712326825870543, -0.7358254695422995484, 0.000000000000000000 ) ) ; -#25407 = CARTESIAN_POINT ( 'NONE', ( -38.24845629298000205, 118.9502302476000040, 87.58082788912000183 ) ) ; -#25408 = DIRECTION ( 'NONE', ( 2.081668263520925717E-15, 0.9743700557921588512, 0.2249510932971553467 ) ) ; -#25409 = ORIENTED_EDGE ( 'NONE', *, *, #37696, .F. ) ; -#25410 = CARTESIAN_POINT ( 'NONE', ( 16.57412657401275524, 123.0642243256057640, 172.1930205136684719 ) ) ; -#25411 = ORIENTED_EDGE ( 'NONE', *, *, #36729, .F. ) ; -#25412 = LINE ( 'NONE', #7375, #29233 ) ; -#25413 = CARTESIAN_POINT ( 'NONE', ( 41.50318924951093891, 120.3350044911163366, 90.14619003234494699 ) ) ; -#25414 = EDGE_CURVE ( 'NONE', #20649, #5506, #37606, .T. ) ; -#25415 = ORIENTED_EDGE ( 'NONE', *, *, #36870, .T. ) ; -#25416 = AXIS2_PLACEMENT_3D ( 'NONE', #18728, #18530, #9561 ) ; -#25417 = CARTESIAN_POINT ( 'NONE', ( 35.04645050414097085, 226.4002260770962778, 75.53733736050621417 ) ) ; -#25418 = CARTESIAN_POINT ( 'NONE', ( 1.939042107997019926, 189.0253960982757633, 103.2917037063839132 ) ) ; -#25419 = CARTESIAN_POINT ( 'NONE', ( 25.49999482590744293, 118.1133917706950598, 89.08575900863124275 ) ) ; -#25420 = AXIS2_PLACEMENT_3D ( 'NONE', #16339, #25975, #9828 ) ; -#25421 = CONICAL_SURFACE ( 'NONE', #35146, 48.00000000000691358, 0.7853981633972819676 ) ; -#25422 = ORIENTED_EDGE ( 'NONE', *, *, #7407, .F. ) ; -#25423 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25424 = CARTESIAN_POINT ( 'NONE', ( -39.66922356035500741, 107.0867199669675358, 184.9165548509024006 ) ) ; -#25425 = VERTEX_POINT ( 'NONE', #19179 ) ; -#25426 = DIRECTION ( 'NONE', ( -0.0004161288024563961291, -0.5299192578740949955, -0.8480479980348919478 ) ) ; -#25427 = CARTESIAN_POINT ( 'NONE', ( -25.49213558285381254, 194.2771767961476996, 102.9136721320308538 ) ) ; -#25428 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748607925, 179.1800746285725552, 103.5747911656959133 ) ) ; -#25429 = ORIENTED_EDGE ( 'NONE', *, *, #22616, .T. ) ; -#25430 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19588, #13270, #579, #25756 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25431 = CARTESIAN_POINT ( 'NONE', ( 2.929713194329027992, 190.0626957488375979, 106.6094977884659585 ) ) ; -#25432 = DIRECTION ( 'NONE', ( 0.0005884949961256158652, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25433 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, -0.000000000000000000, 0.9999998176071844824 ) ) ; -#25434 = VERTEX_POINT ( 'NONE', #587 ) ; -#25435 = ADVANCED_FACE ( 'NONE', ( #25558 ), #5480, .F. ) ; -#25436 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501097082, 181.7423509807036908, 104.7012344479479395 ) ) ; -#25437 = CARTESIAN_POINT ( 'NONE', ( 40.02829803166415701, 120.8820227754755905, 90.61547142951589251 ) ) ; -#25438 = ADVANCED_FACE ( 'NONE', ( #19985 ), #14081, .F. ) ; -#25439 = EDGE_CURVE ( 'NONE', #6111, #10930, #40093, .T. ) ; -#25441 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#25440 = CARTESIAN_POINT ( 'NONE', ( 37.28562273015844397, 178.8217641854361091, 136.8524436601264540 ) ) ; -#25442 = ORIENTED_EDGE ( 'NONE', *, *, #1697, .T. ) ; -#25443 = VECTOR ( 'NONE', #39459, 1000.000000000000000 ) ; -#25444 = CARTESIAN_POINT ( 'NONE', ( -19.44534333246823721, 148.3822623830060365, 180.6034369735336895 ) ) ; -#25445 = ORIENTED_EDGE ( 'NONE', *, *, #3138, .F. ) ; -#25446 = CARTESIAN_POINT ( 'NONE', ( 3.666638747408697441, 128.4736512688499488, 89.82433808099703754 ) ) ; -#25447 = EDGE_CURVE ( 'NONE', #21126, #11864, #29221, .T. ) ; -#25448 = CONICAL_SURFACE ( 'NONE', #29986, 5.999999999882503765, 0.7853981634237914289 ) ; -#25449 = CONICAL_SURFACE ( 'NONE', #29344, 2.999999999897231984, 0.7853981633957719533 ) ; -#25450 = CARTESIAN_POINT ( 'NONE', ( -36.55035161422085110, 265.0550681697489495, 206.0315697972555427 ) ) ; -#25451 = ORIENTED_EDGE ( 'NONE', *, *, #4707, .T. ) ; -#25452 = VECTOR ( 'NONE', #25433, 1000.000000000000114 ) ; -#25453 = ORIENTED_EDGE ( 'NONE', *, *, #27211, .F. ) ; -#25454 = CARTESIAN_POINT ( 'NONE', ( 15.83499441773212091, 126.1668223937077187, 91.67911834837939011 ) ) ; -#25455 = ADVANCED_FACE ( 'NONE', ( #13868 ), #10814, .T. ) ; -#25456 = CARTESIAN_POINT ( 'NONE', ( 28.46433317245000438, 130.4256741636303047, 90.26002097362676579 ) ) ; -#25457 = CARTESIAN_POINT ( 'NONE', ( 36.06386299210247870, 192.3813622508035905, 104.3665697773190715 ) ) ; -#25458 = CARTESIAN_POINT ( 'NONE', ( 36.35265157396000291, 191.8665494351999996, 104.3770947058000047 ) ) ; -#25459 = ORIENTED_EDGE ( 'NONE', *, *, #23721, .T. ) ; -#25460 = ORIENTED_EDGE ( 'NONE', *, *, #32747, .F. ) ; -#25461 = ORIENTED_EDGE ( 'NONE', *, *, #1574, .T. ) ; -#25462 = CARTESIAN_POINT ( 'NONE', ( -6.034877889022303599, 176.8731890827487803, 103.2377949967901003 ) ) ; -#25463 = LINE ( 'NONE', #9110, #33746 ) ; -#25464 = CARTESIAN_POINT ( 'NONE', ( 39.35924215062428289, 182.9779358206116342, 104.9518492583050886 ) ) ; -#25465 = EDGE_CURVE ( 'NONE', #6175, #7200, #35712, .T. ) ; -#25466 = ORIENTED_EDGE ( 'NONE', *, *, #22733, .T. ) ; -#25467 = LINE ( 'NONE', #3758, #24568 ) ; -#25468 = ORIENTED_EDGE ( 'NONE', *, *, #13157, .F. ) ; -#25469 = DIRECTION ( 'NONE', ( 0.0005884949961191475150, -0.2249510543439081633, 0.9743698870671259060 ) ) ; -#25470 = ORIENTED_EDGE ( 'NONE', *, *, #32675, .F. ) ; -#25471 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; -#25472 = AXIS2_PLACEMENT_3D ( 'NONE', #11220, #2228, #8564 ) ; -#25473 = CARTESIAN_POINT ( 'NONE', ( -2.298658047590000031, 191.0926590853000278, 106.2034744358000040 ) ) ; -#25474 = CARTESIAN_POINT ( 'NONE', ( -2.435788377003461846, 191.0000002182038941, 106.3158216037667358 ) ) ; -#25475 = AXIS2_PLACEMENT_3D ( 'NONE', #4771, #17439, #26881 ) ; -#25476 = ORIENTED_EDGE ( 'NONE', *, *, #35820, .T. ) ; -#25477 = CARTESIAN_POINT ( 'NONE', ( 2.941278393888057341, 209.7096877029368613, 73.05672770647804271 ) ) ; -#25478 = ORIENTED_EDGE ( 'NONE', *, *, #6162, .F. ) ; -#25479 = CIRCLE ( 'NONE', #7818, 5.500000000083335117 ) ; -#25480 = ORIENTED_EDGE ( 'NONE', *, *, #28982, .F. ) ; -#25481 = CARTESIAN_POINT ( 'NONE', ( -20.49973909911777881, 191.9757886370473443, 104.4339460251406706 ) ) ; -#25482 = DIRECTION ( 'NONE', ( 0.1305262373691799260, 0.9659798014921964215, 0.2232620085624539286 ) ) ; -#25483 = AXIS2_PLACEMENT_3D ( 'NONE', #20216, #1214, #38234 ) ; -#25484 = CARTESIAN_POINT ( 'NONE', ( 13.49990341355065837, 123.9200986791754246, 91.13891943753979774 ) ) ; -#25485 = CARTESIAN_POINT ( 'NONE', ( 20.50147081074398869, 137.9496117188596429, 94.05447709496644393 ) ) ; -#25486 = EDGE_LOOP ( 'NONE', ( #18765, #22552, #6600, #432 ) ) ; -#25487 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2393, #31202, #14867, #21200 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999992929045369294 ), - .UNSPECIFIED. ) ; -#25488 = LINE ( 'NONE', #12804, #26694 ) ; -#25489 = EDGE_CURVE ( 'NONE', #38998, #16388, #33881, .T. ) ; -#25490 = ADVANCED_FACE ( 'NONE', ( #8967 ), #18333, .F. ) ; -#25491 = FACE_OUTER_BOUND ( 'NONE', #15701, .T. ) ; -#25492 = VERTEX_POINT ( 'NONE', #20602 ) ; -#25493 = ORIENTED_EDGE ( 'NONE', *, *, #17309, .T. ) ; -#25494 = FACE_OUTER_BOUND ( 'NONE', #19465, .T. ) ; -#25495 = DIRECTION ( 'NONE', ( 0.0001338301624287874996, 0.9743705222004039879, 0.2249490332417534988 ) ) ; -#25496 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178539432571E-05, -0.0002331579774923554001 ) ) ; -#25497 = CARTESIAN_POINT ( 'NONE', ( 20.00028792540915035, 151.9820690596619102, 94.72877128701482263 ) ) ; -#25498 = CARTESIAN_POINT ( 'NONE', ( -0.4555724343627732265, 211.0000000000011653, 73.55877932795836216 ) ) ; -#25499 = ORIENTED_EDGE ( 'NONE', *, *, #16975, .F. ) ; -#25500 = ORIENTED_EDGE ( 'NONE', *, *, #23301, .T. ) ; -#25501 = CARTESIAN_POINT ( 'NONE', ( 37.35925905962992033, 145.4105082909675275, 281.9992692111848100 ) ) ; -#25502 = AXIS2_PLACEMENT_3D ( 'NONE', #4197, #34864, #6874 ) ; -#25503 = CARTESIAN_POINT ( 'NONE', ( -20.49853923645481757, 186.5872419690744550, 105.3081126573685822 ) ) ; -#25504 = VECTOR ( 'NONE', #7510, 1000.000000000000000 ) ; -#25505 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34753, #10046, #19224, #31731 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25506 = ORIENTED_EDGE ( 'NONE', *, *, #3572, .F. ) ; -#25507 = CARTESIAN_POINT ( 'NONE', ( -38.93790737325827678, 191.2886348490596902, 104.1810045873903050 ) ) ; -#25508 = CIRCLE ( 'NONE', #19579, 5.500000000080834894 ) ; -#25509 = VERTEX_POINT ( 'NONE', #36753 ) ; -#25510 = LINE ( 'NONE', #8965, #8537 ) ; -#25511 = EDGE_CURVE ( 'NONE', #26891, #27880, #39165, .T. ) ; -#25512 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#25513 = CARTESIAN_POINT ( 'NONE', ( -41.54213446450223302, 190.5842469323372086, 103.6778548217435372 ) ) ; -#25514 = VERTEX_POINT ( 'NONE', #40021 ) ; -#25515 = CARTESIAN_POINT ( 'NONE', ( 28.25941677355000081, 125.5847679582000040, 89.14271750808001116 ) ) ; -#25516 = DIRECTION ( 'NONE', ( 0.7933533411653073131, 0.5931840316265227786, 0.1368326740407717623 ) ) ; -#25517 = CARTESIAN_POINT ( 'NONE', ( -20.45366101552173532, 211.0901972962080322, 75.63591788811629613 ) ) ; -#25518 = PLANE ( 'NONE', #22233 ) ; -#25519 = CARTESIAN_POINT ( 'NONE', ( -77.81044467944656162, 193.2853083808247163, 188.4036545891195544 ) ) ; -#25520 = ORIENTED_EDGE ( 'NONE', *, *, #27056, .T. ) ; -#25521 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921578520, 0.2249510932971586774 ) ) ; -#25522 = CARTESIAN_POINT ( 'NONE', ( 1.209138936786560592, 189.1031875914025306, 103.7138824602396596 ) ) ; -#25523 = CARTESIAN_POINT ( 'NONE', ( -2.316587851187592140, 189.2328037104950624, 106.4210707141687493 ) ) ; -#25524 = EDGE_CURVE ( 'NONE', #25874, #17201, #39366, .T. ) ; -#25525 = CARTESIAN_POINT ( 'NONE', ( 39.69446386203616584, 161.8153251821185563, 196.1471770628630793 ) ) ; -#25526 = DIRECTION ( 'NONE', ( -0.6087613488993157684, 0.7729391301027055405, 0.1788147679649486899 ) ) ; -#25527 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#25528 = FACE_OUTER_BOUND ( 'NONE', #37020, .T. ) ; -#25529 = AXIS2_PLACEMENT_3D ( 'NONE', #37123, #30993, #2380 ) ; -#25530 = ADVANCED_FACE ( 'NONE', ( #36353 ), #18938, .T. ) ; -#25531 = VECTOR ( 'NONE', #12182, 1000.000000000000000 ) ; -#25532 = VERTEX_POINT ( 'NONE', #3004 ) ; -#25533 = CONICAL_SURFACE ( 'NONE', #36613, 2.503101642511124325, 0.7853981633721776046 ) ; -#25534 = AXIS2_PLACEMENT_3D ( 'NONE', #13398, #3371, #3775 ) ; -#25535 = EDGE_CURVE ( 'NONE', #7238, #20110, #3602, .T. ) ; -#25536 = EDGE_CURVE ( 'NONE', #17579, #6068, #3801, .T. ) ; -#25537 = EDGE_CURVE ( 'NONE', #25759, #32563, #9161, .T. ) ; -#25538 = CARTESIAN_POINT ( 'NONE', ( 6.036802112625085925, 176.8031174218945409, 103.1161773563228081 ) ) ; -#25539 = CARTESIAN_POINT ( 'NONE', ( 19.99905349769186458, 193.8169544161346494, 102.6908434160864800 ) ) ; -#25540 = ORIENTED_EDGE ( 'NONE', *, *, #211, .T. ) ; -#25541 = CARTESIAN_POINT ( 'NONE', ( 22.67196836059710918, 115.6131113076032477, 87.75389050448781347 ) ) ; -#25542 = CARTESIAN_POINT ( 'NONE', ( -25.99151685856759997, 191.8641472349464436, 103.9340191741391521 ) ) ; -#25543 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25544 = FACE_OUTER_BOUND ( 'NONE', #26799, .T. ) ; -#25545 = CARTESIAN_POINT ( 'NONE', ( 3.857291306865842095, 143.6128663871600111, 95.55518041699281184 ) ) ; -#25546 = CARTESIAN_POINT ( 'NONE', ( -20.99990893075895571, 136.4130174721703668, 91.33008588846020359 ) ) ; -#25547 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #15813, #31571, #28505, #25654 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.3157706852075154447, 1.746568277883796982 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8365544822326855812, 0.8365544822326855812, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#25548 = ORIENTED_EDGE ( 'NONE', *, *, #22733, .F. ) ; -#25549 = VERTEX_POINT ( 'NONE', #21831 ) ; -#25550 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25551 = CARTESIAN_POINT ( 'NONE', ( 20.50146814542411278, 184.4050074329408915, 104.7795556516932436 ) ) ; -#25552 = DIRECTION ( 'NONE', ( -0.6087614810001780175, 0.7729390313185915407, 0.1788147452386051883 ) ) ; -#25553 = ORIENTED_EDGE ( 'NONE', *, *, #14079, .T. ) ; -#25554 = FACE_OUTER_BOUND ( 'NONE', #1594, .T. ) ; -#25555 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34509, #15724, #22833, #29172 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25556 = EDGE_LOOP ( 'NONE', ( #35420, #28169, #13710, #7194 ) ) ; -#25557 = VECTOR ( 'NONE', #16549, 1000.000000000000114 ) ; -#25558 = FACE_OUTER_BOUND ( 'NONE', #36983, .T. ) ; -#25559 = CARTESIAN_POINT ( 'NONE', ( -4.217709453195823244, 130.5806486384503842, 89.80238664217760913 ) ) ; -#25560 = CARTESIAN_POINT ( 'NONE', ( -3.669188902168228683, 128.3225182885998947, 90.47807979629892827 ) ) ; -#25561 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099476, 179.7424522643767375, 101.1388664481733173 ) ) ; -#25562 = AXIS2_PLACEMENT_3D ( 'NONE', #33061, #30214, #11821 ) ; -#25563 = VECTOR ( 'NONE', #22085, 1000.000000000000227 ) ; -#25564 = FACE_OUTER_BOUND ( 'NONE', #16379, .T. ) ; -#25565 = CARTESIAN_POINT ( 'NONE', ( -45.96073629545556827, 185.2536905089892514, 105.5287798515274176 ) ) ; -#25566 = DIRECTION ( 'NONE', ( 0.0005884949961178157895, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25567 = CARTESIAN_POINT ( 'NONE', ( 14.17154132021859780, 182.3114712258959571, 104.3000443475247749 ) ) ; -#25568 = VERTEX_POINT ( 'NONE', #149 ) ; -#25569 = VERTEX_POINT ( 'NONE', #34275 ) ; -#25570 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#25571 = CARTESIAN_POINT ( 'NONE', ( -30.06407784565124430, 177.7873364699197793, 100.7165267053679969 ) ) ; -#25572 = CARTESIAN_POINT ( 'NONE', ( -22.64184747305000300, 158.4882854875999953, 96.51307724670000709 ) ) ; -#25573 = ADVANCED_FACE ( 'NONE', ( #6272 ), #18727, .F. ) ; -#25574 = ORIENTED_EDGE ( 'NONE', *, *, #25634, .T. ) ; -#25575 = CARTESIAN_POINT ( 'NONE', ( -20.51767729163077547, 205.5669979433283743, 76.31342074382325791 ) ) ; -#25576 = ORIENTED_EDGE ( 'NONE', *, *, #12318, .T. ) ; -#25577 = CARTESIAN_POINT ( 'NONE', ( 5.666638401077995546, 182.0642691150685550, 102.1955013911927352 ) ) ; -#25578 = VERTEX_POINT ( 'NONE', #20143 ) ; -#25579 = ADVANCED_FACE ( 'NONE', ( #26112 ), #16675, .T. ) ; -#25580 = DIRECTION ( 'NONE', ( -0.1305262051638224619, -0.9660383185115548610, -0.2230086925052462976 ) ) ; -#25581 = FACE_OUTER_BOUND ( 'NONE', #28954, .T. ) ; -#25582 = VECTOR ( 'NONE', #9464, 1000.000000000000114 ) ; -#25583 = EDGE_CURVE ( 'NONE', #7856, #27296, #35876, .T. ) ; -#25584 = CARTESIAN_POINT ( 'NONE', ( -12.62895464393706924, 177.1149013944556145, 103.6296996846185152 ) ) ; -#25585 = EDGE_CURVE ( 'NONE', #39006, #26460, #4410, .T. ) ; -#25586 = CONICAL_SURFACE ( 'NONE', #19012, 8.500000000023945290, 0.7853981633972964005 ) ; -#25587 = LINE ( 'NONE', #34538, #27252 ) ; -#25588 = EDGE_CURVE ( 'NONE', #6068, #982, #10165, .T. ) ; -#25589 = AXIS2_PLACEMENT_3D ( 'NONE', #31113, #15560, #23 ) ; -#25590 = CARTESIAN_POINT ( 'NONE', ( -2.469696937619000110, 209.6697490365999954, 73.43898226951000652 ) ) ; -#25591 = CARTESIAN_POINT ( 'NONE', ( 38.49272623736000298, 118.5587213001000038, 89.80777509628001098 ) ) ; -#25592 = EDGE_LOOP ( 'NONE', ( #15478, #20146, #40230, #21895, #13336, #513, #17672, #29894, #33555, #21437, #36388, #6752, #34748, #14146, #8320, #7418, #27143, #27464, #23938, #10649, #39703, #34306, #35998, #37206 ) ) ; -#25593 = CARTESIAN_POINT ( 'NONE', ( -39.42639396830977461, 119.7153704062085353, 90.39411697856569106 ) ) ; -#25594 = CARTESIAN_POINT ( 'NONE', ( -22.78222448785094656, 147.3951731907068563, 96.77445160504784383 ) ) ; -#25595 = DIRECTION ( 'NONE', ( 0.6087614115774879764, -0.7730004600455407937, -0.1785492440296699013 ) ) ; -#25597 = EDGE_LOOP ( 'NONE', ( #29523, #1134, #30477, #5484 ) ) ; -#25596 = CARTESIAN_POINT ( 'NONE', ( -13.49052885539015278, 188.3420772061585353, 103.1432726234667427 ) ) ; -#25598 = ORIENTED_EDGE ( 'NONE', *, *, #24485, .T. ) ; -#25599 = VERTEX_POINT ( 'NONE', #16474 ) ; -#25600 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9981, #552, #28381, #38183 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.0008906419405732026156 ), - .UNSPECIFIED. ) ; -#25601 = ORIENTED_EDGE ( 'NONE', *, *, #23916, .F. ) ; -#25602 = LINE ( 'NONE', #8899, #1334 ) ; -#25603 = DIRECTION ( 'NONE', ( -0.1305262373691799260, -0.9659798014921964215, -0.2232620085624539286 ) ) ; -#25604 = ORIENTED_EDGE ( 'NONE', *, *, #13373, .T. ) ; -#25605 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25606 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052565999616 ) ) ; -#25607 = CARTESIAN_POINT ( 'NONE', ( -38.26352553902000153, 118.9655503529000100, 87.58139881257000070 ) ) ; -#25608 = CARTESIAN_POINT ( 'NONE', ( -22.99976245438101330, 118.1131156702000169, 90.28469153849982831 ) ) ; -#25609 = ORIENTED_EDGE ( 'NONE', *, *, #32117, .F. ) ; -#25610 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25611 = ORIENTED_EDGE ( 'NONE', *, *, #27589, .T. ) ; -#25612 = CARTESIAN_POINT ( 'NONE', ( -25.18449714766744307, 116.8540101816006427, 89.78296773362393424 ) ) ; -#25613 = VECTOR ( 'NONE', #34725, 1000.000000000000227 ) ; -#25614 = CARTESIAN_POINT ( 'NONE', ( -2.454714023685454993, 208.9999998232322014, 74.98064760642650128 ) ) ; -#25615 = ORIENTED_EDGE ( 'NONE', *, *, #20094, .F. ) ; -#25616 = CIRCLE ( 'NONE', #17076, 10.00000000000000533 ) ; -#25617 = ORIENTED_EDGE ( 'NONE', *, *, #4873, .T. ) ; -#25618 = DIRECTION ( 'NONE', ( 0.7933532411131101192, 0.5932638852154232811, 0.1364866195435442964 ) ) ; -#25619 = AXIS2_PLACEMENT_3D ( 'NONE', #35302, #13659, #1375 ) ; -#25620 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.261220487827980678E-14, 0.9999998176071847045 ) ) ; -#25621 = ADVANCED_FACE ( 'NONE', ( #38362 ), #21923, .T. ) ; -#25622 = FACE_OUTER_BOUND ( 'NONE', #38903, .T. ) ; -#25623 = EDGE_CURVE ( 'NONE', #34118, #37905, #14238, .T. ) ; -#25624 = EDGE_CURVE ( 'NONE', #662, #38536, #39974, .T. ) ; -#25625 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #28336, #6633, #37722 ), - ( #12384, #37132, #9128 ), - ( #15649, #21610, #37530 ), - ( #25078, #113, #15460 ), - ( #18496, #40381, #12575 ), - ( #34441, #31004, #9327 ), - ( #24882, #6840, #12998 ), - ( #21805, #15842, #2970 ), - ( #9731, #306, #6434 ), - ( #22409, #34639, #34243 ) ), - .UNSPECIFIED., .F., .F., .T. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 2, 2, 2, 4 ), - ( 3, 3 ), - ( 0.05538191844473741576, 0.1462505983937870679, 0.2371192783428366924, 0.3279879582918863168, 0.4188566382409359967 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.9441684504446133941, 1.000000000000000000), - ( 1.000000000000000000, 0.9410511299423663933, 1.000000000000000000), - ( 1.000000000000000000, 0.9350843932276490245, 1.000000000000000000), - ( 1.000000000000000000, 0.9167142712460382148, 1.000000000000000000), - ( 1.000000000000000000, 0.9042814830954841732, 1.000000000000000000), - ( 1.000000000000000000, 0.8733377745246642121, 1.000000000000000000), - ( 1.000000000000000000, 0.8548373006127086837, 1.000000000000000000), - ( 1.000000000000000000, 0.8135092030853890988, 1.000000000000000000), - ( 1.000000000000000000, 0.7907138362263389508, 1.000000000000000000), - ( 1.000000000000000000, 0.7669877085542754491, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#25626 = EDGE_LOOP ( 'NONE', ( #19250, #32641, #29047, #31049 ) ) ; -#25627 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#25628 = CARTESIAN_POINT ( 'NONE', ( 22.50071804764001371, 153.6597986086584910, 96.31184697053201660 ) ) ; -#25629 = ORIENTED_EDGE ( 'NONE', *, *, #3726, .T. ) ; -#25630 = ADVANCED_FACE ( 'NONE', ( #24049 ), #6899, .T. ) ; -#25631 = LINE ( 'NONE', #6785, #8881 ) ; -#25632 = DIRECTION ( 'NONE', ( -5.204170427930391307E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#25633 = CARTESIAN_POINT ( 'NONE', ( -28.81763517994743751, 225.0820812896716632, 76.07590975914473574 ) ) ; -#25634 = EDGE_CURVE ( 'NONE', #20950, #4106, #27131, .T. ) ; -#25635 = ORIENTED_EDGE ( 'NONE', *, *, #22510, .T. ) ; -#25636 = LINE ( 'NONE', #7802, #38051 ) ; -#25637 = CARTESIAN_POINT ( 'NONE', ( 1.214526914179933081, 188.4681291261784111, 106.2423989390525207 ) ) ; -#25638 = CARTESIAN_POINT ( 'NONE', ( -37.92154252050418961, 118.5963699847487192, 87.57341342349630509 ) ) ; -#25639 = LINE ( 'NONE', #12956, #25452 ) ; -#25640 = EDGE_CURVE ( 'NONE', #27113, #8395, #4260, .T. ) ; -#25641 = ORIENTED_EDGE ( 'NONE', *, *, #23630, .F. ) ; -#25642 = CARTESIAN_POINT ( 'NONE', ( 26.00730275886190057, 120.2355259078189818, 90.47935005272459819 ) ) ; -#25643 = DIRECTION ( 'NONE', ( -0.0005884949961232365835, 0.2249510543439025012, -0.9743698870671272383 ) ) ; -#25644 = CARTESIAN_POINT ( 'NONE', ( -20.33181978585839289, 137.5888522171624686, 94.16684457232651084 ) ) ; -#25645 = CIRCLE ( 'NONE', #2137, 22.00000000001089973 ) ; -#25647 = CARTESIAN_POINT ( 'NONE', ( -11.75635721658684574, 154.1573362836760737, 95.25004801869390292 ) ) ; -#25646 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25648 = EDGE_CURVE ( 'NONE', #4584, #27521, #11782, .T. ) ; -#25649 = AXIS2_PLACEMENT_3D ( 'NONE', #31422, #5867, #34069 ) ; -#25650 = CARTESIAN_POINT ( 'NONE', ( 20.00104065772422146, 118.8155603627228203, 94.25570476258155850 ) ) ; -#25651 = ORIENTED_EDGE ( 'NONE', *, *, #36361, .F. ) ; -#25652 = CARTESIAN_POINT ( 'NONE', ( 15.67905408082599727, 145.8568665348935554, 183.6205611131604485 ) ) ; -#25653 = CARTESIAN_POINT ( 'NONE', ( -35.93776700278350233, 192.3813625493561119, 104.4100568030667660 ) ) ; -#25654 = CARTESIAN_POINT ( 'NONE', ( 31.82998378949513452, 157.8941376960632397, 186.4072502462622367 ) ) ; -#25655 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#25656 = ORIENTED_EDGE ( 'NONE', *, *, #2466, .F. ) ; -#25657 = ORIENTED_EDGE ( 'NONE', *, *, #10960, .F. ) ; -#25658 = FACE_OUTER_BOUND ( 'NONE', #3335, .T. ) ; -#25659 = CARTESIAN_POINT ( 'NONE', ( 22.78191781013921968, 158.2317512751428126, 98.73560149028561739 ) ) ; -#25660 = CARTESIAN_POINT ( 'NONE', ( -46.20100370308558269, 125.7463382206120173, 91.79056768027822955 ) ) ; -#25661 = CARTESIAN_POINT ( 'NONE', ( 3.168077512235829563, 183.4518822370066289, 105.0831384053979036 ) ) ; -#25662 = ORIENTED_EDGE ( 'NONE', *, *, #5662, .F. ) ; -#25663 = VERTEX_POINT ( 'NONE', #23844 ) ; -#25664 = DIRECTION ( 'NONE', ( -0.0005884949961166157945, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#25665 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825842615387340, 0.0005734119041737265748 ) ) ; -#25666 = CARTESIAN_POINT ( 'NONE', ( -25.53470936712000139, 185.3002260771000067, 32.42391899273999911 ) ) ; -#25667 = ORIENTED_EDGE ( 'NONE', *, *, #24055, .F. ) ; -#25668 = FACE_OUTER_BOUND ( 'NONE', #5959, .T. ) ; -#25669 = VERTEX_POINT ( 'NONE', #37709 ) ; -#25670 = CARTESIAN_POINT ( 'NONE', ( 20.50029382287623037, 174.4060969903238458, 100.4185135684600993 ) ) ; -#25671 = ORIENTED_EDGE ( 'NONE', *, *, #16682, .F. ) ; -#25672 = AXIS2_PLACEMENT_3D ( 'NONE', #19719, #34454, #25496 ) ; -#25673 = EDGE_CURVE ( 'NONE', #12970, #29757, #34310, .T. ) ; -#25674 = EDGE_CURVE ( 'NONE', #26075, #28651, #4946, .T. ) ; -#25675 = EDGE_CURVE ( 'NONE', #15031, #27146, #12776, .T. ) ; -#25676 = AXIS2_PLACEMENT_3D ( 'NONE', #23626, #10959, #5200 ) ; -#25677 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364818587623, 136.5649596138779884, 181.4686487119677167 ) ) ; -#25678 = ADVANCED_FACE ( 'NONE', ( #10475 ), #24670, .T. ) ; -#25679 = DIRECTION ( 'NONE', ( 0.0005884949961216892102, -0.2249510543439063592, 0.9743698870671262391 ) ) ; -#25680 = ORIENTED_EDGE ( 'NONE', *, *, #15906, .T. ) ; -#25681 = LINE ( 'NONE', #31395, #15749 ) ; -#25682 = VECTOR ( 'NONE', #22959, 1000.000000000000000 ) ; -#25683 = CARTESIAN_POINT ( 'NONE', ( -2.502144820012000004, 190.3949449552999909, 106.2773598966000037 ) ) ; -#25684 = CARTESIAN_POINT ( 'NONE', ( -12.63633101993597130, 136.6777708571482606, 94.29709491087972140 ) ) ; -#25685 = EDGE_CURVE ( 'NONE', #1228, #10977, #24998, .T. ) ; -#25686 = ORIENTED_EDGE ( 'NONE', *, *, #2312, .F. ) ; -#25687 = PLANE ( 'NONE', #17752 ) ; -#25688 = CARTESIAN_POINT ( 'NONE', ( -20.49970532888763941, 191.4139234226054498, 104.3698659823340478 ) ) ; -#25689 = CARTESIAN_POINT ( 'NONE', ( 20.29385838999352742, 212.4069381654295796, 73.04624710044845415 ) ) ; -#25690 = LINE ( 'NONE', #6843, #36614 ) ; -#25691 = EDGE_CURVE ( 'NONE', #19108, #33611, #12147, .T. ) ; -#25692 = CARTESIAN_POINT ( 'NONE', ( -42.56963625464027245, 120.8513313564750575, 90.65827283841386475 ) ) ; -#25693 = VERTEX_POINT ( 'NONE', #29675 ) ; -#25694 = CARTESIAN_POINT ( 'NONE', ( 22.20643291937885877, 214.0123450240148202, 76.04556629009920243 ) ) ; -#25695 = CARTESIAN_POINT ( 'NONE', ( 25.43540111634469270, 117.4590002937401181, 89.75256112228039740 ) ) ; -#25696 = CARTESIAN_POINT ( 'NONE', ( -37.34320747774000182, 117.7695368308999946, 90.15184626625000419 ) ) ; -#25697 = ORIENTED_EDGE ( 'NONE', *, *, #12326, .F. ) ; -#25698 = AXIS2_PLACEMENT_3D ( 'NONE', #15420, #37485, #9690 ) ; -#25699 = CARTESIAN_POINT ( 'NONE', ( 31.79421363390603261, 220.4002260770989778, 73.53930126518000066 ) ) ; -#25700 = ORIENTED_EDGE ( 'NONE', *, *, #12641, .F. ) ; -#25701 = CARTESIAN_POINT ( 'NONE', ( -28.46358003787008784, 130.0931529937463438, 92.44131419057775645 ) ) ; -#25702 = CARTESIAN_POINT ( 'NONE', ( -3.953839019659958431, 174.7728703276109741, 102.6551122695953637 ) ) ; -#25703 = VECTOR ( 'NONE', #24201, 1000.000000000000000 ) ; -#25704 = CARTESIAN_POINT ( 'NONE', ( -12.63780404429605042, 128.4714928439248638, 89.83368724503242220 ) ) ; -#25705 = ORIENTED_EDGE ( 'NONE', *, *, #33158, .T. ) ; -#25706 = VERTEX_POINT ( 'NONE', #35770 ) ; -#25707 = ORIENTED_EDGE ( 'NONE', *, *, #20188, .T. ) ; -#25708 = CARTESIAN_POINT ( 'NONE', ( -42.69294731529282672, 103.5236703916287553, 167.6615886432229843 ) ) ; -#25709 = PLANE ( 'NONE', #34654 ) ; -#25710 = DIRECTION ( 'NONE', ( -0.6087614883550946931, 0.7730004026499607273, 0.1785492307423600378 ) ) ; -#25711 = ORIENTED_EDGE ( 'NONE', *, *, #38782, .T. ) ; -#25712 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 171.7660675377210282, 184.4841745997615021 ) ) ; -#25713 = CARTESIAN_POINT ( 'NONE', ( -25.75129388820000287, 120.5227984420999974, 87.74993035635000638 ) ) ; -#25714 = CARTESIAN_POINT ( 'NONE', ( 36.51299379403999978, 191.8889899160000141, 104.5096745278000157 ) ) ; -#25715 = CARTESIAN_POINT ( 'NONE', ( 2.959628761272101283, 209.6631827712477900, 76.05717346085170050 ) ) ; -#25716 = CARTESIAN_POINT ( 'NONE', ( 45.31676687487262711, 123.9859615478322183, 91.32887818729398077 ) ) ; -#25717 = CARTESIAN_POINT ( 'NONE', ( -15.49970618539471268, 185.7934281236995844, 103.0692296848312282 ) ) ; -#25718 = ORIENTED_EDGE ( 'NONE', *, *, #37288, .F. ) ; -#25719 = CARTESIAN_POINT ( 'NONE', ( 28.30074384216000283, 125.2974345084000021, 88.73412754224999333 ) ) ; -#25720 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13898, #4066, #39030, #4889 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25721 = CARTESIAN_POINT ( 'NONE', ( -20.51763439869084849, 207.5364665811183613, 76.82466709321089127 ) ) ; -#25722 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; -#25723 = EDGE_CURVE ( 'NONE', #15729, #27481, #26952, .T. ) ; -#25724 = EDGE_CURVE ( 'NONE', #12087, #30603, #39595, .T. ) ; -#25725 = CARTESIAN_POINT ( 'NONE', ( -25.74931979772765800, 116.9126722973494168, 90.28333678314174904 ) ) ; -#25726 = CARTESIAN_POINT ( 'NONE', ( 21.23524577242590183, 158.6168070940844075, 96.25967206434769707 ) ) ; -#25727 = ORIENTED_EDGE ( 'NONE', *, *, #29362, .T. ) ; -#25728 = CARTESIAN_POINT ( 'NONE', ( -21.21399091018682981, 129.1232532189451376, 89.98933777676734280 ) ) ; -#25729 = CARTESIAN_POINT ( 'NONE', ( -15.56570128697116395, 127.6534963204462514, 175.2992203924931687 ) ) ; -#25730 = VECTOR ( 'NONE', #11990, 999.9999999999998863 ) ; -#25731 = AXIS2_PLACEMENT_3D ( 'NONE', #28297, #12960, #34597 ) ; -#25732 = CARTESIAN_POINT ( 'NONE', ( 36.43823293609931824, 191.7962655817395046, 104.3583410344040772 ) ) ; -#25733 = CARTESIAN_POINT ( 'NONE', ( 20.50153854971994960, 118.8155953598612484, 89.75541792533370256 ) ) ; -#25734 = VECTOR ( 'NONE', #21524, 1000.000000000000227 ) ; -#25735 = CARTESIAN_POINT ( 'NONE', ( 38.47818596117896561, 119.0222560628710369, 90.24976562745140996 ) ) ; -#25736 = CARTESIAN_POINT ( 'NONE', ( 31.79365004200798595, 115.2698610323616890, 176.5535528959301530 ) ) ; -#25737 = PLANE ( 'NONE', #701 ) ; -#25738 = CARTESIAN_POINT ( 'NONE', ( 18.98783187499508074, 148.3993599496172351, 183.8670116001150632 ) ) ; -#25739 = ORIENTED_EDGE ( 'NONE', *, *, #28383, .T. ) ; -#25740 = CARTESIAN_POINT ( 'NONE', ( 6.037208908824005960, 176.8656333337133333, 103.2162234373518004 ) ) ; -#25741 = ADVANCED_FACE ( 'NONE', ( #11884 ), #20875, .T. ) ; -#25742 = CARTESIAN_POINT ( 'NONE', ( -45.38224234400345125, 124.4312361121064896, 88.40754498314288412 ) ) ; -#25743 = CARTESIAN_POINT ( 'NONE', ( -16.53785153513707584, 123.0772470471530085, 172.1883206570706477 ) ) ; -#25744 = ORIENTED_EDGE ( 'NONE', *, *, #20235, .T. ) ; -#25745 = DIRECTION ( 'NONE', ( 0.0006039748499252115509, 0.000000000000000000, 0.9999998176071738243 ) ) ; -#25746 = CARTESIAN_POINT ( 'NONE', ( -25.99159371425722398, 191.8593449687673456, 103.9335660634491063 ) ) ; -#25747 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319403664923 ) ) ; -#25748 = LINE ( 'NONE', #974, #25504 ) ; -#25749 = CARTESIAN_POINT ( 'NONE', ( 22.78079353263602869, 153.8098031058628692, 95.66210622315543333 ) ) ; -#25750 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#25751 = VERTEX_POINT ( 'NONE', #5323 ) ; -#25752 = DIRECTION ( 'NONE', ( 0.7942820423213359238, 0.5918950211223032998, 0.1370267171630252800 ) ) ; -#25753 = AXIS2_PLACEMENT_3D ( 'NONE', #9625, #34733, #6735 ) ; -#25754 = CARTESIAN_POINT ( 'NONE', ( 35.74933844504462854, 114.7932138186078816, 87.24619258741343231 ) ) ; -#25755 = AXIS2_PLACEMENT_3D ( 'NONE', #1576, #2201, #24079 ) ; -#25756 = CARTESIAN_POINT ( 'NONE', ( -23.36150835703034190, 130.4188133218702319, 90.28973853220963974 ) ) ; -#25757 = EDGE_LOOP ( 'NONE', ( #35016, #16511, #9618, #24951 ) ) ; -#25758 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474973922409778, 155.7928101624883936, 98.18628735359267523 ) ) ; -#25759 = VERTEX_POINT ( 'NONE', #30275 ) ; -#25760 = PLANE ( 'NONE', #29983 ) ; -#25761 = CARTESIAN_POINT ( 'NONE', ( -13.59692594909000007, 163.2545600168000135, 28.07991271570000080 ) ) ; -#25762 = DIRECTION ( 'NONE', ( 0.0004161288024514938006, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#25763 = CARTESIAN_POINT ( 'NONE', ( 37.79562854142448458, 218.5902260770999987, 75.53567692577773585 ) ) ; -#25764 = ADVANCED_FACE ( 'NONE', ( #8618 ), #15382, .T. ) ; -#25765 = ADVANCED_FACE ( 'NONE', ( #21082 ), #14751, .T. ) ; -#25766 = CARTESIAN_POINT ( 'NONE', ( 34.29411924272742596, 218.5902260770999987, 73.03779129371591239 ) ) ; -#25767 = CARTESIAN_POINT ( 'NONE', ( 20.50042280545328310, 118.5813761975761764, 87.75531210468815857 ) ) ; -#25768 = EDGE_LOOP ( 'NONE', ( #26793, #38716, #37262, #10337 ) ) ; -#25769 = LINE ( 'NONE', #24972, #6957 ) ; -#25770 = CARTESIAN_POINT ( 'NONE', ( 30.07022246028604329, 177.5684875020558877, 100.8237775184044267 ) ) ; -#25771 = CARTESIAN_POINT ( 'NONE', ( 5.703605760174398576, 177.7921183530763471, 100.6960230178058282 ) ) ; -#25772 = CARTESIAN_POINT ( 'NONE', ( -20.51844305912966249, 206.3036150481032394, 75.12978008876878278 ) ) ; -#25773 = ORIENTED_EDGE ( 'NONE', *, *, #7830, .F. ) ; -#25774 = EDGE_LOOP ( 'NONE', ( #9745, #9548, #35045, #28624 ) ) ; -#25775 = LINE ( 'NONE', #29025, #11368 ) ; -#25776 = ORIENTED_EDGE ( 'NONE', *, *, #32762, .T. ) ; -#25777 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35377, #17180, #35567, #16574 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25778 = LINE ( 'NONE', #3271, #24929 ) ; -#25779 = AXIS2_PLACEMENT_3D ( 'NONE', #603, #409, #16344 ) ; -#25780 = CIRCLE ( 'NONE', #40114, 2.000000000000011546 ) ; -#25781 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#25782 = CIRCLE ( 'NONE', #15323, 5.999999999944575002 ) ; -#25783 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4051, #25565, #22089, #10224, #1197, #22889, #19399, #13676, #22496, #38216, #9818, #31896, #35113, #10422, #19597, #3855 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 4 ), - ( 8.202606158603310806E-15, 0.0003993169203146928721, 0.0007986338406211832127, 0.001197950760927673662, 0.001597267681234163786, 0.001996584601540654126, 0.002395901521847144684, 0.003194535362460158325 ), - .UNSPECIFIED. ) ; -#25784 = CARTESIAN_POINT ( 'NONE', ( -25.99964915362324192, 120.0929955239077032, 90.47318932755659660 ) ) ; -#25785 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8858, #37056, #21325, #27672 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.699745388805494750, 1.699780469277642814 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999998974467008, 0.9999999998974467008, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#25786 = CARTESIAN_POINT ( 'NONE', ( 39.31906229016909293, 129.4589100703372821, 89.51864490113773343 ) ) ; -#25787 = ADVANCED_FACE ( 'NONE', ( #33739 ), #18188, .T. ) ; -#25788 = CARTESIAN_POINT ( 'NONE', ( -2.578765801273999791, 209.0167477900000108, 73.48847337076000485 ) ) ; -#25789 = CARTESIAN_POINT ( 'NONE', ( 38.34695031038000224, 118.7616814038999991, 90.10264553476001481 ) ) ; -#25790 = ORIENTED_EDGE ( 'NONE', *, *, #28799, .T. ) ; -#25791 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825924600143509, 0.0005734119022810348423 ) ) ; -#25792 = CARTESIAN_POINT ( 'NONE', ( 35.55352252806802227, 109.6131156654499961, 87.24631085522547380 ) ) ; -#25793 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; -#25794 = CARTESIAN_POINT ( 'NONE', ( -26.00624846271685442, 190.8511609718977127, 106.8090059743847178 ) ) ; -#25795 = ORIENTED_EDGE ( 'NONE', *, *, #4366, .F. ) ; -#25796 = ORIENTED_EDGE ( 'NONE', *, *, #11825, .F. ) ; -#25797 = ORIENTED_EDGE ( 'NONE', *, *, #22451, .T. ) ; -#25798 = CARTESIAN_POINT ( 'NONE', ( 44.05441677404900958, 112.7011882844216615, 88.72434494931374616 ) ) ; -#25799 = EDGE_CURVE ( 'NONE', #29453, #39083, #3537, .T. ) ; -#25800 = CARTESIAN_POINT ( 'NONE', ( 38.29229177720002042, 119.0091981861925206, 87.46444357072304854 ) ) ; -#25801 = CARTESIAN_POINT ( 'NONE', ( 2.431955026391375618, 158.3626469589818271, 101.3438727543389035 ) ) ; -#25802 = DIRECTION ( 'NONE', ( -0.6087614810001780175, 0.7729390313185915407, 0.1788147452386051883 ) ) ; -#25803 = ORIENTED_EDGE ( 'NONE', *, *, #29306, .F. ) ; -#25804 = AXIS2_PLACEMENT_3D ( 'NONE', #17901, #11594, #17495 ) ; -#25805 = CARTESIAN_POINT ( 'NONE', ( 14.81744580022004243, 163.8812281945125733, 152.8157487480565351 ) ) ; -#25806 = ADVANCED_FACE ( 'NONE', ( #18996 ), #38224, .F. ) ; -#25807 = CARTESIAN_POINT ( 'NONE', ( 20.94615154526903567, 129.3425601203839221, 89.50137061379278691 ) ) ; -#25808 = CARTESIAN_POINT ( 'NONE', ( -12.63633103062601570, 183.4475335476649889, 105.0947473920673190 ) ) ; -#25809 = CARTESIAN_POINT ( 'NONE', ( -40.55546040064906776, 184.3694241705995296, 104.8082140455743883 ) ) ; -#25810 = ORIENTED_EDGE ( 'NONE', *, *, #28293, .T. ) ; -#25811 = CARTESIAN_POINT ( 'NONE', ( 94.27346847287640230, 222.2365666497040024, 195.1387431474686309 ) ) ; -#25812 = ORIENTED_EDGE ( 'NONE', *, *, #25623, .T. ) ; -#25813 = CARTESIAN_POINT ( 'NONE', ( -14.78542059478467330, 183.3574060367851359, 102.5063981592711571 ) ) ; -#25814 = CIRCLE ( 'NONE', #8170, 2.499999999994495514 ) ; -#25815 = ADVANCED_FACE ( 'NONE', ( #28231 ), #31284, .F. ) ; -#25816 = EDGE_CURVE ( 'NONE', #25194, #1872, #4913, .T. ) ; -#25817 = CARTESIAN_POINT ( 'NONE', ( -2.435788377003461846, 191.0000002182038941, 106.3158216037667358 ) ) ; -#25818 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319350685384 ) ) ; -#25819 = ORIENTED_EDGE ( 'NONE', *, *, #23122, .T. ) ; -#25820 = ADVANCED_FACE ( 'NONE', ( #15472 ), #27966, .F. ) ; -#25821 = ORIENTED_EDGE ( 'NONE', *, *, #5337, .T. ) ; -#25822 = CARTESIAN_POINT ( 'NONE', ( -19.99991124754194516, 196.0294354676498472, 104.9180633642943405 ) ) ; -#25823 = EDGE_CURVE ( 'NONE', #24745, #9304, #25096, .T. ) ; -#25824 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391912172 ) ) ; -#25825 = CARTESIAN_POINT ( 'NONE', ( 20.25014673412999855, 188.1903989944999864, 103.3444460256000212 ) ) ; -#25826 = VERTEX_POINT ( 'NONE', #24902 ) ; -#25827 = CARTESIAN_POINT ( 'NONE', ( 20.26084502294995460, 118.1108187821794502, 87.51605973384316428 ) ) ; -#25828 = CARTESIAN_POINT ( 'NONE', ( -12.68284606093999933, 201.2278123622000123, 28.07991271570000080 ) ) ; -#25829 = ORIENTED_EDGE ( 'NONE', *, *, #31340, .T. ) ; -#25830 = CARTESIAN_POINT ( 'NONE', ( 27.07873119645540783, 119.5134203564188198, 171.3751642805570157 ) ) ; -#25831 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29177, #12827, #26113, #4006 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25832 = CARTESIAN_POINT ( 'NONE', ( 36.49264889551449897, 191.3170871187571151, 103.7999128507424871 ) ) ; -#25833 = ORIENTED_EDGE ( 'NONE', *, *, #19030, .T. ) ; -#25834 = CARTESIAN_POINT ( 'NONE', ( 1.373544093530520760, 188.5169685701486344, 106.2535783728023659 ) ) ; -#25835 = CARTESIAN_POINT ( 'NONE', ( -37.67574118798827243, 118.8155645602721222, 87.29053938956874958 ) ) ; -#25836 = CARTESIAN_POINT ( 'NONE', ( -3.233981241130774009, 126.1655476077336573, 88.78248592047526699 ) ) ; -#25837 = EDGE_CURVE ( 'NONE', #19459, #34206, #19099, .T. ) ; -#25838 = AXIS2_PLACEMENT_3D ( 'NONE', #34376, #28861, #840 ) ; -#25839 = AXIS2_PLACEMENT_3D ( 'NONE', #39316, #39517, #17641 ) ; -#25840 = VERTEX_POINT ( 'NONE', #12213 ) ; -#25841 = CARTESIAN_POINT ( 'NONE', ( 26.00471032461299714, 120.1087538276019870, 90.45505707459361133 ) ) ; -#25842 = CARTESIAN_POINT ( 'NONE', ( 37.28972153584570037, 172.2751332797207624, 165.2090122940432195 ) ) ; -#25843 = CIRCLE ( 'NONE', #38858, 2.000000000000011546 ) ; -#25844 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7269, #28963, #4003, #31085 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 5.777484129617390118E-06, 0.0006658699108300950801 ), - .UNSPECIFIED. ) ; -#25846 = CARTESIAN_POINT ( 'NONE', ( -9.003483374562920361, 152.5917386336430468, 94.88693858845569196 ) ) ; -#25845 = CARTESIAN_POINT ( 'NONE', ( -22.49823373369745028, 184.2867141917648723, 105.2913686032300973 ) ) ; -#25847 = ORIENTED_EDGE ( 'NONE', *, *, #36994, .T. ) ; -#25848 = DIRECTION ( 'NONE', ( 0.0006039748319383109534, 1.233022124494217175E-14, 0.9999998176071845934 ) ) ; -#25849 = CARTESIAN_POINT ( 'NONE', ( 15.94054669826102177, 152.1475402096681080, 184.5616883112009816 ) ) ; -#25850 = VERTEX_POINT ( 'NONE', #39792 ) ; -#25851 = CARTESIAN_POINT ( 'NONE', ( 21.30326722320182498, 111.8959539139345623, 163.3359429212474652 ) ) ; -#25852 = ADVANCED_FACE ( 'NONE', ( #24698 ), #11466, .T. ) ; -#25853 = CARTESIAN_POINT ( 'NONE', ( -77.86967201343009037, 193.6973639405334211, 188.4988971914144997 ) ) ; -#25854 = EDGE_LOOP ( 'NONE', ( #5970, #35708, #35550, #38919, #23555, #13161, #37450, #26854, #12290, #31369 ) ) ; -#25855 = VERTEX_POINT ( 'NONE', #6451 ) ; -#25856 = CARTESIAN_POINT ( 'NONE', ( 35.54796091243969869, 209.7096538831000032, 78.03703491673005033 ) ) ; -#25857 = EDGE_CURVE ( 'NONE', #4191, #16108, #16667, .T. ) ; -#25858 = CARTESIAN_POINT ( 'NONE', ( -46.10293086928386685, 125.3510531446604119, 91.69924967890207768 ) ) ; -#25859 = DIRECTION ( 'NONE', ( 0.7066905234128858515, 0.1590644159615968445, -0.6894106292284863935 ) ) ; -#25860 = CARTESIAN_POINT ( 'NONE', ( 35.91400125412999955, 192.1945380241000123, 104.2261858913000054 ) ) ; -#25861 = EDGE_CURVE ( 'NONE', #12419, #21377, #18920, .T. ) ; -#25862 = ORIENTED_EDGE ( 'NONE', *, *, #38505, .F. ) ; -#25863 = ORIENTED_EDGE ( 'NONE', *, *, #15698, .T. ) ; -#25864 = AXIS2_PLACEMENT_3D ( 'NONE', #36399, #2263, #15335 ) ; -#25865 = CARTESIAN_POINT ( 'NONE', ( -15.49852918184222439, 151.4059875814179463, 97.18286991562941068 ) ) ; -#25866 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #20672, #16973, #39672, #38860 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.218337603126023794, 4.671255600858287949 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9829783718293336747, 0.9829783718293336747, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#25867 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, 2.333520449303964377E-14, 0.9999998176071847045 ) ) ; -#25868 = CIRCLE ( 'NONE', #11488, 7.999999999987271515 ) ; -#25869 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -1.540743955509789367E-33, 0.0006039748319385908944 ) ) ; -#25870 = ORIENTED_EDGE ( 'NONE', *, *, #33527, .T. ) ; -#25871 = ADVANCED_FACE ( 'NONE', ( #25900 ), #17984, .T. ) ; -#25872 = EDGE_LOOP ( 'NONE', ( #40105, #14926, #20387, #9804 ) ) ; -#25873 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; -#25874 = VERTEX_POINT ( 'NONE', #37948 ) ; -#25875 = CARTESIAN_POINT ( 'NONE', ( -37.48991906556833698, 117.3311509667802568, 89.72388382565569032 ) ) ; -#25876 = CONICAL_SURFACE ( 'NONE', #39525, 2.503060577177303347, 0.7853981633905392501 ) ; -#25877 = CARTESIAN_POINT ( 'NONE', ( 26.00891783773975874, 196.5784392904109836, 103.8593946022765522 ) ) ; -#25878 = LINE ( 'NONE', #34822, #29429 ) ; -#25879 = ORIENTED_EDGE ( 'NONE', *, *, #33080, .F. ) ; -#25880 = CARTESIAN_POINT ( 'NONE', ( -38.09245941673125202, 165.8295026144894848, 188.3351898487784979 ) ) ; -#25881 = CARTESIAN_POINT ( 'NONE', ( -20.00025820447960001, 138.1823733798348428, 91.56700283718186029 ) ) ; -#25882 = CARTESIAN_POINT ( 'NONE', ( -85.24348513260991922, 108.2328939675489039, 25.03902193712222513 ) ) ; -#25883 = EDGE_LOOP ( 'NONE', ( #12746, #37666, #2897, #10527 ) ) ; -#25884 = CARTESIAN_POINT ( 'NONE', ( -15.49823494792000034, 183.2823103887000116, 105.0552522186000033 ) ) ; -#25885 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#25886 = DIRECTION ( 'NONE', ( 0.9914446600486714889, -0.1270322995874083039, -0.03000468167651988011 ) ) ; -#25887 = FACE_OUTER_BOUND ( 'NONE', #21509, .T. ) ; -#25888 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#25889 = ORIENTED_EDGE ( 'NONE', *, *, #37343, .F. ) ; -#25890 = VECTOR ( 'NONE', #8505, 1000.000000000000000 ) ; -#25891 = CARTESIAN_POINT ( 'NONE', ( 5.672673928745917138, 188.3446234544624360, 103.1322799088097213 ) ) ; -#25892 = VECTOR ( 'NONE', #37535, 1000.000000000000000 ) ; -#25893 = CARTESIAN_POINT ( 'NONE', ( -38.51153276251000079, 118.3243097615000039, 89.55231124261001696 ) ) ; -#25894 = ORIENTED_EDGE ( 'NONE', *, *, #18898, .T. ) ; -#25895 = ORIENTED_EDGE ( 'NONE', *, *, #22906, .T. ) ; -#25896 = EDGE_CURVE ( 'NONE', #26354, #8120, #3625, .T. ) ; -#25898 = VECTOR ( 'NONE', #36655, 1000.000000000000114 ) ; -#25897 = FACE_OUTER_BOUND ( 'NONE', #15424, .T. ) ; -#25899 = EDGE_CURVE ( 'NONE', #18328, #326, #4467, .T. ) ; -#25900 = FACE_OUTER_BOUND ( 'NONE', #11316, .T. ) ; -#25901 = LINE ( 'NONE', #37949, #34594 ) ; -#25902 = EDGE_CURVE ( 'NONE', #31162, #14004, #35853, .T. ) ; -#25903 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37667, #13330, #25822, #6573, #19244, #22548, #451, #55, #25217, #7185 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000013494206, 0.5000000000026988412, 0.7500000000040483172, 1.000000000005397682 ), - .UNSPECIFIED. ) ; -#25904 = CARTESIAN_POINT ( 'NONE', ( 23.36189990591568133, 177.7981167418394648, 100.6835809371482071 ) ) ; -#25905 = FACE_OUTER_BOUND ( 'NONE', #39579, .T. ) ; -#25906 = ORIENTED_EDGE ( 'NONE', *, *, #33397, .F. ) ; -#25907 = ORIENTED_EDGE ( 'NONE', *, *, #6486, .T. ) ; -#25908 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#25909 = LINE ( 'NONE', #16269, #7230 ) ; -#25910 = ADVANCED_FACE ( 'NONE', ( #14008 ), #21317, .F. ) ; -#25911 = EDGE_LOOP ( 'NONE', ( #4169, #25175, #14015, #13528 ) ) ; -#25912 = CARTESIAN_POINT ( 'NONE', ( -25.50869118940049418, 205.9699382466141060, 75.53276979609236719 ) ) ; -#25913 = CARTESIAN_POINT ( 'NONE', ( 35.76259268655000056, 114.4925971151999988, 87.35906496734000370 ) ) ; -#25914 = CARTESIAN_POINT ( 'NONE', ( 20.31802304245822199, 148.9701552444815889, 180.2359233600722064 ) ) ; -#25915 = CARTESIAN_POINT ( 'NONE', ( 2.967323546165053560, 209.6397747443908202, 76.05789313520143935 ) ) ; -#25916 = EDGE_CURVE ( 'NONE', #18594, #36032, #14218, .T. ) ; -#25917 = CARTESIAN_POINT ( 'NONE', ( 37.65057158750833821, 122.6594394773597969, 91.02725657039249541 ) ) ; -#25918 = CARTESIAN_POINT ( 'NONE', ( 21.72804141255551968, 135.8412665901933281, 91.00123227078390187 ) ) ; -#25919 = ORIENTED_EDGE ( 'NONE', *, *, #17142, .T. ) ; -#25920 = CARTESIAN_POINT ( 'NONE', ( 28.43207377478999831, 125.3828625717000023, 88.75274922023000101 ) ) ; -#25921 = AXIS2_PLACEMENT_3D ( 'NONE', #23407, #29746, #9794 ) ; -#25922 = CARTESIAN_POINT ( 'NONE', ( 28.26067382423566698, 125.1347711400599110, 91.09124888412546284 ) ) ; -#25923 = DIRECTION ( 'NONE', ( -6.938893903907188146E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#25924 = DIRECTION ( 'NONE', ( 0.0005884949961234757585, -0.2249510543439061094, 0.9743698870671263501 ) ) ; -#25925 = CARTESIAN_POINT ( 'NONE', ( 4.661269518560463787, 124.5726190011685617, 88.40996077378878226 ) ) ; -#25926 = ORIENTED_EDGE ( 'NONE', *, *, #31623, .F. ) ; -#25927 = EDGE_CURVE ( 'NONE', #23376, #1726, #38938, .T. ) ; -#25928 = CARTESIAN_POINT ( 'NONE', ( 21.26009136220303120, 136.4215387128503494, 93.70123539943294588 ) ) ; -#25929 = CARTESIAN_POINT ( 'NONE', ( 0.5903394205705844167, 189.0001744873707139, 103.6876116629842954 ) ) ; -#25930 = CARTESIAN_POINT ( 'NONE', ( -75.43462682692893395, 196.7891049527112841, 189.2142300545978344 ) ) ; -#25931 = CONICAL_SURFACE ( 'NONE', #6318, 2.503106776662724187, 0.7853981633574818044 ) ; -#25932 = CARTESIAN_POINT ( 'NONE', ( 12.63660632401984607, 130.0048512205758868, 92.26772709118364446 ) ) ; -#25933 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555410 ) ) ; -#25934 = CARTESIAN_POINT ( 'NONE', ( -20.51998460911297784, 211.0905570173818546, 73.57089872868714053 ) ) ; -#25935 = CARTESIAN_POINT ( 'NONE', ( -20.24838124913999948, 187.6253075150000029, 105.8042051877000063 ) ) ; -#25936 = CARTESIAN_POINT ( 'NONE', ( -39.35534632512823805, 183.2999964971099303, 101.9948315917579293 ) ) ; -#25937 = CARTESIAN_POINT ( 'NONE', ( -20.49878101475079006, 193.0431070017871207, 106.3366395002382774 ) ) ; -#25938 = LINE ( 'NONE', #23252, #387 ) ; -#25939 = EDGE_LOOP ( 'NONE', ( #30963, #13284, #33305, #12638 ) ) ; -#25940 = FACE_OUTER_BOUND ( 'NONE', #8955, .T. ) ; -#25941 = FACE_OUTER_BOUND ( 'NONE', #37692, .T. ) ; -#25942 = ORIENTED_EDGE ( 'NONE', *, *, #16099, .F. ) ; -#25943 = CARTESIAN_POINT ( 'NONE', ( -24.30274708465592326, 117.2756935949167314, 170.8452364414067688 ) ) ; -#25944 = CARTESIAN_POINT ( 'NONE', ( -25.99172658142667558, 191.8212920557626830, 103.9312229004612931 ) ) ; -#25945 = CONICAL_SURFACE ( 'NONE', #22002, 2.502999999907702389, 0.7853981633983988520 ) ; -#25946 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#25947 = CARTESIAN_POINT ( 'NONE', ( 36.06506287055499627, 192.7079431075819969, 106.3534797050179890 ) ) ; -#25948 = EDGE_CURVE ( 'NONE', #15910, #27558, #33690, .T. ) ; -#25949 = DIRECTION ( 'NONE', ( 0.0005884949961212082581, -0.2249510543439042498, 0.9743698870671267942 ) ) ; -#25950 = EDGE_CURVE ( 'NONE', #8723, #16362, #14622, .T. ) ; -#25951 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825803063353275, 0.0005734119050868656054 ) ) ; -#25952 = CARTESIAN_POINT ( 'NONE', ( 36.20498506693999730, 192.7754826498999989, 106.1893283618999959 ) ) ; -#25953 = AXIS2_PLACEMENT_3D ( 'NONE', #5186, #2145, #20947 ) ; -#25954 = ORIENTED_EDGE ( 'NONE', *, *, #29997, .F. ) ; -#25955 = CARTESIAN_POINT ( 'NONE', ( -2.749347475841000144, 209.4717962128000295, 75.90003642860000355 ) ) ; -#25956 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6080, #12029, #31038, #3007, #31849, #6470 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 4 ), - ( 0.000000000000000000, 0.3333332908269993622, 0.6666665931978983384, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#25957 = CARTESIAN_POINT ( 'NONE', ( 17.91044079408289846, 122.0699274945536672, 171.9639141926653849 ) ) ; -#25958 = LINE ( 'NONE', #4240, #1715 ) ; -#25959 = CARTESIAN_POINT ( 'NONE', ( -26.71688048469999899, 177.4879621182000164, 100.9019602402999993 ) ) ; -#25960 = ORIENTED_EDGE ( 'NONE', *, *, #38928, .F. ) ; -#25961 = CARTESIAN_POINT ( 'NONE', ( 6.035661899977945666, 177.4419340092994162, 100.9146504478096489 ) ) ; -#25962 = ORIENTED_EDGE ( 'NONE', *, *, #1043, .F. ) ; -#25963 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386880390 ) ) ; -#25964 = CARTESIAN_POINT ( 'NONE', ( 25.99899579567804864, 120.3902236066977025, 87.43149108636995948 ) ) ; -#25965 = ORIENTED_EDGE ( 'NONE', *, *, #3172, .F. ) ; -#25966 = DIRECTION ( 'NONE', ( 0.7855473026356902810, 0.6188014303620729128, -0.0004744508866335531562 ) ) ; -#25967 = CARTESIAN_POINT ( 'NONE', ( -15.49852919137054741, 126.2381079287689403, 91.37240600825562353 ) ) ; -#25968 = CARTESIAN_POINT ( 'NONE', ( -19.34721860474193633, 124.8429025638662750, 177.8375121285605189 ) ) ; -#25969 = CARTESIAN_POINT ( 'NONE', ( -0.4540625018068648600, 211.4999999999330385, 76.05877887195120479 ) ) ; -#25970 = EDGE_LOOP ( 'NONE', ( #33541, #29923, #25739, #31575 ) ) ; -#25971 = ORIENTED_EDGE ( 'NONE', *, *, #31944, .F. ) ; -#25972 = EDGE_CURVE ( 'NONE', #25255, #6456, #11496, .T. ) ; -#25973 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; -#25974 = CARTESIAN_POINT ( 'NONE', ( -13.49052885539015278, 188.3420772061585353, 103.1432726234667427 ) ) ; -#25975 = DIRECTION ( 'NONE', ( 0.0005884949961217588160, -0.2249510543439091625, 0.9743698870671256840 ) ) ; -#25976 = VECTOR ( 'NONE', #33983, 1000.000000000000114 ) ; -#25977 = LINE ( 'NONE', #16927, #12483 ) ; -#25978 = VERTEX_POINT ( 'NONE', #2554 ) ; -#25979 = ORIENTED_EDGE ( 'NONE', *, *, #13931, .F. ) ; -#25980 = CARTESIAN_POINT ( 'NONE', ( -20.40297810709813220, 153.0607523594057966, 190.9281641407467589 ) ) ; -#25981 = CONICAL_SURFACE ( 'NONE', #24013, 6.500001124525312868, 0.7853982240593504471 ) ; -#25982 = CARTESIAN_POINT ( 'NONE', ( 2.538357414086004127, 209.1910662834000050, 73.57953838714999506 ) ) ; -#25983 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.782262518445068689E-15, 0.0006039748319343033085 ) ) ; -#25984 = CARTESIAN_POINT ( 'NONE', ( 26.18206239126000412, 190.7066273046999925, 106.8817066621000009 ) ) ; -#25985 = CARTESIAN_POINT ( 'NONE', ( -2.215708771335000105, 209.6118119513000124, 73.69668462555000588 ) ) ; -#25986 = CARTESIAN_POINT ( 'NONE', ( 38.13603377551000051, 118.9082903320999947, 90.39814881894000109 ) ) ; -#25987 = ORIENTED_EDGE ( 'NONE', *, *, #10455, .T. ) ; -#25988 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999894129, 179.7376864901495992, 101.1595092802908198 ) ) ; -#25989 = CARTESIAN_POINT ( 'NONE', ( 25.99211731546482795, 209.7096512574500480, 76.04280604205342797 ) ) ; -#25990 = CARTESIAN_POINT ( 'NONE', ( -13.83865842395234935, 150.1303200752071803, 181.2121488737601283 ) ) ; -#25991 = EDGE_CURVE ( 'NONE', #38021, #11146, #35237, .T. ) ; -#25992 = ADVANCED_FACE ( 'NONE', ( #21158 ), #14831, .T. ) ; -#25994 = ORIENTED_EDGE ( 'NONE', *, *, #12233, .F. ) ; -#25993 = CARTESIAN_POINT ( 'NONE', ( -26.03762780489454798, 190.4430338229397819, 106.7148013156263175 ) ) ; -#25995 = ORIENTED_EDGE ( 'NONE', *, *, #617, .F. ) ; -#25996 = ORIENTED_EDGE ( 'NONE', *, *, #3666, .T. ) ; -#25997 = VERTEX_POINT ( 'NONE', #18664 ) ; -#25998 = CARTESIAN_POINT ( 'NONE', ( -34.98386828774999913, 220.4002260771000010, 28.07991271570000080 ) ) ; -#25999 = AXIS2_PLACEMENT_3D ( 'NONE', #6277, #3207, #5472 ) ; -#26000 = LINE ( 'NONE', #32518, #7879 ) ; -#26001 = CARTESIAN_POINT ( 'NONE', ( 20.00000190450869653, 184.9707748627797912, 102.3447125600660002 ) ) ; -#26002 = VECTOR ( 'NONE', #40202, 999.9999999999998863 ) ; -#26003 = ORIENTED_EDGE ( 'NONE', *, *, #25071, .T. ) ; -#26004 = FACE_BOUND ( 'NONE', #17876, .T. ) ; -#26005 = FACE_OUTER_BOUND ( 'NONE', #14499, .T. ) ; -#26006 = FACE_OUTER_BOUND ( 'NONE', #880, .T. ) ; -#26007 = CARTESIAN_POINT ( 'NONE', ( -25.02288790548047004, 130.6107454572028246, 89.82190017567243956 ) ) ; -#26008 = ORIENTED_EDGE ( 'NONE', *, *, #22325, .F. ) ; -#26009 = CARTESIAN_POINT ( 'NONE', ( 36.05775026078000423, 118.8155664120999973, 94.24600759115000415 ) ) ; -#26010 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #18869, #16214 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26011 = VERTEX_POINT ( 'NONE', #30968 ) ; -#26012 = CARTESIAN_POINT ( 'NONE', ( 8.121789135547750504, 134.9201405189939180, 90.79681010353952786 ) ) ; -#26013 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#26014 = FACE_OUTER_BOUND ( 'NONE', #1741, .T. ) ; -#26015 = CARTESIAN_POINT ( 'NONE', ( 25.91449224139000407, 181.3172170175000133, 104.3199862606000039 ) ) ; -#26016 = ORIENTED_EDGE ( 'NONE', *, *, #16779, .T. ) ; -#26017 = EDGE_CURVE ( 'NONE', #2346, #18635, #10862, .T. ) ; -#26018 = CARTESIAN_POINT ( 'NONE', ( -2.389070030422000279, 190.4669482803000164, 104.1095728949999994 ) ) ; -#26019 = CARTESIAN_POINT ( 'NONE', ( 20.50144823217644330, 191.6366434279915438, 106.4097421862435766 ) ) ; -#26020 = CARTESIAN_POINT ( 'NONE', ( 2.942907856069000072, 190.9056063678999919, 106.6791766134000170 ) ) ; -#26021 = ORIENTED_EDGE ( 'NONE', *, *, #24214, .F. ) ; -#26022 = CARTESIAN_POINT ( 'NONE', ( -21.50356562057856991, 213.7091158727889990, 73.07149169719511406 ) ) ; -#26023 = DIRECTION ( 'NONE', ( 0.0006039748319395907457, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#26024 = VERTEX_POINT ( 'NONE', #12351 ) ; -#26025 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; -#26026 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32921, #32526, #16966, #35979 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26027 = EDGE_CURVE ( 'NONE', #19409, #7166, #31764, .T. ) ; -#26028 = VECTOR ( 'NONE', #16190, 1000.000000000000000 ) ; -#26029 = EDGE_LOOP ( 'NONE', ( #9201, #15467, #7831 ) ) ; -#26030 = CARTESIAN_POINT ( 'NONE', ( -3.589080270979503773, 149.3464402625826608, 130.0539584791989967 ) ) ; -#26031 = VECTOR ( 'NONE', #31368, 999.9999999999998863 ) ; -#26032 = CARTESIAN_POINT ( 'NONE', ( 25.49182901039327831, 209.7089661076149127, 75.54314178666862745 ) ) ; -#26033 = EDGE_CURVE ( 'NONE', #9657, #36005, #26010, .T. ) ; -#26034 = ORIENTED_EDGE ( 'NONE', *, *, #37881, .F. ) ; -#26035 = ORIENTED_EDGE ( 'NONE', *, *, #173, .T. ) ; -#26036 = CARTESIAN_POINT ( 'NONE', ( 26.00011972461669174, 120.0901139229121100, 90.43138363690108861 ) ) ; -#26037 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#26038 = ADVANCED_FACE ( 'NONE', ( #3534 ), #29803, .F. ) ; -#26039 = EDGE_CURVE ( 'NONE', #20184, #9884, #9425, .T. ) ; -#26041 = CARTESIAN_POINT ( 'NONE', ( 39.77206948006279674, 161.5605239982007504, 197.5119495795953810 ) ) ; -#26040 = CARTESIAN_POINT ( 'NONE', ( 20.48183248207558549, 208.2252159794623196, 76.03069286372645763 ) ) ; -#26042 = ADVANCED_FACE ( 'NONE', ( #7209 ), #34799, .T. ) ; -#26043 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#26044 = VERTEX_POINT ( 'NONE', #38292 ) ; -#26045 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#26046 = CARTESIAN_POINT ( 'NONE', ( -39.61053789571219852, 75.07173372617528173, 323.7343870505221730 ) ) ; -#26047 = ORIENTED_EDGE ( 'NONE', *, *, #28089, .F. ) ; -#26048 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20167, #25738, #13644, #29592 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 4.799113383051342829, 4.799119433357724063 ), - .UNSPECIFIED. ) ; -#26049 = ORIENTED_EDGE ( 'NONE', *, *, #9235, .F. ) ; -#26050 = FACE_OUTER_BOUND ( 'NONE', #8566, .T. ) ; -#26051 = CIRCLE ( 'NONE', #5787, 5.249999999999986677 ) ; -#26052 = CARTESIAN_POINT ( 'NONE', ( -44.97770985034782854, 124.1127469420047191, 93.47909829974288698 ) ) ; -#26053 = CARTESIAN_POINT ( 'NONE', ( -3.070528409906000178, 190.8178548437000188, 106.9268874777999940 ) ) ; -#26054 = CARTESIAN_POINT ( 'NONE', ( 36.02403025217999755, 191.5672976319999918, 103.8486584797000063 ) ) ; -#26055 = ORIENTED_EDGE ( 'NONE', *, *, #14679, .T. ) ; -#26056 = CIRCLE ( 'NONE', #7727, 4.999999999999990230 ) ; -#26057 = ORIENTED_EDGE ( 'NONE', *, *, #3474, .T. ) ; -#26058 = CARTESIAN_POINT ( 'NONE', ( -6.034883611057908936, 176.9196591974746866, 103.3121627513912841 ) ) ; -#26059 = VECTOR ( 'NONE', #32168, 999.9999999999998863 ) ; -#26060 = CARTESIAN_POINT ( 'NONE', ( 20.50147081996105314, 160.1804844985509817, 99.18687942156120130 ) ) ; -#26061 = CARTESIAN_POINT ( 'NONE', ( -13.54026526282000198, 167.3593566666999948, 28.07991271570000080 ) ) ; -#26062 = VECTOR ( 'NONE', #4064, 1000.000000000000114 ) ; -#26063 = ORIENTED_EDGE ( 'NONE', *, *, #6354, .T. ) ; -#26064 = EDGE_CURVE ( 'NONE', #16908, #10983, #33298, .T. ) ; -#26065 = CARTESIAN_POINT ( 'NONE', ( -13.50000254163585822, 174.5144785022299061, 99.94784507006426111 ) ) ; -#26066 = ORIENTED_EDGE ( 'NONE', *, *, #33527, .F. ) ; -#26067 = CARTESIAN_POINT ( 'NONE', ( -38.15302004047697437, 118.1466911995112667, 89.71266419572562256 ) ) ; -#26068 = CARTESIAN_POINT ( 'NONE', ( 22.50136996952335267, 157.6320572232312998, 99.11047108320519783 ) ) ; -#26069 = ORIENTED_EDGE ( 'NONE', *, *, #5918, .F. ) ; -#26070 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#26071 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#26072 = FACE_OUTER_BOUND ( 'NONE', #9111, .T. ) ; -#26073 = EDGE_CURVE ( 'NONE', #38119, #1188, #14131, .T. ) ; -#26074 = VERTEX_POINT ( 'NONE', #2109 ) ; -#26075 = VERTEX_POINT ( 'NONE', #40306 ) ; -#26076 = CARTESIAN_POINT ( 'NONE', ( 21.21575625058384063, 175.4487304674486552, 102.7114009836462003 ) ) ; -#26077 = FACE_OUTER_BOUND ( 'NONE', #25883, .T. ) ; -#26078 = DIRECTION ( 'NONE', ( -0.6087614810001780175, 0.7729390313185915407, 0.1788147452386051883 ) ) ; -#26079 = AXIS2_PLACEMENT_3D ( 'NONE', #6877, #16080, #16676 ) ; -#26080 = EDGE_CURVE ( 'NONE', #26158, #27515, #24054, .T. ) ; -#26081 = CARTESIAN_POINT ( 'NONE', ( -41.28986358703587456, 120.5685454323574817, 90.59221360106587895 ) ) ; -#26082 = EDGE_LOOP ( 'NONE', ( #2693, #25030, #22215, #28295, #386 ) ) ; -#26083 = EDGE_CURVE ( 'NONE', #20184, #30729, #13119, .T. ) ; -#26084 = AXIS2_PLACEMENT_3D ( 'NONE', #3165, #11992, #110 ) ; -#26085 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366368657916, 137.4659008082770697, 177.5714312369256049 ) ) ; -#26086 = EDGE_CURVE ( 'NONE', #2177, #32373, #21925, .T. ) ; -#26087 = AXIS2_PLACEMENT_3D ( 'NONE', #8224, #20472, #29090 ) ; -#26088 = CARTESIAN_POINT ( 'NONE', ( -37.71441295843000319, 118.5995274305000038, 90.44743091121000589 ) ) ; -#26089 = EDGE_CURVE ( 'NONE', #12175, #15089, #39557, .T. ) ; -#26090 = ORIENTED_EDGE ( 'NONE', *, *, #19633, .F. ) ; -#26091 = EDGE_CURVE ( 'NONE', #929, #9411, #25505, .T. ) ; -#26092 = EDGE_LOOP ( 'NONE', ( #17814, #31735, #16082, #13525, #2760, #30126, #5750, #39939 ) ) ; -#26093 = CARTESIAN_POINT ( 'NONE', ( -28.46145970092849709, 130.2180706372660666, 92.64122260005370890 ) ) ; -#26094 = CARTESIAN_POINT ( 'NONE', ( 35.21203317443208647, 88.41000286829014954, 281.4602140209115646 ) ) ; -#26095 = DIRECTION ( 'NONE', ( -0.0005884949961238380989, 0.2249510543439045829, -0.9743698870671267942 ) ) ; -#26096 = ORIENTED_EDGE ( 'NONE', *, *, #6519, .F. ) ; -#26097 = ORIENTED_EDGE ( 'NONE', *, *, #17488, .F. ) ; -#26098 = DIRECTION ( 'NONE', ( 0.0004161288024528962161, 0.5299192578740949955, 0.8480479980348919478 ) ) ; -#26099 = ORIENTED_EDGE ( 'NONE', *, *, #23963, .T. ) ; -#26100 = ORIENTED_EDGE ( 'NONE', *, *, #38338, .F. ) ; -#26101 = CARTESIAN_POINT ( 'NONE', ( 5.675840488321574284, 188.3446150673902650, 103.1322824216947396 ) ) ; -#26102 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498896523, 181.7471167547632547, 104.6805916157985195 ) ) ; -#26103 = CARTESIAN_POINT ( 'NONE', ( -27.08876248542915377, 119.4912842839333535, 171.3567424277059956 ) ) ; -#26104 = CARTESIAN_POINT ( 'NONE', ( -45.39606049366843621, 123.6566771517818637, 91.23024032489176705 ) ) ; -#26105 = ORIENTED_EDGE ( 'NONE', *, *, #39031, .T. ) ; -#26106 = CARTESIAN_POINT ( 'NONE', ( -25.50911727185309630, 206.5315393778744522, 74.85791579066014378 ) ) ; -#26107 = DIRECTION ( 'NONE', ( -0.0004161288024448787037, 0.8480480898058688766, -0.5299191110098189217 ) ) ; -#26108 = CYLINDRICAL_SURFACE ( 'NONE', #30292, 1.000000000000015099 ) ; -#26109 = CARTESIAN_POINT ( 'NONE', ( 3.038435836854210148, 209.3322921572255950, 76.08940849261169603 ) ) ; -#26110 = AXIS2_PLACEMENT_3D ( 'NONE', #32827, #4807, #17269 ) ; -#26111 = ORIENTED_EDGE ( 'NONE', *, *, #38180, .T. ) ; -#26112 = FACE_OUTER_BOUND ( 'NONE', #29178, .T. ) ; -#26113 = CARTESIAN_POINT ( 'NONE', ( -14.90630211925956417, 176.5437391631601258, 100.4202597877415712 ) ) ; -#26114 = CARTESIAN_POINT ( 'NONE', ( 31.51045601729472878, 191.4722053967427371, 106.4044942135075615 ) ) ; -#26115 = ORIENTED_EDGE ( 'NONE', *, *, #24289, .T. ) ; -#26116 = VECTOR ( 'NONE', #32909, 1000.000000000000114 ) ; -#26117 = CARTESIAN_POINT ( 'NONE', ( -1.458415330480473004, 144.9404864492774720, 129.0359332386186679 ) ) ; -#26118 = AXIS2_PLACEMENT_3D ( 'NONE', #29600, #17302, #29205 ) ; -#26119 = CARTESIAN_POINT ( 'NONE', ( -37.23839612158430157, 105.3143004547666521, 178.4910803265802031 ) ) ; -#26120 = CARTESIAN_POINT ( 'NONE', ( -44.46004285478915108, 188.8078265508242168, 105.8352584314367135 ) ) ; -#26121 = CARTESIAN_POINT ( 'NONE', ( -12.63650000504985549, 176.7400935515184131, 103.0299816119349714 ) ) ; -#26122 = EDGE_LOOP ( 'NONE', ( #23405, #6878, #11274, #26003 ) ) ; -#26123 = CARTESIAN_POINT ( 'NONE', ( 37.33774095389934899, 168.2370055128168644, 182.6413831928035165 ) ) ; -#26124 = CARTESIAN_POINT ( 'NONE', ( 0.7564024116337380033, 189.0098714485679636, 103.6863029074804530 ) ) ; -#26125 = CARTESIAN_POINT ( 'NONE', ( -30.04734455941837368, 126.8158942839318399, 89.11987558063840709 ) ) ; -#26126 = EDGE_CURVE ( 'NONE', #39643, #35545, #22328, .T. ) ; -#26127 = ADVANCED_FACE ( 'NONE', ( #19631 ), #23254, .F. ) ; -#26128 = CARTESIAN_POINT ( 'NONE', ( 12.63710206518894630, 130.0516725572641690, 92.34265652479372477 ) ) ; -#26129 = ADVANCED_FACE ( 'NONE', ( #13515 ), #1432, .T. ) ; -#26130 = CARTESIAN_POINT ( 'NONE', ( -25.87155708262000076, 191.7567966093000109, 104.0465514997000014 ) ) ; -#26131 = DIRECTION ( 'NONE', ( -0.0005734119072323138125, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#26132 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825921615701389, 0.0005734119023492946932 ) ) ; -#26133 = EDGE_CURVE ( 'NONE', #39877, #23218, #4619, .T. ) ; -#26134 = CARTESIAN_POINT ( 'NONE', ( -44.76727314987169137, 188.9782592361786726, 103.7990538156673637 ) ) ; -#26135 = DIRECTION ( 'NONE', ( 0.7855473026356903921, 0.6188014303620726908, -0.0004744508866335689855 ) ) ; -#26136 = VERTEX_POINT ( 'NONE', #35547 ) ; -#26137 = EDGE_CURVE ( 'NONE', #31137, #4945, #32722, .T. ) ; -#26138 = CARTESIAN_POINT ( 'NONE', ( 29.05503365078199707, 110.6131156702000027, 89.75023623571587450 ) ) ; -#26139 = ADVANCED_FACE ( 'NONE', ( #38440 ), #24552, .T. ) ; -#26140 = CONICAL_SURFACE ( 'NONE', #39157, 59.40509898907522768, 0.7853981633972503262 ) ; -#26141 = CARTESIAN_POINT ( 'NONE', ( -12.63649281425979254, 129.9703308616587947, 92.23232912629561042 ) ) ; -#26142 = VECTOR ( 'NONE', #4349, 1000.000000000000000 ) ; -#26143 = ORIENTED_EDGE ( 'NONE', *, *, #12885, .F. ) ; -#26144 = CARTESIAN_POINT ( 'NONE', ( -24.62180453110569545, 117.2407823713247694, 170.8370874554811394 ) ) ; -#26145 = CARTESIAN_POINT ( 'NONE', ( 46.05118615274398763, 124.8743111081185049, 91.53352630994533001 ) ) ; -#26146 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33097, #33502, #30660, #14510, #2453, #23710, #18913, #6445, #39428, #2043, #2659, #24537, #8381, #26995, #15124, #5293, #8787, #30245, #26788, #14916, #3377, #5085, #39637, #39233, #5491, #11236, #21256, #2244 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 1, 2, 2, 1, 1, 1, 2, 2, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999994391153, 0.1874999999991534549, 0.2187499999989995225, 0.2343749999989190869, 0.2421874999988790911, 0.2460937499988591071, 0.2499999999988390953, 0.3749999999987644328, 0.4374999999987063126, 0.4687499999986773913, 0.4843749999986785570, 0.4999999999986797228, 0.6249999999987549959, 0.6874999999987920773, 0.7187499999988170574, 0.7343749999988294919, 0.7421874999988588018, 0.7499999999988880006, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26147 = AXIS2_PLACEMENT_3D ( 'NONE', #14121, #36590, #8594 ) ; -#26148 = LINE ( 'NONE', #23066, #8479 ) ; -#26149 = CARTESIAN_POINT ( 'NONE', ( 20.00140612192502942, 118.1043503129110093, 90.25575274657424529 ) ) ; -#26150 = AXIS2_PLACEMENT_3D ( 'NONE', #33995, #17642, #24007 ) ; -#26151 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319392994206 ) ) ; -#26152 = CYLINDRICAL_SURFACE ( 'NONE', #7595, 2.000000000000011546 ) ; -#26153 = ORIENTED_EDGE ( 'NONE', *, *, #24333, .T. ) ; -#26154 = EDGE_CURVE ( 'NONE', #34987, #19810, #28891, .T. ) ; -#26155 = FACE_OUTER_BOUND ( 'NONE', #29779, .T. ) ; -#26156 = CARTESIAN_POINT ( 'NONE', ( -16.53681909317384324, 122.5194902194745055, 174.6067105814985609 ) ) ; -#26157 = PLANE ( 'NONE', #422 ) ; -#26158 = VERTEX_POINT ( 'NONE', #23729 ) ; -#26159 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971554578 ) ) ; -#26160 = CARTESIAN_POINT ( 'NONE', ( 3.777496618107850868, 136.7362355281202326, 94.04957486231310781 ) ) ; -#26161 = ORIENTED_EDGE ( 'NONE', *, *, #25068, .F. ) ; -#26162 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319388554398 ) ) ; -#26163 = CARTESIAN_POINT ( 'NONE', ( -37.97633501673850986, 143.6343013820186627, 291.5814806899745122 ) ) ; -#26164 = VERTEX_POINT ( 'NONE', #14531 ) ; -#26165 = CARTESIAN_POINT ( 'NONE', ( 24.86432580519088376, 181.7359623805197089, 104.1607194630871049 ) ) ; -#26166 = CARTESIAN_POINT ( 'NONE', ( -15.99825050089035550, 126.1262029676268668, 91.86002998339648684 ) ) ; -#26167 = CARTESIAN_POINT ( 'NONE', ( -30.06929056564133518, 176.9377538507572467, 103.3599937213831481 ) ) ; -#26168 = FACE_OUTER_BOUND ( 'NONE', #18273, .T. ) ; -#26169 = ORIENTED_EDGE ( 'NONE', *, *, #11278, .T. ) ; -#26170 = FACE_OUTER_BOUND ( 'NONE', #19610, .T. ) ; -#26171 = CIRCLE ( 'NONE', #13747, 59.40509898897001051 ) ; -#26172 = CARTESIAN_POINT ( 'NONE', ( -4.584463781762333490, 177.3496358541460722, 100.6000816012465719 ) ) ; -#26173 = LINE ( 'NONE', #4259, #5124 ) ; -#26174 = AXIS2_PLACEMENT_3D ( 'NONE', #27315, #39743, #18066 ) ; -#26176 = EDGE_LOOP ( 'NONE', ( #15216, #29975, #25797, #24705 ) ) ; -#26175 = ADVANCED_FACE ( 'NONE', ( #5509 ), #38248, .F. ) ; -#26177 = CIRCLE ( 'NONE', #2687, 4.999999999999990230 ) ; -#26178 = FACE_OUTER_BOUND ( 'NONE', #3045, .T. ) ; -#26179 = ADVANCED_FACE ( 'NONE', ( #36398 ), #27226, .F. ) ; -#26180 = VERTEX_POINT ( 'NONE', #11873 ) ; -#26181 = FACE_OUTER_BOUND ( 'NONE', #10478, .T. ) ; -#26182 = CARTESIAN_POINT ( 'NONE', ( 33.55689699144527083, 164.0672018394440386, 187.8347355915257424 ) ) ; -#26183 = DIRECTION ( 'NONE', ( 0.0005884949961238529524, -0.2249510543439058596, 0.9743698870671263501 ) ) ; -#26184 = ADVANCED_FACE ( 'NONE', ( #33722, #5727, #6319 ), #40458, .F. ) ; -#26185 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#26186 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#26187 = CARTESIAN_POINT ( 'NONE', ( 28.46780168972100000, 130.8254044408606660, 90.01024004489680408 ) ) ; -#26188 = EDGE_CURVE ( 'NONE', #31921, #1239, #8229, .T. ) ; -#26189 = DIRECTION ( 'NONE', ( 0.6086215548477215131, 0.7730393818215737234, 0.1788572534946829551 ) ) ; -#26190 = CARTESIAN_POINT ( 'NONE', ( 38.68092143719999854, 118.3938811684000143, 89.51262490514000092 ) ) ; -#26191 = VERTEX_POINT ( 'NONE', #12457 ) ; -#26192 = DIRECTION ( 'NONE', ( 0.0005884949961244022093, -0.2249510543439064980, 0.9743698870671262391 ) ) ; -#26193 = CARTESIAN_POINT ( 'NONE', ( 39.31413750895951154, 144.6232979504316063, 291.5347991813059707 ) ) ; -#26194 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -3.519737327345223780E-16, 0.0006039748319385488274 ) ) ; -#26195 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825945353352502, 0.0005734119018001440160 ) ) ; -#26196 = VERTEX_POINT ( 'NONE', #9207 ) ; -#26197 = EDGE_LOOP ( 'NONE', ( #5983, #22876, #38126, #17004 ) ) ; -#26198 = VECTOR ( 'NONE', #8929, 1000.000000000000227 ) ; -#26199 = ADVANCED_FACE ( 'NONE', ( #6119 ), #34976, .T. ) ; -#26200 = EDGE_LOOP ( 'NONE', ( #2825, #35011, #10361, #21567 ) ) ; -#26201 = CARTESIAN_POINT ( 'NONE', ( 30.17789666961413175, 126.0876384020114784, 91.82323258389868670 ) ) ; -#26202 = AXIS2_PLACEMENT_3D ( 'NONE', #18979, #37409, #3437 ) ; -#26203 = CARTESIAN_POINT ( 'NONE', ( -9.583319590155999990, 187.4804039283999941, 105.7643101227000102 ) ) ; -#26204 = CONICAL_SURFACE ( 'NONE', #33361, 2.503090990479985400, 0.7853981633820344976 ) ; -#26205 = CARTESIAN_POINT ( 'NONE', ( -38.70467835487419705, 118.9896782172050536, 90.01319670810939044 ) ) ; -#26206 = ORIENTED_EDGE ( 'NONE', *, *, #6537, .T. ) ; -#26207 = CARTESIAN_POINT ( 'NONE', ( -2.452854177136032376, 209.7096538831000032, 78.05998645682016956 ) ) ; -#26208 = DIRECTION ( 'NONE', ( 0.0005884949961245723206, -0.2249510543439059984, 0.9743698870671263501 ) ) ; -#26209 = CARTESIAN_POINT ( 'NONE', ( -38.80491609783999962, 119.2274846327999995, 87.75209770429999878 ) ) ; -#26210 = CARTESIAN_POINT ( 'NONE', ( 13.50176813047575131, 173.8418126276867213, 102.8614805459236976 ) ) ; -#26211 = VERTEX_POINT ( 'NONE', #6508 ) ; -#26212 = CARTESIAN_POINT ( 'NONE', ( 13.85658554608545678, 124.7833813612844693, 174.0357207340887271 ) ) ; -#26213 = ORIENTED_EDGE ( 'NONE', *, *, #33725, .F. ) ; -#26214 = LINE ( 'NONE', #10671, #37684 ) ; -#26215 = CARTESIAN_POINT ( 'NONE', ( -20.51188059855327950, 203.6447578621130390, 85.96051626286971725 ) ) ; -#26216 = CARTESIAN_POINT ( 'NONE', ( 16.59040448417249891, 121.5622698803751121, 177.2309519810485767 ) ) ; -#26217 = CARTESIAN_POINT ( 'NONE', ( -22.98769208757434157, 131.0176466878757253, 89.91461220895010342 ) ) ; -#26218 = VERTEX_POINT ( 'NONE', #12875 ) ; -#26219 = VERTEX_POINT ( 'NONE', #25349 ) ; -#26220 = CARTESIAN_POINT ( 'NONE', ( -0.6433655274230000165, 188.6108429602000172, 103.1975560712999993 ) ) ; -#26221 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989940797, 0.1373964268091562024 ) ) ; -#26222 = CARTESIAN_POINT ( 'NONE', ( 3.199885833601999963, 190.8329213794999930, 106.9264235504000169 ) ) ; -#26223 = EDGE_CURVE ( 'NONE', #6019, #5116, #9808, .T. ) ; -#26224 = EDGE_LOOP ( 'NONE', ( #6008, #39296, #39851, #28217 ) ) ; -#26225 = CONICAL_SURFACE ( 'NONE', #34676, 51.90509899264980476, 0.7853981633972885179 ) ; -#26226 = DIRECTION ( 'NONE', ( -1.387778772392002640E-15, 0.9743700557921582961, 0.2249510932971574839 ) ) ; -#26227 = CARTESIAN_POINT ( 'NONE', ( -25.50006284340070906, 118.1130153187805689, 89.78316558933853742 ) ) ; -#26228 = EDGE_CURVE ( 'NONE', #4779, #4523, #20105, .T. ) ; -#26229 = VERTEX_POINT ( 'NONE', #29214 ) ; -#26230 = CIRCLE ( 'NONE', #38596, 2.499999999999997335 ) ; -#26231 = AXIS2_PLACEMENT_3D ( 'NONE', #24180, #5344, #18002 ) ; -#26232 = EDGE_LOOP ( 'NONE', ( #26523, #13432, #12718, #6571 ) ) ; -#26233 = CARTESIAN_POINT ( 'NONE', ( 30.05084665326030446, 185.2025551396338585, 102.9053044902910869 ) ) ; -#26234 = ORIENTED_EDGE ( 'NONE', *, *, #11911, .F. ) ; -#26235 = CARTESIAN_POINT ( 'NONE', ( -26.00800983458967508, 191.5260122442129216, 103.8858970416150385 ) ) ; -#26236 = CARTESIAN_POINT ( 'NONE', ( 19.99933118494021755, 196.5785306413737601, 103.8628508136982731 ) ) ; -#26237 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#26238 = VERTEX_POINT ( 'NONE', #13862 ) ; -#26239 = ORIENTED_EDGE ( 'NONE', *, *, #37899, .T. ) ; -#26240 = CARTESIAN_POINT ( 'NONE', ( 26.00569871841100067, 120.1361694506069853, 90.45417752614380902 ) ) ; -#26241 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490428653439, 156.2427122712157086, 96.23754757944941218 ) ) ; -#26243 = CARTESIAN_POINT ( 'NONE', ( -13.49833818120469964, 188.0172640734645597, 103.3462508437664553 ) ) ; -#26242 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490399013737, 151.3708619921459615, 95.11279211292851699 ) ) ; -#26244 = EDGE_CURVE ( 'NONE', #32437, #24067, #25958, .T. ) ; -#26245 = CARTESIAN_POINT ( 'NONE', ( -38.81660742513911089, 106.4213634552623517, 168.3324163836322782 ) ) ; -#26246 = VERTEX_POINT ( 'NONE', #38591 ) ; -#26247 = CARTESIAN_POINT ( 'NONE', ( -2.070178905375853251, 189.2110454056422668, 103.3369857030061638 ) ) ; -#26248 = CARTESIAN_POINT ( 'NONE', ( 21.83140103668416998, 176.0486778938952739, 102.8495379525328985 ) ) ; -#26249 = CARTESIAN_POINT ( 'NONE', ( -8.332516390861295363, 151.1890326084896401, 94.90479451117724352 ) ) ; -#26250 = ORIENTED_EDGE ( 'NONE', *, *, #24781, .F. ) ; -#26251 = CYLINDRICAL_SURFACE ( 'NONE', #40039, 2.000000000000011546 ) ; -#26253 = CIRCLE ( 'NONE', #26892, 6.499999999981660004 ) ; -#26252 = CARTESIAN_POINT ( 'NONE', ( 2.562971096207687260, 190.9999997773000189, 104.2603522706010750 ) ) ; -#26254 = CIRCLE ( 'NONE', #28220, 5.249999999999986677 ) ; -#26255 = CARTESIAN_POINT ( 'NONE', ( 5.671051541955929309, 187.5796154020130757, 105.9111029366380308 ) ) ; -#26256 = LINE ( 'NONE', #32964, #39161 ) ; -#26257 = ORIENTED_EDGE ( 'NONE', *, *, #31288, .T. ) ; -#26258 = ORIENTED_EDGE ( 'NONE', *, *, #11233, .F. ) ; -#26259 = EDGE_CURVE ( 'NONE', #15606, #8964, #7314, .T. ) ; -#26260 = VERTEX_POINT ( 'NONE', #26554 ) ; -#26261 = CARTESIAN_POINT ( 'NONE', ( -23.36699950098072165, 134.2659706838206262, 93.72240624211983118 ) ) ; -#26262 = VERTEX_POINT ( 'NONE', #13666 ) ; -#26263 = CARTESIAN_POINT ( 'NONE', ( -35.60304309402999934, 192.7598035524999887, 106.7122942566000035 ) ) ; -#26264 = EDGE_CURVE ( 'NONE', #10007, #25177, #19977, .T. ) ; -#26265 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#26266 = CARTESIAN_POINT ( 'NONE', ( 2.564266820190244545, 191.0024198337800669, 106.3123278577045738 ) ) ; -#26267 = EDGE_CURVE ( 'NONE', #15841, #36524, #392, .T. ) ; -#26268 = VERTEX_POINT ( 'NONE', #11766 ) ; -#26269 = CARTESIAN_POINT ( 'NONE', ( -20.00006126831510400, 120.3902141372887087, 87.45929000627990035 ) ) ; -#26270 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825907063166864, 0.0005734119026844853358 ) ) ; -#26271 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#26272 = CARTESIAN_POINT ( 'NONE', ( 44.41682338754539217, 189.0408562691112877, 103.4406660154240285 ) ) ; -#26273 = ORIENTED_EDGE ( 'NONE', *, *, #32170, .F. ) ; -#26274 = CARTESIAN_POINT ( 'NONE', ( 23.36366720388904383, 183.4529741750082508, 105.0711814503917765 ) ) ; -#26275 = CONICAL_SURFACE ( 'NONE', #11235, 5.500000000083335117, 0.7853981634365208020 ) ; -#26276 = CARTESIAN_POINT ( 'NONE', ( 20.38505473614282693, 212.5804310127830377, 73.04619202014056611 ) ) ; -#26277 = CARTESIAN_POINT ( 'NONE', ( 21.45549066267129135, 213.0890993161042957, 75.54548350635269571 ) ) ; -#26278 = CONICAL_SURFACE ( 'NONE', #8657, 51.90509899272856842, 0.7853981633972877408 ) ; -#26279 = AXIS2_PLACEMENT_3D ( 'NONE', #19478, #25848, #10095 ) ; -#26280 = DIRECTION ( 'NONE', ( -0.0003759831730439093154, 0.7826081568524194676, -0.6225145230954155506 ) ) ; -#26281 = ORIENTED_EDGE ( 'NONE', *, *, #22487, .F. ) ; -#26282 = CARTESIAN_POINT ( 'NONE', ( -1.762796036252210596, 151.6652447677504369, 130.5904578368505327 ) ) ; -#26283 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #32872, #16919 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26284 = CARTESIAN_POINT ( 'NONE', ( -35.69719521574999987, 115.1371617642000160, 90.43415643094000700 ) ) ; -#26285 = ORIENTED_EDGE ( 'NONE', *, *, #30308, .F. ) ; -#26286 = ORIENTED_EDGE ( 'NONE', *, *, #246, .F. ) ; -#26287 = LINE ( 'NONE', #17246, #17924 ) ; -#26288 = DIRECTION ( 'NONE', ( 0.7855473026356902810, 0.6188014303620729128, -0.0004744508866335532104 ) ) ; -#26289 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#26290 = ORIENTED_EDGE ( 'NONE', *, *, #7127, .T. ) ; -#26291 = VERTEX_POINT ( 'NONE', #34027 ) ; -#26292 = CARTESIAN_POINT ( 'NONE', ( -42.56963625464027245, 120.8513313564750575, 90.65827283841386475 ) ) ; -#26293 = ORIENTED_EDGE ( 'NONE', *, *, #3750, .T. ) ; -#26294 = ORIENTED_EDGE ( 'NONE', *, *, #36984, .F. ) ; -#26295 = CARTESIAN_POINT ( 'NONE', ( 77.74752315181704887, 192.2565373609087089, 194.3622733290381461 ) ) ; -#26296 = CARTESIAN_POINT ( 'NONE', ( -44.76913686494872735, 108.4408363393548882, 169.8241779223887136 ) ) ; -#26297 = CARTESIAN_POINT ( 'NONE', ( -29.94780647241524107, 109.6131156702000027, 87.78587210735845758 ) ) ; -#26298 = VECTOR ( 'NONE', #15226, 1000.000000000000114 ) ; -#26299 = ADVANCED_FACE ( 'NONE', ( #18471 ), #2943, .F. ) ; -#26300 = ORIENTED_EDGE ( 'NONE', *, *, #16259, .F. ) ; -#26301 = LINE ( 'NONE', #23030, #26522 ) ; -#26302 = LINE ( 'NONE', #13622, #1276 ) ; -#26304 = AXIS2_PLACEMENT_3D ( 'NONE', #35514, #1605, #14090 ) ; -#26303 = CARTESIAN_POINT ( 'NONE', ( 36.49546895817999825, 191.9015982269000062, 104.5102558848000029 ) ) ; -#26305 = CARTESIAN_POINT ( 'NONE', ( 3.012748634343953125, 209.4749847006376342, 76.06918713120469988 ) ) ; -#26306 = EDGE_CURVE ( 'NONE', #25514, #6360, #15704, .T. ) ; -#26307 = ORIENTED_EDGE ( 'NONE', *, *, #1147, .T. ) ; -#26308 = AXIS2_PLACEMENT_3D ( 'NONE', #1927, #31554, #28685 ) ; -#26309 = CARTESIAN_POINT ( 'NONE', ( 22.78008436521043123, 158.4318469938418730, 96.38708833722530755 ) ) ; -#26310 = CARTESIAN_POINT ( 'NONE', ( -23.35804788357050654, 177.0119981395035893, 103.4735393260193064 ) ) ; -#26311 = ORIENTED_EDGE ( 'NONE', *, *, #2644, .F. ) ; -#26312 = CARTESIAN_POINT ( 'NONE', ( 0.5932910502135863018, 188.6078699368097205, 103.1961229790743175 ) ) ; -#26313 = CARTESIAN_POINT ( 'NONE', ( 16.16445611541705674, 122.9245094293323888, 174.2137880000448718 ) ) ; -#26314 = ADVANCED_FACE ( 'NONE', ( #25053 ), #30578, .F. ) ; -#26315 = CARTESIAN_POINT ( 'NONE', ( -20.16670854996598550, 160.6934792717234473, 96.93531027717119741 ) ) ; -#26316 = EDGE_CURVE ( 'NONE', #18111, #6578, #33825, .T. ) ; -#26317 = DIRECTION ( 'NONE', ( -0.1305263947813612435, -0.9659212020967549162, -0.2235153050807486830 ) ) ; -#26318 = EDGE_CURVE ( 'NONE', #8044, #17792, #19283, .T. ) ; -#26319 = ORIENTED_EDGE ( 'NONE', *, *, #30375, .F. ) ; -#26320 = CARTESIAN_POINT ( 'NONE', ( -22.69003647934751555, 158.3009287201703046, 96.21327555204996429 ) ) ; -#26321 = ADVANCED_FACE ( 'NONE', ( #29111 ), #22980, .F. ) ; -#26322 = CARTESIAN_POINT ( 'NONE', ( -13.50000254341547468, 185.9068427740967593, 102.5779769526163960 ) ) ; -#26323 = DIRECTION ( 'NONE', ( -0.0005884949961257158286, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#26324 = LINE ( 'NONE', #17492, #24954 ) ; -#26325 = ORIENTED_EDGE ( 'NONE', *, *, #9560, .T. ) ; -#26326 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#26327 = CARTESIAN_POINT ( 'NONE', ( 22.89468650464132793, 120.6933875991700944, 183.2782711976167889 ) ) ; -#26328 = CARTESIAN_POINT ( 'NONE', ( 25.63631768314000325, 192.1800716756999918, 104.2809280454000174 ) ) ; -#26329 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #15338, #12462 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26330 = CARTESIAN_POINT ( 'NONE', ( -20.49933784730817266, 194.4843916009270401, 105.7062759226449771 ) ) ; -#26331 = CIRCLE ( 'NONE', #39379, 6.499999999986447285 ) ; -#26332 = CARTESIAN_POINT ( 'NONE', ( -15.66646951627509488, 138.1199964649966603, 91.89200017561881850 ) ) ; -#26333 = ORIENTED_EDGE ( 'NONE', *, *, #10517, .F. ) ; -#26334 = PLANE ( 'NONE', #20326 ) ; -#26335 = CIRCLE ( 'NONE', #8717, 47.50000000000962075 ) ; -#26336 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16022, #28513, #12975, #25457 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26337 = CARTESIAN_POINT ( 'NONE', ( -30.11526611033000123, 185.0088482550999913, 105.2061072122999974 ) ) ; -#26338 = AXIS2_PLACEMENT_3D ( 'NONE', #24092, #12414, #33471 ) ; -#26339 = CARTESIAN_POINT ( 'NONE', ( -45.34134577087812801, 120.7154725862561406, 105.4905015689576402 ) ) ; -#26340 = CARTESIAN_POINT ( 'NONE', ( -20.49852830327300879, 119.8277974066376999, 89.89548907266683386 ) ) ; -#26341 = CARTESIAN_POINT ( 'NONE', ( 28.46511207851075653, 181.6173849797036439, 104.1311689223658448 ) ) ; -#26342 = DIRECTION ( 'NONE', ( -0.0002393071182782278061, -0.2252352986010052738, 0.9743043687658489160 ) ) ; -#26343 = LINE ( 'NONE', #16709, #30551 ) ; -#26344 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.261220487827980362E-14, 0.9999998176071844824 ) ) ; -#26345 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4706, #5107, #10662, #39254 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26346 = CARTESIAN_POINT ( 'NONE', ( 35.93887322615999835, 192.6195093084999996, 106.4794051886999995 ) ) ; -#26347 = ORIENTED_EDGE ( 'NONE', *, *, #21799, .T. ) ; -#26348 = CARTESIAN_POINT ( 'NONE', ( -2.849818446583026521, 209.7134542144498539, 76.06022768558052860 ) ) ; -#26349 = FACE_OUTER_BOUND ( 'NONE', #36848, .T. ) ; -#26350 = ADVANCED_FACE ( 'NONE', ( #16612 ), #482, .T. ) ; -#26351 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; -#26352 = VERTEX_POINT ( 'NONE', #34805 ) ; -#26353 = CARTESIAN_POINT ( 'NONE', ( 19.98273361849968310, 207.8686263722649983, 77.26501546795368824 ) ) ; -#26354 = VERTEX_POINT ( 'NONE', #13571 ) ; -#26355 = EDGE_CURVE ( 'NONE', #18851, #30696, #13368, .T. ) ; -#26356 = CARTESIAN_POINT ( 'NONE', ( 20.00000522920557700, 138.5176112521621690, 91.62015419223651236 ) ) ; -#26357 = CARTESIAN_POINT ( 'NONE', ( 24.83917560697537397, 115.7109693989694819, 87.25278205238181783 ) ) ; -#26358 = ORIENTED_EDGE ( 'NONE', *, *, #6264, .T. ) ; -#26359 = CARTESIAN_POINT ( 'NONE', ( 36.48374016940825015, 191.5972485995277452, 106.3709165627377473 ) ) ; -#26360 = VECTOR ( 'NONE', #8794, 999.9999999999998863 ) ; -#26361 = EDGE_CURVE ( 'NONE', #31227, #12564, #23028, .T. ) ; -#26362 = DIRECTION ( 'NONE', ( -0.0005884949961230354640, 0.2249510543439063315, -0.9743698870671264611 ) ) ; -#26363 = CARTESIAN_POINT ( 'NONE', ( 36.06296285845981942, 194.2771771405940058, 102.8764942496974442 ) ) ; -#26364 = DIRECTION ( 'NONE', ( -3.854941057724316235E-15, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#26365 = CARTESIAN_POINT ( 'NONE', ( 22.64345175836523794, 177.7183216167047988, 100.6687544531553300 ) ) ; -#26366 = CARTESIAN_POINT ( 'NONE', ( -13.55691060191283093, 147.9587722923776312, 94.33323613806213359 ) ) ; -#26367 = EDGE_CURVE ( 'NONE', #13796, #21433, #10223, .T. ) ; -#26368 = ORIENTED_EDGE ( 'NONE', *, *, #6334, .F. ) ; -#26369 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; -#26370 = CARTESIAN_POINT ( 'NONE', ( 30.06906075427019331, 177.1956492900629598, 101.0567532827656123 ) ) ; -#26371 = CARTESIAN_POINT ( 'NONE', ( 45.12876369734329529, 130.2598771944438170, 92.77743955731769177 ) ) ; -#26372 = CARTESIAN_POINT ( 'NONE', ( 16.34205233782973110, 152.1117390883541418, 181.2100924961355020 ) ) ; -#26373 = EDGE_LOOP ( 'NONE', ( #18484, #28012, #11641, #31722 ) ) ; -#26374 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 3.780719906273090593E-12, 291.5295797804326980 ) ) ; -#26375 = CARTESIAN_POINT ( 'NONE', ( -39.59757934998344098, 114.7797396141357638, 151.0610028020948334 ) ) ; -#26376 = CARTESIAN_POINT ( 'NONE', ( 3.230168859074256993, 129.2213076314029365, 89.48405965364526082 ) ) ; -#26377 = CARTESIAN_POINT ( 'NONE', ( 22.79650250807785028, 156.9263452827057392, 182.1842925253231726 ) ) ; -#26378 = FACE_OUTER_BOUND ( 'NONE', #36566, .T. ) ; -#26379 = CARTESIAN_POINT ( 'NONE', ( 25.42423066774999896, 190.7516350470000077, 106.0994300395999943 ) ) ; -#26380 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; -#26381 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#26382 = CARTESIAN_POINT ( 'NONE', ( -37.91710613048000056, 190.5102213490000054, 106.6127102881000042 ) ) ; -#26383 = CIRCLE ( 'NONE', #4143, 2.500000015113077012 ) ; -#26384 = AXIS2_PLACEMENT_3D ( 'NONE', #22369, #7003, #26386 ) ; -#26385 = ORIENTED_EDGE ( 'NONE', *, *, #34145, .T. ) ; -#26386 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#26387 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; -#26388 = CARTESIAN_POINT ( 'NONE', ( 22.99030223357639002, 211.0902260770999987, 73.03848514436592154 ) ) ; -#26389 = DIRECTION ( 'NONE', ( -0.7933533411653074241, -0.5931840316265225566, -0.1368326740407711517 ) ) ; -#26390 = FACE_OUTER_BOUND ( 'NONE', #38396, .T. ) ; -#26391 = ORIENTED_EDGE ( 'NONE', *, *, #7492, .T. ) ; -#26392 = ORIENTED_EDGE ( 'NONE', *, *, #854, .T. ) ; -#26393 = ORIENTED_EDGE ( 'NONE', *, *, #21442, .F. ) ; -#26394 = CARTESIAN_POINT ( 'NONE', ( -13.50149634685153188, 124.6162873816535352, 88.77554189603409895 ) ) ; -#26395 = ADVANCED_FACE ( 'NONE', ( #10917 ), #35812, .F. ) ; -#26396 = EDGE_CURVE ( 'NONE', #6620, #17466, #17213, .T. ) ; -#26397 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250611660, 132.8554482850408931, 90.84904174544594468 ) ) ; -#26398 = ADVANCED_FACE ( 'NONE', ( #29717 ), #1701, .F. ) ; -#26400 = EDGE_CURVE ( 'NONE', #1388, #5869, #36292, .T. ) ; -#26399 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #511, #24693, #25092, #9537, #3378, #22017 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26401 = ORIENTED_EDGE ( 'NONE', *, *, #12280, .T. ) ; -#26402 = CARTESIAN_POINT ( 'NONE', ( 14.17036433007075757, 182.7613733346053380, 102.3513045738081502 ) ) ; -#26403 = DIRECTION ( 'NONE', ( -0.0005884949961239352434, 0.2249510543439079413, -0.9743698870671259060 ) ) ; -#26404 = CARTESIAN_POINT ( 'NONE', ( -38.16683231563000334, 119.1115699835000044, 87.44296902379001324 ) ) ; -#26405 = CARTESIAN_POINT ( 'NONE', ( -36.58517893228000162, 117.6712416552000207, 87.16057593239999335 ) ) ; -#26406 = ORIENTED_EDGE ( 'NONE', *, *, #18771, .F. ) ; -#26407 = EDGE_CURVE ( 'NONE', #37286, #38119, #6169, .T. ) ; -#26408 = CARTESIAN_POINT ( 'NONE', ( 24.53469179845202675, 109.6131156702000027, 89.75296640898022815 ) ) ; -#26409 = ORIENTED_EDGE ( 'NONE', *, *, #37564, .T. ) ; -#26410 = CARTESIAN_POINT ( 'NONE', ( 16.29171451679812677, 147.1883472421681347, 179.8230240704290566 ) ) ; -#26411 = DIRECTION ( 'NONE', ( 0.0005734119072322988505, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#26412 = CARTESIAN_POINT ( 'NONE', ( 5.670716164162284301, 130.2572556929138443, 92.67712889164683077 ) ) ; -#26413 = LINE ( 'NONE', #35563, #10436 ) ; -#26414 = CARTESIAN_POINT ( 'NONE', ( -12.63763155967610174, 181.4131765941279184, 104.2789412034183130 ) ) ; -#26415 = AXIS2_PLACEMENT_3D ( 'NONE', #11705, #28248, #24185 ) ; -#26416 = EDGE_CURVE ( 'NONE', #13145, #20943, #561, .T. ) ; -#26417 = ORIENTED_EDGE ( 'NONE', *, *, #34101, .F. ) ; -#26418 = CARTESIAN_POINT ( 'NONE', ( -2.206982623110000041, 189.3059093070999950, 103.3589691778000059 ) ) ; -#26419 = CARTESIAN_POINT ( 'NONE', ( 13.50176625667807428, 160.0671410552039333, 99.67807866355113333 ) ) ; -#26420 = AXIS2_PLACEMENT_3D ( 'NONE', #26987, #11642, #17945 ) ; -#26421 = CARTESIAN_POINT ( 'NONE', ( 28.46551015877975033, 129.9757720508976888, 92.20876074269682476 ) ) ; -#26422 = CARTESIAN_POINT ( 'NONE', ( 2.428544953242000037, 191.0028154567999934, 106.1725792724000144 ) ) ; -#26423 = AXIS2_PLACEMENT_3D ( 'NONE', #31676, #19968, #566 ) ; -#26424 = ORIENTED_EDGE ( 'NONE', *, *, #256, .F. ) ; -#26425 = CARTESIAN_POINT ( 'NONE', ( 22.78080448403245839, 154.4094593426142978, 95.28739704982865533 ) ) ; -#26426 = CARTESIAN_POINT ( 'NONE', ( 38.56885418974432866, 118.4610218664272452, 89.66265752007532797 ) ) ; -#26427 = ORIENTED_EDGE ( 'NONE', *, *, #38572, .F. ) ; -#26428 = ORIENTED_EDGE ( 'NONE', *, *, #32131, .F. ) ; -#26429 = ORIENTED_EDGE ( 'NONE', *, *, #12007, .T. ) ; -#26430 = ORIENTED_EDGE ( 'NONE', *, *, #24145, .T. ) ; -#26431 = CARTESIAN_POINT ( 'NONE', ( -28.25392304131139909, 186.4523300311939806, 105.2782402284340009 ) ) ; -#26432 = CARTESIAN_POINT ( 'NONE', ( 37.96459664868978479, 191.1136021723184797, 105.6336056618651327 ) ) ; -#26433 = ORIENTED_EDGE ( 'NONE', *, *, #27154, .F. ) ; -#26434 = CARTESIAN_POINT ( 'NONE', ( -15.56603823848756463, 127.7826210529339761, 174.7414047399441586 ) ) ; -#26435 = ORIENTED_EDGE ( 'NONE', *, *, #20944, .T. ) ; -#26436 = CARTESIAN_POINT ( 'NONE', ( 26.00477353184719931, 120.1786686628320098, 90.46666206596498228 ) ) ; -#26437 = CARTESIAN_POINT ( 'NONE', ( 25.50773672857076235, 191.9759150222000130, 101.9060413065578530 ) ) ; -#26439 = CARTESIAN_POINT ( 'NONE', ( -13.49827548779789765, 187.9541051343499873, 103.3857169024480243 ) ) ; -#26438 = CARTESIAN_POINT ( 'NONE', ( -26.71540924721000110, 176.9255844822999961, 103.3378849579000018 ) ) ; -#26440 = SECURITY_CLASSIFICATION ( '', '', #2841 ) ; -#26441 = AXIS2_PLACEMENT_3D ( 'NONE', #28935, #28540, #35429 ) ; -#26442 = VERTEX_POINT ( 'NONE', #18025 ) ; -#26443 = AXIS2_PLACEMENT_3D ( 'NONE', #13490, #10022, #35329 ) ; -#26444 = ORIENTED_EDGE ( 'NONE', *, *, #36499, .F. ) ; -#26445 = CARTESIAN_POINT ( 'NONE', ( -36.12226215597334544, 191.9555097253573877, 104.4198144025714470 ) ) ; -#26446 = EDGE_CURVE ( 'NONE', #12675, #21782, #36114, .T. ) ; -#26447 = AXIS2_PLACEMENT_3D ( 'NONE', #14620, #19913, #23211 ) ; -#26448 = EDGE_CURVE ( 'NONE', #25158, #5478, #12241, .T. ) ; -#26449 = ORIENTED_EDGE ( 'NONE', *, *, #10086, .F. ) ; -#26450 = CARTESIAN_POINT ( 'NONE', ( -36.02057461644638181, 116.0743563047277860, 87.28953981649921445 ) ) ; -#26451 = CARTESIAN_POINT ( 'NONE', ( -45.66754398715169572, 124.0145021363698987, 91.55527929137910803 ) ) ; -#26452 = LINE ( 'NONE', #38901, #11100 ) ; -#26453 = VERTEX_POINT ( 'NONE', #12945 ) ; -#26454 = ORIENTED_EDGE ( 'NONE', *, *, #2929, .F. ) ; -#26455 = ORIENTED_EDGE ( 'NONE', *, *, #23807, .F. ) ; -#26456 = DIRECTION ( 'NONE', ( -0.0005884949961207905150, 0.2249510543439056653, -0.9743698870671265722 ) ) ; -#26457 = FACE_OUTER_BOUND ( 'NONE', #13454, .T. ) ; -#26458 = ORIENTED_EDGE ( 'NONE', *, *, #13005, .T. ) ; -#26459 = CARTESIAN_POINT ( 'NONE', ( -35.43417201705999986, 192.6082312290999994, 106.9072920318999991 ) ) ; -#26460 = VERTEX_POINT ( 'NONE', #34580 ) ; -#26461 = DIRECTION ( 'NONE', ( -0.0006039748319417796414, 6.167438909946999677E-15, -0.9999998176071844824 ) ) ; -#26462 = CARTESIAN_POINT ( 'NONE', ( 2.730823538927626970, 190.9423656580330544, 106.4698396510861329 ) ) ; -#26463 = EDGE_LOOP ( 'NONE', ( #36701, #27106, #23607, #32316 ) ) ; -#26464 = CARTESIAN_POINT ( 'NONE', ( -30.07299557348812868, 135.2291654960487222, 91.32134674634657756 ) ) ; -#26465 = CIRCLE ( 'NONE', #8851, 2.000000000000000000 ) ; -#26466 = ADVANCED_FACE ( 'NONE', ( #16391 ), #9672, .F. ) ; -#26467 = CARTESIAN_POINT ( 'NONE', ( 15.99998384348811875, 126.8035267017516787, 88.91816380576780432 ) ) ; -#26468 = CIRCLE ( 'NONE', #36258, 5.499999999738594880 ) ; -#26469 = DIRECTION ( 'NONE', ( -4.163336342338438714E-15, 0.9743700557921581851, 0.2249510932971575949 ) ) ; -#26470 = CARTESIAN_POINT ( 'NONE', ( 21.21575639516963463, 182.9122697023876754, 104.4344951008579443 ) ) ; -#26471 = ORIENTED_EDGE ( 'NONE', *, *, #1410, .F. ) ; -#26472 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7450, #17660, #2149, #20740 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26473 = CIRCLE ( 'NONE', #6872, 2.500000000128479449 ) ; -#26474 = CARTESIAN_POINT ( 'NONE', ( -39.56097452997838104, 120.1276920425286363, 87.66704820878976534 ) ) ; -#26475 = LINE ( 'NONE', #1509, #18587 ) ; -#26476 = CARTESIAN_POINT ( 'NONE', ( 22.33741204818806381, 213.5250432875125455, 75.54510607509934061 ) ) ; -#26477 = VERTEX_POINT ( 'NONE', #16582 ) ; -#26478 = CARTESIAN_POINT ( 'NONE', ( -25.02259563561056410, 181.9805275934310487, 102.1947033449129236 ) ) ; -#26480 = CARTESIAN_POINT ( 'NONE', ( -38.33390653700000428, 118.5050223875999933, 89.85075258204000193 ) ) ; -#26479 = FACE_OUTER_BOUND ( 'NONE', #31073, .T. ) ; -#26481 = EDGE_LOOP ( 'NONE', ( #7050, #8602, #17048, #37491 ) ) ; -#26482 = ORIENTED_EDGE ( 'NONE', *, *, #20814, .F. ) ; -#26483 = DIRECTION ( 'NONE', ( 0.0005884949961231158034, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#26484 = LINE ( 'NONE', #29354, #3928 ) ; -#26485 = DIRECTION ( 'NONE', ( 0.0005884949961230071663, -0.2249510543439071641, 0.9743698870671261281 ) ) ; -#26486 = VERTEX_POINT ( 'NONE', #4108 ) ; -#26487 = EDGE_CURVE ( 'NONE', #12603, #11146, #21525, .T. ) ; -#26488 = VECTOR ( 'NONE', #24994, 999.9999999999998863 ) ; -#26489 = ORIENTED_EDGE ( 'NONE', *, *, #35308, .T. ) ; -#26490 = CARTESIAN_POINT ( 'NONE', ( -37.31472541183903502, 185.8277164819467373, 106.5063005560201077 ) ) ; -#26491 = VERTEX_POINT ( 'NONE', #3317 ) ; -#26492 = CONICAL_SURFACE ( 'NONE', #36946, 9.999999999987895904, 0.7853981633973070586 ) ; -#26493 = VERTEX_POINT ( 'NONE', #10286 ) ; -#26494 = CARTESIAN_POINT ( 'NONE', ( 20.00000279695219874, 118.8155797008581374, 87.25566994753728522 ) ) ; -#26495 = CARTESIAN_POINT ( 'NONE', ( -2.438441564891038915, 191.9759150222000130, 101.9229200978912075 ) ) ; -#26496 = CIRCLE ( 'NONE', #8880, 2.000000000091077368 ) ; -#26497 = CARTESIAN_POINT ( 'NONE', ( 19.33143288873693777, 125.0839867570798276, 178.0727432645037140 ) ) ; -#26498 = CIRCLE ( 'NONE', #23873, 2.000000000012064127 ) ; -#26499 = AXIS2_PLACEMENT_3D ( 'NONE', #3358, #9720, #18486 ) ; -#26500 = EDGE_CURVE ( 'NONE', #2594, #23127, #12739, .T. ) ; -#26501 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19385, #22680, #38397, #31879 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26502 = ORIENTED_EDGE ( 'NONE', *, *, #31058, .F. ) ; -#26503 = CARTESIAN_POINT ( 'NONE', ( 14.03369338234965547, 177.4093650441238594, 100.6026262734140886 ) ) ; -#26504 = CIRCLE ( 'NONE', #8886, 17.00000000000405009 ) ; -#26505 = CARTESIAN_POINT ( 'NONE', ( 15.75161875086000052, 126.6561517763000211, 91.70662082261000592 ) ) ; -#26506 = CARTESIAN_POINT ( 'NONE', ( 36.68571676468000220, 115.8645254848999997, 87.83987621432000026 ) ) ; -#26507 = CARTESIAN_POINT ( 'NONE', ( 37.41381076609000189, 191.3544000862000019, 104.1956138584999962 ) ) ; -#26508 = CARTESIAN_POINT ( 'NONE', ( -25.83450491736957488, 120.6757604736500156, 87.67667375659091533 ) ) ; -#26509 = LINE ( 'NONE', #17067, #8232 ) ; -#26510 = CARTESIAN_POINT ( 'NONE', ( -34.95668960138998926, 225.9002260769401857, 73.07961704690882243 ) ) ; -#26511 = ORIENTED_EDGE ( 'NONE', *, *, #29313, .F. ) ; -#26512 = CARTESIAN_POINT ( 'NONE', ( -20.51848083070238360, 208.9757843690321124, 75.68082748707900009 ) ) ; -#26513 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32198, #17020, #18038, #33790 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.003332437842000458231 ), - .UNSPECIFIED. ) ; -#26514 = CARTESIAN_POINT ( 'NONE', ( -28.94720267997999841, 110.6131156702000027, 88.78526795067999444 ) ) ; -#26515 = CARTESIAN_POINT ( 'NONE', ( 20.49952841817542293, 195.9524980432203449, 104.0580825165111918 ) ) ; -#26516 = CARTESIAN_POINT ( 'NONE', ( -48.18209110666130357, 87.27946979429619034, 302.5876467172398065 ) ) ; -#26517 = VERTEX_POINT ( 'NONE', #31757 ) ; -#26518 = CARTESIAN_POINT ( 'NONE', ( -13.46733474056920699, 153.4793893552323709, 97.83137644993696824 ) ) ; -#26519 = EDGE_CURVE ( 'NONE', #18457, #38693, #19457, .T. ) ; -#26520 = CARTESIAN_POINT ( 'NONE', ( 1.765977884755008054, 189.4024649853499795, 103.7998658718349674 ) ) ; -#26521 = CARTESIAN_POINT ( 'NONE', ( -2.851221542150457200, 209.7096659646922774, 76.06022685436926167 ) ) ; -#26522 = VECTOR ( 'NONE', #9961, 1000.000000000000114 ) ; -#26523 = ORIENTED_EDGE ( 'NONE', *, *, #12830, .F. ) ; -#26524 = DIRECTION ( 'NONE', ( -0.0005884949961226875435, 0.2249510543439053323, -0.9743698870671265722 ) ) ; -#26525 = ORIENTED_EDGE ( 'NONE', *, *, #15596, .F. ) ; -#26526 = CARTESIAN_POINT ( 'NONE', ( -25.87094890256999946, 191.7877093630999923, 104.0495366172000047 ) ) ; -#26527 = CIRCLE ( 'NONE', #8902, 2.499999842035334652 ) ; -#26528 = CARTESIAN_POINT ( 'NONE', ( 37.28139794753688108, 124.9423866440358069, 93.60865750304402866 ) ) ; -#26529 = CARTESIAN_POINT ( 'NONE', ( -25.01941299468369806, 212.6267528717874598, 73.57339763463777160 ) ) ; -#26530 = CARTESIAN_POINT ( 'NONE', ( -19.99670393405153490, 118.1131156702000169, 90.28287776640389950 ) ) ; -#26531 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12242, #11846, #36982, #6286 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0001747927338281522725, 0.0002406710670090404878 ), - .UNSPECIFIED. ) ; -#26532 = CARTESIAN_POINT ( 'NONE', ( 16.41758150636829683, 152.5211099512976887, 181.7218298998406283 ) ) ; -#26533 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#26534 = ORIENTED_EDGE ( 'NONE', *, *, #2587, .F. ) ; -#26535 = AXIS2_PLACEMENT_3D ( 'NONE', #8402, #17971, #14933 ) ; -#26536 = EDGE_CURVE ( 'NONE', #8699, #1973, #852, .T. ) ; -#26537 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#26538 = EDGE_CURVE ( 'NONE', #21098, #33439, #24622, .T. ) ; -#26539 = CARTESIAN_POINT ( 'NONE', ( -15.49852919459145184, 184.4001630190128367, 104.8001769099776652 ) ) ; -#26540 = CARTESIAN_POINT ( 'NONE', ( 44.84982446188305261, 177.0778658525795493, 147.7896410935606184 ) ) ; -#26541 = CARTESIAN_POINT ( 'NONE', ( 36.84464589683999947, 190.4136331379999945, 106.8139093804000055 ) ) ; -#26542 = CARTESIAN_POINT ( 'NONE', ( 32.40796694493486285, 176.2190259035834856, 100.3167171782768321 ) ) ; -#26543 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700562689210365, 0.2249510912320714373 ) ) ; -#26544 = EDGE_CURVE ( 'NONE', #9147, #5625, #37148, .T. ) ; -#26545 = ADVANCED_FACE ( 'NONE', ( #10077 ), #34970, .F. ) ; -#26546 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251395983, 181.3676414799208203, 104.1015739576456411 ) ) ; -#26547 = EDGE_LOOP ( 'NONE', ( #1384, #26561, #32013, #2733 ) ) ; -#26548 = EDGE_CURVE ( 'NONE', #13536, #14788, #16193, .T. ) ; -#26549 = ORIENTED_EDGE ( 'NONE', *, *, #35945, .F. ) ; -#26550 = CARTESIAN_POINT ( 'NONE', ( 35.83878747195931425, 167.1160280305729771, 182.3999273569982336 ) ) ; -#26551 = DIRECTION ( 'NONE', ( 0.0005884949961222158072, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#26552 = EDGE_CURVE ( 'NONE', #15606, #72, #249, .T. ) ; -#26553 = CARTESIAN_POINT ( 'NONE', ( -32.44499774467648479, 136.5818299423348492, 91.20491734193556965 ) ) ; -#26554 = CARTESIAN_POINT ( 'NONE', ( 8.048542122852918368, 150.7638762473669658, 97.53355711752999468 ) ) ; -#26555 = EDGE_LOOP ( 'NONE', ( #23819, #14427, #32888, #36436 ) ) ; -#26556 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#26557 = AXIS2_PLACEMENT_3D ( 'NONE', #8904, #34369, #6365 ) ; -#26558 = ORIENTED_EDGE ( 'NONE', *, *, #3431, .T. ) ; -#26559 = VECTOR ( 'NONE', #11650, 999.9999999999998863 ) ; -#26560 = DIRECTION ( 'NONE', ( -0.0005884949961254009763, 0.2249510543439060262, -0.9743698870671263501 ) ) ; -#26561 = ORIENTED_EDGE ( 'NONE', *, *, #11085, .F. ) ; -#26562 = CARTESIAN_POINT ( 'NONE', ( 36.65077066423717866, 191.4293016981708035, 106.3500278736450753 ) ) ; -#26563 = AXIS2_PLACEMENT_3D ( 'NONE', #15786, #15991, #28479 ) ; -#26564 = FACE_OUTER_BOUND ( 'NONE', #26688, .T. ) ; -#26565 = FACE_OUTER_BOUND ( 'NONE', #28703, .T. ) ; -#26566 = AXIS2_PLACEMENT_3D ( 'NONE', #10978, #32058, #32448 ) ; -#26567 = FACE_OUTER_BOUND ( 'NONE', #15084, .T. ) ; -#26568 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #40178, #39776, #33845, #37126 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26569 = CARTESIAN_POINT ( 'NONE', ( -5.669748535203316564, 124.7404542330243800, 88.96810042129679630 ) ) ; -#26570 = ORIENTED_EDGE ( 'NONE', *, *, #25037, .F. ) ; -#26571 = CARTESIAN_POINT ( 'NONE', ( -0.03375341898833555260, -31.76863880746333280, 137.4221703796379188 ) ) ; -#26572 = ADVANCED_FACE ( 'NONE', ( #37473 ), #9471, .T. ) ; -#26573 = CARTESIAN_POINT ( 'NONE', ( 12.63088349563799184, 181.6904995670203391, 101.5918601121804556 ) ) ; -#26574 = CARTESIAN_POINT ( 'NONE', ( 22.49999922077095604, 184.9675253677921773, 102.3424519572064355 ) ) ; -#26575 = ORIENTED_EDGE ( 'NONE', *, *, #10280, .F. ) ; -#26576 = CARTESIAN_POINT ( 'NONE', ( -45.30267887931935178, 123.9248666885585806, 93.18489076007304561 ) ) ; -#26577 = ORIENTED_EDGE ( 'NONE', *, *, #7272, .T. ) ; -#26578 = CARTESIAN_POINT ( 'NONE', ( 19.99994303953296182, 119.3449851748513737, 87.25570516597396420 ) ) ; -#26579 = CARTESIAN_POINT ( 'NONE', ( -38.95517892727801268, 209.7096538831000032, 75.58203249027424420 ) ) ; -#26580 = DIRECTION ( 'NONE', ( -3.469446951887147924E-15, 0.9743700557921581851, 0.2249510932971580390 ) ) ; -#26581 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -3.869599770875634371E-16, -0.0006039748319386379488 ) ) ; -#26582 = CARTESIAN_POINT ( 'NONE', ( 18.08289561727003658, 152.6324032069051384, 184.7487331658680887 ) ) ; -#26583 = CIRCLE ( 'NONE', #27911, 1.650000000000002798 ) ; -#26584 = CARTESIAN_POINT ( 'NONE', ( -13.01298190969827040, 181.6879564457013885, 101.6067526251711826 ) ) ; -#26585 = CIRCLE ( 'NONE', #10275, 6.500000000082327034 ) ; -#26586 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#26587 = VECTOR ( 'NONE', #17241, 1000.000000000000114 ) ; -#26588 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 1.540743955509788340E-33, 0.0006039748319384538513 ) ) ; -#26589 = EDGE_CURVE ( 'NONE', #22348, #38150, #10249, .T. ) ; -#26590 = FACE_OUTER_BOUND ( 'NONE', #6378, .T. ) ; -#26591 = CARTESIAN_POINT ( 'NONE', ( 3.326633047918813535, 183.2667907456296632, 101.9613865925673508 ) ) ; -#26592 = ORIENTED_EDGE ( 'NONE', *, *, #1225, .F. ) ; -#26593 = AXIS2_PLACEMENT_3D ( 'NONE', #25251, #6023, #9704 ) ; -#26594 = EDGE_CURVE ( 'NONE', #29915, #38998, #8835, .T. ) ; -#26595 = DIRECTION ( 'NONE', ( -0.7072262180194089920, -0.6509452856072081017, -0.2758646619118033660 ) ) ; -#26596 = DIRECTION ( 'NONE', ( 0.9999998268368057719, 0.0001323825923583700991, -0.0005734119003960201286 ) ) ; -#26597 = CARTESIAN_POINT ( 'NONE', ( 19.56153773728087941, 148.7179920449207202, 184.4707757878970256 ) ) ; -#26598 = CARTESIAN_POINT ( 'NONE', ( 26.01072490218321676, 191.2306769852524724, 106.8537119624654110 ) ) ; -#26599 = EDGE_CURVE ( 'NONE', #22006, #7652, #1060, .T. ) ; -#26601 = ORIENTED_EDGE ( 'NONE', *, *, #19003, .T. ) ; -#26600 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; -#26602 = ORIENTED_EDGE ( 'NONE', *, *, #21951, .F. ) ; -#26603 = EDGE_LOOP ( 'NONE', ( #37925, #930, #6890, #24142 ) ) ; -#26604 = ADVANCED_FACE ( 'NONE', ( #34779 ), #3682, .F. ) ; -#26605 = EDGE_LOOP ( 'NONE', ( #17054, #34962, #15415, #38270, #21269, #2672, #4291, #31083, #18925, #20477, #19655 ) ) ; -#26606 = FACE_OUTER_BOUND ( 'NONE', #40075, .T. ) ; -#26607 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; -#26608 = ORIENTED_EDGE ( 'NONE', *, *, #28882, .T. ) ; -#26609 = ORIENTED_EDGE ( 'NONE', *, *, #11627, .F. ) ; -#26610 = FACE_BOUND ( 'NONE', #29176, .T. ) ; -#26611 = CARTESIAN_POINT ( 'NONE', ( -30.07831637853678686, 134.9151858147922667, 90.81876078434068233 ) ) ; -#26612 = CARTESIAN_POINT ( 'NONE', ( -37.83922575564000113, 118.0391086144000070, 87.84578005413000312 ) ) ; -#26613 = ORIENTED_EDGE ( 'NONE', *, *, #20670, .T. ) ; -#26614 = CARTESIAN_POINT ( 'NONE', ( 3.334680587944353736, 185.2725092996106184, 105.3322985861469760 ) ) ; -#26615 = AXIS2_PLACEMENT_3D ( 'NONE', #6178, #5784, #40317 ) ; -#26616 = ORIENTED_EDGE ( 'NONE', *, *, #5291, .F. ) ; -#26617 = CARTESIAN_POINT ( 'NONE', ( 4.133310199970877008, 187.8594049812016067, 103.0211881142743238 ) ) ; -#26618 = CARTESIAN_POINT ( 'NONE', ( 35.56910103317023442, 113.0588457072281585, 90.24630199347080861 ) ) ; -#26619 = VECTOR ( 'NONE', #39903, 1000.000000000000000 ) ; -#26620 = DIRECTION ( 'NONE', ( 4.047688110583664430E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; -#26621 = VERTEX_POINT ( 'NONE', #26426 ) ; -#26622 = FACE_OUTER_BOUND ( 'NONE', #3061, .T. ) ; -#26623 = CARTESIAN_POINT ( 'NONE', ( 0.6372482775786000309, 189.0047147329999859, 103.6952764219000045 ) ) ; -#26624 = CARTESIAN_POINT ( 'NONE', ( -40.30153468720526178, 187.7974083947837585, 108.1652340796715492 ) ) ; -#26625 = CARTESIAN_POINT ( 'NONE', ( -37.68439733255148383, 188.7463803737940395, 106.3301322885044016 ) ) ; -#26626 = ORIENTED_EDGE ( 'NONE', *, *, #20294, .F. ) ; -#26627 = ORIENTED_EDGE ( 'NONE', *, *, #583, .T. ) ; -#26628 = CARTESIAN_POINT ( 'NONE', ( 36.09418572946387371, 97.50014116332937419, 154.5721339787388047 ) ) ; -#26629 = CARTESIAN_POINT ( 'NONE', ( -23.01879311717446086, 214.0903458147471383, 76.07243274013872281 ) ) ; -#26630 = ORIENTED_EDGE ( 'NONE', *, *, #39490, .F. ) ; -#26631 = ORIENTED_EDGE ( 'NONE', *, *, #17625, .T. ) ; -#26632 = EDGE_CURVE ( 'NONE', #3089, #3943, #27897, .T. ) ; -#26633 = EDGE_CURVE ( 'NONE', #15772, #38661, #6285, .T. ) ; -#26634 = ORIENTED_EDGE ( 'NONE', *, *, #34996, .F. ) ; -#26635 = EDGE_CURVE ( 'NONE', #11146, #22, #35155, .T. ) ; -#26636 = VERTEX_POINT ( 'NONE', #7387 ) ; -#26637 = EDGE_CURVE ( 'NONE', #31429, #37342, #7599, .T. ) ; -#26638 = DIRECTION ( 'NONE', ( -0.9999998268368966992, -0.0001323825576369143267, 0.0005734117500054078387 ) ) ; -#26639 = CARTESIAN_POINT ( 'NONE', ( -8.472443777046803959, 150.6153475619768187, 96.99609267642283328 ) ) ; -#26640 = VERTEX_POINT ( 'NONE', #20058 ) ; -#26641 = LINE ( 'NONE', #35799, #32361 ) ; -#26642 = ORIENTED_EDGE ( 'NONE', *, *, #3626, .T. ) ; -#26643 = EDGE_CURVE ( 'NONE', #10604, #2295, #31282, .T. ) ; -#26644 = CARTESIAN_POINT ( 'NONE', ( 28.12620697607000508, 124.5905266982999962, 91.30778919159000395 ) ) ; -#26645 = AXIS2_PLACEMENT_3D ( 'NONE', #34720, #31699, #13484 ) ; -#26646 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; -#26647 = AXIS2_PLACEMENT_3D ( 'NONE', #39089, #33153, #23983 ) ; -#26649 = PLANE ( 'NONE', #22061 ) ; -#26648 = FACE_OUTER_BOUND ( 'NONE', #21142, .T. ) ; -#26650 = ORIENTED_EDGE ( 'NONE', *, *, #4355, .F. ) ; -#26651 = EDGE_CURVE ( 'NONE', #9209, #39608, #30479, .T. ) ; -#26652 = ORIENTED_EDGE ( 'NONE', *, *, #16204, .T. ) ; -#26653 = ORIENTED_EDGE ( 'NONE', *, *, #14903, .F. ) ; -#26654 = LINE ( 'NONE', #20081, #16518 ) ; -#26655 = EDGE_CURVE ( 'NONE', #31583, #6212, #22953, .T. ) ; -#26656 = CARTESIAN_POINT ( 'NONE', ( 36.04689830202195822, 205.5673820495391055, 76.27844315541416620 ) ) ; -#26657 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#26658 = ORIENTED_EDGE ( 'NONE', *, *, #19855, .F. ) ; -#26659 = ORIENTED_EDGE ( 'NONE', *, *, #29507, .T. ) ; -#26660 = ORIENTED_EDGE ( 'NONE', *, *, #28431, .F. ) ; -#26661 = CARTESIAN_POINT ( 'NONE', ( 20.14702854017319922, 209.7098729452407326, 73.21335924537376627 ) ) ; -#26662 = CARTESIAN_POINT ( 'NONE', ( -37.21052966546948682, 132.5657015190818697, 337.0064682716691777 ) ) ; -#26663 = CARTESIAN_POINT ( 'NONE', ( 26.07151325143000165, 121.8396282002999982, 87.76599268405001908 ) ) ; -#26664 = ORIENTED_EDGE ( 'NONE', *, *, #13399, .F. ) ; -#26665 = CARTESIAN_POINT ( 'NONE', ( -35.47176629106999712, 192.2367679710000061, 106.9459547420999996 ) ) ; -#26666 = VERTEX_POINT ( 'NONE', #32351 ) ; -#26667 = LINE ( 'NONE', #1294, #16363 ) ; -#26668 = ORIENTED_EDGE ( 'NONE', *, *, #4249, .T. ) ; -#26669 = DIRECTION ( 'NONE', ( 0.0006039748319395906373, 1.291365685536979971E-14, 0.9999998176071844824 ) ) ; -#26670 = CONICAL_SURFACE ( 'NONE', #22730, 10.00000000000456346, 0.7853981633973012855 ) ; -#26671 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178570922545E-05, 0.0002331579774915894113 ) ) ; -#26672 = FACE_OUTER_BOUND ( 'NONE', #34818, .T. ) ; -#26673 = CYLINDRICAL_SURFACE ( 'NONE', #26725, 2.000000000000011546 ) ; -#26674 = EDGE_CURVE ( 'NONE', #35038, #34336, #33736, .T. ) ; -#26675 = ORIENTED_EDGE ( 'NONE', *, *, #624, .F. ) ; -#26676 = EDGE_CURVE ( 'NONE', #2746, #34239, #29285, .T. ) ; -#26677 = ADVANCED_FACE ( 'NONE', ( #22687 ), #40255, .F. ) ; -#26678 = CARTESIAN_POINT ( 'NONE', ( 3.867708199630259358, 137.2814764503893628, 91.68658596503725278 ) ) ; -#26679 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552150381, 77.14301703112145958, 291.5584375788748162 ) ) ; -#26680 = ORIENTED_EDGE ( 'NONE', *, *, #38423, .T. ) ; -#26681 = EDGE_CURVE ( 'NONE', #9823, #38321, #35009, .T. ) ; -#26682 = LINE ( 'NONE', #16841, #33858 ) ; -#26684 = CARTESIAN_POINT ( 'NONE', ( 14.74038206972566023, 158.6023471296159357, 96.26025645282702214 ) ) ; -#26683 = FACE_OUTER_BOUND ( 'NONE', #9959, .T. ) ; -#26685 = EDGE_CURVE ( 'NONE', #11816, #11521, #9062, .T. ) ; -#26686 = AXIS2_PLACEMENT_3D ( 'NONE', #23334, #32920, #8191 ) ; -#26687 = ORIENTED_EDGE ( 'NONE', *, *, #1352, .F. ) ; -#26688 = EDGE_LOOP ( 'NONE', ( #12652, #10580, #15223, #37918 ) ) ; -#26689 = CARTESIAN_POINT ( 'NONE', ( -35.94780306588808116, 112.9281708003797036, 87.78949364045074333 ) ) ; -#26690 = AXIS2_PLACEMENT_3D ( 'NONE', #14498, #39622, #30033 ) ; -#26691 = DIRECTION ( 'NONE', ( 0.0005884949961253973984, -0.2249510543501614945, 0.9743698870656820610 ) ) ; -#26692 = CARTESIAN_POINT ( 'NONE', ( -24.13060896835314395, 149.4040876299065417, 197.0825913028203900 ) ) ; -#26693 = PLANE ( 'NONE', #34751 ) ; -#26694 = VECTOR ( 'NONE', #37939, 1000.000000000000114 ) ; -#26695 = FACE_OUTER_BOUND ( 'NONE', #28142, .T. ) ; -#26696 = ORIENTED_EDGE ( 'NONE', *, *, #19082, .T. ) ; -#26697 = EDGE_LOOP ( 'NONE', ( #14013, #36017, #23895, #27823, #38525, #4181, #35843, #22195, #5056 ) ) ; -#26698 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#26699 = ORIENTED_EDGE ( 'NONE', *, *, #2020, .T. ) ; -#26700 = VERTEX_POINT ( 'NONE', #10411 ) ; -#26701 = CARTESIAN_POINT ( 'NONE', ( 5.667981290316929766, 188.0310117602156197, 103.3282556105816639 ) ) ; -#26702 = FACE_OUTER_BOUND ( 'NONE', #32558, .T. ) ; -#26703 = EDGE_CURVE ( 'NONE', #14375, #28275, #16716, .T. ) ; -#26704 = CARTESIAN_POINT ( 'NONE', ( 39.42035703641028022, 114.3667165859880015, 151.6079144922757109 ) ) ; -#26705 = ORIENTED_EDGE ( 'NONE', *, *, #32564, .T. ) ; -#26706 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749094291, 179.1800746285969410, 103.5747911657857685 ) ) ; -#26707 = CARTESIAN_POINT ( 'NONE', ( 36.03687122555673739, 218.5902260770998282, 61.03673652647002257 ) ) ; -#26708 = CARTESIAN_POINT ( 'NONE', ( -36.15951732602999869, 191.7854204790999972, 104.2892810376000057 ) ) ; -#26709 = CARTESIAN_POINT ( 'NONE', ( 38.07467335044000123, 191.1277935667999941, 103.8765590109999977 ) ) ; -#26710 = CARTESIAN_POINT ( 'NONE', ( -25.50095891563999828, 120.6767459707999990, 88.04209109285001489 ) ) ; -#26711 = DIRECTION ( 'NONE', ( -0.7933535320750288999, 0.5931614265262136199, 0.1369295264925108890 ) ) ; -#26712 = ORIENTED_EDGE ( 'NONE', *, *, #23802, .T. ) ; -#26713 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#26714 = CARTESIAN_POINT ( 'NONE', ( -23.35627702857092913, 177.0509736354910615, 103.5359117850035773 ) ) ; -#26715 = ORIENTED_EDGE ( 'NONE', *, *, #3350, .T. ) ; -#26716 = CARTESIAN_POINT ( 'NONE', ( 0.6204049449089953372, 188.6158442063491520, 103.1979476084812717 ) ) ; -#26717 = CARTESIAN_POINT ( 'NONE', ( -13.50000077922901731, 184.9627595935803868, 102.3630947892575307 ) ) ; -#26718 = DIRECTION ( 'NONE', ( 0.7066903833891088338, 9.361005957145118576E-05, -0.7075229277292088836 ) ) ; -#26719 = CARTESIAN_POINT ( 'NONE', ( -43.16067970895235106, 137.0136042933273472, 338.0369414682852494 ) ) ; -#26720 = ORIENTED_EDGE ( 'NONE', *, *, #18430, .T. ) ; -#26721 = FACE_OUTER_BOUND ( 'NONE', #10180, .T. ) ; -#26722 = VECTOR ( 'NONE', #2818, 1000.000000000000000 ) ; -#26723 = CARTESIAN_POINT ( 'NONE', ( 2.562971096584431230, 190.9999997793927093, 104.2603522665603890 ) ) ; -#26724 = CARTESIAN_POINT ( 'NONE', ( 20.00004282447493864, 191.5259056233101091, 103.8580927373495371 ) ) ; -#26725 = AXIS2_PLACEMENT_3D ( 'NONE', #13785, #23801, #20315 ) ; -#26726 = ORIENTED_EDGE ( 'NONE', *, *, #8276, .F. ) ; -#26727 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971578447 ) ) ; -#26728 = VECTOR ( 'NONE', #29859, 1000.000000000000114 ) ; -#26729 = ADVANCED_FACE ( 'NONE', ( #13667 ), #382, .T. ) ; -#26730 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#26731 = EDGE_CURVE ( 'NONE', #22702, #127, #33210, .T. ) ; -#26732 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971554023 ) ) ; -#26733 = CONICAL_SURFACE ( 'NONE', #18845, 6.000000000012161827, 0.7853981634347138030 ) ; -#26734 = CARTESIAN_POINT ( 'NONE', ( -20.60932504597193926, 129.3771293980497603, 89.53443240656145008 ) ) ; -#26735 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#26736 = DIRECTION ( 'NONE', ( 0.5988683521957647304, -0.8008474865655316188, 0.000000000000000000 ) ) ; -#26737 = ORIENTED_EDGE ( 'NONE', *, *, #2396, .F. ) ; -#26738 = CYLINDRICAL_SURFACE ( 'NONE', #36352, 2.000000000000000000 ) ; -#26739 = CARTESIAN_POINT ( 'NONE', ( 20.39369772661039448, 175.8775066034073404, 100.2451275383852902 ) ) ; -#26740 = CARTESIAN_POINT ( 'NONE', ( 3.667815741540035646, 183.5629855103865964, 104.5953232250576406 ) ) ; -#26741 = CARTESIAN_POINT ( 'NONE', ( 36.95058457225000126, 190.7035229651999941, 106.6077189348000047 ) ) ; -#26742 = LINE ( 'NONE', #36340, #10471 ) ; -#26743 = CARTESIAN_POINT ( 'NONE', ( -1.762796036274244527, 145.3269866793034168, 129.1252078605875795 ) ) ; -#26744 = CARTESIAN_POINT ( 'NONE', ( -5.667825639563665696, 130.0010482692081553, 92.27601498940221347 ) ) ; -#26745 = CARTESIAN_POINT ( 'NONE', ( 23.00089693216080988, 115.1133509736824152, 90.25389292129368357 ) ) ; -#26746 = ORIENTED_EDGE ( 'NONE', *, *, #38445, .T. ) ; -#26748 = VECTOR ( 'NONE', #33334, 1000.000000000000114 ) ; -#26747 = CARTESIAN_POINT ( 'NONE', ( 27.30382602036842954, 110.6131156702000027, 87.75129355648586227 ) ) ; -#26749 = CARTESIAN_POINT ( 'NONE', ( -31.01530004135919327, 135.0949612155151272, 90.86078308433575046 ) ) ; -#26750 = AXIS2_PLACEMENT_3D ( 'NONE', #2239, #39024, #17747 ) ; -#26751 = ORIENTED_EDGE ( 'NONE', *, *, #35733, .F. ) ; -#26752 = FACE_OUTER_BOUND ( 'NONE', #34600, .T. ) ; -#26753 = AXIS2_PLACEMENT_3D ( 'NONE', #16707, #23461, #13656 ) ; -#26754 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9882, #248, #16192, #31756, #22149, #12944, #25827, #10485, #28478, #32156 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000549560, 0.3750000000000826006, 0.4375000000000809353, 0.5000000000000792699, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26755 = CARTESIAN_POINT ( 'NONE', ( 25.50041447495308233, 118.1134306400200416, 89.75249416949174019 ) ) ; -#26756 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26899, #39334, #2353, #2152 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26757 = CONICAL_SURFACE ( 'NONE', #19555, 51.90509898885028406, 0.7853981633972950682 ) ; -#26758 = ORIENTED_EDGE ( 'NONE', *, *, #11037, .F. ) ; -#26759 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971567068 ) ) ; -#26760 = CARTESIAN_POINT ( 'NONE', ( -22.49852798327293613, 137.6294278362846910, 94.00652773583050248 ) ) ; -#26761 = ORIENTED_EDGE ( 'NONE', *, *, #34355, .T. ) ; -#26762 = PLANE ( 'NONE', #21730 ) ; -#26763 = ADVANCED_FACE ( 'NONE', ( #28806 ), #9604, .T. ) ; -#26764 = FACE_OUTER_BOUND ( 'NONE', #25768, .T. ) ; -#26765 = CARTESIAN_POINT ( 'NONE', ( -12.63215091093176135, 130.3073820208400377, 92.77172047309325364 ) ) ; -#26766 = CARTESIAN_POINT ( 'NONE', ( -35.93631444825950183, 190.8511609687279815, 106.8150034675900173 ) ) ; -#26767 = CARTESIAN_POINT ( 'NONE', ( 37.40434350968867250, 145.4460227941551409, 282.5393146728916918 ) ) ; -#26768 = ORIENTED_EDGE ( 'NONE', *, *, #1315, .F. ) ; -#26769 = ORIENTED_EDGE ( 'NONE', *, *, #28889, .T. ) ; -#26770 = DIRECTION ( 'NONE', ( -0.0006039748319378610095, -9.939046677758948188E-15, -0.9999998176071845934 ) ) ; -#26771 = CARTESIAN_POINT ( 'NONE', ( -20.49970524097187763, 120.2776284062741325, 87.94673202274765345 ) ) ; -#26772 = FACE_OUTER_BOUND ( 'NONE', #35371, .T. ) ; -#26773 = CARTESIAN_POINT ( 'NONE', ( -26.77281046845786960, 181.6852968820032004, 101.6144925486012482 ) ) ; -#26774 = EDGE_CURVE ( 'NONE', #36789, #16908, #29004, .T. ) ; -#26775 = ORIENTED_EDGE ( 'NONE', *, *, #6235, .T. ) ; -#26776 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971571786 ) ) ; -#26777 = ADVANCED_FACE ( 'NONE', ( #10004 ), #31884, .F. ) ; -#26778 = CARTESIAN_POINT ( 'NONE', ( -42.64899167230314703, 121.2509807306891503, 91.18371451274786921 ) ) ; -#26780 = EDGE_CURVE ( 'NONE', #11951, #26904, #14162, .T. ) ; -#26779 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; -#26781 = LINE ( 'NONE', #30041, #5848 ) ; -#26782 = CARTESIAN_POINT ( 'NONE', ( 29.40506628721518112, 160.9732782815168832, 187.1184765030605774 ) ) ; -#26783 = AXIS2_PLACEMENT_3D ( 'NONE', #24770, #9221, #21693 ) ; -#26784 = VECTOR ( 'NONE', #30979, 1000.000000000000000 ) ; -#26785 = CARTESIAN_POINT ( 'NONE', ( 20.00016034875645943, 127.4394136103090887, 89.06260552501319694 ) ) ; -#26786 = VECTOR ( 'NONE', #21426, 1000.000000000000000 ) ; -#26787 = CARTESIAN_POINT ( 'NONE', ( -22.78373664920998465, 158.6756214348941967, 96.81298893720612853 ) ) ; -#26788 = CARTESIAN_POINT ( 'NONE', ( -25.70423657749428514, 209.7106478409149020, 73.37976546826619995 ) ) ; -#26789 = CARTESIAN_POINT ( 'NONE', ( 25.37184720669000271, 191.3685744429000124, 106.2318680839000109 ) ) ; -#26790 = CARTESIAN_POINT ( 'NONE', ( 38.47734842322999782, 119.0019185009000040, 87.58017102035999812 ) ) ; -#26791 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319351121233 ) ) ; -#26792 = CARTESIAN_POINT ( 'NONE', ( 26.01908888004416198, 121.3240759725699576, 87.64707579647844682 ) ) ; -#26793 = ORIENTED_EDGE ( 'NONE', *, *, #13984, .F. ) ; -#26794 = DIRECTION ( 'NONE', ( 0.0003761318146485119322, -0.7826081568524122511, 0.6225145230056309265 ) ) ; -#26795 = FACE_OUTER_BOUND ( 'NONE', #3749, .T. ) ; -#26796 = CARTESIAN_POINT ( 'NONE', ( -20.99988231331349198, 183.1828074682273098, 102.1277500980325925 ) ) ; -#26797 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#26798 = DIRECTION ( 'NONE', ( 0.0005884949961208347504, -0.2249510543439081633, 0.9743698870671259060 ) ) ; -#26799 = EDGE_LOOP ( 'NONE', ( #24032, #17353, #31347, #21978 ) ) ; -#26800 = ORIENTED_EDGE ( 'NONE', *, *, #36994, .F. ) ; -#26801 = ORIENTED_EDGE ( 'NONE', *, *, #38114, .T. ) ; -#26802 = CARTESIAN_POINT ( 'NONE', ( -23.35464359634993770, 177.7881151143831744, 100.7126876897662697 ) ) ; -#26803 = CARTESIAN_POINT ( 'NONE', ( 44.67372889100202826, 177.7390009530348891, 153.4812792797092413 ) ) ; -#26804 = CARTESIAN_POINT ( 'NONE', ( 42.84319492119625039, 107.4629127437788441, 150.2239362889277174 ) ) ; -#26805 = ORIENTED_EDGE ( 'NONE', *, *, #13647, .T. ) ; -#26806 = FACE_BOUND ( 'NONE', #8467, .T. ) ; -#26807 = AXIS2_PLACEMENT_3D ( 'NONE', #15451, #33643, #12190 ) ; -#26808 = AXIS2_PLACEMENT_3D ( 'NONE', #37707, #28129, #9715 ) ; -#26809 = CARTESIAN_POINT ( 'NONE', ( -38.08733905160174515, 161.7245877003365706, 191.3073351807457811 ) ) ; -#26810 = PLANE ( 'NONE', #17523 ) ; -#26811 = DIRECTION ( 'NONE', ( 0.0005884949961195158185, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#26812 = CARTESIAN_POINT ( 'NONE', ( -37.26090046766999819, 117.2573710810000165, 87.85948469216999968 ) ) ; -#26813 = ORIENTED_EDGE ( 'NONE', *, *, #29397, .T. ) ; -#26814 = CARTESIAN_POINT ( 'NONE', ( -2.935232621041004020, 190.8511156531020276, 106.7950609103722286 ) ) ; -#26815 = EDGE_CURVE ( 'NONE', #14158, #19947, #9574, .T. ) ; -#26816 = CIRCLE ( 'NONE', #2000, 2.000000000000011546 ) ; -#26817 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20009, #32501, #38814, #4471, #14107, #16533, #32894, #26376, #35738, #29845 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.002118074346442883234, 0.2515885557598321887, 0.5010590371732214221, 0.7505295185866107666, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26818 = AXIS2_PLACEMENT_3D ( 'NONE', #15845, #6636, #911 ) ; -#26819 = CARTESIAN_POINT ( 'NONE', ( 20.49249339799013470, 105.2139170029020079, 152.4743314729049644 ) ) ; -#26820 = CARTESIAN_POINT ( 'NONE', ( 46.51603001997818865, 125.2609579198457368, 89.05674941267899669 ) ) ; -#26821 = EDGE_LOOP ( 'NONE', ( #33841, #28557, #12527, #34978 ) ) ; -#26822 = ORIENTED_EDGE ( 'NONE', *, *, #7124, .T. ) ; -#26823 = EDGE_CURVE ( 'NONE', #36593, #9503, #4324, .T. ) ; -#26824 = CARTESIAN_POINT ( 'NONE', ( -2.210524828757970184, 189.3034206159340158, 103.3540988507229912 ) ) ; -#26825 = CARTESIAN_POINT ( 'NONE', ( 0.8837433930371000335, 188.6289352372000110, 103.1999597849000025 ) ) ; -#26826 = DIRECTION ( 'NONE', ( -0.0005884949961246006183, 0.2249510543439056653, -0.9743698870671265722 ) ) ; -#26827 = CARTESIAN_POINT ( 'NONE', ( 26.28854775478996686, 121.8696897106344892, 90.85179081473795293 ) ) ; -#26828 = ORIENTED_EDGE ( 'NONE', *, *, #23813, .F. ) ; -#26829 = EDGE_CURVE ( 'NONE', #19329, #8486, #25430, .T. ) ; -#26830 = EDGE_LOOP ( 'NONE', ( #20663, #23726, #39280, #38803, #19752, #30217, #11321, #22164, #7249, #1251, #34140 ) ) ; -#26831 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023851578 ) ) ; -#26832 = ORIENTED_EDGE ( 'NONE', *, *, #17835, .T. ) ; -#26833 = EDGE_CURVE ( 'NONE', #38150, #5749, #38277, .T. ) ; -#26834 = ORIENTED_EDGE ( 'NONE', *, *, #27574, .T. ) ; -#26835 = EDGE_CURVE ( 'NONE', #22159, #21490, #3018, .T. ) ; -#26836 = ADVANCED_FACE ( 'NONE', ( #35309 ), #7315, .T. ) ; -#26837 = ORIENTED_EDGE ( 'NONE', *, *, #23204, .F. ) ; -#26838 = ORIENTED_EDGE ( 'NONE', *, *, #25034, .T. ) ; -#26839 = CARTESIAN_POINT ( 'NONE', ( 22.33620396352009152, 213.5250434016230940, 73.54492077792029647 ) ) ; -#26840 = CARTESIAN_POINT ( 'NONE', ( -20.01736593119981222, 207.8686407175673594, 77.28911966098117148 ) ) ; -#26841 = VECTOR ( 'NONE', #6599, 1000.000000000000114 ) ; -#26842 = ORIENTED_EDGE ( 'NONE', *, *, #28633, .T. ) ; -#26843 = DIRECTION ( 'NONE', ( 0.0005884949961212082581, -0.2249510543439042498, 0.9743698870671267942 ) ) ; -#26844 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#26845 = ORIENTED_EDGE ( 'NONE', *, *, #36932, .F. ) ; -#26846 = AXIS2_PLACEMENT_3D ( 'NONE', #11204, #36131, #36345 ) ; -#26847 = CARTESIAN_POINT ( 'NONE', ( 26.66063621298999919, 123.4172645953999989, 90.86668199093000453 ) ) ; -#26848 = VECTOR ( 'NONE', #29874, 1000.000000000000114 ) ; -#26849 = DIRECTION ( 'NONE', ( 0.7933533411653088674, -0.5930537057989926364, -0.1373964268091528718 ) ) ; -#26850 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38545, #7065, #25503, #3587 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26852 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#26851 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#26853 = ORIENTED_EDGE ( 'NONE', *, *, #20486, .T. ) ; -#26854 = ORIENTED_EDGE ( 'NONE', *, *, #30017, .T. ) ; -#26855 = CARTESIAN_POINT ( 'NONE', ( -36.05603307849823835, 192.0347168703188174, 104.4252530631643339 ) ) ; -#26856 = CYLINDRICAL_SURFACE ( 'NONE', #39343, 2.000000000000001332 ) ; -#26857 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38302, #31372, #10316, #3344, #22778, #1486, #14188, #17421, #35810, #11506, #7622, #2113, #14583, #26450, #8026, #27068, #23781, #23379, #1902, #8240, #4550, #16814, #35604, #39297 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 1, 1, 1, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999919231, 0.1874999999999908684, 0.2187499999999934774, 0.2499999999999960587, 0.3749999999999950595, 0.4374999999999977240, 0.4687499999999958922, 0.4843749999999950040, 0.4999999999999941158, 0.6249999999999951150, 0.6874999999999963363, 0.7187499999999970024, 0.7343749999999953371, 0.7499999999999935607, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26858 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #38598, #38214, #4246, #6925 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.570796326794905662, 3.321000581826871301 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7606123116729073264, 0.7606123116729073264, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#26859 = ORIENTED_EDGE ( 'NONE', *, *, #18060, .T. ) ; -#26860 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930881478 ) ) ; -#26861 = CARTESIAN_POINT ( 'NONE', ( -37.20408499830807614, 118.8543451047710278, 123.0175147464529886 ) ) ; -#26862 = CARTESIAN_POINT ( 'NONE', ( -22.78207419572857617, 153.6036766290901596, 98.03674867519744396 ) ) ; -#26863 = VERTEX_POINT ( 'NONE', #31690 ) ; -#26864 = EDGE_CURVE ( 'NONE', #28866, #29827, #3640, .T. ) ; -#26865 = VERTEX_POINT ( 'NONE', #23076 ) ; -#26866 = EDGE_CURVE ( 'NONE', #30574, #24578, #16907, .T. ) ; -#26867 = FACE_OUTER_BOUND ( 'NONE', #10035, .T. ) ; -#26868 = CARTESIAN_POINT ( 'NONE', ( 15.99999439207489615, 185.9093013714976053, 102.5638074086867846 ) ) ; -#26869 = CIRCLE ( 'NONE', #30125, 5.249999999999986677 ) ; -#26870 = EDGE_LOOP ( 'NONE', ( #36400, #7785 ) ) ; -#26871 = ADVANCED_FACE ( 'NONE', ( #15034 ), #30778, .T. ) ; -#26872 = CARTESIAN_POINT ( 'NONE', ( 30.06805065029857005, 135.2198668957702807, 91.25923900005884093 ) ) ; -#26873 = VECTOR ( 'NONE', #10038, 1000.000000000000000 ) ; -#26874 = ADVANCED_FACE ( 'NONE', ( #32475 ), #39554, .F. ) ; -#26875 = CARTESIAN_POINT ( 'NONE', ( -22.49829783392772953, 153.4788092355344702, 97.83669617681565001 ) ) ; -#26876 = VERTEX_POINT ( 'NONE', #27324 ) ; -#26877 = CARTESIAN_POINT ( 'NONE', ( 6.666633792382095969, 120.3902219392796411, 87.44316696365504527 ) ) ; -#26878 = ADVANCED_FACE ( 'NONE', ( #23271 ), #24458, .F. ) ; -#26879 = CARTESIAN_POINT ( 'NONE', ( -46.23974599993426438, 125.3236958879561058, 88.95620493717709110 ) ) ; -#26880 = CYLINDRICAL_SURFACE ( 'NONE', #40449, 2.000000000000014655 ) ; -#26881 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825920995632343, 0.0005734119023635456634 ) ) ; -#26882 = EDGE_LOOP ( 'NONE', ( #18569, #34062, #9448, #5916 ) ) ; -#26883 = PLANE ( 'NONE', #8161 ) ; -#26884 = DIRECTION ( 'NONE', ( 0.0002393071182786170076, 0.2252352986010032476, -0.9743043687658492491 ) ) ; -#26885 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38802, #2229, #20197, #4867 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26886 = ORIENTED_EDGE ( 'NONE', *, *, #10336, .F. ) ; -#26887 = CARTESIAN_POINT ( 'NONE', ( 37.28741399843698900, 124.9789241431960392, 93.24647550195996359 ) ) ; -#26888 = AXIS2_PLACEMENT_3D ( 'NONE', #5372, #10372, #35272 ) ; -#26890 = CARTESIAN_POINT ( 'NONE', ( 5.666638401078098575, 182.0642691150555663, 102.1955013913653545 ) ) ; -#26889 = CARTESIAN_POINT ( 'NONE', ( 13.61340840401525654, 135.2710827206831823, 90.87448932346926256 ) ) ; -#26891 = VERTEX_POINT ( 'NONE', #7517 ) ; -#26892 = AXIS2_PLACEMENT_3D ( 'NONE', #26983, #27194, #33284 ) ; -#26893 = ORIENTED_EDGE ( 'NONE', *, *, #32627, .F. ) ; -#26894 = CARTESIAN_POINT ( 'NONE', ( 25.02024140749000125, 130.2799456493999912, 91.25476132727000333 ) ) ; -#26895 = CARTESIAN_POINT ( 'NONE', ( 38.63435032335372910, 118.5239118084539172, 89.66224185811006464 ) ) ; -#26896 = ORIENTED_EDGE ( 'NONE', *, *, #40232, .F. ) ; -#26897 = CARTESIAN_POINT ( 'NONE', ( 2.580582809155000046, 209.5994064289000107, 75.67760466619000681 ) ) ; -#26898 = CARTESIAN_POINT ( 'NONE', ( 37.30457061651406292, 191.0696620593575688, 106.2962842821977176 ) ) ; -#26899 = CARTESIAN_POINT ( 'NONE', ( 14.74167426920670465, 136.8705781667366068, 91.75623271434285755 ) ) ; -#26900 = ORIENTED_EDGE ( 'NONE', *, *, #3256, .T. ) ; -#26901 = ORIENTED_EDGE ( 'NONE', *, *, #32667, .F. ) ; -#26902 = CARTESIAN_POINT ( 'NONE', ( -5.674480817841737412, 181.6879534348617824, 101.6022789869470131 ) ) ; -#26903 = VERTEX_POINT ( 'NONE', #11971 ) ; -#26904 = VERTEX_POINT ( 'NONE', #27536 ) ; -#26905 = CARTESIAN_POINT ( 'NONE', ( 3.882702609227124846, 148.9606115484772602, 129.9617790688552077 ) ) ; -#26906 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #25305, #21826 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26907 = CARTESIAN_POINT ( 'NONE', ( 47.95588724831284111, 89.52656283054035669, 291.5279987808671081 ) ) ; -#26908 = ORIENTED_EDGE ( 'NONE', *, *, #4825, .F. ) ; -#26909 = EDGE_CURVE ( 'NONE', #12627, #21765, #16627, .T. ) ; -#26910 = ORIENTED_EDGE ( 'NONE', *, *, #21824, .F. ) ; -#26911 = EDGE_CURVE ( 'NONE', #24195, #31968, #8847, .T. ) ; -#26912 = ORIENTED_EDGE ( 'NONE', *, *, #39528, .T. ) ; -#26913 = DIRECTION ( 'NONE', ( -0.6772239534962611884, 0.7357769477300126759, 0.000000000000000000 ) ) ; -#26914 = EDGE_CURVE ( 'NONE', #22883, #2849, #22681, .T. ) ; -#26915 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#26916 = CARTESIAN_POINT ( 'NONE', ( -36.17829791151999785, 192.0984349645000009, 104.5680916760999963 ) ) ; -#26917 = CARTESIAN_POINT ( 'NONE', ( 36.26754167136000007, 191.5402796886000090, 103.9582622207999947 ) ) ; -#26919 = EDGE_CURVE ( 'NONE', #27687, #20220, #12844, .T. ) ; -#26918 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23105, #32899, #38426, #17341 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26920 = CARTESIAN_POINT ( 'NONE', ( -25.52832686761000147, 121.2413356678000014, 88.17240013551000288 ) ) ; -#26921 = PLANE ( 'NONE', #1471 ) ; -#26922 = DIRECTION ( 'NONE', ( 0.5988683521957514078, -0.8008474865655416108, 6.245004513516477772E-14 ) ) ; -#26923 = CARTESIAN_POINT ( 'NONE', ( 3.666638747417580557, 185.7959654145790864, 103.0582394725906568 ) ) ; -#26924 = CARTESIAN_POINT ( 'NONE', ( -25.05644770639884200, 131.0181980617547026, 89.91603302966900912 ) ) ; -#26925 = ORIENTED_EDGE ( 'NONE', *, *, #8352, .T. ) ; -#26926 = EDGE_CURVE ( 'NONE', #22589, #36851, #2364, .T. ) ; -#26927 = CARTESIAN_POINT ( 'NONE', ( -16.15249828763665363, 151.1189587783885884, 184.8292094970151425 ) ) ; -#26928 = LINE ( 'NONE', #36094, #8401 ) ; -#26929 = VECTOR ( 'NONE', #594, 1000.000000000000114 ) ; -#26930 = PLANE ( 'NONE', #16989 ) ; -#26931 = DIRECTION ( 'NONE', ( -0.0001408404346091657539, 0.2255194953558361803, -0.9742386449830560124 ) ) ; -#26932 = ORIENTED_EDGE ( 'NONE', *, *, #21557, .F. ) ; -#26934 = ADVANCED_FACE ( 'NONE', ( #18278 ), #26157, .T. ) ; -#26933 = CARTESIAN_POINT ( 'NONE', ( -20.89282324149344561, 183.0959377177359215, 101.9365769416837253 ) ) ; -#26935 = AXIS2_PLACEMENT_3D ( 'NONE', #13558, #31778, #268 ) ; -#26936 = CARTESIAN_POINT ( 'NONE', ( 13.88399914228467757, 136.0347715473272672, 91.56378953181273062 ) ) ; -#26937 = CARTESIAN_POINT ( 'NONE', ( -8.573576785595708571, 209.7096749608995196, 76.06368285521188000 ) ) ; -#26938 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7981, #20242, #20445, #36189 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999992929598529035 ), - .UNSPECIFIED. ) ; -#26939 = ORIENTED_EDGE ( 'NONE', *, *, #13099, .F. ) ; -#26940 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7154541036601359538, -0.6986597351757660723 ) ) ; -#26941 = VERTEX_POINT ( 'NONE', #35707 ) ; -#26942 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #30194, #17084, #35681, #11372 ), - .UNSPECIFIED., .F., .F. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.0003551482881305434674, 1.571423989884809469 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8046736173937256709, 0.8046736173937256709, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#26943 = CARTESIAN_POINT ( 'NONE', ( -1.458415328224369478, 144.9404864464127058, 129.0359332379569253 ) ) ; -#26944 = CARTESIAN_POINT ( 'NONE', ( 16.57214424012681064, 121.8478803258931720, 177.5755000349597026 ) ) ; -#26945 = CARTESIAN_POINT ( 'NONE', ( 26.14938448941000004, 192.1174886745999970, 103.7633825134000034 ) ) ; -#26946 = CARTESIAN_POINT ( 'NONE', ( 6.032339368669187962, 135.0240263800323817, 90.96470306000986739 ) ) ; -#26947 = ORIENTED_EDGE ( 'NONE', *, *, #32073, .T. ) ; -#26948 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#26949 = CARTESIAN_POINT ( 'NONE', ( 3.062737380639022344, 196.5784460000043055, 103.8732377138169483 ) ) ; -#26950 = LINE ( 'NONE', #14875, #30319 ) ; -#26951 = CARTESIAN_POINT ( 'NONE', ( 22.50046737220517201, 154.0096474681598124, 95.53736714637915384 ) ) ; -#26952 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1863, #23742, #26215, #7581 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26953 = CARTESIAN_POINT ( 'NONE', ( 19.01970210477341894, 125.1712956467094529, 177.2425045390261573 ) ) ; -#26954 = PLANE ( 'NONE', #18931 ) ; -#26955 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#26956 = AXIS2_PLACEMENT_3D ( 'NONE', #21434, #18326, #3194 ) ; -#26957 = CARTESIAN_POINT ( 'NONE', ( -20.49852829818812694, 127.1805961891525385, 91.59301651659605170 ) ) ; -#26958 = CARTESIAN_POINT ( 'NONE', ( -38.41439781631743955, 118.8735558289109235, 87.72267610939334759 ) ) ; -#26959 = EDGE_LOOP ( 'NONE', ( #36023, #4822, #14099, #1813 ) ) ; -#26960 = CONICAL_SURFACE ( 'NONE', #9319, 2.502999999946897702, 0.7853981633984010724 ) ; -#26961 = CARTESIAN_POINT ( 'NONE', ( 3.697220241243522221, 144.1788877089946652, 93.10421244235104155 ) ) ; -#26962 = AXIS2_PLACEMENT_3D ( 'NONE', #37196, #39842, #18560 ) ; -#26963 = CARTESIAN_POINT ( 'NONE', ( -32.41149745080540612, 136.4913485010586101, 91.18400781810954925 ) ) ; -#26964 = ORIENTED_EDGE ( 'NONE', *, *, #22278, .F. ) ; -#26965 = CARTESIAN_POINT ( 'NONE', ( 2.564209066518882807, 190.9903029846934430, 106.3100561862119378 ) ) ; -#26966 = ADVANCED_FACE ( 'NONE', ( #11767 ), #38592, .F. ) ; -#26967 = EDGE_CURVE ( 'NONE', #8977, #3835, #36641, .T. ) ; -#26968 = ORIENTED_EDGE ( 'NONE', *, *, #12007, .F. ) ; -#26969 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28814, #989, #7122, #13482 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26970 = CARTESIAN_POINT ( 'NONE', ( -17.09842820193908963, 152.0927262417674797, 183.8356208079428882 ) ) ; -#26971 = ORIENTED_EDGE ( 'NONE', *, *, #11406, .F. ) ; -#26972 = CARTESIAN_POINT ( 'NONE', ( 36.35311034930725071, 191.7638335428474647, 106.3857863246174134 ) ) ; -#26973 = DIRECTION ( 'NONE', ( 0.0006039748319385908944, 1.293414132305980107E-14, 0.9999998176071845934 ) ) ; -#26974 = LINE ( 'NONE', #36143, #19433 ) ; -#26975 = CARTESIAN_POINT ( 'NONE', ( -12.63707001172994104, 130.8324915394589709, 90.02598128956542212 ) ) ; -#26976 = DIRECTION ( 'NONE', ( 0.6087611427401034003, 0.7731004639645453480, 0.1781166575802726748 ) ) ; -#26977 = ORIENTED_EDGE ( 'NONE', *, *, #10789, .F. ) ; -#26978 = CARTESIAN_POINT ( 'NONE', ( 39.59524713850000666, 119.9028460329000154, 87.70178263936999485 ) ) ; -#26979 = DIRECTION ( 'NONE', ( -1.040834085586078261E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#26980 = AXIS2_PLACEMENT_3D ( 'NONE', #1790, #38994, #14471 ) ; -#26981 = CARTESIAN_POINT ( 'NONE', ( -20.27003028652000083, 210.4001054583000041, 73.32073907762999454 ) ) ; -#26982 = ORIENTED_EDGE ( 'NONE', *, *, #33500, .T. ) ; -#26983 = CARTESIAN_POINT ( 'NONE', ( -13.55543936442094122, 163.9606856050033343, 100.5933294418133102 ) ) ; -#26984 = ORIENTED_EDGE ( 'NONE', *, *, #6662, .T. ) ; -#26985 = ORIENTED_EDGE ( 'NONE', *, *, #36551, .T. ) ; -#26986 = CIRCLE ( 'NONE', #17165, 58.90509898899682639 ) ; -#26987 = CARTESIAN_POINT ( 'NONE', ( -38.94544030404210844, 127.6228067830301711, 91.70624984242061828 ) ) ; -#26988 = CARTESIAN_POINT ( 'NONE', ( -42.36692568814963522, 121.1167509210004170, 92.72420472768362742 ) ) ; -#26989 = CARTESIAN_POINT ( 'NONE', ( 14.89442708580793528, 182.7495487637143015, 104.5717966455644898 ) ) ; -#26990 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#26991 = EDGE_CURVE ( 'NONE', #14963, #35463, #32676, .T. ) ; -#26992 = VECTOR ( 'NONE', #30576, 1000.000000000000000 ) ; -#26993 = CARTESIAN_POINT ( 'NONE', ( -24.86074681069491632, 213.4929432232339082, 73.07351935051005398 ) ) ; -#26994 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38189, #22664, #7099, #16697, #10393, #35088 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#26995 = CARTESIAN_POINT ( 'NONE', ( -25.78537060397050595, 209.7107784368876651, 73.29872942540529834 ) ) ; -#26996 = DIRECTION ( 'NONE', ( -0.7075337269008449281, -1.092317403744933227E-14, -0.7066795775298735371 ) ) ; -#26997 = CARTESIAN_POINT ( 'NONE', ( 37.93651756058999780, 118.4146852817000024, 87.57225098144000697 ) ) ; -#26998 = CARTESIAN_POINT ( 'NONE', ( 39.06502905710053142, 190.9636352783319069, 106.2825191316666888 ) ) ; -#26999 = CARTESIAN_POINT ( 'NONE', ( 28.52919418227002879, 125.2871234584923883, 88.56050369811191558 ) ) ; -#27000 = VERTEX_POINT ( 'NONE', #2567 ) ; -#27001 = CARTESIAN_POINT ( 'NONE', ( 39.81119971704559646, 75.02554102933939362, 323.6757538848392528 ) ) ; -#27002 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250898248, 132.4055461763671246, 92.79778151964485744 ) ) ; -#27003 = CARTESIAN_POINT ( 'NONE', ( -28.47344760044883216, 181.6851202344923308, 101.6154648382260035 ) ) ; -#27004 = FACE_OUTER_BOUND ( 'NONE', #11006, .T. ) ; -#27006 = ORIENTED_EDGE ( 'NONE', *, *, #18337, .T. ) ; -#27005 = FACE_OUTER_BOUND ( 'NONE', #16383, .T. ) ; -#27007 = ORIENTED_EDGE ( 'NONE', *, *, #27909, .F. ) ; -#27008 = ORIENTED_EDGE ( 'NONE', *, *, #39113, .F. ) ; -#27009 = CARTESIAN_POINT ( 'NONE', ( 43.53526136507346678, 121.9496774062499043, 88.05073105187337035 ) ) ; -#27010 = VERTEX_POINT ( 'NONE', #29609 ) ; -#27011 = CARTESIAN_POINT ( 'NONE', ( -23.35885086855935810, 177.6508992509094185, 100.7984980571552143 ) ) ; -#27012 = VECTOR ( 'NONE', #1271, 1000.000000000000114 ) ; -#27013 = DIRECTION ( 'NONE', ( 0.0005884949961231208991, -0.2249510543439063315, 0.9743698870671262391 ) ) ; -#27014 = FACE_OUTER_BOUND ( 'NONE', #7999, .T. ) ; -#27015 = EDGE_CURVE ( 'NONE', #24627, #39281, #34655, .T. ) ; -#27016 = AXIS2_PLACEMENT_3D ( 'NONE', #9052, #2722, #36853 ) ; -#27017 = EDGE_CURVE ( 'NONE', #14571, #20733, #6856, .T. ) ; -#27018 = EDGE_LOOP ( 'NONE', ( #16784, #14762, #9756, #38101 ) ) ; -#27019 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#27020 = CONICAL_SURFACE ( 'NONE', #23735, 6.500000000009604761, 0.7853981634430725611 ) ; -#27021 = CARTESIAN_POINT ( 'NONE', ( -13.49295016813580439, 187.6291709519775850, 106.0054573042264110 ) ) ; -#27022 = CARTESIAN_POINT ( 'NONE', ( -37.61513335043999717, 118.9651505575999977, 87.16503455104999887 ) ) ; -#27023 = ORIENTED_EDGE ( 'NONE', *, *, #3115, .F. ) ; -#27024 = LINE ( 'NONE', #17986, #8788 ) ; -#27025 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13111, #10648, #4078, #13510 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27026 = ORIENTED_EDGE ( 'NONE', *, *, #37957, .T. ) ; -#27027 = CARTESIAN_POINT ( 'NONE', ( -5.668235839012000454, 187.2935674866481293, 105.4622348367114881 ) ) ; -#27028 = DIRECTION ( 'NONE', ( 0.7933530821293306445, 0.5932640870757670548, 0.1364866662427089150 ) ) ; -#27029 = CARTESIAN_POINT ( 'NONE', ( 20.24598356238904273, 184.3484679134213593, 105.0290154610982682 ) ) ; -#27030 = FACE_BOUND ( 'NONE', #3769, .T. ) ; -#27031 = CARTESIAN_POINT ( 'NONE', ( 3.168077837919118345, 126.1295738578562009, 91.84923819592059147 ) ) ; -#27032 = CARTESIAN_POINT ( 'NONE', ( -12.63742615055529228, 181.2452767761304813, 104.3838565639638460 ) ) ; -#27033 = ORIENTED_EDGE ( 'NONE', *, *, #34527, .F. ) ; -#27034 = CARTESIAN_POINT ( 'NONE', ( 76.10601358361097368, 156.3575724116847425, 95.70494597593847175 ) ) ; -#27035 = CARTESIAN_POINT ( 'NONE', ( 38.11757776978107159, 119.1971814748143146, 87.25517274288121428 ) ) ; -#27036 = CARTESIAN_POINT ( 'NONE', ( -3.668109984895000508, 181.5006555260000027, 104.6367796092000049 ) ) ; -#27037 = CARTESIAN_POINT ( 'NONE', ( -35.74942256790419037, 191.5232899416273824, 106.9256828509688120 ) ) ; -#27038 = VERTEX_POINT ( 'NONE', #92 ) ; -#27039 = LINE ( 'NONE', #7795, #37466 ) ; -#27040 = VERTEX_POINT ( 'NONE', #27726 ) ; -#27041 = ADVANCED_FACE ( 'NONE', ( #37701 ), #12360, .F. ) ; -#27042 = AXIS2_PLACEMENT_3D ( 'NONE', #24129, #15519, #25338 ) ; -#27043 = ORIENTED_EDGE ( 'NONE', *, *, #28034, .F. ) ; -#27044 = CARTESIAN_POINT ( 'NONE', ( -26.71605068641907010, 124.3153334168429325, 88.88266128990301240 ) ) ; -#27045 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6351, #39896, #21521, #18803, #11905, #36841, #33958, #2885, #21714, #12297, #37438, #8844, #31309, #3276 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000517364, 0.3750000000000776046, 0.5000000000001034728, 0.6250000000001293410, 0.6875000000001078027, 0.7500000000000863754, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27046 = ORIENTED_EDGE ( 'NONE', *, *, #23620, .F. ) ; -#27047 = CONICAL_SURFACE ( 'NONE', #887, 8.500000000041723069, 0.7853981633973075027 ) ; -#27048 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474981082756854, 150.9209598835162467, 97.06153188701080126 ) ) ; -#27049 = PLANE ( 'NONE', #4458 ) ; -#27050 = CARTESIAN_POINT ( 'NONE', ( -40.30153468720526178, 187.7974083947837585, 108.1652340796715492 ) ) ; -#27051 = CONICAL_SURFACE ( 'NONE', #8774, 5.999999999841580056, 0.7853981633778843729 ) ; -#27052 = ORIENTED_EDGE ( 'NONE', *, *, #4323, .T. ) ; -#27053 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2440, #18144, #6093, #3217 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27054 = DIRECTION ( 'NONE', ( 0.0005884949961199716171, -0.2249510543439088850, 0.9743698870671256840 ) ) ; -#27055 = EDGE_LOOP ( 'NONE', ( #6310, #15804, #33482, #19296, #14455, #20300, #5603, #26449, #22588, #34608, #24060, #29152, #9810, #10591, #33375, #4693, #19070, #25819, #17656, #11276, #26720, #38197 ) ) ; -#27056 = EDGE_CURVE ( 'NONE', #12430, #9057, #12173, .T. ) ; -#27057 = CARTESIAN_POINT ( 'NONE', ( 26.49281508937000140, 122.3671901727000062, 90.96660212795001144 ) ) ; -#27058 = LINE ( 'NONE', #23161, #3206 ) ; -#27060 = CARTESIAN_POINT ( 'NONE', ( -28.46611168752988874, 181.6098482732715240, 104.1638139686604063 ) ) ; -#27059 = CARTESIAN_POINT ( 'NONE', ( 1.752039179668189783, 151.6655327357930219, 130.5892088565730091 ) ) ; -#27061 = ORIENTED_EDGE ( 'NONE', *, *, #20396, .T. ) ; -#27062 = ADVANCED_FACE ( 'NONE', ( #34028 ), #24658, .F. ) ; -#27063 = ORIENTED_EDGE ( 'NONE', *, *, #16853, .T. ) ; -#27064 = EDGE_CURVE ( 'NONE', #11505, #33548, #37572, .T. ) ; -#27065 = ADVANCED_FACE ( 'NONE', ( #12764 ), #27253, .T. ) ; -#27066 = EDGE_LOOP ( 'NONE', ( #27734, #17044, #37385, #38878, #30911 ) ) ; -#27067 = EDGE_CURVE ( 'NONE', #5068, #29516, #4351, .T. ) ; -#27068 = CARTESIAN_POINT ( 'NONE', ( -36.29655452800435000, 116.7398215997537250, 87.28970650145031129 ) ) ; -#27069 = EDGE_CURVE ( 'NONE', #19402, #22354, #455, .T. ) ; -#27070 = CARTESIAN_POINT ( 'NONE', ( 45.36150865113177844, 124.3281719932639078, 88.32935533049811738 ) ) ; -#27071 = CARTESIAN_POINT ( 'NONE', ( -32.80403412233768279, 153.0051697192221525, 292.8436197697606076 ) ) ; -#27072 = ORIENTED_EDGE ( 'NONE', *, *, #38885, .F. ) ; -#27073 = AXIS2_PLACEMENT_3D ( 'NONE', #4267, #20414, #10636 ) ; -#27074 = CIRCLE ( 'NONE', #12031, 4.499999999969424458 ) ; -#27075 = ORIENTED_EDGE ( 'NONE', *, *, #20420, .T. ) ; -#27076 = ORIENTED_EDGE ( 'NONE', *, *, #2587, .T. ) ; -#27077 = CARTESIAN_POINT ( 'NONE', ( -28.94810864222802849, 110.6131156702000027, 87.28526822420690223 ) ) ; -#27078 = CIRCLE ( 'NONE', #12067, 2.499999998777807875 ) ; -#27079 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #664, #25638, #37886, #25835 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27080 = CARTESIAN_POINT ( 'NONE', ( 26.02916777764000500, 122.7390752681000095, 88.31594180099000369 ) ) ; -#27081 = ORIENTED_EDGE ( 'NONE', *, *, #27909, .T. ) ; -#27082 = FACE_OUTER_BOUND ( 'NONE', #39141, .T. ) ; -#27083 = CARTESIAN_POINT ( 'NONE', ( 3.075509731022991744, 190.8879536221248543, 106.8135930214097016 ) ) ; -#27084 = EDGE_LOOP ( 'NONE', ( #19136, #7884, #32017, #2165 ) ) ; -#27085 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421484904, 126.1293544849782222, 91.84293499097150004 ) ) ; -#27086 = CARTESIAN_POINT ( 'NONE', ( -6.037299711039155525, 177.1908694358191099, 101.0774571033729785 ) ) ; -#27087 = CARTESIAN_POINT ( 'NONE', ( 3.667815737396929343, 128.0237491602000262, 91.77307785488999059 ) ) ; -#27088 = CARTESIAN_POINT ( 'NONE', ( 3.751221408336166352, 145.8377404464781932, 93.31995143763465705 ) ) ; -#27089 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6108, #34113, #3429, #28598, #6910, #9799, #9590, #15711, #31464, #3633, #37787 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999659717, 0.1874999999999533429, 0.2499999999999407141, 0.4999999999999737987, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27090 = VERTEX_POINT ( 'NONE', #34611 ) ; -#27091 = CARTESIAN_POINT ( 'NONE', ( 5.958856854324413810, 148.4719693777741725, 97.00569074539359349 ) ) ; -#27092 = PLANE ( 'NONE', #18207 ) ; -#27093 = AXIS2_PLACEMENT_3D ( 'NONE', #555, #31864, #7698 ) ; -#27094 = AXIS2_PLACEMENT_3D ( 'NONE', #37771, #3614, #22258 ) ; -#27095 = CONICAL_SURFACE ( 'NONE', #30999, 48.00000000000466116, 0.7853981633973027288 ) ; -#27096 = ORIENTED_EDGE ( 'NONE', *, *, #18611, .F. ) ; -#27097 = EDGE_CURVE ( 'NONE', #3459, #3422, #31580, .T. ) ; -#27098 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049120382, 153.7268358530341743, 98.24418217438510226 ) ) ; -#27099 = AXIS2_PLACEMENT_3D ( 'NONE', #15660, #9540, #33458 ) ; -#27100 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #8694, #39943, #11139, #17847 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.1794079282370794892, 1.009264216782575829 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9434301930918600476, 0.9434301930918600476, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#27101 = CARTESIAN_POINT ( 'NONE', ( 15.50029467954679596, 184.8540555714758966, 102.8336351796044426 ) ) ; -#27102 = VERTEX_POINT ( 'NONE', #37107 ) ; -#27104 = EDGE_LOOP ( 'NONE', ( #20833, #32736, #11033, #17493 ) ) ; -#27103 = EDGE_CURVE ( 'NONE', #13591, #3287, #11731, .T. ) ; -#27105 = DIRECTION ( 'NONE', ( 0.0006039760799765779781, 0.000000000000000000, 0.9999998176064307520 ) ) ; -#27106 = ORIENTED_EDGE ( 'NONE', *, *, #22890, .F. ) ; -#27107 = DIRECTION ( 'NONE', ( -0.7933535320750288999, 0.5931614265262136199, 0.1369295264925108890 ) ) ; -#27108 = EDGE_CURVE ( 'NONE', #5671, #5625, #21980, .T. ) ; -#27109 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#27110 = LINE ( 'NONE', #8281, #15702 ) ; -#27111 = CARTESIAN_POINT ( 'NONE', ( 12.64218737472634402, 177.6868538132959827, 100.7583657957452630 ) ) ; -#27112 = ORIENTED_EDGE ( 'NONE', *, *, #21723, .T. ) ; -#27113 = VERTEX_POINT ( 'NONE', #37910 ) ; -#27114 = CARTESIAN_POINT ( 'NONE', ( -37.46813412068708260, 187.1458312067469762, 105.9604857125427060 ) ) ; -#27115 = VERTEX_POINT ( 'NONE', #34418 ) ; -#27116 = VERTEX_POINT ( 'NONE', #27930 ) ; -#27117 = EDGE_CURVE ( 'NONE', #34711, #25492, #6356, .T. ) ; -#27118 = LINE ( 'NONE', #29363, #15212 ) ; -#27119 = CARTESIAN_POINT ( 'NONE', ( -16.85990575226742649, 148.9750591898919652, 176.9023370295861355 ) ) ; -#27120 = CARTESIAN_POINT ( 'NONE', ( 3.036536040797000346, 209.1865194081000254, 73.08174489113000050 ) ) ; -#27121 = ORIENTED_EDGE ( 'NONE', *, *, #19586, .F. ) ; -#27122 = ORIENTED_EDGE ( 'NONE', *, *, #26318, .F. ) ; -#27123 = EDGE_LOOP ( 'NONE', ( #36812, #33633, #8109, #36489 ) ) ; -#27124 = CARTESIAN_POINT ( 'NONE', ( -35.93638238082320413, 190.3639747180721713, 106.7025276796284317 ) ) ; -#27125 = CARTESIAN_POINT ( 'NONE', ( -36.02452622425000328, 191.9021276050999916, 104.3034201498000186 ) ) ; -#27126 = CARTESIAN_POINT ( 'NONE', ( 36.40864326631000125, 191.7024945688000059, 104.2333916175000041 ) ) ; -#27127 = ORIENTED_EDGE ( 'NONE', *, *, #1588, .F. ) ; -#27128 = CARTESIAN_POINT ( 'NONE', ( -25.83460698300319081, 120.7121441152833512, 87.70047778154363982 ) ) ; -#27129 = VECTOR ( 'NONE', #8053, 1000.000000000000114 ) ; -#27130 = ORIENTED_EDGE ( 'NONE', *, *, #6117, .F. ) ; -#27131 = LINE ( 'NONE', #30377, #8196 ) ; -#27132 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; -#27133 = CARTESIAN_POINT ( 'NONE', ( -23.35927170582755252, 176.8628753195245338, 103.2348938219602417 ) ) ; -#27134 = ORIENTED_EDGE ( 'NONE', *, *, #20094, .T. ) ; -#27135 = CIRCLE ( 'NONE', #34921, 5.999999999985974775 ) ; -#27136 = CARTESIAN_POINT ( 'NONE', ( -20.51847108333184977, 208.9445514787146010, 75.69061570010751439 ) ) ; -#27137 = CYLINDRICAL_SURFACE ( 'NONE', #3925, 2.000000000000014655 ) ; -#27138 = CARTESIAN_POINT ( 'NONE', ( -20.00100377755662961, 193.8169056301028945, 102.7149817412491473 ) ) ; -#27139 = ORIENTED_EDGE ( 'NONE', *, *, #19773, .F. ) ; -#27140 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971541810 ) ) ; -#27141 = CARTESIAN_POINT ( 'NONE', ( -35.45366962857106330, 209.7096538831000032, 78.07991812242501339 ) ) ; -#27142 = CARTESIAN_POINT ( 'NONE', ( -28.46737701145232791, 131.0177980776269067, 89.91795667690330163 ) ) ; -#27143 = ORIENTED_EDGE ( 'NONE', *, *, #15969, .T. ) ; -#27144 = CARTESIAN_POINT ( 'NONE', ( 30.03671969012000176, 185.1161778121999930, 105.1945559053000068 ) ) ; -#27145 = ORIENTED_EDGE ( 'NONE', *, *, #8299, .F. ) ; -#27146 = VERTEX_POINT ( 'NONE', #15820 ) ; -#27147 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#27148 = FACE_OUTER_BOUND ( 'NONE', #22519, .T. ) ; -#27149 = CARTESIAN_POINT ( 'NONE', ( -20.89285664280696864, 129.6089482465050366, 89.58812326051432251 ) ) ; -#27150 = CARTESIAN_POINT ( 'NONE', ( 77.77061555252048208, 193.1292924429064328, 190.4585453522111322 ) ) ; -#27151 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -2.074124140377000483E-15, -0.0006039748319395083463 ) ) ; -#27152 = ADVANCED_FACE ( 'NONE', ( #31178 ), #9601, .F. ) ; -#27153 = EDGE_LOOP ( 'NONE', ( #32177, #5061, #39918, #31755 ) ) ; -#27154 = EDGE_CURVE ( 'NONE', #20460, #16454, #4552, .T. ) ; -#27155 = EDGE_CURVE ( 'NONE', #12177, #39651, #8330, .T. ) ; -#27156 = EDGE_CURVE ( 'NONE', #12519, #21533, #38105, .T. ) ; -#27157 = AXIS2_PLACEMENT_3D ( 'NONE', #15413, #70, #36672 ) ; -#27158 = CARTESIAN_POINT ( 'NONE', ( -13.46986788395000012, 176.3366685932843154, 152.9217693939943388 ) ) ; -#27159 = CONICAL_SURFACE ( 'NONE', #17980, 4.999999999985747401, 0.7853981633878592827 ) ; -#27160 = VECTOR ( 'NONE', #9073, 1000.000000000000114 ) ; -#27161 = CARTESIAN_POINT ( 'NONE', ( -15.83167356403315473, 184.3257607663358044, 105.1253098898049387 ) ) ; -#27163 = AXIS2_PLACEMENT_3D ( 'NONE', #33529, #5524, #30491 ) ; -#27162 = CARTESIAN_POINT ( 'NONE', ( -2.853038766185818087, 209.7096500570610544, 73.06022702708840200 ) ) ; -#27164 = EDGE_CURVE ( 'NONE', #16454, #14577, #878, .T. ) ; -#27165 = CARTESIAN_POINT ( 'NONE', ( 20.33352780025000683, 184.8935324260419009, 102.6687779362811028 ) ) ; -#27166 = CARTESIAN_POINT ( 'NONE', ( 30.39240633519054668, 177.7944416303146511, 100.6816479718193165 ) ) ; -#27167 = AXIS2_PLACEMENT_3D ( 'NONE', #9816, #22289, #6721 ) ; -#27168 = CARTESIAN_POINT ( 'NONE', ( -14.42530067724887211, 135.8540152427108865, 91.19705531837325907 ) ) ; -#27169 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12240, #27405, #11843, #15108, #24728, #8776, #21240, #34094, #33689, #37372, #5696, #9373, #33896, #21847, #18739, #40033, #3216, #15692, #8980, #18142, #18348, #27603, #30647, #2643, #12040, #24522, #36980, #28978, #3609, #4213, #9776, #25732, #15887, #38182, #19562, #16689, #7088 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 1, 1, 2, 2, 2, 1, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000004381218, 0.1875000000006571965, 0.2500000000008762435, 0.3750000000013145041, 0.4375000000015357715, 0.4687500000016565083, 0.4843750000017174595, 0.4921875000018005597, 0.4960937500018024471, 0.5000000000018044455, 0.6250000000013739010, 0.6875000000011586287, 0.7187500000010510481, 0.7500000000009433565, 0.8125000000007281953, 0.8750000000005129230, 0.9375000000002976508, 0.9687500000001487699, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27170 = CARTESIAN_POINT ( 'NONE', ( 20.00140612192502942, 118.1043503129110093, 90.25575274657424529 ) ) ; -#27171 = ORIENTED_EDGE ( 'NONE', *, *, #32975, .F. ) ; -#27172 = ADVANCED_FACE ( 'NONE', ( #13369 ), #21362, .F. ) ; -#27173 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#27174 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#27175 = ORIENTED_EDGE ( 'NONE', *, *, #7047, .T. ) ; -#27176 = CARTESIAN_POINT ( 'NONE', ( 2.564136881974701687, 190.9806058647903910, 106.3073107177100383 ) ) ; -#27177 = CARTESIAN_POINT ( 'NONE', ( 15.99994032177352921, 147.4776376511197782, 93.69121532839281485 ) ) ; -#27178 = EDGE_LOOP ( 'NONE', ( #546, #37528, #40116, #19962 ) ) ; -#27179 = ADVANCED_FACE ( 'NONE', ( #29314 ), #25931, .F. ) ; -#27180 = DIRECTION ( 'NONE', ( -0.0005884949961217841863, 0.2249510543439048882, -0.9743698870671267942 ) ) ; -#27181 = ORIENTED_EDGE ( 'NONE', *, *, #27155, .F. ) ; -#27182 = CARTESIAN_POINT ( 'NONE', ( 35.75412536925829698, 191.7929377062473861, 106.8971639774647144 ) ) ; -#27183 = CARTESIAN_POINT ( 'NONE', ( -35.45668950273073250, 209.7096538831000032, 73.07991903442916737 ) ) ; -#27184 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; -#27185 = CIRCLE ( 'NONE', #7559, 2.000000000024883651 ) ; -#27186 = CARTESIAN_POINT ( 'NONE', ( -12.63088703835403237, 131.0198726340251199, 89.90887950976862442 ) ) ; -#27187 = CARTESIAN_POINT ( 'NONE', ( -22.49962777877401265, 154.4034663070004285, 95.31336199324331915 ) ) ; -#27188 = CIRCLE ( 'NONE', #32384, 9.500000000010519585 ) ; -#27189 = ORIENTED_EDGE ( 'NONE', *, *, #12639, .T. ) ; -#27190 = CARTESIAN_POINT ( 'NONE', ( 39.30609899383000538, 120.4425404122000174, 87.28662907337999854 ) ) ; -#27191 = CARTESIAN_POINT ( 'NONE', ( 24.12242862685433664, 148.1961789144971817, 202.2538657011056102 ) ) ; -#27192 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -6.964038142101568045E-16, -0.0006039748319386693907 ) ) ; -#27193 = VECTOR ( 'NONE', #32474, 1000.000000000000114 ) ; -#27194 = DIRECTION ( 'NONE', ( 0.0005884949961235587000, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#27195 = ORIENTED_EDGE ( 'NONE', *, *, #32541, .T. ) ; -#27196 = CARTESIAN_POINT ( 'NONE', ( -42.81549985150758886, 107.4643023349349136, 150.2765521728149736 ) ) ; -#27197 = CARTESIAN_POINT ( 'NONE', ( -42.51147045056379170, 121.3536403223778990, 91.20814212496861728 ) ) ; -#27198 = CARTESIAN_POINT ( 'NONE', ( 20.50176505208000322, 122.6615237520999955, 91.03809521265999649 ) ) ; -#27199 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#27200 = CARTESIAN_POINT ( 'NONE', ( -8.473620765651141085, 161.4179317431856475, 97.43745832156695030 ) ) ; -#27201 = EDGE_CURVE ( 'NONE', #38073, #36559, #16419, .T. ) ; -#27202 = ADVANCED_FACE ( 'NONE', ( #10513 ), #7625, .F. ) ; -#27203 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971541255 ) ) ; -#27204 = CARTESIAN_POINT ( 'NONE', ( 33.97154681763998951, 93.67127063227000860, 291.5380259722100504 ) ) ; -#27205 = CARTESIAN_POINT ( 'NONE', ( -38.87088589341672673, 169.4517328299331780, 182.9034801424807029 ) ) ; -#27206 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; -#27207 = CARTESIAN_POINT ( 'NONE', ( 25.99865086485452537, 120.9964097819282642, 87.57144042600342004 ) ) ; -#27208 = CARTESIAN_POINT ( 'NONE', ( 15.99998384348811875, 126.8035267017516787, 88.91816380576780432 ) ) ; -#27209 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563182 ) ) ; -#27210 = CARTESIAN_POINT ( 'NONE', ( 3.784352160272999921, 140.7284765685000139, 92.39694077657001969 ) ) ; -#27211 = EDGE_CURVE ( 'NONE', #33804, #17164, #14190, .T. ) ; -#27212 = VECTOR ( 'NONE', #12061, 1000.000000000000114 ) ; -#27213 = CARTESIAN_POINT ( 'NONE', ( 38.93356763724558078, 170.2781293624805699, 164.4932373185801850 ) ) ; -#27214 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -4.437389905419016117E-16, 0.0006039748319385540316 ) ) ; -#27215 = CONICAL_SURFACE ( 'NONE', #15430, 2.503093623396721146, 0.7853981633639495197 ) ; -#27216 = EDGE_LOOP ( 'NONE', ( #28960, #8493, #39954, #39043 ) ) ; -#27218 = VERTEX_POINT ( 'NONE', #23782 ) ; -#27217 = CARTESIAN_POINT ( 'NONE', ( 42.93478411035056297, 121.9318606513537020, 87.77717731540884927 ) ) ; -#27219 = ORIENTED_EDGE ( 'NONE', *, *, #5331, .T. ) ; -#27220 = ORIENTED_EDGE ( 'NONE', *, *, #34487, .F. ) ; -#27221 = EDGE_CURVE ( 'NONE', #4804, #11374, #38307, .T. ) ; -#27222 = CARTESIAN_POINT ( 'NONE', ( -1.525667636861250287, 188.8616647511590543, 103.2559959374175236 ) ) ; -#27223 = ORIENTED_EDGE ( 'NONE', *, *, #26703, .F. ) ; -#27224 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 136.7477301991403920, 291.5295797804309359 ) ) ; -#27225 = VECTOR ( 'NONE', #11563, 1000.000000000000114 ) ; -#27226 = PLANE ( 'NONE', #26535 ) ; -#27227 = CARTESIAN_POINT ( 'NONE', ( 17.25783335673383689, 152.2632692426403196, 183.6728012514050477 ) ) ; -#27228 = DIRECTION ( 'NONE', ( -0.7857167650892391553, 0.6185862428610305885, 0.0004745532376930882020 ) ) ; -#27229 = AXIS2_PLACEMENT_3D ( 'NONE', #26571, #32877, #32294 ) ; -#27230 = ORIENTED_EDGE ( 'NONE', *, *, #5435, .T. ) ; -#27231 = DIRECTION ( 'NONE', ( -0.7075337269147008445, -1.091623643673001211E-14, -0.7066795775160008564 ) ) ; -#27232 = EDGE_CURVE ( 'NONE', #13439, #275, #5152, .T. ) ; -#27233 = FACE_OUTER_BOUND ( 'NONE', #39971, .T. ) ; -#27234 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; -#27235 = CARTESIAN_POINT ( 'NONE', ( -21.10558883492248583, 128.7602791373870730, 92.12913287932676099 ) ) ; -#27236 = CARTESIAN_POINT ( 'NONE', ( -13.00716834305086955, 131.0198804054314223, 89.90909991712500471 ) ) ; -#27237 = VERTEX_POINT ( 'NONE', #8028 ) ; -#27238 = CARTESIAN_POINT ( 'NONE', ( -23.01874678158921839, 213.5902083388722303, 75.57231541044464507 ) ) ; -#27239 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048966905, 181.0091974213203230, 104.5428127881150999 ) ) ; -#27240 = CARTESIAN_POINT ( 'NONE', ( -13.50000077923909636, 138.1929969156116726, 91.56544231091193353 ) ) ; -#27241 = CARTESIAN_POINT ( 'NONE', ( -20.49852807266789867, 190.9630690214611946, 106.3183227610936541 ) ) ; -#27242 = VERTEX_POINT ( 'NONE', #23992 ) ; -#27243 = CARTESIAN_POINT ( 'NONE', ( -26.33557301288999852, 190.3678653649000125, 103.4797773831000001 ) ) ; -#27244 = CARTESIAN_POINT ( 'NONE', ( 0.8401941610674000804, 188.8905993856999999, 103.5322243624000009 ) ) ; -#27245 = CARTESIAN_POINT ( 'NONE', ( 27.17743447187414318, 123.4215292580052221, 91.20952440399904049 ) ) ; -#27246 = AXIS2_PLACEMENT_3D ( 'NONE', #9919, #38499, #29514 ) ; -#27247 = ORIENTED_EDGE ( 'NONE', *, *, #19761, .T. ) ; -#27248 = ORIENTED_EDGE ( 'NONE', *, *, #35275, .F. ) ; -#27249 = LINE ( 'NONE', #21302, #40083 ) ; -#27250 = AXIS2_PLACEMENT_3D ( 'NONE', #3693, #19027, #25603 ) ; -#27251 = ORIENTED_EDGE ( 'NONE', *, *, #35017, .F. ) ; -#27252 = VECTOR ( 'NONE', #31915, 1000.000000000000114 ) ; -#27253 = CONICAL_SURFACE ( 'NONE', #36358, 5.999999999818071750, 0.7853981634251957500 ) ; -#27254 = VERTEX_POINT ( 'NONE', #14378 ) ; -#27255 = ORIENTED_EDGE ( 'NONE', *, *, #7499, .T. ) ; -#27256 = EDGE_CURVE ( 'NONE', #31088, #8695, #32775, .T. ) ; -#27257 = ADVANCED_FACE ( 'NONE', ( #4752 ), #20487, .T. ) ; -#27258 = CARTESIAN_POINT ( 'NONE', ( 23.36440065337908223, 177.7945738895225247, 100.6859232455937416 ) ) ; -#27259 = LINE ( 'NONE', #24182, #27364 ) ; -#27260 = CARTESIAN_POINT ( 'NONE', ( 39.00196056141868439, 77.94040643632342835, 289.0507669139796008 ) ) ; -#27261 = EDGE_LOOP ( 'NONE', ( #14735, #2976, #10611, #27922, #13481 ) ) ; -#27262 = DIRECTION ( 'NONE', ( -0.9914446601362026934, 0.1270323331361944419, 0.03000453674670350637 ) ) ; -#27263 = CARTESIAN_POINT ( 'NONE', ( 27.65309753470299725, 123.9773721635429951, 91.33935050507260200 ) ) ; -#27264 = CARTESIAN_POINT ( 'NONE', ( -21.57450310159030238, 182.6228315559495741, 101.9988072502208212 ) ) ; -#27266 = DIRECTION ( 'NONE', ( -0.0005884949961210389057, 0.2249510543439053878, -0.9743698870671265722 ) ) ; -#27265 = CARTESIAN_POINT ( 'NONE', ( 30.80382538193063269, 110.6131156702000027, 87.74917964457411301 ) ) ; -#27267 = ORIENTED_EDGE ( 'NONE', *, *, #36545, .F. ) ; -#27268 = CARTESIAN_POINT ( 'NONE', ( 3.683263386174287390, 143.5730025742587941, 95.72479304125442923 ) ) ; -#27269 = VERTEX_POINT ( 'NONE', #14792 ) ; -#27270 = AXIS2_PLACEMENT_3D ( 'NONE', #27077, #4963, #23996 ) ; -#27271 = CONICAL_SURFACE ( 'NONE', #20047, 6.500000265539895850, 0.7853981634182136684 ) ; -#27272 = ORIENTED_EDGE ( 'NONE', *, *, #28303, .F. ) ; -#27273 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#27274 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22391, #26261, #31795, #35221, #35612, #13772, #31990, #29122, #20090, #10519, #17014, #1493, #32581, #16230, #19691, #10115, #4356 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999995810573, 0.1874999999994061417, 0.2187499999993340605, 0.2343749999993136601, 0.2499999999992932320, 0.3749999999992274513, 0.4374999999992445487, 0.4687499999992961186, 0.4999999999993476330, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27275 = CARTESIAN_POINT ( 'NONE', ( 0.05451946023377000211, 104.1131156707999992, 90.26775191081999594 ) ) ; -#27276 = LINE ( 'NONE', #25008, #7168 ) ; -#27277 = CARTESIAN_POINT ( 'NONE', ( 12.63590952075130680, 130.8251385450179498, 90.01817474871077707 ) ) ; -#27278 = ORIENTED_EDGE ( 'NONE', *, *, #10016, .T. ) ; -#27279 = ORIENTED_EDGE ( 'NONE', *, *, #14827, .T. ) ; -#27280 = ORIENTED_EDGE ( 'NONE', *, *, #15367, .T. ) ; -#27281 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25366, #37816, #13088, #34727 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27282 = DIRECTION ( 'NONE', ( -0.6075493383219883192, 0.7739051213223903103, 0.1787586772592882622 ) ) ; -#27283 = DIRECTION ( 'NONE', ( 0.6087614810001779064, -0.7729390313185916517, -0.1788147452386051328 ) ) ; -#27284 = CARTESIAN_POINT ( 'NONE', ( 27.64719006305000093, 124.9731607461000209, 88.83074499660999379 ) ) ; -#27285 = ORIENTED_EDGE ( 'NONE', *, *, #23671, .T. ) ; -#27286 = CARTESIAN_POINT ( 'NONE', ( 2.563067459505968149, 191.9759150222000130, 104.4198997672286708 ) ) ; -#27287 = CARTESIAN_POINT ( 'NONE', ( 16.00175042068614317, 126.1291850884666559, 91.84138073825745607 ) ) ; -#27288 = EDGE_CURVE ( 'NONE', #19255, #32274, #17819, .T. ) ; -#27289 = CARTESIAN_POINT ( 'NONE', ( 0.7279486067032001628, 188.9986663015000090, 105.7364963328000158 ) ) ; -#27290 = CARTESIAN_POINT ( 'NONE', ( -20.51978786315646630, 209.7094320854081104, 73.57086927696296641 ) ) ; -#27291 = EDGE_CURVE ( 'NONE', #30592, #21265, #17626, .T. ) ; -#27292 = CARTESIAN_POINT ( 'NONE', ( 13.49904929520333496, 124.5822511035611200, 88.69986977077229540 ) ) ; -#27293 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#27294 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394469186868, 3.303562273565746580E-12, 297.5584364845187224 ) ) ; -#27295 = CIRCLE ( 'NONE', #22703, 6.499999999995704769 ) ; -#27296 = VERTEX_POINT ( 'NONE', #14985 ) ; -#27297 = CARTESIAN_POINT ( 'NONE', ( -20.50092100153493746, 194.2771564787859120, 102.9104786413515740 ) ) ; -#27298 = EDGE_CURVE ( 'NONE', #10469, #32129, #36854, .T. ) ; -#27299 = EDGE_CURVE ( 'NONE', #28855, #7552, #24419, .T. ) ; -#27300 = CARTESIAN_POINT ( 'NONE', ( 25.12855288015667909, 121.2316270687496882, 173.3448655832455927 ) ) ; -#27301 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24358, #11459, #15337, #23947 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27302 = AXIS2_PLACEMENT_3D ( 'NONE', #11293, #30112, #20903 ) ; -#27303 = CARTESIAN_POINT ( 'NONE', ( -20.23987729197799723, 127.1213856368363935, 91.84448901990914749 ) ) ; -#27304 = EDGE_CURVE ( 'NONE', #27296, #9728, #20707, .T. ) ; -#27305 = ORIENTED_EDGE ( 'NONE', *, *, #37287, .F. ) ; -#27306 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825843381894153, 0.0005734119041516987309 ) ) ; -#27307 = VERTEX_POINT ( 'NONE', #26861 ) ; -#27309 = FACE_OUTER_BOUND ( 'NONE', #5744, .T. ) ; -#27308 = CARTESIAN_POINT ( 'NONE', ( -13.49852954174943775, 184.4003819578410628, 104.7990195063615886 ) ) ; -#27310 = ORIENTED_EDGE ( 'NONE', *, *, #37797, .F. ) ; -#27311 = ORIENTED_EDGE ( 'NONE', *, *, #5138, .T. ) ; -#27312 = EDGE_LOOP ( 'NONE', ( #25919, #17193 ) ) ; -#27313 = CARTESIAN_POINT ( 'NONE', ( 2.858838700789999798, 209.5740437366000322, 75.93782419666000294 ) ) ; -#27314 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#27315 = CARTESIAN_POINT ( 'NONE', ( -15.91639284609066429, 147.2972547718010503, 179.5564254920589633 ) ) ; -#27316 = LINE ( 'NONE', #37493, #29292 ) ; -#27317 = VERTEX_POINT ( 'NONE', #26656 ) ; -#27318 = ORIENTED_EDGE ( 'NONE', *, *, #36781, .T. ) ; -#27319 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501099925, 179.0628333272265138, 104.0826189413126741 ) ) ; -#27320 = ORIENTED_EDGE ( 'NONE', *, *, #34798, .F. ) ; -#27321 = ORIENTED_EDGE ( 'NONE', *, *, #5103, .F. ) ; -#27322 = DIRECTION ( 'NONE', ( 0.0005884949961243941862, -0.2249510543439062205, 0.9743698870671264611 ) ) ; -#27323 = FACE_OUTER_BOUND ( 'NONE', #16621, .T. ) ; -#27324 = CARTESIAN_POINT ( 'NONE', ( -30.05378917699556141, 127.2828694753868319, 89.56979070794703546 ) ) ; -#27325 = CARTESIAN_POINT ( 'NONE', ( 5.666342391617226859, 126.8038441147938897, 88.92139996541325786 ) ) ; -#27326 = ORIENTED_EDGE ( 'NONE', *, *, #11539, .F. ) ; -#27327 = VECTOR ( 'NONE', #25162, 1000.000000000000000 ) ; -#27328 = VERTEX_POINT ( 'NONE', #29918 ) ; -#27329 = DIRECTION ( 'NONE', ( -8.673617379883985182E-16, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#27330 = CARTESIAN_POINT ( 'NONE', ( -35.83302225680999697, 192.4812670013000400, 104.2666808249000070 ) ) ; -#27331 = ORIENTED_EDGE ( 'NONE', *, *, #3306, .T. ) ; -#27332 = CARTESIAN_POINT ( 'NONE', ( -25.50236185757985652, 120.6126476325595149, 88.02435165278710372 ) ) ; -#27333 = AXIS2_PLACEMENT_3D ( 'NONE', #13609, #29550, #10552 ) ; -#27334 = EDGE_LOOP ( 'NONE', ( #11600, #8318, #31195, #23994 ) ) ; -#27335 = DIRECTION ( 'NONE', ( 0.7933530821293333091, 0.5932640870757639462, 0.1364866662427067501 ) ) ; -#27336 = LINE ( 'NONE', #11783, #2334 ) ; -#27337 = CARTESIAN_POINT ( 'NONE', ( 40.92065053834265598, 188.7133225016582401, 107.4565697015391237 ) ) ; -#27338 = ORIENTED_EDGE ( 'NONE', *, *, #14679, .F. ) ; -#27339 = EDGE_CURVE ( 'NONE', #30846, #11409, #29718, .T. ) ; -#27340 = CARTESIAN_POINT ( 'NONE', ( 2.617027381767905947, 189.6880601662373067, 103.4442823028655312 ) ) ; -#27341 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364886960122, 136.5649596138813706, 181.4686487119530511 ) ) ; -#27342 = CARTESIAN_POINT ( 'NONE', ( -18.71851310314255556, 125.9964326179262883, 174.7342168340691444 ) ) ; -#27343 = ORIENTED_EDGE ( 'NONE', *, *, #15186, .T. ) ; -#27344 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319390009397 ) ) ; -#27345 = EDGE_CURVE ( 'NONE', #29247, #36212, #3715, .T. ) ; -#27346 = CARTESIAN_POINT ( 'NONE', ( -45.17838929977841644, 181.0906312430929574, 102.0014284585363669 ) ) ; -#27347 = CARTESIAN_POINT ( 'NONE', ( -2.464592264399565469, 152.1442425547639630, 99.91119810786710786 ) ) ; -#27348 = EDGE_CURVE ( 'NONE', #33558, #17622, #24406, .T. ) ; -#27349 = ORIENTED_EDGE ( 'NONE', *, *, #37295, .T. ) ; -#27350 = CARTESIAN_POINT ( 'NONE', ( 23.39899582248410326, 115.1133771340589078, 90.25365243206073274 ) ) ; -#27351 = ORIENTED_EDGE ( 'NONE', *, *, #35445, .F. ) ; -#27352 = FACE_OUTER_BOUND ( 'NONE', #20030, .T. ) ; -#27353 = ADVANCED_FACE ( 'NONE', ( #11715 ), #21372, .F. ) ; -#27354 = DIRECTION ( 'NONE', ( 0.0005884949961234757585, -0.2249510543439061094, 0.9743698870671263501 ) ) ; -#27355 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #12251, #14724, #18360, #30460 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.7409400382494353288, 1.570796326794934972 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9434301930918597145, 0.9434301930918597145, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#27356 = CARTESIAN_POINT ( 'NONE', ( 35.93444066825000505, 112.3658808786999970, 89.86862849967999978 ) ) ; -#27357 = EDGE_CURVE ( 'NONE', #3915, #34342, #10921, .T. ) ; -#27358 = CIRCLE ( 'NONE', #20815, 22.50000000000000000 ) ; -#27359 = EDGE_CURVE ( 'NONE', #9444, #19947, #34577, .T. ) ; -#27360 = CARTESIAN_POINT ( 'NONE', ( 16.16793458963470442, 152.6396212324820283, 181.6320889425181520 ) ) ; -#27361 = CARTESIAN_POINT ( 'NONE', ( 39.06349078196001301, 191.0388279120988670, 103.7341189576915355 ) ) ; -#27362 = ORIENTED_EDGE ( 'NONE', *, *, #7322, .T. ) ; -#27363 = AXIS2_PLACEMENT_3D ( 'NONE', #25219, #12727, #34575 ) ; -#27364 = VECTOR ( 'NONE', #36631, 1000.000000000000114 ) ; -#27365 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7787, #32738, #17179, #14149 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.1624460549302637891 ), - .UNSPECIFIED. ) ; -#27366 = AXIS2_PLACEMENT_3D ( 'NONE', #17006, #13968, #25655 ) ; -#27367 = CARTESIAN_POINT ( 'NONE', ( -22.78369572533183884, 164.5218417749696584, 98.16269547346880131 ) ) ; -#27368 = PLANE ( 'NONE', #9967 ) ; -#27369 = CARTESIAN_POINT ( 'NONE', ( 25.99899579568001329, 120.3902236066962388, 87.43149108637626910 ) ) ; -#27370 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567623 ) ) ; -#27371 = CARTESIAN_POINT ( 'NONE', ( 20.50029254611199292, 184.8549113859068029, 102.8308091169877798 ) ) ; -#27372 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#27373 = CARTESIAN_POINT ( 'NONE', ( 30.07478355117409308, 177.7951688118731681, 100.6820556990014950 ) ) ; -#27374 = CARTESIAN_POINT ( 'NONE', ( -13.55691060191180064, 164.5230632409279110, 98.15740472410433881 ) ) ; -#27375 = CARTESIAN_POINT ( 'NONE', ( 13.55396812693302522, 147.9623613014291266, 94.31769043477856940 ) ) ; -#27376 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15869, #9152, #333, #34074 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27377 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799573900, 177.7873482353427619, 100.7165294113391383 ) ) ; -#27378 = ORIENTED_EDGE ( 'NONE', *, *, #20289, .T. ) ; -#27379 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250095450, 179.6252109630099767, 101.6466942237843796 ) ) ; -#27380 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394468896823, 3.782579493148625290E-12, 297.5584364845186087 ) ) ; -#27381 = ORIENTED_EDGE ( 'NONE', *, *, #2449, .F. ) ; -#27382 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971563459 ) ) ; -#27383 = CARTESIAN_POINT ( 'NONE', ( -19.99964517258172947, 117.7157836421189216, 90.27986412374295355 ) ) ; -#27384 = ORIENTED_EDGE ( 'NONE', *, *, #34626, .T. ) ; -#27385 = CARTESIAN_POINT ( 'NONE', ( -38.12611163673999926, 119.3162191407000137, 87.30866421832999436 ) ) ; -#27386 = CIRCLE ( 'NONE', #12324, 4.999999999999994671 ) ; -#27387 = DIRECTION ( 'NONE', ( 0.7856007465114022148, 0.6187337610642621444, 0.000000000000000000 ) ) ; -#27388 = CARTESIAN_POINT ( 'NONE', ( -3.651672906231635540, 143.5611994651619909, 95.75907850071710925 ) ) ; -#27389 = ORIENTED_EDGE ( 'NONE', *, *, #11677, .T. ) ; -#27390 = LINE ( 'NONE', #15494, #7247 ) ; -#27391 = EDGE_CURVE ( 'NONE', #8395, #15910, #1906, .T. ) ; -#27392 = ADVANCED_FACE ( 'NONE', ( #8242 ), #40311, .T. ) ; -#27393 = AXIS2_PLACEMENT_3D ( 'NONE', #21039, #39417, #20203 ) ; -#27394 = CARTESIAN_POINT ( 'NONE', ( -45.08998768082118858, 123.9203394008390546, 88.31264828985601412 ) ) ; -#27395 = CIRCLE ( 'NONE', #7758, 51.40509898896370089 ) ; -#27396 = EDGE_CURVE ( 'NONE', #30695, #14229, #28461, .T. ) ; -#27397 = CARTESIAN_POINT ( 'NONE', ( -38.39983396593000720, 119.0472737981999956, 90.29717073674000005 ) ) ; -#27398 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091565633 ) ) ; -#27399 = CIRCLE ( 'NONE', #32582, 2.000000000000000000 ) ; -#27400 = CARTESIAN_POINT ( 'NONE', ( -5.672125672682539310, 124.4606923108509733, 88.52038950313867360 ) ) ; -#27401 = ORIENTED_EDGE ( 'NONE', *, *, #7399, .F. ) ; -#27402 = CARTESIAN_POINT ( 'NONE', ( 38.12805139583999647, 119.0312398597000083, 87.35084105904999774 ) ) ; -#27403 = EDGE_CURVE ( 'NONE', #7664, #20184, #22455, .T. ) ; -#27404 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 1.222278445071001364E-14, 0.7075337269147008445 ) ) ; -#27405 = CARTESIAN_POINT ( 'NONE', ( 37.84581718655127958, 191.4135594927475097, 104.3344286323177954 ) ) ; -#27406 = ORIENTED_EDGE ( 'NONE', *, *, #24939, .F. ) ; -#27407 = LINE ( 'NONE', #22050, #31469 ) ; -#27408 = ORIENTED_EDGE ( 'NONE', *, *, #35730, .T. ) ; -#27409 = ORIENTED_EDGE ( 'NONE', *, *, #6799, .F. ) ; -#27410 = CARTESIAN_POINT ( 'NONE', ( 25.01935866475762182, 130.6173723549316605, 89.79320596012071576 ) ) ; -#27411 = FACE_OUTER_BOUND ( 'NONE', #10043, .T. ) ; -#27412 = DIRECTION ( 'NONE', ( -0.7933535320750290110, 0.5931614265262136199, 0.1369295264925107503 ) ) ; -#27413 = DIRECTION ( 'NONE', ( 0.0005884933334881037141, -0.2249510526608013983, 0.9743698874567060519 ) ) ; -#27414 = EDGE_CURVE ( 'NONE', #39678, #5998, #35138, .T. ) ; -#27415 = DIRECTION ( 'NONE', ( 0.7933535325932937754, -0.5931614258681804364, -0.1369295263402622864 ) ) ; -#27416 = CARTESIAN_POINT ( 'NONE', ( 47.89610325056636952, 151.2242448213897319, 192.5437635430896819 ) ) ; -#27417 = CARTESIAN_POINT ( 'NONE', ( 12.31559066567325367, 137.3572934308675713, 91.35375981364765607 ) ) ; -#27418 = DIRECTION ( 'NONE', ( -0.7933532411131102302, -0.5932638852154232811, -0.1364866195435443241 ) ) ; -#27419 = EDGE_CURVE ( 'NONE', #29667, #16580, #27386, .T. ) ; -#27420 = CONICAL_SURFACE ( 'NONE', #574, 4.999999999982097876, 0.7853981633697728615 ) ; -#27421 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35370, #16381, #34961, #16186, #26217, #12935 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27422 = MECHANICAL_CONTEXT ( 'NONE', #17458, 'mechanical' ) ; -#27423 = PLANE ( 'NONE', #33063 ) ; -#27424 = CYLINDRICAL_SURFACE ( 'NONE', #26962, 2.000000000000014655 ) ; -#27425 = DIRECTION ( 'NONE', ( -0.7066905416103477222, -0.1590642632756053831, 0.6894106458034008345 ) ) ; -#27426 = CARTESIAN_POINT ( 'NONE', ( -35.45366962862317450, 209.7096538831000032, 78.07991812243204777 ) ) ; -#27427 = CIRCLE ( 'NONE', #14989, 2.499999999576044907 ) ; -#27428 = CARTESIAN_POINT ( 'NONE', ( -13.55573361191907900, 164.0731611322038077, 100.1061444981561408 ) ) ; -#27429 = CARTESIAN_POINT ( 'NONE', ( -20.00111603559079398, 118.1131148921541438, 87.27965578728156970 ) ) ; -#27430 = VECTOR ( 'NONE', #10450, 1000.000000000000114 ) ; -#27431 = CIRCLE ( 'NONE', #21546, 5.499999999739705991 ) ; -#27433 = ORIENTED_EDGE ( 'NONE', *, *, #28345, .T. ) ; -#27432 = FACE_OUTER_BOUND ( 'NONE', #23361, .T. ) ; -#27434 = ORIENTED_EDGE ( 'NONE', *, *, #20292, .F. ) ; -#27435 = ORIENTED_EDGE ( 'NONE', *, *, #10517, .T. ) ; -#27436 = DIRECTION ( 'NONE', ( 0.0005884949961247527318, -0.2249510186043635618, 0.9743698953182508005 ) ) ; -#27437 = ORIENTED_EDGE ( 'NONE', *, *, #18306, .F. ) ; -#27438 = CARTESIAN_POINT ( 'NONE', ( -12.64562993050861550, 181.6872450680611450, 101.6064063805796280 ) ) ; -#27439 = CARTESIAN_POINT ( 'NONE', ( 15.94054669826102177, 152.1475402096681080, 184.5616883112009816 ) ) ; -#27440 = CARTESIAN_POINT ( 'NONE', ( -20.33171350620593998, 151.3650611303846745, 97.34744253172874551 ) ) ; -#27441 = ORIENTED_EDGE ( 'NONE', *, *, #14118, .T. ) ; -#27442 = CARTESIAN_POINT ( 'NONE', ( 17.00047812746359810, 137.4649845012766889, 177.5753949225429551 ) ) ; -#27443 = CARTESIAN_POINT ( 'NONE', ( -15.92170901910063030, 128.4476379086294742, 89.31701114597424862 ) ) ; -#27444 = FACE_OUTER_BOUND ( 'NONE', #28459, .T. ) ; -#27445 = ORIENTED_EDGE ( 'NONE', *, *, #21427, .T. ) ; -#27446 = DIRECTION ( 'NONE', ( -3.172065784687725564E-14, -1.000000000000000000, 1.586032892343862782E-14 ) ) ; -#27448 = ADVANCED_FACE ( 'NONE', ( #434 ), #27882, .F. ) ; -#27447 = CARTESIAN_POINT ( 'NONE', ( 23.00089693216080988, 115.1133509736824152, 90.25389292129368357 ) ) ; -#27449 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923097663, 174.5173791610835394, 99.93528093894383346 ) ) ; -#27450 = EDGE_CURVE ( 'NONE', #25001, #24833, #5123, .T. ) ; -#27451 = CARTESIAN_POINT ( 'NONE', ( 36.04593084803799741, 218.5902260770999987, 76.03673379060180082 ) ) ; -#27452 = LINE ( 'NONE', #9419, #11919 ) ; -#27453 = ORIENTED_EDGE ( 'NONE', *, *, #31380, .F. ) ; -#27454 = AXIS2_PLACEMENT_3D ( 'NONE', #2776, #27739, #15449 ) ; -#27455 = CARTESIAN_POINT ( 'NONE', ( -27.05502880751999939, 187.5923345152000081, 103.6304557127999999 ) ) ; -#27456 = VECTOR ( 'NONE', #36907, 1000.000000000000000 ) ; -#27457 = CARTESIAN_POINT ( 'NONE', ( 1.112502188512960233, 189.0830338811350089, 103.7168849198249916 ) ) ; -#27458 = CARTESIAN_POINT ( 'NONE', ( 19.98271301993268523, 207.8686081833218111, 77.26500776042075813 ) ) ; -#27459 = EDGE_CURVE ( 'NONE', #8778, #2569, #28017, .T. ) ; -#27460 = AXIS2_PLACEMENT_3D ( 'NONE', #39647, #17962, #1629 ) ; -#27461 = VECTOR ( 'NONE', #35836, 1000.000000000000114 ) ; -#27462 = ORIENTED_EDGE ( 'NONE', *, *, #28253, .F. ) ; -#27463 = CARTESIAN_POINT ( 'NONE', ( -38.92541764308131036, 120.0374990424048463, 87.39585669205436602 ) ) ; -#27464 = ORIENTED_EDGE ( 'NONE', *, *, #8872, .T. ) ; -#27465 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9951, #10154, #35440, #19123 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27466 = ADVANCED_FACE ( 'NONE', ( #18228 ), #15584, .F. ) ; -#27467 = ORIENTED_EDGE ( 'NONE', *, *, #26829, .F. ) ; -#27468 = ORIENTED_EDGE ( 'NONE', *, *, #33734, .F. ) ; -#27469 = CARTESIAN_POINT ( 'NONE', ( -36.54932486753000376, 191.3500546173000032, 106.5983459909000004 ) ) ; -#27470 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048998880, 130.3419545076689872, 92.84535593378656415 ) ) ; -#27471 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#27472 = ORIENTED_EDGE ( 'NONE', *, *, #32392, .T. ) ; -#27473 = CARTESIAN_POINT ( 'NONE', ( 44.89367770789063883, 186.3539630622880452, 107.7797755496722232 ) ) ; -#27474 = CARTESIAN_POINT ( 'NONE', ( -5.674480817841737412, 181.6879534348617824, 101.6022789869470131 ) ) ; -#27475 = ORIENTED_EDGE ( 'NONE', *, *, #6724, .T. ) ; -#27476 = CARTESIAN_POINT ( 'NONE', ( 26.93890014261980070, 123.1557182139219861, 91.15008746119400485 ) ) ; -#27477 = CARTESIAN_POINT ( 'NONE', ( -35.98374720110734870, 191.5283369128620166, 103.8926017044265677 ) ) ; -#27479 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825963545604135, 0.0005734119013806925416 ) ) ; -#27478 = CARTESIAN_POINT ( 'NONE', ( 44.64491191134371917, 188.7542347311224376, 105.7690686227471559 ) ) ; -#27480 = ORIENTED_EDGE ( 'NONE', *, *, #27525, .F. ) ; -#27481 = VERTEX_POINT ( 'NONE', #34559 ) ; -#27482 = CIRCLE ( 'NONE', #32658, 2.500000000019892532 ) ; -#27483 = ORIENTED_EDGE ( 'NONE', *, *, #17090, .T. ) ; -#27484 = CIRCLE ( 'NONE', #32661, 4.999999999999990230 ) ; -#27485 = ORIENTED_EDGE ( 'NONE', *, *, #28386, .T. ) ; -#27486 = CARTESIAN_POINT ( 'NONE', ( -13.46889156257816289, 158.5525648645036938, 96.60790243539881317 ) ) ; -#27487 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557966386011, 0.2249510932777509520 ) ) ; -#27488 = CARTESIAN_POINT ( 'NONE', ( 31.91158941450065356, 174.0369345777030787, 102.3790021461855133 ) ) ; -#27489 = CARTESIAN_POINT ( 'NONE', ( 12.63561476618584045, 130.7779140762933139, 90.04768401957028345 ) ) ; -#27490 = CARTESIAN_POINT ( 'NONE', ( 20.50029382287623037, 174.4060969903238458, 100.4185135684600993 ) ) ; -#27491 = ORIENTED_EDGE ( 'NONE', *, *, #33032, .F. ) ; -#27492 = VERTEX_POINT ( 'NONE', #9256 ) ; -#27494 = EDGE_CURVE ( 'NONE', #15729, #27991, #33656, .T. ) ; -#27493 = CARTESIAN_POINT ( 'NONE', ( -30.44899449634186439, 126.4238598052008484, 91.93747207210981287 ) ) ; -#27495 = ADVANCED_FACE ( 'NONE', ( #37061 ), #12710, .F. ) ; -#27496 = LINE ( 'NONE', #37265, #30806 ) ; -#27497 = ORIENTED_EDGE ( 'NONE', *, *, #20235, .F. ) ; -#27498 = CARTESIAN_POINT ( 'NONE', ( -15.49970617126520445, 160.6260167168586293, 97.25887387978653464 ) ) ; -#27499 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33575, #39917, #8664, #2518, #3104, #5570, #24811, #11928, #15576, #15193, #31328, #24409, #37261, #27679, #9258, #6174, #3300 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999996597722, 0.1874999999995457522, 0.2187499999995137223, 0.2343749999995289324, 0.2499999999995441424, 0.3749999999996101452, 0.4374999999996431188, 0.4687499999996596611, 0.4999999999996761479, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27500 = CARTESIAN_POINT ( 'NONE', ( 28.64682496188636307, 225.5077044860236981, 75.54120257392457916 ) ) ; -#27501 = EDGE_CURVE ( 'NONE', #17427, #34518, #9734, .T. ) ; -#27502 = CARTESIAN_POINT ( 'NONE', ( 1.714626986300999967, 188.8646296950000192, 106.1286134521000122 ) ) ; -#27503 = CARTESIAN_POINT ( 'NONE', ( -18.59008601221150414, 148.0291187291159076, 184.1143154653856868 ) ) ; -#27504 = VECTOR ( 'NONE', #17687, 1000.000000000000000 ) ; -#27505 = CIRCLE ( 'NONE', #11841, 6.000000000000007994 ) ; -#27506 = CARTESIAN_POINT ( 'NONE', ( -37.63979538605995145, 190.3649484233513363, 106.7037812967066230 ) ) ; -#27507 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#27508 = DIRECTION ( 'NONE', ( 0.7947985590179719173, -0.5913221741348984040, -0.1365039814779490934 ) ) ; -#27509 = VECTOR ( 'NONE', #2150, 999.9999999999998863 ) ; -#27510 = ORIENTED_EDGE ( 'NONE', *, *, #22389, .T. ) ; -#27511 = CONICAL_SURFACE ( 'NONE', #29435, 4.500000144651047584, 0.7853905226630654157 ) ; -#27512 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; -#27513 = LINE ( 'NONE', #18651, #7760 ) ; -#27514 = ADVANCED_FACE ( 'NONE', ( #33976 ), #24809, .T. ) ; -#27515 = VERTEX_POINT ( 'NONE', #27677 ) ; -#27516 = CARTESIAN_POINT ( 'NONE', ( -5.668273565523921143, 188.0786322607826548, 103.3040616047431399 ) ) ; -#27517 = VERTEX_POINT ( 'NONE', #5974 ) ; -#27518 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30001, #21816, #39790, #24696 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 7.107475445351315358E-12, 0.1624485751913120335 ), - .UNSPECIFIED. ) ; -#27520 = CARTESIAN_POINT ( 'NONE', ( -12.63793912156000765, 182.0618459069391122, 102.2059974568395120 ) ) ; -#27519 = CARTESIAN_POINT ( 'NONE', ( 15.66685956167340343, 184.8912588079487591, 102.6710766810445392 ) ) ; -#27521 = VERTEX_POINT ( 'NONE', #2902 ) ; -#27522 = ORIENTED_EDGE ( 'NONE', *, *, #6897, .T. ) ; -#27523 = VERTEX_POINT ( 'NONE', #37258 ) ; -#27524 = CARTESIAN_POINT ( 'NONE', ( 2.340793176021000122, 209.5025667088000318, 75.42211677110000778 ) ) ; -#27525 = EDGE_CURVE ( 'NONE', #32129, #32940, #17571, .T. ) ; -#27526 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554023 ) ) ; -#27527 = LINE ( 'NONE', #39950, #31392 ) ; -#27528 = PLANE ( 'NONE', #4436 ) ; -#27529 = ORIENTED_EDGE ( 'NONE', *, *, #3526, .F. ) ; -#27530 = ORIENTED_EDGE ( 'NONE', *, *, #4029, .F. ) ; -#27531 = PLANE ( 'NONE', #15461 ) ; -#27532 = ORIENTED_EDGE ( 'NONE', *, *, #38510, .F. ) ; -#27533 = ORIENTED_EDGE ( 'NONE', *, *, #11955, .T. ) ; -#27535 = CIRCLE ( 'NONE', #23553, 1.650000000000002798 ) ; -#27534 = CARTESIAN_POINT ( 'NONE', ( 35.55533445255997549, 0.000000000000000000, 90.24631030814052224 ) ) ; -#27536 = CARTESIAN_POINT ( 'NONE', ( 20.50147082588080139, 126.8719997938822530, 91.49700837604584081 ) ) ; -#27537 = CARTESIAN_POINT ( 'NONE', ( -0.04020359587071615365, 82.61272530282539606, 339.3741737412128145 ) ) ; -#27538 = CARTESIAN_POINT ( 'NONE', ( 35.90057853183999725, 192.3630497469999909, 104.2039593241999995 ) ) ; -#27539 = ORIENTED_EDGE ( 'NONE', *, *, #38295, .T. ) ; -#27540 = CIRCLE ( 'NONE', #67, 6.000000000084652285 ) ; -#27541 = EDGE_LOOP ( 'NONE', ( #27408, #9678, #6332, #1280 ) ) ; -#27542 = CARTESIAN_POINT ( 'NONE', ( -5.669717579209783587, 123.9552506004847885, 91.12636042124255198 ) ) ; -#27543 = CIRCLE ( 'NONE', #30109, 2.749999999949217511 ) ; -#27544 = ADVANCED_FACE ( 'NONE', ( #9453 ), #3886, .F. ) ; -#27545 = CARTESIAN_POINT ( 'NONE', ( -35.80474254444001048, 191.4979743564000216, 103.7561588177000118 ) ) ; -#27546 = EDGE_CURVE ( 'NONE', #19190, #16912, #32221, .T. ) ; -#27547 = ORIENTED_EDGE ( 'NONE', *, *, #11086, .F. ) ; -#27548 = CARTESIAN_POINT ( 'NONE', ( -20.49921872406353529, 118.1134456025284152, 89.78002774633898753 ) ) ; -#27549 = ORIENTED_EDGE ( 'NONE', *, *, #8158, .T. ) ; -#27550 = CARTESIAN_POINT ( 'NONE', ( -21.21281391978411435, 175.4431137808699930, 102.7357300634946000 ) ) ; -#27551 = CARTESIAN_POINT ( 'NONE', ( 40.76229226433929398, 189.9128859572081751, 106.7721059889926494 ) ) ; -#27552 = EDGE_LOOP ( 'NONE', ( #5167, #21357, #39062, #33733 ) ) ; -#27553 = CARTESIAN_POINT ( 'NONE', ( 3.535984824131890747, 174.6891947503640949, 103.0598728709964576 ) ) ; -#27554 = CARTESIAN_POINT ( 'NONE', ( 39.01174084412672016, 119.4050079532688073, 90.28720122941795978 ) ) ; -#27555 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#27556 = CARTESIAN_POINT ( 'NONE', ( 23.64619383740999936, 151.9652147202999970, 28.07991271570000080 ) ) ; -#27557 = CARTESIAN_POINT ( 'NONE', ( -45.04873142129282115, 180.7068112024259108, 104.1363975995551243 ) ) ; -#27558 = VERTEX_POINT ( 'NONE', #16964 ) ; -#27559 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21739, #18631, #31139, #3108, #37461, #3906, #20250, #10670, #7777, #35560, #29671 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999635292, 0.3749999999999452660, 0.4374999999999819034, 0.4687500000000114908, 0.5000000000000410783, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27560 = CARTESIAN_POINT ( 'NONE', ( 16.00202263909956457, 151.2883905618018048, 97.64994197610543836 ) ) ; -#27561 = VERTEX_POINT ( 'NONE', #35361 ) ; -#27562 = DIRECTION ( 'NONE', ( -0.6087616187692346248, 0.7730003051580285334, 0.1785492081725818525 ) ) ; -#27563 = AXIS2_PLACEMENT_3D ( 'NONE', #28468, #29071, #25818 ) ; -#27564 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#27565 = CARTESIAN_POINT ( 'NONE', ( 3.578322037500690556, 147.6465767615097491, 129.6583090332095196 ) ) ; -#27566 = VECTOR ( 'NONE', #29524, 1000.000000000000114 ) ; -#27567 = EDGE_CURVE ( 'NONE', #31820, #20475, #4091, .T. ) ; -#27568 = LINE ( 'NONE', #19470, #38082 ) ; -#27569 = CARTESIAN_POINT ( 'NONE', ( 6.034364035348885658, 135.2945551070078238, 91.39763805326617785 ) ) ; -#27570 = ORIENTED_EDGE ( 'NONE', *, *, #35262, .T. ) ; -#27571 = CARTESIAN_POINT ( 'NONE', ( 18.08127464052524758, 152.6344612320365286, 184.7492086203702115 ) ) ; -#27572 = ORIENTED_EDGE ( 'NONE', *, *, #13824, .T. ) ; -#27573 = CARTESIAN_POINT ( 'NONE', ( -21.21281391978411435, 175.4431137808699930, 102.7357300634946000 ) ) ; -#27574 = EDGE_CURVE ( 'NONE', #34116, #16205, #27358, .T. ) ; -#27575 = CARTESIAN_POINT ( 'NONE', ( 21.84292934196066938, 154.3261023328925035, 95.26871761115269521 ) ) ; -#27576 = FACE_OUTER_BOUND ( 'NONE', #7458, .T. ) ; -#27577 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825873969720803, 0.0005734119034471432848 ) ) ; -#27578 = CYLINDRICAL_SURFACE ( 'NONE', #28481, 6.000000000000001776 ) ; -#27579 = VERTEX_POINT ( 'NONE', #25807 ) ; -#27580 = LINE ( 'NONE', #21218, #4060 ) ; -#27581 = EDGE_CURVE ( 'NONE', #31116, #16448, #9703, .T. ) ; -#27582 = CARTESIAN_POINT ( 'NONE', ( -37.62184588523724926, 212.3970731564136543, 75.58122719057897143 ) ) ; -#27583 = ORIENTED_EDGE ( 'NONE', *, *, #33140, .T. ) ; -#27584 = CARTESIAN_POINT ( 'NONE', ( 22.78079777786205540, 154.2095749712152326, 95.41230100879079146 ) ) ; -#27585 = EDGE_CURVE ( 'NONE', #31021, #11953, #7801, .T. ) ; -#27586 = EDGE_CURVE ( 'NONE', #33981, #38443, #37765, .T. ) ; -#27587 = VERTEX_POINT ( 'NONE', #16374 ) ; -#27588 = FACE_OUTER_BOUND ( 'NONE', #13312, .T. ) ; -#27589 = EDGE_CURVE ( 'NONE', #18436, #8550, #20114, .T. ) ; -#27590 = AXIS2_PLACEMENT_3D ( 'NONE', #29585, #38978, #1774 ) ; -#27591 = EDGE_CURVE ( 'NONE', #1138, #18169, #37135, .T. ) ; -#27592 = CIRCLE ( 'NONE', #14484, 4.500000113611068997 ) ; -#27593 = CARTESIAN_POINT ( 'NONE', ( 19.99976926757112849, 160.7481248081381295, 96.75239270071580222 ) ) ; -#27594 = ORIENTED_EDGE ( 'NONE', *, *, #2308, .T. ) ; -#27595 = CARTESIAN_POINT ( 'NONE', ( 29.05442967595000070, 103.6131156702000027, 88.75023641814000541 ) ) ; -#27596 = CARTESIAN_POINT ( 'NONE', ( 25.82478768046470208, 211.0921739042685772, 73.20852435745831599 ) ) ; -#27597 = FACE_OUTER_BOUND ( 'NONE', #6442, .T. ) ; -#27598 = CARTESIAN_POINT ( 'NONE', ( -3.537740281288561217, 141.9213324163776520, 92.42018393066655335 ) ) ; -#27599 = CARTESIAN_POINT ( 'NONE', ( -5.670700517399569485, 124.5227858738960549, 88.61975888496604625 ) ) ; -#27600 = EDGE_LOOP ( 'NONE', ( #20327, #40117, #27349, #34697 ) ) ; -#27601 = LINE ( 'NONE', #2027, #21253 ) ; -#27602 = DIRECTION ( 'NONE', ( 0.0001408404346092376365, -0.2249510911124609214, 0.9743700461176365568 ) ) ; -#27603 = CARTESIAN_POINT ( 'NONE', ( 36.60852988986350454, 191.6979107518085641, 104.3488059467087226 ) ) ; -#27604 = CARTESIAN_POINT ( 'NONE', ( -15.94501487834972053, 152.5969443588147669, 182.5988326182429375 ) ) ; -#27605 = EDGE_LOOP ( 'NONE', ( #25862, #39208, #4079, #34427 ) ) ; -#27606 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#27607 = CARTESIAN_POINT ( 'NONE', ( -28.46611168752988874, 181.6098482732715240, 104.1638139686604063 ) ) ; -#27608 = LINE ( 'NONE', #14910, #5218 ) ; -#27609 = CARTESIAN_POINT ( 'NONE', ( -20.50041084545262748, 195.9128271245631367, 104.1754392423040940 ) ) ; -#27610 = DIRECTION ( 'NONE', ( 0.0005884949961259270312, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#27611 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#27612 = CONICAL_SURFACE ( 'NONE', #14511, 2.249999999870928136, 0.7853981634347139140 ) ; -#27613 = CYLINDRICAL_SURFACE ( 'NONE', #18056, 1.999999999999996891 ) ; -#27614 = VECTOR ( 'NONE', #36732, 1000.000000000000114 ) ; -#27615 = CARTESIAN_POINT ( 'NONE', ( 4.722758528658833832, 181.8696323351509534, 101.6379838739853909 ) ) ; -#27616 = FACE_OUTER_BOUND ( 'NONE', #34425, .T. ) ; -#27617 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#27618 = DIRECTION ( 'NONE', ( -0.6087613186456907188, 0.7729176985478710682, 0.1789074850089337476 ) ) ; -#27619 = ADVANCED_FACE ( 'NONE', ( #13522 ), #6764, .F. ) ; -#27620 = CARTESIAN_POINT ( 'NONE', ( -25.50804057823069471, 190.9260211217805363, 106.3128357153982648 ) ) ; -#27621 = CARTESIAN_POINT ( 'NONE', ( 36.67804389992350167, 191.3728214856969885, 106.3843505564480267 ) ) ; -#27622 = ORIENTED_EDGE ( 'NONE', *, *, #6680, .F. ) ; -#27623 = CARTESIAN_POINT ( 'NONE', ( 36.01453331615999787, 191.5443466055999977, 106.7568071878999945 ) ) ; -#27624 = ORIENTED_EDGE ( 'NONE', *, *, #33953, .T. ) ; -#27625 = ORIENTED_EDGE ( 'NONE', *, *, #3255, .F. ) ; -#27626 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; -#27627 = ADVANCED_FACE ( 'NONE', ( #26005 ), #36475, .F. ) ; -#27628 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#27629 = EDGE_CURVE ( 'NONE', #34827, #12043, #29267, .T. ) ; -#27630 = DIRECTION ( 'NONE', ( -0.0006039748319481906373, -1.291365685536980129E-14, -0.9999998176071845934 ) ) ; -#27631 = VERTEX_POINT ( 'NONE', #29873 ) ; -#27632 = CARTESIAN_POINT ( 'NONE', ( 2.563994175896955774, 190.9709097722040099, 106.3045652864306874 ) ) ; -#27633 = EDGE_CURVE ( 'NONE', #20831, #3941, #3881, .T. ) ; -#27634 = LINE ( 'NONE', #34327, #40385 ) ; -#27635 = PLANE ( 'NONE', #7910 ) ; -#27636 = CARTESIAN_POINT ( 'NONE', ( -20.33313848355735587, 151.8903170490826255, 95.07394865144232199 ) ) ; -#27637 = AXIS2_PLACEMENT_3D ( 'NONE', #2556, #14833, #37301 ) ; -#27638 = VERTEX_POINT ( 'NONE', #24152 ) ; -#27639 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -1.240298884185379714E-30, 0.0006039748319385905692 ) ) ; -#27640 = CARTESIAN_POINT ( 'NONE', ( 23.36350214670024172, 176.7448593257297773, 103.0093387781554384 ) ) ; -#27641 = CARTESIAN_POINT ( 'NONE', ( -3.537745534793053981, 170.7699642429265907, 99.08042198971619996 ) ) ; -#27642 = CARTESIAN_POINT ( 'NONE', ( -4.664801184097494335, 188.1377569219451402, 103.0907645738648739 ) ) ; -#27643 = DIRECTION ( 'NONE', ( 0.0005884949961228996135, -0.2249510543439057764, 0.9743698870671265722 ) ) ; -#27644 = ORIENTED_EDGE ( 'NONE', *, *, #10166, .T. ) ; -#27645 = CARTESIAN_POINT ( 'NONE', ( 44.87323697063200001, 186.3386389082236860, 107.7764265916358113 ) ) ; -#27646 = CARTESIAN_POINT ( 'NONE', ( 1.550213941691470199, 189.2649696120780050, 103.7693551905349949 ) ) ; -#27647 = LINE ( 'NONE', #24576, #2553 ) ; -#27648 = ORIENTED_EDGE ( 'NONE', *, *, #33543, .T. ) ; -#27649 = CARTESIAN_POINT ( 'NONE', ( -3.862039046939059528, 136.7519072660630854, 93.97138356709339746 ) ) ; -#27650 = EDGE_LOOP ( 'NONE', ( #24262, #32885, #38438, #10122 ) ) ; -#27651 = CARTESIAN_POINT ( 'NONE', ( -15.94429875659460905, 121.8910548932331182, 174.4616802850389661 ) ) ; -#27652 = LINE ( 'NONE', #21908, #8688 ) ; -#27653 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989908600, 0.1373964268091705798 ) ) ; -#27654 = FACE_OUTER_BOUND ( 'NONE', #13935, .T. ) ; -#27655 = CARTESIAN_POINT ( 'NONE', ( -37.45185207060172417, 190.9974902301310919, 106.3324920097530821 ) ) ; -#27656 = FACE_OUTER_BOUND ( 'NONE', #29551, .T. ) ; -#27657 = CARTESIAN_POINT ( 'NONE', ( 25.82374571092184112, 209.7098874176531638, 73.20956759009925463 ) ) ; -#27658 = CIRCLE ( 'NONE', #25698, 58.90509898146415679 ) ; -#27659 = ORIENTED_EDGE ( 'NONE', *, *, #533, .F. ) ; -#27660 = EDGE_CURVE ( 'NONE', #5402, #5612, #6438, .T. ) ; -#27661 = FACE_OUTER_BOUND ( 'NONE', #11974, .T. ) ; -#27662 = EDGE_CURVE ( 'NONE', #11781, #36191, #11690, .T. ) ; -#27663 = CARTESIAN_POINT ( 'NONE', ( 20.00175897098971589, 118.8155681873422651, 90.25573236258343002 ) ) ; -#27664 = AXIS2_PLACEMENT_3D ( 'NONE', #3146, #30976, #37498 ) ; -#27665 = ADVANCED_FACE ( 'NONE', ( #2474 ), #35787, .T. ) ; -#27667 = DIRECTION ( 'NONE', ( -0.9999998268367413790, -0.0001323826169910145747, 0.0005734120070777408776 ) ) ; -#27666 = CARTESIAN_POINT ( 'NONE', ( -45.14842465761670809, 169.6367057394601829, 151.6138213944554707 ) ) ; -#27668 = VECTOR ( 'NONE', #9450, 1000.000000000000227 ) ; -#27669 = ORIENTED_EDGE ( 'NONE', *, *, #38025, .F. ) ; -#27670 = ADVANCED_FACE ( 'NONE', ( #36188 ), #11670, .F. ) ; -#27671 = CARTESIAN_POINT ( 'NONE', ( 20.36617596090313853, 116.6171548778993525, 87.25548363208405078 ) ) ; -#27672 = CARTESIAN_POINT ( 'NONE', ( 15.94070757266567995, 152.8237909711254190, 181.6389010276846818 ) ) ; -#27673 = ORIENTED_EDGE ( 'NONE', *, *, #14354, .F. ) ; -#27674 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000092726, 179.7424522644023739, 101.1388664480621884 ) ) ; -#27675 = EDGE_CURVE ( 'NONE', #8695, #30770, #18174, .T. ) ; -#27676 = CARTESIAN_POINT ( 'NONE', ( -14.61177127432338629, 128.1281455356962908, 179.5008378358747620 ) ) ; -#27677 = CARTESIAN_POINT ( 'NONE', ( 22.99909745638999681, 115.1133511170128969, 87.25389341346352978 ) ) ; -#27678 = DIRECTION ( 'NONE', ( 5.666202469657695111E-15, 0.9743700557921586292, 0.2249510932971561794 ) ) ; -#27679 = CARTESIAN_POINT ( 'NONE', ( -12.63882556139555113, 135.1005122211433047, 91.10176790521497026 ) ) ; -#27680 = ORIENTED_EDGE ( 'NONE', *, *, #12311, .F. ) ; -#27681 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32503, #11040, #35135, #38622 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 7.571344363706689254E-07, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27682 = ORIENTED_EDGE ( 'NONE', *, *, #33393, .F. ) ; -#27683 = CARTESIAN_POINT ( 'NONE', ( 6.272186690383747099, 163.3822237695354147, 99.93465344309498732 ) ) ; -#27684 = CARTESIAN_POINT ( 'NONE', ( 22.78193024034098357, 164.0779716071806718, 100.0853080456561202 ) ) ; -#27685 = CARTESIAN_POINT ( 'NONE', ( 22.50176469968679527, 151.2986505458790703, 97.64827954977749869 ) ) ; -#27686 = ADVANCED_FACE ( 'NONE', ( #11062 ), #26810, .F. ) ; -#27687 = VERTEX_POINT ( 'NONE', #17368 ) ; -#27688 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971521271 ) ) ; -#27689 = AXIS2_PLACEMENT_3D ( 'NONE', #18161, #26595, #36389 ) ; -#27690 = CARTESIAN_POINT ( 'NONE', ( 35.04524256069789345, 217.7719116313999734, 73.53733772509932010 ) ) ; -#27691 = CARTESIAN_POINT ( 'NONE', ( 2.942908037749000449, 190.9186745520999864, 106.6822150708999999 ) ) ; -#27692 = CIRCLE ( 'NONE', #28950, 4.499999999983483434 ) ; -#27693 = CARTESIAN_POINT ( 'NONE', ( 32.45263285945821252, 152.9980946676346889, 291.5389433581793242 ) ) ; -#27694 = CARTESIAN_POINT ( 'NONE', ( -12.15421709199686617, 125.0604765512531884, 178.7580882214065525 ) ) ; -#27695 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22843, #13238, #25721, #38174, #22647, #35073, #32053, #38964, #35464, #23642, #14651, #36306, #32829, #27136, #26512, #11170, #10771, #4810 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999709677, 0.1874999999999551470, 0.2187499999999615585, 0.2499999999999680256, 0.5000000000000517364, 0.6250000000000819345, 0.6875000000000873746, 0.7187500000000924816, 0.7500000000000976996, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27696 = CONICAL_SURFACE ( 'NONE', #36118, 2.500000004064246717, 0.7853981633778827076 ) ; -#27697 = FACE_BOUND ( 'NONE', #11681, .T. ) ; -#27698 = LINE ( 'NONE', #39723, #11789 ) ; -#27699 = LINE ( 'NONE', #17838, #30011 ) ; -#27700 = EDGE_LOOP ( 'NONE', ( #33142, #3771, #37913, #32883 ) ) ; -#27701 = CARTESIAN_POINT ( 'NONE', ( -19.99878781686340901, 118.5855806922666744, 90.27986360592157666 ) ) ; -#27702 = CARTESIAN_POINT ( 'NONE', ( -19.99806018810932429, 127.0618145191346713, 92.07850957579123019 ) ) ; -#27703 = ORIENTED_EDGE ( 'NONE', *, *, #30313, .F. ) ; -#27704 = CARTESIAN_POINT ( 'NONE', ( -5.664667741263813561, 188.2818546945390494, 103.1770723517569905 ) ) ; -#27705 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28873, #35184, #7190, #4107, #16581, #39068 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27706 = EDGE_LOOP ( 'NONE', ( #36619, #18669, #35311, #27075 ) ) ; -#27707 = EDGE_CURVE ( 'NONE', #34340, #32409, #5342, .T. ) ; -#27708 = EDGE_CURVE ( 'NONE', #15252, #14369, #19487, .T. ) ; -#27710 = CARTESIAN_POINT ( 'NONE', ( -17.18000789323316724, 121.5355521580427904, 176.6660631287034846 ) ) ; -#27709 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; -#27711 = ORIENTED_EDGE ( 'NONE', *, *, #27918, .F. ) ; -#27712 = ORIENTED_EDGE ( 'NONE', *, *, #32312, .T. ) ; -#27713 = CIRCLE ( 'NONE', #36828, 9.499999999981838528 ) ; -#27714 = EDGE_LOOP ( 'NONE', ( #21175, #26435, #4155, #15823 ) ) ; -#27715 = CARTESIAN_POINT ( 'NONE', ( 2.849529448806000342, 209.6052812332999906, 75.93649384533000557 ) ) ; -#27716 = CARTESIAN_POINT ( 'NONE', ( 39.01510409419797298, 183.0181244353566967, 104.9791813424711364 ) ) ; -#27717 = CARTESIAN_POINT ( 'NONE', ( 40.77511261360605488, 183.2838136414375185, 107.0263220726274227 ) ) ; -#27718 = CARTESIAN_POINT ( 'NONE', ( 5.666344154416935730, 188.3446284886178717, 103.1322861692058268 ) ) ; -#27720 = ORIENTED_EDGE ( 'NONE', *, *, #3259, .T. ) ; -#27719 = CONICAL_SURFACE ( 'NONE', #8139, 2.502986730286343775, 0.7853981633516999850 ) ; -#27721 = ORIENTED_EDGE ( 'NONE', *, *, #17415, .T. ) ; -#27722 = ORIENTED_EDGE ( 'NONE', *, *, #22444, .T. ) ; -#27723 = VERTEX_POINT ( 'NONE', #2064 ) ; -#27724 = DIRECTION ( 'NONE', ( -0.1945914028283885489, 0.07350731974101876176, -0.9781261983454748732 ) ) ; -#27725 = AXIS2_PLACEMENT_3D ( 'NONE', #7323, #1391, #26162 ) ; -#27726 = CARTESIAN_POINT ( 'NONE', ( 26.00820924362151487, 193.8169252988725475, 102.6872016750469072 ) ) ; -#27727 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394468896823, 3.782579493148625290E-12, 297.5584364845186087 ) ) ; -#27728 = DIRECTION ( 'NONE', ( -0.7933535325932956628, 0.5931614258681777718, 0.1369295263402618701 ) ) ; -#27729 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33457, #27161, #33052, #26539 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27730 = ORIENTED_EDGE ( 'NONE', *, *, #5054, .T. ) ; -#27731 = ORIENTED_EDGE ( 'NONE', *, *, #6616, .F. ) ; -#27732 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; -#27733 = DIRECTION ( 'NONE', ( 0.0005884949961245230978, -0.2249510543439041388, 0.9743698870671267942 ) ) ; -#27734 = ORIENTED_EDGE ( 'NONE', *, *, #9642, .F. ) ; -#27735 = DIRECTION ( 'NONE', ( -0.7933533411653073131, 0.5930537057989939687, 0.1373964268091565077 ) ) ; -#27736 = EDGE_CURVE ( 'NONE', #27950, #479, #23948, .T. ) ; -#27737 = VERTEX_POINT ( 'NONE', #33326 ) ; -#27738 = CARTESIAN_POINT ( 'NONE', ( 30.44722912950143012, 185.6116624768459360, 102.4863628262051947 ) ) ; -#27739 = DIRECTION ( 'NONE', ( 0.0002393071182784984501, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#27740 = ORIENTED_EDGE ( 'NONE', *, *, #21577, .T. ) ; -#27741 = CYLINDRICAL_SURFACE ( 'NONE', #8535, 7.999999999999993783 ) ; -#27742 = CARTESIAN_POINT ( 'NONE', ( -15.87307211637148008, 126.0321397929661487, 88.75931998815980251 ) ) ; -#27743 = CYLINDRICAL_SURFACE ( 'NONE', #27771, 9.999999999999996447 ) ; -#27744 = AXIS2_PLACEMENT_3D ( 'NONE', #22507, #19198, #207 ) ; -#27745 = CIRCLE ( 'NONE', #21221, 6.000000000000007994 ) ; -#27746 = FACE_OUTER_BOUND ( 'NONE', #38655, .T. ) ; -#27747 = VERTEX_POINT ( 'NONE', #7771 ) ; -#27748 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#27749 = AXIS2_PLACEMENT_3D ( 'NONE', #27210, #39238, #17759 ) ; -#27750 = DIRECTION ( 'NONE', ( 0.0005884949961228995051, -0.2249510543439057486, 0.9743698870671265722 ) ) ; -#27751 = CARTESIAN_POINT ( 'NONE', ( -38.55305068042999750, 118.7961394416000047, 87.84745821114999842 ) ) ; -#27752 = LINE ( 'NONE', #17902, #20938 ) ; -#27753 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#27754 = EDGE_LOOP ( 'NONE', ( #21177, #21042, #30350, #35448 ) ) ; -#27755 = CARTESIAN_POINT ( 'NONE', ( -29.78153554572921635, 185.0889519713750815, 104.9678231777716633 ) ) ; -#27756 = EDGE_LOOP ( 'NONE', ( #21543, #21196, #36270, #19222 ) ) ; -#27757 = CARTESIAN_POINT ( 'NONE', ( -37.35285048055809654, 145.6614909859866884, 280.9747434382983329 ) ) ; -#27758 = EDGE_CURVE ( 'NONE', #19097, #12909, #29665, .T. ) ; -#27759 = EDGE_CURVE ( 'NONE', #18878, #38902, #24897, .T. ) ; -#27760 = FACE_OUTER_BOUND ( 'NONE', #12187, .T. ) ; -#27761 = CARTESIAN_POINT ( 'NONE', ( -19.99827944177191341, 118.8155627782461181, 90.27982142893266371 ) ) ; -#27762 = ORIENTED_EDGE ( 'NONE', *, *, #27899, .F. ) ; -#27763 = CARTESIAN_POINT ( 'NONE', ( -6.957132718426895401, 133.0026170453613190, 282.5627442275269914 ) ) ; -#27764 = DIRECTION ( 'NONE', ( 0.0005884949961244997875, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#27765 = CARTESIAN_POINT ( 'NONE', ( -14.29753826611796619, 135.9209370902451042, 91.38347899765265936 ) ) ; -#27766 = CARTESIAN_POINT ( 'NONE', ( -36.27425416885741782, 116.2195830436171775, 90.28969357976914978 ) ) ; -#27767 = EDGE_LOOP ( 'NONE', ( #7638, #9376, #24557 ) ) ; -#27768 = CONICAL_SURFACE ( 'NONE', #38812, 3.000000000033070879, 0.7853981634068039064 ) ; -#27769 = CARTESIAN_POINT ( 'NONE', ( 9.584790827646999745, 123.9927411031000020, 91.09544851567000023 ) ) ; -#27770 = CARTESIAN_POINT ( 'NONE', ( 13.46889286300669930, 154.2077898831500136, 95.41751144764988624 ) ) ; -#27771 = AXIS2_PLACEMENT_3D ( 'NONE', #109, #21406, #18092 ) ; -#27772 = ORIENTED_EDGE ( 'NONE', *, *, #14814, .T. ) ; -#27773 = CARTESIAN_POINT ( 'NONE', ( -23.36257451788618411, 135.1062575246979520, 91.11938333801428769 ) ) ; -#27774 = CIRCLE ( 'NONE', #19876, 47.99999999995232969 ) ; -#27775 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319379635751 ) ) ; -#27776 = ORIENTED_EDGE ( 'NONE', *, *, #25414, .T. ) ; -#27777 = CARTESIAN_POINT ( 'NONE', ( 20.50411903179696793, 118.8156364820424358, 94.25541735824513978 ) ) ; -#27778 = EDGE_CURVE ( 'NONE', #24370, #29127, #26051, .T. ) ; -#27779 = CARTESIAN_POINT ( 'NONE', ( -31.75344637200684517, 110.2231456982468814, 198.5388746951010432 ) ) ; -#27780 = CARTESIAN_POINT ( 'NONE', ( -3.608144113922426843, 143.5503432561750117, 95.80119337602084784 ) ) ; -#27781 = VERTEX_POINT ( 'NONE', #28026 ) ; -#27782 = CARTESIAN_POINT ( 'NONE', ( 36.01401218609490940, 191.3156446998485762, 106.8565349524990040 ) ) ; -#27783 = CARTESIAN_POINT ( 'NONE', ( -16.99952089899032615, 137.4668171152774221, 177.5674675513082263 ) ) ; -#27784 = CARTESIAN_POINT ( 'NONE', ( 15.95616423589712340, 121.8747789553152785, 174.5819126748912709 ) ) ; -#27785 = CARTESIAN_POINT ( 'NONE', ( -25.26699933410839805, 116.1375375319907306, 90.28304547366768418 ) ) ; -#27786 = CARTESIAN_POINT ( 'NONE', ( -5.670809738135598188, 124.5658457816913938, 88.68866924740245850 ) ) ; -#27787 = ORIENTED_EDGE ( 'NONE', *, *, #40057, .T. ) ; -#27788 = ORIENTED_EDGE ( 'NONE', *, *, #7348, .F. ) ; -#27789 = CARTESIAN_POINT ( 'NONE', ( 30.05382551891246834, 103.6131156702177094, 87.74963262556697430 ) ) ; -#27790 = FACE_OUTER_BOUND ( 'NONE', #13668, .T. ) ; -#27791 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #1342, #33221 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27792 = LINE ( 'NONE', #40429, #1880 ) ; -#27793 = EDGE_CURVE ( 'NONE', #16151, #16282, #12705, .T. ) ; -#27794 = CARTESIAN_POINT ( 'NONE', ( 21.99952075582769950, 136.5637738048187089, 181.4737781874725044 ) ) ; -#27795 = EDGE_LOOP ( 'NONE', ( #22326, #13136, #33119, #17775 ) ) ; -#27796 = CARTESIAN_POINT ( 'NONE', ( 3.501248248212571301, 127.9869503391333438, 91.93573239970081090 ) ) ; -#27797 = FACE_OUTER_BOUND ( 'NONE', #8094, .T. ) ; -#27798 = AXIS2_PLACEMENT_3D ( 'NONE', #25234, #9680, #34982 ) ; -#27799 = CARTESIAN_POINT ( 'NONE', ( 23.36327396620029262, 181.6167095797193838, 104.1340943760966411 ) ) ; -#27800 = DIRECTION ( 'NONE', ( -0.0001358670886401176173, -0.9743700647852195917, -0.2249510133130793177 ) ) ; -#27801 = EDGE_CURVE ( 'NONE', #35660, #26941, #30885, .T. ) ; -#27802 = CARTESIAN_POINT ( 'NONE', ( -20.50069624036807880, 196.1175417876341385, 103.6936179443737842 ) ) ; -#27803 = AXIS2_PLACEMENT_3D ( 'NONE', #5111, #30080, #8616 ) ; -#27804 = CARTESIAN_POINT ( 'NONE', ( -26.43704716554000100, 188.3998508720999894, 105.9012352929000116 ) ) ; -#27805 = AXIS2_PLACEMENT_3D ( 'NONE', #13626, #23040, #33838 ) ; -#27806 = CARTESIAN_POINT ( 'NONE', ( 21.21741576901515458, 116.0712868709253200, 186.7718674688779288 ) ) ; -#27807 = AXIS2_PLACEMENT_3D ( 'NONE', #10099, #19675, #19276 ) ; -#27808 = EDGE_CURVE ( 'NONE', #38190, #10767, #9408, .T. ) ; -#27809 = EDGE_CURVE ( 'NONE', #36719, #12211, #28638, .T. ) ; -#27810 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14982, #37059, #3100, #12310, #11921, #30929, #37257, #33571 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 4 ), - ( 6.352770773062192013E-11, 0.001095641011820102685, 0.002191300338002477761, 0.003286959664184305099, 0.004382618990366680609, 0.005478278251420251425 ), - .UNSPECIFIED. ) ; -#27811 = EDGE_CURVE ( 'NONE', #17411, #31921, #16056, .T. ) ; -#27812 = LINE ( 'NONE', #36584, #38930 ) ; -#27813 = EDGE_CURVE ( 'NONE', #8681, #28855, #12210, .T. ) ; -#27814 = APPROVAL_STATUS ( 'not_yet_approved' ) ; -#27815 = CARTESIAN_POINT ( 'NONE', ( -25.49213558285381254, 194.2771767961476996, 102.9136721320308538 ) ) ; -#27816 = ORIENTED_EDGE ( 'NONE', *, *, #39576, .F. ) ; -#27817 = CARTESIAN_POINT ( 'NONE', ( -35.45414161172500656, 207.8686442644066403, 77.29845580048690579 ) ) ; -#27818 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927789245053, 0.0005734119022072690875 ) ) ; -#27819 = CARTESIAN_POINT ( 'NONE', ( 39.72066838923261400, 121.2692008855572539, 123.5482992136137597 ) ) ; -#27820 = CARTESIAN_POINT ( 'NONE', ( 37.96378718164481114, 191.4246119842719622, 104.2864744074900045 ) ) ; -#27821 = CARTESIAN_POINT ( 'NONE', ( 36.34654930669000095, 190.7274350762999973, 106.8916613049999995 ) ) ; -#27822 = ORIENTED_EDGE ( 'NONE', *, *, #30793, .F. ) ; -#27823 = ORIENTED_EDGE ( 'NONE', *, *, #33534, .T. ) ; -#27824 = CARTESIAN_POINT ( 'NONE', ( -3.749561473961237290, 136.3728858009279179, 91.13934745270415760 ) ) ; -#27825 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#27826 = AXIS2_PLACEMENT_3D ( 'NONE', #24091, #26556, #36348 ) ; -#27827 = CARTESIAN_POINT ( 'NONE', ( -37.60586764323186060, 218.5902260770999987, 73.08121708413270312 ) ) ; -#27828 = AXIS2_PLACEMENT_3D ( 'NONE', #21110, #33363, #21321 ) ; -#27829 = ORIENTED_EDGE ( 'NONE', *, *, #1517, .F. ) ; -#27830 = CARTESIAN_POINT ( 'NONE', ( -39.84439478701000326, 119.3836004598999949, 89.66600107623999349 ) ) ; -#27831 = EDGE_CURVE ( 'NONE', #29835, #29701, #39071, .T. ) ; -#27832 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#27833 = CONICAL_SURFACE ( 'NONE', #24474, 5.003062882472611328, 0.7854392545927519897 ) ; -#27834 = CARTESIAN_POINT ( 'NONE', ( -14.02911757408319637, 130.6396467055756148, 89.82193326635079700 ) ) ; -#27835 = VERTEX_POINT ( 'NONE', #37018 ) ; -#27836 = AXIS2_PLACEMENT_3D ( 'NONE', #19914, #23614, #29753 ) ; -#27837 = DIRECTION ( 'NONE', ( 0.0005884949961259158639, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#27838 = CARTESIAN_POINT ( 'NONE', ( 23.36476570799907293, 176.9958500756095248, 103.4110070592336115 ) ) ; -#27839 = AXIS2_PLACEMENT_3D ( 'NONE', #5213, #39358, #39566 ) ; -#27840 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#27841 = DIRECTION ( 'NONE', ( -0.7933533416835739649, 0.5930537051408141247, 0.1373964266575323501 ) ) ; -#27842 = LINE ( 'NONE', #5938, #17103 ) ; -#27843 = ORIENTED_EDGE ( 'NONE', *, *, #1177, .F. ) ; -#27844 = ORIENTED_EDGE ( 'NONE', *, *, #35442, .T. ) ; -#27845 = DIRECTION ( 'NONE', ( 0.0004161288024481686067, -0.8480480898038740278, 0.5299191110130112570 ) ) ; -#27846 = CARTESIAN_POINT ( 'NONE', ( 2.031020583090000109, 189.6346843048000039, 103.8749406049000044 ) ) ; -#27847 = LINE ( 'NONE', #21900, #3817 ) ; -#27848 = EDGE_CURVE ( 'NONE', #28666, #34570, #26329, .T. ) ; -#27849 = ORIENTED_EDGE ( 'NONE', *, *, #6849, .F. ) ; -#27850 = DIRECTION ( 'NONE', ( 0.0006039748319384690301, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#27851 = EDGE_LOOP ( 'NONE', ( #20766, #3905, #24673, #21502, #14358 ) ) ; -#27852 = EDGE_CURVE ( 'NONE', #23346, #40336, #8429, .T. ) ; -#27853 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178587041921E-05, 0.0002331579774917524482 ) ) ; -#27854 = EDGE_CURVE ( 'NONE', #19817, #40341, #7085, .T. ) ; -#27855 = FACE_OUTER_BOUND ( 'NONE', #963, .T. ) ; -#27856 = CARTESIAN_POINT ( 'NONE', ( 22.99181599359000217, 213.5902260771004819, 75.54481431629028521 ) ) ; -#27857 = VECTOR ( 'NONE', #32469, 1000.000000000000114 ) ; -#27858 = CARTESIAN_POINT ( 'NONE', ( -37.93529217406000242, 191.1032702454000116, 105.7304225791999954 ) ) ; -#27859 = EDGE_CURVE ( 'NONE', #2177, #34329, #27634, .T. ) ; -#27860 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -1.540743955509788340E-33, -0.0006039748319384538513 ) ) ; -#27861 = ADVANCED_FACE ( 'NONE', ( #33730 ), #21884, .T. ) ; -#27862 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#27863 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12022, #8960, #5876, #27977, #40209, #25106, #12412, #18329, #36961, #12223, #24711 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000003338441, 0.3750000000005007661, 0.4375000000005456191, 0.4687500000004894418, 0.5000000000004332090, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27864 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; -#27865 = CARTESIAN_POINT ( 'NONE', ( -36.46111710323000210, 191.2984778848999952, 106.4996631324000020 ) ) ; -#27866 = VERTEX_POINT ( 'NONE', #5733 ) ; -#27867 = AXIS2_PLACEMENT_3D ( 'NONE', #30767, #34016, #21773 ) ; -#27868 = DIRECTION ( 'NONE', ( 0.7933309737288272157, 0.5932206757314845147, 0.1368034941335623256 ) ) ; -#27869 = CARTESIAN_POINT ( 'NONE', ( -35.43647108214479857, 192.2306391127845586, 103.9283466409799956 ) ) ; -#27870 = LINE ( 'NONE', #33963, #22285 ) ; -#27871 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24216, #40124, #6183, #30330, #12132, #11937, #36663, #14996, #9067, #21550, #5788, #8673 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998647748, 0.3749999999998180344, 0.4374999999997946643, 0.4687499999998108735, 0.4843749999998041567, 0.4999999999997974953, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27872 = AXIS2_PLACEMENT_3D ( 'NONE', #5328, #24165, #15350 ) ; -#27873 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29999, #18108, #36947, #8744, #18314, #30614, #21205, #8948, #1996, #14873 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000001213474, 0.3750000000001508238, 0.4375000000001346145, 0.5000000000001184608, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27875 = CARTESIAN_POINT ( 'NONE', ( 16.22247671335948382, 122.0701589875174164, 174.5870958018068109 ) ) ; -#27874 = DIRECTION ( 'NONE', ( 0.0005884949961280474054, -0.2249510543439049992, 0.9743698870671266832 ) ) ; -#27876 = VERTEX_POINT ( 'NONE', #12665 ) ; -#27877 = ORIENTED_EDGE ( 'NONE', *, *, #4651, .F. ) ; -#27878 = CARTESIAN_POINT ( 'NONE', ( 20.19546531881924167, 117.0454142389978216, 87.25558673703422130 ) ) ; -#27879 = LINE ( 'NONE', #17620, #37416 ) ; -#27880 = VERTEX_POINT ( 'NONE', #37215 ) ; -#27881 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250100069, 132.8554482850266538, 90.84904174538198163 ) ) ; -#27882 = PLANE ( 'NONE', #39736 ) ; -#27883 = DIRECTION ( 'NONE', ( -0.0006039748319389448864, -1.387638830454547823E-14, -0.9999998176071845934 ) ) ; -#27884 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971556798 ) ) ; -#27885 = ORIENTED_EDGE ( 'NONE', *, *, #10397, .T. ) ; -#27886 = ORIENTED_EDGE ( 'NONE', *, *, #8837, .F. ) ; -#27887 = AXIS2_PLACEMENT_3D ( 'NONE', #8994, #37397, #12254 ) ; -#27888 = FACE_OUTER_BOUND ( 'NONE', #27055, .T. ) ; -#27889 = AXIS2_PLACEMENT_3D ( 'NONE', #26397, #2674, #5311 ) ; -#27890 = AXIS2_PLACEMENT_3D ( 'NONE', #9632, #6949, #31719 ) ; -#27891 = CARTESIAN_POINT ( 'NONE', ( 13.53487526333000091, 138.6412561347999883, 152.4718672074000381 ) ) ; -#27892 = VERTEX_POINT ( 'NONE', #25155 ) ; -#27893 = ORIENTED_EDGE ( 'NONE', *, *, #1368, .F. ) ; -#27894 = CARTESIAN_POINT ( 'NONE', ( -36.31334435454239440, 190.8477745772199796, 106.8181128475319923 ) ) ; -#27895 = EDGE_CURVE ( 'NONE', #38686, #38924, #11704, .T. ) ; -#27896 = CARTESIAN_POINT ( 'NONE', ( 2.428755075693000087, 191.0298806613000409, 106.1808864122999978 ) ) ; -#27897 = CIRCLE ( 'NONE', #16098, 2.499999999403085482 ) ; -#27898 = EDGE_CURVE ( 'NONE', #37032, #30211, #22924, .T. ) ; -#27899 = EDGE_CURVE ( 'NONE', #39862, #23240, #18863, .T. ) ; -#27900 = CARTESIAN_POINT ( 'NONE', ( 2.792698159047999784, 190.1826233186000081, 106.4537760261000017 ) ) ; -#27901 = CARTESIAN_POINT ( 'NONE', ( -30.17967539261260868, 185.9478675171641271, 102.6005988726028590 ) ) ; -#27902 = CARTESIAN_POINT ( 'NONE', ( 0.03687779169341001001, 7.827067153267001387E-13, 61.05847962042000887 ) ) ; -#27903 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971568178 ) ) ; -#27904 = DIRECTION ( 'NONE', ( 0.0005884949958159830120, -0.2249510543438417998, 0.9743698870671413381 ) ) ; -#27905 = EDGE_CURVE ( 'NONE', #34620, #35660, #35509, .T. ) ; -#27906 = ORIENTED_EDGE ( 'NONE', *, *, #12820, .F. ) ; -#27907 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; -#27908 = CARTESIAN_POINT ( 'NONE', ( -30.05261224253734298, 126.8329673299385405, 91.51853050536497847 ) ) ; -#27909 = EDGE_CURVE ( 'NONE', #23147, #9444, #39096, .T. ) ; -#27910 = EDGE_LOOP ( 'NONE', ( #34364, #786, #27917, #5362 ) ) ; -#27911 = AXIS2_PLACEMENT_3D ( 'NONE', #34037, #6029, #2950 ) ; -#27912 = PLANE ( 'NONE', #5790 ) ; -#27913 = ORIENTED_EDGE ( 'NONE', *, *, #31153, .F. ) ; -#27914 = AXIS2_PLACEMENT_3D ( 'NONE', #2546, #24438, #11546 ) ; -#27916 = CARTESIAN_POINT ( 'NONE', ( 12.63956951859096911, 174.7946995548854829, 102.5655858247352796 ) ) ; -#27915 = CARTESIAN_POINT ( 'NONE', ( -5.675054657474391639, 124.3656264979204167, 88.36836997283377571 ) ) ; -#27917 = ORIENTED_EDGE ( 'NONE', *, *, #4164, .F. ) ; -#27918 = EDGE_CURVE ( 'NONE', #31494, #7275, #19986, .T. ) ; -#27919 = VERTEX_POINT ( 'NONE', #23084 ) ; -#27920 = CARTESIAN_POINT ( 'NONE', ( 25.49139087232281398, 206.5303696782877694, 74.82836958929388516 ) ) ; -#27921 = CARTESIAN_POINT ( 'NONE', ( 36.06505478247691343, 192.7057421170999874, 106.3400883090996132 ) ) ; -#27922 = ORIENTED_EDGE ( 'NONE', *, *, #35945, .T. ) ; -#27923 = CARTESIAN_POINT ( 'NONE', ( 2.588302065746999947, 209.5753207051000118, 75.67882707907000395 ) ) ; -#27924 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#27925 = EDGE_LOOP ( 'NONE', ( #26746, #18861, #17888, #7725 ) ) ; -#27926 = ORIENTED_EDGE ( 'NONE', *, *, #39262, .T. ) ; -#27927 = ORIENTED_EDGE ( 'NONE', *, *, #8780, .T. ) ; -#27928 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#27929 = DIRECTION ( 'NONE', ( 0.0006039748319386520434, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#27930 = CARTESIAN_POINT ( 'NONE', ( 39.82491996314075777, 141.3585264024648609, 285.0163987782322579 ) ) ; -#27931 = CARTESIAN_POINT ( 'NONE', ( -18.71851310314255556, 125.9964326179262883, 174.7342168340691444 ) ) ; -#27932 = ORIENTED_EDGE ( 'NONE', *, *, #20055, .T. ) ; -#27933 = ORIENTED_EDGE ( 'NONE', *, *, #34223, .F. ) ; -#27934 = CARTESIAN_POINT ( 'NONE', ( 21.83140111251249493, 182.3124853075107978, 104.2956521028678054 ) ) ; -#27935 = CARTESIAN_POINT ( 'NONE', ( -20.50069624036807880, 196.1175417876341385, 103.6936179443737842 ) ) ; -#27936 = CARTESIAN_POINT ( 'NONE', ( -20.49852834086299325, 137.6294258426618455, 94.00531932011546132 ) ) ; -#27937 = VERTEX_POINT ( 'NONE', #32481 ) ; -#27938 = DIRECTION ( 'NONE', ( 0.0005884949961279900511, -0.2249510543439064425, 0.9743698870671262391 ) ) ; -#27939 = CARTESIAN_POINT ( 'NONE', ( -39.94461650407871645, 190.2993241498186308, 106.6900227966467156 ) ) ; -#27940 = VERTEX_POINT ( 'NONE', #22286 ) ; -#27941 = VECTOR ( 'NONE', #36245, 1000.000000000000000 ) ; -#27942 = EDGE_CURVE ( 'NONE', #12341, #33655, #28613, .T. ) ; -#27943 = EDGE_CURVE ( 'NONE', #34776, #39273, #26858, .T. ) ; -#27944 = CARTESIAN_POINT ( 'NONE', ( -28.34683059422810558, 187.0784819827278795, 103.2026163153525715 ) ) ; -#27945 = CARTESIAN_POINT ( 'NONE', ( -3.683436850352686864, 167.8539730530844167, 101.3349470994127302 ) ) ; -#27946 = AXIS2_PLACEMENT_3D ( 'NONE', #4646, #4839, #13463 ) ; -#27947 = DIRECTION ( 'NONE', ( -0.0006039748319384734753, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#27948 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 181.5973583084323764, 103.1065612386186103 ) ) ; -#27949 = EDGE_CURVE ( 'NONE', #40156, #29048, #5385, .T. ) ; -#27950 = VERTEX_POINT ( 'NONE', #38004 ) ; -#27951 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.000000000000000000, 1.000000000000000000 ) ) ; -#27952 = ORIENTED_EDGE ( 'NONE', *, *, #27156, .T. ) ; -#27953 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; -#27954 = LINE ( 'NONE', #18304, #17916 ) ; -#27955 = CARTESIAN_POINT ( 'NONE', ( 38.68493554284999902, 118.3875614923999962, 89.50458756611999434 ) ) ; -#27956 = EDGE_CURVE ( 'NONE', #20733, #4624, #10010, .T. ) ; -#27957 = CARTESIAN_POINT ( 'NONE', ( -40.62250926484631464, 78.19640176074449300, 284.1891008884034591 ) ) ; -#27958 = ORIENTED_EDGE ( 'NONE', *, *, #11085, .T. ) ; -#27959 = DIRECTION ( 'NONE', ( -0.6087613508315110611, 0.7729392205173687413, 0.1788143705628724156 ) ) ; -#27960 = EDGE_LOOP ( 'NONE', ( #2108, #4727 ) ) ; -#27961 = CARTESIAN_POINT ( 'NONE', ( 44.93984957629947274, 145.3877245808612031, 285.0133094889154677 ) ) ; -#27962 = EDGE_CURVE ( 'NONE', #28925, #17225, #35811, .T. ) ; -#27963 = ORIENTED_EDGE ( 'NONE', *, *, #34479, .T. ) ; -#27964 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18119, #2804, #31214, #34456 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#27965 = AXIS2_PLACEMENT_3D ( 'NONE', #29831, #17121, #14490 ) ; -#27966 = PLANE ( 'NONE', #9519 ) ; -#27967 = DIRECTION ( 'NONE', ( 0.9999998176071833722, -2.081668157636497989E-12, -0.0006039748339932807545 ) ) ; -#27968 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971542920 ) ) ; -#27969 = CARTESIAN_POINT ( 'NONE', ( -21.71199968648796030, 158.4246146459098838, 96.24123999348603320 ) ) ; -#27970 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218859315, 3.303188515689728130E-12, 297.5295786860755811 ) ) ; -#27971 = VECTOR ( 'NONE', #38942, 1000.000000000000227 ) ; -#27972 = ORIENTED_EDGE ( 'NONE', *, *, #5561, .T. ) ; -#27973 = CARTESIAN_POINT ( 'NONE', ( 5.667347771331193940, 187.7942676616929418, 103.4761900681965869 ) ) ; -#27974 = CYLINDRICAL_SURFACE ( 'NONE', #9316, 2.000000000000014655 ) ; -#27975 = CARTESIAN_POINT ( 'NONE', ( 116.6745667766377892, 205.5703614864765427, 191.2914269756732040 ) ) ; -#27976 = ORIENTED_EDGE ( 'NONE', *, *, #8636, .F. ) ; -#27977 = CARTESIAN_POINT ( 'NONE', ( 30.06884912282138700, 134.4748413268802096, 93.56566892047057138 ) ) ; -#27978 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 130.4381646051676285, 91.31727167258139843 ) ) ; -#27979 = VERTEX_POINT ( 'NONE', #31888 ) ; -#27980 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971545418 ) ) ; -#27981 = CARTESIAN_POINT ( 'NONE', ( -39.76461490650798680, 169.2256028002626635, 164.4823439763816282 ) ) ; -#27982 = CARTESIAN_POINT ( 'NONE', ( -3.952287704705344851, 143.6302336283734178, 95.46685700466385072 ) ) ; -#27983 = ORIENTED_EDGE ( 'NONE', *, *, #1517, .T. ) ; -#27984 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501097438, 132.2930706491154922, 93.28496646309041296 ) ) ; -#27985 = DIRECTION ( 'NONE', ( -0.7075227875440994740, 0.1589708073325998561, -0.6885780910846993619 ) ) ; -#27986 = CARTESIAN_POINT ( 'NONE', ( -26.15087763400000043, 190.7042518446999964, 106.9127768281999948 ) ) ; -#27987 = EDGE_CURVE ( 'NONE', #15231, #929, #3646, .T. ) ; -#27988 = ADVANCED_FACE ( 'NONE', ( #789 ), #25760, .T. ) ; -#27989 = PLANE ( 'NONE', #7813 ) ; -#27990 = CARTESIAN_POINT ( 'NONE', ( -5.670798188510340232, 124.5598963420014513, 88.67914814188733885 ) ) ; -#27991 = VERTEX_POINT ( 'NONE', #35109 ) ; -#27992 = CARTESIAN_POINT ( 'NONE', ( 19.98635445618997863, 211.0854288155255460, 76.04696776081749476 ) ) ; -#27993 = LINE ( 'NONE', #18541, #17272 ) ; -#27994 = CYLINDRICAL_SURFACE ( 'NONE', #29952, 1.750000000000001998 ) ; -#27995 = VECTOR ( 'NONE', #10573, 999.9999999999998863 ) ; -#27996 = FACE_OUTER_BOUND ( 'NONE', #35786, .T. ) ; -#27997 = ORIENTED_EDGE ( 'NONE', *, *, #25674, .F. ) ; -#27998 = CARTESIAN_POINT ( 'NONE', ( 38.42898351650580935, 118.9831930641796447, 90.24774914394696168 ) ) ; -#27999 = CARTESIAN_POINT ( 'NONE', ( 13.45514494945999928, 202.1123865980000289, 28.07991271570000080 ) ) ; -#28000 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501101346, 132.2930706491314936, 93.28496646302122031 ) ) ; -#28001 = CARTESIAN_POINT ( 'NONE', ( -38.11718854129877343, 118.8155790694493561, 90.29079743518840928 ) ) ; -#28002 = CARTESIAN_POINT ( 'NONE', ( -36.36299666547999720, 191.9032661002999873, 104.5546124913999932 ) ) ; -#28003 = CARTESIAN_POINT ( 'NONE', ( -25.83888629021704730, 190.8929348362623557, 106.6474986096369406 ) ) ; -#28004 = DIRECTION ( 'NONE', ( 0.0005884949961243157984, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#28005 = CARTESIAN_POINT ( 'NONE', ( 38.69679614704350001, 191.0388310801824332, 103.7343411210213873 ) ) ; -#28006 = EDGE_CURVE ( 'NONE', #39173, #23378, #35544, .T. ) ; -#28007 = CARTESIAN_POINT ( 'NONE', ( 21.21575639516963463, 182.9122697023876754, 104.4344951008579443 ) ) ; -#28008 = CARTESIAN_POINT ( 'NONE', ( 30.44722912950143012, 185.6116624768459360, 102.4863628262051947 ) ) ; -#28009 = CARTESIAN_POINT ( 'NONE', ( 26.75419196830544166, 181.6923716698377689, 101.5837815084677658 ) ) ; -#28010 = CYLINDRICAL_SURFACE ( 'NONE', #1936, 5.999999999651004501 ) ; -#28011 = CARTESIAN_POINT ( 'NONE', ( 36.18932490265000013, 192.0082684861000075, 104.3659335172000198 ) ) ; -#28012 = ORIENTED_EDGE ( 'NONE', *, *, #33764, .F. ) ; -#28013 = CARTESIAN_POINT ( 'NONE', ( 36.78843971972000304, 191.5252555525999867, 106.2249300401000056 ) ) ; -#28014 = ORIENTED_EDGE ( 'NONE', *, *, #18752, .F. ) ; -#28015 = ORIENTED_EDGE ( 'NONE', *, *, #34274, .F. ) ; -#28017 = CIRCLE ( 'NONE', #9066, 4.999999999999990230 ) ; -#28016 = FACE_OUTER_BOUND ( 'NONE', #14763, .T. ) ; -#28018 = CARTESIAN_POINT ( 'NONE', ( 37.96506445775530381, 190.7637513255541535, 106.4080848624315081 ) ) ; -#28019 = ADVANCED_FACE ( 'NONE', ( #7121 ), #10418, .F. ) ; -#28020 = CYLINDRICAL_SURFACE ( 'NONE', #13444, 8.999999999999994671 ) ; -#28021 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11447, #26598, #8391, #17349 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28022 = AXIS2_PLACEMENT_3D ( 'NONE', #4682, #29439, #13895 ) ; -#28023 = ORIENTED_EDGE ( 'NONE', *, *, #35974, .T. ) ; -#28024 = CARTESIAN_POINT ( 'NONE', ( 36.49193471766000130, 191.9013877111999875, 104.5110495927000045 ) ) ; -#28025 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#28026 = CARTESIAN_POINT ( 'NONE', ( 13.49436806345008399, 123.6932719124138345, 91.28058047958029420 ) ) ; -#28027 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#28028 = DIRECTION ( 'NONE', ( -0.7933533411653073131, 0.5930537057989940797, 0.1373964268091562024 ) ) ; -#28029 = EDGE_LOOP ( 'NONE', ( #27483, #30488, #30092, #23843 ) ) ; -#28030 = DIRECTION ( 'NONE', ( 0.0005884949961241434102, -0.2249510543439057764, 0.9743698870671265722 ) ) ; -#28031 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11645, #11036, #14105, #35943 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28032 = CARTESIAN_POINT ( 'NONE', ( 23.36189990591568133, 175.3591898460452114, 100.1205101937285349 ) ) ; -#28033 = EDGE_CURVE ( 'NONE', #27218, #34462, #37999, .T. ) ; -#28034 = EDGE_CURVE ( 'NONE', #18635, #39966, #14282, .T. ) ; -#28035 = CARTESIAN_POINT ( 'NONE', ( -12.64523939051215073, 134.9174765714697344, 90.80875027841997849 ) ) ; -#28036 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.110223024625155594E-14, -1.000000000000000000 ) ) ; -#28037 = EDGE_CURVE ( 'NONE', #7067, #12730, #33228, .T. ) ; -#28038 = ORIENTED_EDGE ( 'NONE', *, *, #3720, .T. ) ; -#28039 = FACE_OUTER_BOUND ( 'NONE', #26122, .T. ) ; -#28040 = CARTESIAN_POINT ( 'NONE', ( 1.548525489068410366, 189.2671695052339658, 103.7726728760049895 ) ) ; -#28041 = CARTESIAN_POINT ( 'NONE', ( -45.39695617069071432, 130.9021434594297091, 91.44093725908659565 ) ) ; -#28042 = VERTEX_POINT ( 'NONE', #8353 ) ; -#28043 = CARTESIAN_POINT ( 'NONE', ( 18.92701962846999919, 153.5843418025999938, 96.63868624690000786 ) ) ; -#28044 = ORIENTED_EDGE ( 'NONE', *, *, #1928, .T. ) ; -#28045 = CARTESIAN_POINT ( 'NONE', ( -3.169906973560626895, 184.1222312815566795, 102.1628149875517408 ) ) ; -#28046 = VECTOR ( 'NONE', #16281, 1000.000000000000000 ) ; -#28047 = CARTESIAN_POINT ( 'NONE', ( -15.94446165338357702, 121.2066837107214212, 177.4195636231463027 ) ) ; -#28048 = FACE_OUTER_BOUND ( 'NONE', #4791, .T. ) ; -#28049 = CONICAL_SURFACE ( 'NONE', #26084, 51.90509899263580706, 0.7853981633972871856 ) ; -#28050 = CIRCLE ( 'NONE', #5877, 2.999999999919165550 ) ; -#28051 = AXIS2_PLACEMENT_3D ( 'NONE', #29491, #7604, #10897 ) ; -#28052 = PLANE ( 'NONE', #9802 ) ; -#28053 = CARTESIAN_POINT ( 'NONE', ( -3.669581230394507898, 185.7947741359049019, 103.0623953380812168 ) ) ; -#28054 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#28055 = CARTESIAN_POINT ( 'NONE', ( 25.99030105615392827, 209.7097546603872900, 73.04280869622928662 ) ) ; -#28056 = ORIENTED_EDGE ( 'NONE', *, *, #10890, .T. ) ; -#28057 = LINE ( 'NONE', #21915, #25734 ) ; -#28058 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319364164186 ) ) ; -#28059 = LINE ( 'NONE', #30, #16364 ) ; -#28061 = CARTESIAN_POINT ( 'NONE', ( 15.05947164863658116, 123.5176133570900845, 178.5140257238748518 ) ) ; -#28060 = FACE_OUTER_BOUND ( 'NONE', #24199, .T. ) ; -#28062 = ORIENTED_EDGE ( 'NONE', *, *, #12138, .F. ) ; -#28063 = ADVANCED_FACE ( 'NONE', ( #30019 ), #32867, .F. ) ; -#28064 = DIRECTION ( 'NONE', ( 0.0005734119072320155485, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#28065 = ORIENTED_EDGE ( 'NONE', *, *, #18242, .F. ) ; -#28066 = ORIENTED_EDGE ( 'NONE', *, *, #39635, .T. ) ; -#28067 = CARTESIAN_POINT ( 'NONE', ( 39.68494082915999854, 119.6892224767999977, 90.21586879058999386 ) ) ; -#28068 = CARTESIAN_POINT ( 'NONE', ( -13.49083856689536987, 187.6673735495426740, 106.0664666259349644 ) ) ; -#28069 = AXIS2_PLACEMENT_3D ( 'NONE', #4307, #291, #103 ) ; -#28070 = EDGE_CURVE ( 'NONE', #26260, #3107, #22173, .T. ) ; -#28071 = CARTESIAN_POINT ( 'NONE', ( 14.55294048017762698, 182.5605668518259392, 101.7915615195478409 ) ) ; -#28072 = CARTESIAN_POINT ( 'NONE', ( -20.00062605139820704, 196.5784656963837733, 103.8871944330217048 ) ) ; -#28073 = CARTESIAN_POINT ( 'NONE', ( 29.42812340194186049, 130.8370083103818615, 89.84125070675843006 ) ) ; -#28074 = PLANE ( 'NONE', #35372 ) ; -#28075 = VERTEX_POINT ( 'NONE', #20398 ) ; -#28076 = CARTESIAN_POINT ( 'NONE', ( 15.95616231907572313, 121.8746118785549157, 174.5826276267837613 ) ) ; -#28077 = VECTOR ( 'NONE', #27904, 1000.000000000000114 ) ; -#28078 = VERTEX_POINT ( 'NONE', #39005 ) ; -#28079 = VECTOR ( 'NONE', #32074, 1000.000000000000114 ) ; -#28080 = DIRECTION ( 'NONE', ( 0.0005884949961228831336, -0.2249510543439064980, 0.9743698870671262391 ) ) ; -#28081 = EDGE_CURVE ( 'NONE', #4354, #7294, #14119, .T. ) ; -#28082 = ADVANCED_FACE ( 'NONE', ( #21027 ), #27420, .T. ) ; -#28083 = VECTOR ( 'NONE', #24122, 1000.000000000000114 ) ; -#28084 = PLANE ( 'NONE', #24259 ) ; -#28085 = CARTESIAN_POINT ( 'NONE', ( -23.37153626856268218, 181.6857280266875421, 101.6124992246220842 ) ) ; -#28086 = EDGE_CURVE ( 'NONE', #35965, #6128, #34624, .T. ) ; -#28087 = ORIENTED_EDGE ( 'NONE', *, *, #2088, .T. ) ; -#28088 = CARTESIAN_POINT ( 'NONE', ( -36.18404661049999760, 190.9553995324999960, 106.8395213493000000 ) ) ; -#28089 = EDGE_CURVE ( 'NONE', #89, #27242, #6466, .T. ) ; -#28090 = FACE_OUTER_BOUND ( 'NONE', #6612, .T. ) ; -#28091 = DIRECTION ( 'NONE', ( -0.0005884949961227775323, 0.2249510543439063315, -0.9743698870671264611 ) ) ; -#28092 = ORIENTED_EDGE ( 'NONE', *, *, #10347, .T. ) ; -#28093 = ORIENTED_EDGE ( 'NONE', *, *, #7141, .T. ) ; -#28094 = CARTESIAN_POINT ( 'NONE', ( 2.962527580964340324, 190.0861127772304258, 106.6265932751835805 ) ) ; -#28095 = FACE_OUTER_BOUND ( 'NONE', #40405, .T. ) ; -#28096 = CARTESIAN_POINT ( 'NONE', ( 21.27838750203562768, 176.7284879462769425, 100.4410577670730333 ) ) ; -#28097 = CARTESIAN_POINT ( 'NONE', ( -27.20710394601999838, 124.5624848500000041, 90.85369269781000412 ) ) ; -#28098 = CARTESIAN_POINT ( 'NONE', ( -20.01219580461844316, 201.3437115538952469, 84.98297556926431184 ) ) ; -#28099 = CARTESIAN_POINT ( 'NONE', ( 26.73277628323574717, 120.3821797830261033, 171.5759152015846496 ) ) ; -#28100 = CARTESIAN_POINT ( 'NONE', ( 82.77222000466073837, 72.24422888835732692, 166.6196021931943960 ) ) ; -#28101 = VECTOR ( 'NONE', #34473, 1000.000000000000114 ) ; -#28102 = EDGE_CURVE ( 'NONE', #11668, #12094, #32595, .T. ) ; -#28103 = AXIS2_PLACEMENT_3D ( 'NONE', #29963, #36290, #36494 ) ; -#28104 = EDGE_LOOP ( 'NONE', ( #4176, #1671, #18865 ) ) ; -#28105 = AXIS2_PLACEMENT_3D ( 'NONE', #26579, #29639, #5284 ) ; -#28106 = DIRECTION ( 'NONE', ( 0.0005884949961239352434, -0.2249510543439079413, 0.9743698870671259060 ) ) ; -#28107 = EDGE_LOOP ( 'NONE', ( #9708, #22862 ) ) ; -#28109 = CARTESIAN_POINT ( 'NONE', ( 40.29675614866165745, 187.8287955346809213, 108.1243603913822824 ) ) ; -#28108 = CARTESIAN_POINT ( 'NONE', ( 36.14780637420843590, 192.0877688002536843, 104.3837537224991934 ) ) ; -#28110 = ORIENTED_EDGE ( 'NONE', *, *, #33953, .F. ) ; -#28111 = ORIENTED_EDGE ( 'NONE', *, *, #15906, .F. ) ; -#28112 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; -#28113 = EDGE_CURVE ( 'NONE', #36005, #4191, #23477, .T. ) ; -#28114 = CARTESIAN_POINT ( 'NONE', ( 40.91997143381097146, 127.4822456336884358, 89.05980178640240297 ) ) ; -#28115 = CARTESIAN_POINT ( 'NONE', ( -40.69272868350516603, 120.3526484630499880, 90.54200919470581255 ) ) ; -#28116 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#28117 = ORIENTED_EDGE ( 'NONE', *, *, #1257, .T. ) ; -#28118 = VERTEX_POINT ( 'NONE', #2220 ) ; -#28119 = CARTESIAN_POINT ( 'NONE', ( -19.35302328312414488, 125.0106235229416285, 177.9777102502699222 ) ) ; -#28120 = DIRECTION ( 'NONE', ( -0.0006039748319384231684, -2.335630580398557718E-15, -0.9999998176071847045 ) ) ; -#28121 = CARTESIAN_POINT ( 'NONE', ( 2.460508346168839733, 209.5732971666951698, 73.55701931308026076 ) ) ; -#28122 = CARTESIAN_POINT ( 'NONE', ( -43.19348492542150808, 172.3884102536505907, 184.6076772393078897 ) ) ; -#28123 = ADVANCED_FACE ( 'NONE', ( #39612 ), #14311, .F. ) ; -#28124 = EDGE_LOOP ( 'NONE', ( #17777, #39012, #11181 ) ) ; -#28125 = VERTEX_POINT ( 'NONE', #4663 ) ; -#28126 = FACE_OUTER_BOUND ( 'NONE', #15983, .T. ) ; -#28127 = CARTESIAN_POINT ( 'NONE', ( 20.16844586256894800, 173.8874256999797012, 102.6935641049061019 ) ) ; -#28128 = CARTESIAN_POINT ( 'NONE', ( -15.99823486130475736, 118.9409032897876841, 90.20116722531847131 ) ) ; -#28129 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#28130 = EDGE_CURVE ( 'NONE', #626, #25046, #17117, .T. ) ; -#28131 = VERTEX_POINT ( 'NONE', #37557 ) ; -#28132 = CARTESIAN_POINT ( 'NONE', ( 22.50140346553463644, 157.8319422969905759, 98.98556753889189963 ) ) ; -#28133 = CARTESIAN_POINT ( 'NONE', ( 23.39364800404629818, 165.2216646694212727, 152.9217693189764304 ) ) ; -#28134 = DIRECTION ( 'NONE', ( -0.7933533411653075351, -0.5931840316265221125, -0.1368326740407720954 ) ) ; -#28135 = ORIENTED_EDGE ( 'NONE', *, *, #26536, .T. ) ; -#28136 = AXIS2_PLACEMENT_3D ( 'NONE', #24355, #32915, #20858 ) ; -#28137 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; -#28138 = CARTESIAN_POINT ( 'NONE', ( -29.20104124294445214, 148.3921741051831873, 97.00850424916733061 ) ) ; -#28139 = CARTESIAN_POINT ( 'NONE', ( -5.666776224462409139, 187.4258185150888210, 105.6738796381353751 ) ) ; -#28140 = CARTESIAN_POINT ( 'NONE', ( -38.86369644165072401, 118.8228811219059793, 89.72077589445396484 ) ) ; -#28141 = CARTESIAN_POINT ( 'NONE', ( -42.38963504733576571, 73.00513959036860001, 297.5841473069626772 ) ) ; -#28142 = EDGE_LOOP ( 'NONE', ( #12715, #29161, #11759, #39116, #22127, #23337, #37207, #32723 ) ) ; -#28143 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -2.702666754117757870E-16, 0.0006039748319385827629 ) ) ; -#28144 = ORIENTED_EDGE ( 'NONE', *, *, #25311, .F. ) ; -#28145 = VERTEX_POINT ( 'NONE', #18334 ) ; -#28146 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971551247 ) ) ; -#28147 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; -#28148 = CARTESIAN_POINT ( 'NONE', ( 38.50968654372999822, 118.5704612529000030, 89.80384588171000360 ) ) ; -#28149 = EDGE_LOOP ( 'NONE', ( #39335, #12306, #6469, #18621 ) ) ; -#28150 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; -#28151 = ORIENTED_EDGE ( 'NONE', *, *, #32179, .T. ) ; -#28152 = CARTESIAN_POINT ( 'NONE', ( 6.034640323947002116, 177.1924675530794957, 101.0705349086647828 ) ) ; -#28153 = AXIS2_PLACEMENT_3D ( 'NONE', #23239, #35674, #20152 ) ; -#28154 = CONICAL_SURFACE ( 'NONE', #18316, 2.500000004850577717, 0.7853981634372142473 ) ; -#28155 = ORIENTED_EDGE ( 'NONE', *, *, #5561, .F. ) ; -#28156 = EDGE_CURVE ( 'NONE', #23821, #28951, #37796, .T. ) ; -#28157 = CARTESIAN_POINT ( 'NONE', ( -38.93916630444905280, 183.7310523952955350, 102.0940973430918604 ) ) ; -#28158 = AXIS2_PLACEMENT_3D ( 'NONE', #37998, #10213, #22879 ) ; -#28159 = EDGE_CURVE ( 'NONE', #5720, #14356, #6273, .T. ) ; -#28160 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#28161 = VECTOR ( 'NONE', #7682, 1000.000000000000114 ) ; -#28162 = CARTESIAN_POINT ( 'NONE', ( -37.29474482131207935, 164.7567791378876052, 197.5716176305500085 ) ) ; -#28163 = EDGE_CURVE ( 'NONE', #36719, #38838, #31036, .T. ) ; -#28164 = CARTESIAN_POINT ( 'NONE', ( 23.36232515670958065, 177.1947614343970372, 101.0605990059838462 ) ) ; -#28165 = EDGE_CURVE ( 'NONE', #32551, #23376, #25395, .T. ) ; -#28166 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555133 ) ) ; -#28167 = ORIENTED_EDGE ( 'NONE', *, *, #4497, .T. ) ; -#28168 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#28169 = ORIENTED_EDGE ( 'NONE', *, *, #20209, .F. ) ; -#28170 = VERTEX_POINT ( 'NONE', #27593 ) ; -#28171 = CARTESIAN_POINT ( 'NONE', ( -22.46828090686999957, 162.3883503090999909, 152.4718672074000381 ) ) ; -#28172 = CARTESIAN_POINT ( 'NONE', ( 4.035676230723896474, 174.7936433537998653, 102.5705385170005997 ) ) ; -#28173 = EDGE_CURVE ( 'NONE', #26491, #1098, #12609, .T. ) ; -#28174 = ORIENTED_EDGE ( 'NONE', *, *, #19327, .F. ) ; -#28175 = CARTESIAN_POINT ( 'NONE', ( -23.36173673102033632, 135.2906635749613997, 91.41449413045401684 ) ) ; -#28176 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#28177 = ORIENTED_EDGE ( 'NONE', *, *, #26073, .T. ) ; -#28178 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; -#28179 = ADVANCED_FACE ( 'NONE', ( #12228 ), #37166, .F. ) ; -#28180 = CARTESIAN_POINT ( 'NONE', ( 36.90300980118022522, 190.5697579479422927, 106.7060433226621541 ) ) ; -#28181 = CARTESIAN_POINT ( 'NONE', ( -30.07128175106310408, 134.7905956161418146, 93.39787389195613798 ) ) ; -#28182 = ORIENTED_EDGE ( 'NONE', *, *, #29073, .F. ) ; -#28183 = CARTESIAN_POINT ( 'NONE', ( 27.88838870525999880, 125.3341793757000175, 89.08508767201000467 ) ) ; -#28184 = CARTESIAN_POINT ( 'NONE', ( 3.738724522724006682, 167.8697915648398862, 101.2771627622597634 ) ) ; -#28185 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#28186 = AXIS2_PLACEMENT_3D ( 'NONE', #640, #3899, #13128 ) ; -#28187 = CARTESIAN_POINT ( 'NONE', ( 13.47422552046212019, 158.3810130762119570, 98.09148005191302389 ) ) ; -#28188 = FACE_OUTER_BOUND ( 'NONE', #2276, .T. ) ; -#28189 = ORIENTED_EDGE ( 'NONE', *, *, #17615, .F. ) ; -#28190 = CARTESIAN_POINT ( 'NONE', ( 16.44620207817152036, 122.3647578235614048, 174.6137112058796106 ) ) ; -#28191 = AXIS2_PLACEMENT_3D ( 'NONE', #19414, #4882, #23300 ) ; -#28192 = CARTESIAN_POINT ( 'NONE', ( 35.98188939040999657, 181.5059044966999977, 104.6140438237000012 ) ) ; -#28193 = CARTESIAN_POINT ( 'NONE', ( -45.88101201451510036, 125.0059045045339445, 91.84762798775689419 ) ) ; -#28194 = ORIENTED_EDGE ( 'NONE', *, *, #28880, .F. ) ; -#28195 = ORIENTED_EDGE ( 'NONE', *, *, #37817, .F. ) ; -#28196 = CARTESIAN_POINT ( 'NONE', ( 38.37691917934760966, 118.9413681235701716, 90.24641942494658053 ) ) ; -#28197 = CARTESIAN_POINT ( 'NONE', ( -40.69272868349872851, 120.3526484630613567, 90.54200919472567932 ) ) ; -#28198 = CARTESIAN_POINT ( 'NONE', ( 25.99018610745488900, 211.0908525021142168, 73.04280463953621449 ) ) ; -#28199 = DIRECTION ( 'NONE', ( -0.7069375452530715087, 0.1593035203500499375, -0.6891020936810761111 ) ) ; -#28200 = CARTESIAN_POINT ( 'NONE', ( -25.50169130963128694, 190.9445587163764912, 106.3119803418707789 ) ) ; -#28201 = ORIENTED_EDGE ( 'NONE', *, *, #25535, .T. ) ; -#28202 = CARTESIAN_POINT ( 'NONE', ( -30.96737657860713355, 184.1206350860066152, 102.1792248493828055 ) ) ; -#28203 = FACE_OUTER_BOUND ( 'NONE', #14579, .T. ) ; -#28204 = CARTESIAN_POINT ( 'NONE', ( -22.78329764787637046, 154.4034317766920310, 95.31352365236099899 ) ) ; -#28205 = DIRECTION ( 'NONE', ( -0.6087613505917195411, 0.7729391288371411095, 0.1788147676737769087 ) ) ; -#28206 = ORIENTED_EDGE ( 'NONE', *, *, #7651, .T. ) ; -#28207 = FACE_OUTER_BOUND ( 'NONE', #27084, .T. ) ; -#28208 = DIRECTION ( 'NONE', ( -0.0006039748319369898531, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#28209 = CARTESIAN_POINT ( 'NONE', ( -4.036853220715999946, 137.3587048356999958, 92.90657171102999712 ) ) ; -#28210 = EDGE_CURVE ( 'NONE', #21097, #31137, #39485, .T. ) ; -#28211 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22973, #26249, #4543, #10312 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28212 = AXIS2_PLACEMENT_3D ( 'NONE', #31748, #32537, #3710 ) ; -#28213 = EDGE_CURVE ( 'NONE', #26074, #34665, #38042, .T. ) ; -#28215 = ORIENTED_EDGE ( 'NONE', *, *, #15184, .F. ) ; -#28214 = FACE_OUTER_BOUND ( 'NONE', #34459, .T. ) ; -#28216 = ORIENTED_EDGE ( 'NONE', *, *, #37650, .F. ) ; -#28217 = ORIENTED_EDGE ( 'NONE', *, *, #5766, .T. ) ; -#28218 = CIRCLE ( 'NONE', #8631, 48.00000000000002132 ) ; -#28219 = CARTESIAN_POINT ( 'NONE', ( -3.991797733021813510, 135.9364417893758059, 91.03873269948198299 ) ) ; -#28220 = AXIS2_PLACEMENT_3D ( 'NONE', #35339, #4690, #17148 ) ; -#28221 = CARTESIAN_POINT ( 'NONE', ( 37.96499143901794326, 190.9636352903536363, 106.2831835502989719 ) ) ; -#28222 = DIRECTION ( 'NONE', ( -0.6185863125140933505, -0.7857168535612664151, 0.000000000000000000 ) ) ; -#28223 = ORIENTED_EDGE ( 'NONE', *, *, #5754, .F. ) ; -#28224 = CARTESIAN_POINT ( 'NONE', ( 38.26442139451999935, 118.3961640203000059, 87.79339008044999559 ) ) ; -#28225 = CARTESIAN_POINT ( 'NONE', ( -15.53688711337808392, 141.8436893266793106, 28.08107123285647688 ) ) ; -#28226 = CARTESIAN_POINT ( 'NONE', ( 37.71190864537933862, 212.3970730851055748, 73.53572712575454773 ) ) ; -#28227 = DIRECTION ( 'NONE', ( -0.9999998268368293086, -0.0001323825425856265552, 0.0005734118708436176113 ) ) ; -#28228 = ORIENTED_EDGE ( 'NONE', *, *, #12349, .T. ) ; -#28229 = FACE_OUTER_BOUND ( 'NONE', #10019, .T. ) ; -#28230 = CARTESIAN_POINT ( 'NONE', ( 25.91387799687219129, 211.8752679534836432, 76.04289190268519860 ) ) ; -#28231 = FACE_OUTER_BOUND ( 'NONE', #1743, .T. ) ; -#28232 = CARTESIAN_POINT ( 'NONE', ( 42.83909608654821710, 114.0261269506707720, 121.8710131577738167 ) ) ; -#28233 = CARTESIAN_POINT ( 'NONE', ( -30.07053858951977432, 176.7377855870873873, 103.0399784982492264 ) ) ; -#28234 = ORIENTED_EDGE ( 'NONE', *, *, #20370, .T. ) ; -#28235 = EDGE_CURVE ( 'NONE', #29048, #25314, #4871, .T. ) ; -#28236 = CARTESIAN_POINT ( 'NONE', ( 12.64167983538768247, 177.0102573821494047, 103.4424840777840870 ) ) ; -#28237 = CARTESIAN_POINT ( 'NONE', ( 2.724721502837000209, 190.8511545057000092, 104.0546029546000000 ) ) ; -#28238 = CARTESIAN_POINT ( 'NONE', ( -22.49965381657531438, 154.0036946681026393, 95.56316798547172198 ) ) ; -#28239 = ORIENTED_EDGE ( 'NONE', *, *, #30044, .F. ) ; -#28240 = CIRCLE ( 'NONE', #22370, 2.500000000028349767 ) ; -#28241 = CARTESIAN_POINT ( 'NONE', ( -12.63793912156016042, 182.0618459091404873, 102.2059974569859975 ) ) ; -#28242 = ORIENTED_EDGE ( 'NONE', *, *, #1742, .T. ) ; -#28243 = AXIS2_PLACEMENT_3D ( 'NONE', #29301, #10700, #20287 ) ; -#28244 = PLANE ( 'NONE', #38434 ) ; -#28245 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #1296, #1104, #8045, #39315 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.877759422838638059, 4.066897489514542663 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9970211203892868079, 0.9970211203892868079, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#28246 = CARTESIAN_POINT ( 'NONE', ( -18.71851310314255556, 125.9964326179262883, 174.7342168340691444 ) ) ; -#28247 = CARTESIAN_POINT ( 'NONE', ( 2.812852758428999955, 191.2630064568000137, 104.0643451705000047 ) ) ; -#28248 = DIRECTION ( 'NONE', ( 0.0005884933334877639251, -0.2249510526608011762, 0.9743698874567060519 ) ) ; -#28249 = CARTESIAN_POINT ( 'NONE', ( -36.77540113530000099, 191.4363505423999925, 106.2577542721000015 ) ) ; -#28250 = ORIENTED_EDGE ( 'NONE', *, *, #23674, .T. ) ; -#28251 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#28252 = FACE_OUTER_BOUND ( 'NONE', #2742, .T. ) ; -#28253 = EDGE_CURVE ( 'NONE', #25168, #16126, #22418, .T. ) ; -#28254 = ADVANCED_FACE ( 'NONE', ( #40022 ), #33882, .F. ) ; -#28255 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#28256 = ORIENTED_EDGE ( 'NONE', *, *, #18528, .F. ) ; -#28257 = ORIENTED_EDGE ( 'NONE', *, *, #20059, .T. ) ; -#28258 = ORIENTED_EDGE ( 'NONE', *, *, #34225, .T. ) ; -#28259 = CYLINDRICAL_SURFACE ( 'NONE', #32197, 1.999999999999989564 ) ; -#28260 = CARTESIAN_POINT ( 'NONE', ( -19.46376889861871007, 126.0568456380973288, 176.8090460237677348 ) ) ; -#28261 = CONICAL_SURFACE ( 'NONE', #17780, 4.999999999873454115, 0.7853981633979292276 ) ; -#28262 = VERTEX_POINT ( 'NONE', #1148 ) ; -#28263 = CARTESIAN_POINT ( 'NONE', ( 39.95261991177000027, 119.3835613333999959, 89.61779218156000582 ) ) ; -#28264 = CARTESIAN_POINT ( 'NONE', ( 0.5441254074100964067, 211.4999999999614602, 73.05817544432547095 ) ) ; -#28265 = VECTOR ( 'NONE', #19204, 1000.000000000000227 ) ; -#28266 = DIRECTION ( 'NONE', ( -0.0006039748319391919761, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#28267 = CARTESIAN_POINT ( 'NONE', ( -38.01969208680999657, 119.2054080613999929, 87.30150489016999416 ) ) ; -#28268 = CARTESIAN_POINT ( 'NONE', ( -37.26053171017113641, 122.4594309094748326, 105.8893166679895472 ) ) ; -#28269 = ORIENTED_EDGE ( 'NONE', *, *, #28163, .T. ) ; -#28270 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250613436, 179.6252109630477207, 101.6466942237163522 ) ) ; -#28271 = VERTEX_POINT ( 'NONE', #22039 ) ; -#28272 = CARTESIAN_POINT ( 'NONE', ( -28.70875735419499364, 148.8778593096899669, 94.55457546971690874 ) ) ; -#28273 = LINE ( 'NONE', #3110, #19680 ) ; -#28274 = ORIENTED_EDGE ( 'NONE', *, *, #21153, .T. ) ; -#28275 = VERTEX_POINT ( 'NONE', #4200 ) ; -#28276 = CARTESIAN_POINT ( 'NONE', ( -15.99999263269153182, 160.7450692216915513, 96.77351201758563093 ) ) ; -#28277 = CARTESIAN_POINT ( 'NONE', ( 2.689650463064989339, 189.7940790364034740, 103.4687148295890040 ) ) ; -#28278 = DIRECTION ( 'NONE', ( -0.0005884949961246157971, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#28279 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11475, #40077, #17588, #36819 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 3.455345801775207831E-07, 0.001975602230082555786 ), - .UNSPECIFIED. ) ; -#28280 = ORIENTED_EDGE ( 'NONE', *, *, #12188, .F. ) ; -#28281 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 77.27946979429643193, 322.5967026918629017 ) ) ; -#28282 = CARTESIAN_POINT ( 'NONE', ( -39.67267316526923082, 108.4053246579875776, 179.2050514857695021 ) ) ; -#28283 = ORIENTED_EDGE ( 'NONE', *, *, #35630, .T. ) ; -#28284 = CARTESIAN_POINT ( 'NONE', ( 20.50100932471902482, 118.1127835883590365, 89.75563873136169946 ) ) ; -#28285 = CARTESIAN_POINT ( 'NONE', ( 36.12477503817289204, 191.5193954017357783, 103.8468415931941990 ) ) ; -#28286 = CARTESIAN_POINT ( 'NONE', ( -25.36579399085000119, 120.1305625512000006, 89.82939052176000416 ) ) ; -#28287 = CIRCLE ( 'NONE', #23700, 6.500000058541756331 ) ; -#28288 = EDGE_CURVE ( 'NONE', #27254, #38370, #25831, .T. ) ; -#28289 = ORIENTED_EDGE ( 'NONE', *, *, #31857, .F. ) ; -#28290 = VECTOR ( 'NONE', #39961, 1000.000000000000000 ) ; -#28291 = CARTESIAN_POINT ( 'NONE', ( -13.46516334634018541, 157.8278071510762572, 99.00633757409819680 ) ) ; -#28292 = CARTESIAN_POINT ( 'NONE', ( -13.50742204590874351, 123.6898730104831117, 91.29604175845440750 ) ) ; -#28293 = EDGE_CURVE ( 'NONE', #35987, #16019, #9968, .T. ) ; -#28294 = AXIS2_PLACEMENT_3D ( 'NONE', #480, #3744, #37907 ) ; -#28295 = ORIENTED_EDGE ( 'NONE', *, *, #13267, .T. ) ; -#28296 = CARTESIAN_POINT ( 'NONE', ( 16.17545524454269312, 122.0361947523238229, 178.1139273532624259 ) ) ; -#28297 = CARTESIAN_POINT ( 'NONE', ( -1.458415330454428505, 152.0517121853154379, 130.6798743964100993 ) ) ; -#28298 = EDGE_CURVE ( 'NONE', #20118, #17896, #22811, .T. ) ; -#28299 = ADVANCED_FACE ( 'NONE', ( #38554 ), #19544, .F. ) ; -#28300 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5870, #22031, #33667, #33872 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28302 = CARTESIAN_POINT ( 'NONE', ( 35.76606814934199718, 191.7746197043701386, 103.8954709317327172 ) ) ; -#28301 = CARTESIAN_POINT ( 'NONE', ( 36.15259226440387863, 192.0798216505441758, 104.3835126011738197 ) ) ; -#28303 = EDGE_CURVE ( 'NONE', #38350, #2098, #37964, .T. ) ; -#28304 = ORIENTED_EDGE ( 'NONE', *, *, #16998, .F. ) ; -#28305 = EDGE_CURVE ( 'NONE', #39104, #17992, #13664, .T. ) ; -#28306 = VERTEX_POINT ( 'NONE', #19740 ) ; -#28307 = CARTESIAN_POINT ( 'NONE', ( -15.87151776090180100, 128.5901718154909474, 173.0117519459708433 ) ) ; -#28308 = DIRECTION ( 'NONE', ( 0.0005884984005724823181, -0.2249510543433854981, 0.9743698870651902322 ) ) ; -#28309 = VERTEX_POINT ( 'NONE', #28571 ) ; -#28310 = ORIENTED_EDGE ( 'NONE', *, *, #26500, .F. ) ; -#28311 = DIRECTION ( 'NONE', ( 0.0005884928212895036660, -0.2249510522791091927, 0.9743698875451358710 ) ) ; -#28312 = CARTESIAN_POINT ( 'NONE', ( -23.00157826576616671, 118.1131156702000169, 87.27825658246501916 ) ) ; -#28313 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 77.27946979429631824, 312.5857197240631535 ) ) ; -#28314 = CARTESIAN_POINT ( 'NONE', ( 35.68643125140999928, 191.8664213346000054, 103.8907803534000038 ) ) ; -#28315 = CIRCLE ( 'NONE', #29591, 47.50000000003990408 ) ; -#28316 = ORIENTED_EDGE ( 'NONE', *, *, #12787, .T. ) ; -#28317 = ORIENTED_EDGE ( 'NONE', *, *, #21281, .F. ) ; -#28318 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; -#28319 = FACE_OUTER_BOUND ( 'NONE', #18324, .T. ) ; -#28320 = VECTOR ( 'NONE', #17212, 1000.000000000000114 ) ; -#28321 = CARTESIAN_POINT ( 'NONE', ( -25.99570828418999824, 122.1044024015999980, 88.02969383087000210 ) ) ; -#28322 = ORIENTED_EDGE ( 'NONE', *, *, #3892, .T. ) ; -#28323 = CIRCLE ( 'NONE', #38736, 5.500000000022846613 ) ; -#28324 = ADVANCED_FACE ( 'NONE', ( #28965 ), #21510, .F. ) ; -#28325 = CARTESIAN_POINT ( 'NONE', ( -16.85990575305292083, 127.4181457678018035, 171.9189068126523807 ) ) ; -#28326 = CYLINDRICAL_SURFACE ( 'NONE', #36544, 6.000000000000008882 ) ; -#28327 = ORIENTED_EDGE ( 'NONE', *, *, #16779, .F. ) ; -#28328 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; -#28329 = CARTESIAN_POINT ( 'NONE', ( -5.667037705184884366, 187.3709129604629595, 105.5860125638189118 ) ) ; -#28330 = CARTESIAN_POINT ( 'NONE', ( -0.6151120320699999811, 188.2150256863999971, 106.3550489248000019 ) ) ; -#28331 = CARTESIAN_POINT ( 'NONE', ( 16.92715356280326233, 133.1527996547432338, 149.4950069489673581 ) ) ; -#28332 = EDGE_CURVE ( 'NONE', #21146, #8372, #7721, .T. ) ; -#28333 = ORIENTED_EDGE ( 'NONE', *, *, #26137, .T. ) ; -#28334 = DIRECTION ( 'NONE', ( -0.0005884986055440120847, 0.2249510543433680121, -0.9743698870650705501 ) ) ; -#28335 = EDGE_LOOP ( 'NONE', ( #21873, #12651, #17930, #1377 ) ) ; -#28336 = CARTESIAN_POINT ( 'NONE', ( 42.26901360392582063, 75.77666427028830753, 289.7178605909170415 ) ) ; -#28337 = CARTESIAN_POINT ( 'NONE', ( -38.59856012205000297, 118.8379521557999965, 87.85035348418999490 ) ) ; -#28338 = FACE_OUTER_BOUND ( 'NONE', #9954, .T. ) ; -#28339 = EDGE_CURVE ( 'NONE', #22101, #10159, #38458, .T. ) ; -#28340 = ORIENTED_EDGE ( 'NONE', *, *, #30419, .F. ) ; -#28341 = VECTOR ( 'NONE', #21187, 1000.000000000000000 ) ; -#28342 = VECTOR ( 'NONE', #3521, 1000.000000000000000 ) ; -#28343 = DIRECTION ( 'NONE', ( -0.6088835995545407442, -0.7728434649458200134, -0.1788120266761852595 ) ) ; -#28344 = ORIENTED_EDGE ( 'NONE', *, *, #10892, .F. ) ; -#28345 = EDGE_CURVE ( 'NONE', #33884, #15381, #3403, .T. ) ; -#28346 = CARTESIAN_POINT ( 'NONE', ( 24.99968009405584723, 116.5768933708840649, 89.75284153560482991 ) ) ; -#28347 = AXIS2_PLACEMENT_3D ( 'NONE', #33323, #30072, #39452 ) ; -#28348 = PLANE ( 'NONE', #29210 ) ; -#28349 = ADVANCED_FACE ( 'NONE', ( #35270 ), #11042, .T. ) ; -#28350 = EDGE_LOOP ( 'NONE', ( #9852, #20989, #23508, #6535, #7620, #18054, #34314, #13880 ) ) ; -#28351 = ORIENTED_EDGE ( 'NONE', *, *, #25489, .F. ) ; -#28352 = DIRECTION ( 'NONE', ( -0.0005884949961245386019, 0.2249510543439047772, -0.9743698870671267942 ) ) ; -#28353 = CARTESIAN_POINT ( 'NONE', ( 5.666638401078818887, 184.0130092264801647, 102.6454035786637178 ) ) ; -#28354 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12547, #28503, #38099, #476 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999992929630487914 ), - .UNSPECIFIED. ) ; -#28355 = CARTESIAN_POINT ( 'NONE', ( -20.19472725636804000, 159.7949336108657405, 96.55668671736475517 ) ) ; -#28356 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30202, #2199, #11602, #9948 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28357 = CARTESIAN_POINT ( 'NONE', ( -36.18146673395180102, 116.0141564695149725, 90.28963753848354656 ) ) ; -#28358 = ORIENTED_EDGE ( 'NONE', *, *, #20907, .F. ) ; -#28359 = VERTEX_POINT ( 'NONE', #37755 ) ; -#28360 = CARTESIAN_POINT ( 'NONE', ( 39.71642354168957922, 182.5096340661373802, 106.7714012342299270 ) ) ; -#28361 = FACE_OUTER_BOUND ( 'NONE', #12884, .T. ) ; -#28362 = CARTESIAN_POINT ( 'NONE', ( 37.35431113053603269, 167.9917614804752759, 183.6110637893014825 ) ) ; -#28363 = ORIENTED_EDGE ( 'NONE', *, *, #36822, .F. ) ; -#28364 = CARTESIAN_POINT ( 'NONE', ( 19.98059076253610300, 209.7097557544199162, 73.04669817794425057 ) ) ; -#28365 = DIRECTION ( 'NONE', ( -0.6087611434179115433, 0.7728348325624404547, 0.1792657018023851023 ) ) ; -#28366 = VERTEX_POINT ( 'NONE', #3598 ) ; -#28367 = CARTESIAN_POINT ( 'NONE', ( -20.49823408210000153, 128.0735935753000092, 92.31233318296999357 ) ) ; -#28368 = DIRECTION ( 'NONE', ( -0.7933310414247657372, -0.5931044597393388962, -0.1373060761554398823 ) ) ; -#28369 = ORIENTED_EDGE ( 'NONE', *, *, #13067, .F. ) ; -#28370 = CARTESIAN_POINT ( 'NONE', ( 28.00973715401000419, 125.4209793305000034, 89.10502106993999405 ) ) ; -#28371 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#28372 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971553467 ) ) ; -#28373 = AXIS2_PLACEMENT_3D ( 'NONE', #27002, #14117, #7754 ) ; -#28374 = DIRECTION ( 'NONE', ( 0.9914448564834557054, 0.1271450465211625414, 0.02951666813228253847 ) ) ; -#28375 = CARTESIAN_POINT ( 'NONE', ( 4.722196207747476393, 124.5475539680846708, 88.40413725569121084 ) ) ; -#28376 = ORIENTED_EDGE ( 'NONE', *, *, #5566, .F. ) ; -#28377 = CARTESIAN_POINT ( 'NONE', ( 16.33425786393173595, 122.2176022978402870, 174.5993093248799255 ) ) ; -#28378 = CARTESIAN_POINT ( 'NONE', ( 31.79391164804994219, 225.9002260768944268, 73.03930135624560194 ) ) ; -#28379 = CARTESIAN_POINT ( 'NONE', ( -44.76913686494872735, 168.7247935234274507, 183.7603518044827808 ) ) ; -#28380 = EDGE_CURVE ( 'NONE', #40344, #34013, #31695, .T. ) ; -#28381 = CARTESIAN_POINT ( 'NONE', ( -26.00133084196312083, 118.1145346548141077, 87.28348844432062492 ) ) ; -#28382 = ORIENTED_EDGE ( 'NONE', *, *, #22709, .F. ) ; -#28383 = EDGE_CURVE ( 'NONE', #21313, #28523, #34526, .T. ) ; -#28384 = VERTEX_POINT ( 'NONE', #34867 ) ; -#28385 = CARTESIAN_POINT ( 'NONE', ( 38.37227342911298678, 118.9376377202380723, 90.24635654664764672 ) ) ; -#28386 = EDGE_CURVE ( 'NONE', #38190, #13026, #31847, .T. ) ; -#28387 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552357 ) ) ; -#28388 = CARTESIAN_POINT ( 'NONE', ( -34.95487766943205088, 217.7719116314000303, 76.07961649972587281 ) ) ; -#28389 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #5731, #21280, #8408, #27830 ), - ( #17771, #33728, #37015, #24151 ), - ( #30683, #40260, #2472, #39863 ), - ( #2676, #9010, #21491, #5925 ), - ( #12270, #24762, #37213, #9210 ), - ( #16469, #32045, #9407, #13229 ), - ( #10759, #16274, #32433, #19936 ), - ( #38360, #1144, #19540, #35663 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.09352946601170999963, 0.000000000000000000, 0.3333335556354999896, 0.6666667497720000224, 1.000000000000000000, 1.093335578620999948 ), - ( -0.2707488541708999996, 1.270751830638999991 ), - .UNSPECIFIED. ) ; -#28390 = CARTESIAN_POINT ( 'NONE', ( -9.337769819897999923, 135.1051653709000107, 91.10662228834000587 ) ) ; -#28391 = ORIENTED_EDGE ( 'NONE', *, *, #21332, .F. ) ; -#28392 = CARTESIAN_POINT ( 'NONE', ( -26.00499219198855982, 190.8675043533962992, 106.8127785445518612 ) ) ; -#28393 = ORIENTED_EDGE ( 'NONE', *, *, #38297, .F. ) ; -#28394 = EDGE_CURVE ( 'NONE', #17792, #5601, #36002, .T. ) ; -#28395 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749096068, 132.4103119504883637, 92.77713868752285009 ) ) ; -#28396 = ADVANCED_FACE ( 'NONE', ( #13234 ), #36518, .F. ) ; -#28397 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#28398 = CIRCLE ( 'NONE', #10769, 58.90509898902387675 ) ; -#28399 = ORIENTED_EDGE ( 'NONE', *, *, #16950, .T. ) ; -#28400 = DIRECTION ( 'NONE', ( -0.0006039748319386907495, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#28401 = CARTESIAN_POINT ( 'NONE', ( -25.99151835185281456, 191.8641524188973904, 103.9340199701208292 ) ) ; -#28402 = FACE_OUTER_BOUND ( 'NONE', #4841, .T. ) ; -#28403 = CARTESIAN_POINT ( 'NONE', ( 36.67721844215000004, 191.5565990098999976, 105.0176447302000042 ) ) ; -#28404 = VECTOR ( 'NONE', #16893, 1000.000000000000227 ) ; -#28406 = ORIENTED_EDGE ( 'NONE', *, *, #20042, .F. ) ; -#28405 = CARTESIAN_POINT ( 'NONE', ( 36.36316272580000231, 190.7132676102999937, 106.8883652936000033 ) ) ; -#28407 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #30868, #5499, #11656, #39845 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.1794458056510853106, 1.570796326794893227 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8450807331196341643, 0.8450807331196341643, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#28408 = ORIENTED_EDGE ( 'NONE', *, *, #39857, .F. ) ; -#28409 = ADVANCED_FACE ( 'NONE', ( #32436, #39160 ), #33025, .F. ) ; -#28410 = CARTESIAN_POINT ( 'NONE', ( -3.537750984983824232, 137.3463269818849426, 91.36396247942009552 ) ) ; -#28411 = CARTESIAN_POINT ( 'NONE', ( -10.03596943924098461, 167.8207392792199357, 101.4823675420411888 ) ) ; -#28412 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700560425843094, -0.2249510922124433321 ) ) ; -#28413 = ORIENTED_EDGE ( 'NONE', *, *, #33114, .F. ) ; -#28414 = DIRECTION ( 'NONE', ( 0.7856007465113973298, 0.6187337610642684727, -2.775557561562888984E-15 ) ) ; -#28415 = EDGE_LOOP ( 'NONE', ( #28215, #11685, #38019, #19140, #11815, #3144, #30758, #14148 ) ) ; -#28416 = CARTESIAN_POINT ( 'NONE', ( -3.191561267867959906, 128.9664370676184149, 89.42909670096250352 ) ) ; -#28417 = CARTESIAN_POINT ( 'NONE', ( 13.76428958134252412, 149.7303430850596726, 179.8030703197238722 ) ) ; -#28418 = ORIENTED_EDGE ( 'NONE', *, *, #27585, .F. ) ; -#28419 = FACE_OUTER_BOUND ( 'NONE', #8355, .T. ) ; -#28420 = CARTESIAN_POINT ( 'NONE', ( -9.152368346436000834, 130.1581468331999929, 92.53016161835999753 ) ) ; -#28421 = LINE ( 'NONE', #32097, #1168 ) ; -#28422 = DIRECTION ( 'NONE', ( 0.0002393071182786160318, 0.2252352986010024705, -0.9743043687658494711 ) ) ; -#28423 = CARTESIAN_POINT ( 'NONE', ( -20.00089539691495233, 118.1272453392662527, 87.27993277136866368 ) ) ; -#28424 = CARTESIAN_POINT ( 'NONE', ( 44.87593640575996545, 182.0270868175379064, 126.4518070426625087 ) ) ; -#28425 = VERTEX_POINT ( 'NONE', #26510 ) ; -#28426 = CARTESIAN_POINT ( 'NONE', ( 2.299083559809740773, 189.9861417232580436, 103.9812579833990043 ) ) ; -#28427 = AXIS2_PLACEMENT_3D ( 'NONE', #28270, #25610, #15976 ) ; -#28428 = CIRCLE ( 'NONE', #2959, 1.749999999999998446 ) ; -#28429 = LINE ( 'NONE', #6529, #31923 ) ; -#28430 = EDGE_CURVE ( 'NONE', #30562, #19329, #14083, .T. ) ; -#28431 = EDGE_CURVE ( 'NONE', #25244, #22597, #20768, .T. ) ; -#28432 = AXIS2_PLACEMENT_3D ( 'NONE', #9217, #37613, #13082 ) ; -#28433 = EDGE_LOOP ( 'NONE', ( #6385, #10949, #33166 ) ) ; -#28434 = PLANE ( 'NONE', #25779 ) ; -#28435 = ADVANCED_FACE ( 'NONE', ( #23041 ), #23640, .T. ) ; -#28436 = ORIENTED_EDGE ( 'NONE', *, *, #36640, .F. ) ; -#28437 = CARTESIAN_POINT ( 'NONE', ( 20.00164795315919974, 192.9502750275173355, 106.8376583096656418 ) ) ; -#28438 = EDGE_CURVE ( 'NONE', #25514, #31634, #13028, .T. ) ; -#28439 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 181.5925925342323808, 103.1272040707186051 ) ) ; -#28440 = LINE ( 'NONE', #18600, #20123 ) ; -#28441 = CARTESIAN_POINT ( 'NONE', ( -3.169881913554984720, 185.9062129263137138, 102.5746722649703315 ) ) ; -#28442 = EDGE_CURVE ( 'NONE', #27517, #17622, #27791, .T. ) ; -#28443 = CARTESIAN_POINT ( 'NONE', ( -35.81454439945957802, 108.4403536831198096, 169.8262657571169711 ) ) ; -#28444 = CARTESIAN_POINT ( 'NONE', ( -36.70169623595000274, 190.4202923789999886, 106.8599970589999941 ) ) ; -#28445 = ORIENTED_EDGE ( 'NONE', *, *, #40320, .T. ) ; -#28446 = CARTESIAN_POINT ( 'NONE', ( -5.631497921780000304, 112.1320600213999938, 152.4718672074000381 ) ) ; -#28447 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971574007 ) ) ; -#28448 = CYLINDRICAL_SURFACE ( 'NONE', #9212, 48.00000000000002132 ) ; -#28449 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#28450 = VECTOR ( 'NONE', #16492, 1000.000000000000000 ) ; -#28451 = ORIENTED_EDGE ( 'NONE', *, *, #2132, .F. ) ; -#28452 = EDGE_CURVE ( 'NONE', #1519, #9277, #1758, .T. ) ; -#28453 = CIRCLE ( 'NONE', #20583, 3.000000000000002220 ) ; -#28454 = ORIENTED_EDGE ( 'NONE', *, *, #14388, .F. ) ; -#28455 = CARTESIAN_POINT ( 'NONE', ( -29.94810852811952984, 104.1131156702273302, 87.28587219911912598 ) ) ; -#28456 = VECTOR ( 'NONE', #7659, 1000.000000000000114 ) ; -#28457 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142367503004439, 137.4659008082804519, 177.5714312369109393 ) ) ; -#28458 = AXIS2_PLACEMENT_3D ( 'NONE', #25065, #37512, #40168 ) ; -#28459 = EDGE_LOOP ( 'NONE', ( #34790, #27532, #37116, #14955 ) ) ; -#28460 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#28461 = LINE ( 'NONE', #6562, #33188 ) ; -#28462 = CARTESIAN_POINT ( 'NONE', ( -38.01110030706000487, 119.1986783965000001, 87.29992373471000633 ) ) ; -#28463 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700559946817386, 0.2249510924199318862 ) ) ; -#28464 = ORIENTED_EDGE ( 'NONE', *, *, #39114, .T. ) ; -#28465 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; -#28466 = ORIENTED_EDGE ( 'NONE', *, *, #21795, .F. ) ; -#28467 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#28468 = CARTESIAN_POINT ( 'NONE', ( 36.04411892353203228, 218.5902260770999987, 73.03673433779063373 ) ) ; -#28469 = ORIENTED_EDGE ( 'NONE', *, *, #814, .F. ) ; -#28470 = ORIENTED_EDGE ( 'NONE', *, *, #22668, .T. ) ; -#28471 = DIRECTION ( 'NONE', ( 0.0004161288024578961228, 0.5299192578740949955, 0.8480479980348919478 ) ) ; -#28472 = CARTESIAN_POINT ( 'NONE', ( 0.7394385361564065340, 188.6187616188480263, 103.1985492530441348 ) ) ; -#28473 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564570 ) ) ; -#28474 = EDGE_LOOP ( 'NONE', ( #15268, #14385, #30115, #31744 ) ) ; -#28475 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #39038, #2049, #23931, #4695 ), - .UNSPECIFIED., .F., .F. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.137875966956429785, 6.279468620546222013 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.3333333333333337034, 0.3333333333333337034, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#28476 = EDGE_CURVE ( 'NONE', #26158, #25434, #29729, .T. ) ; -#28477 = ORIENTED_EDGE ( 'NONE', *, *, #25079, .T. ) ; -#28478 = CARTESIAN_POINT ( 'NONE', ( 20.07473376121614450, 118.1084071564281430, 87.33016715071195790 ) ) ; -#28479 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#28480 = EDGE_CURVE ( 'NONE', #21867, #36048, #5214, .T. ) ; -#28481 = AXIS2_PLACEMENT_3D ( 'NONE', #31020, #9347, #37544 ) ; -#28482 = ORIENTED_EDGE ( 'NONE', *, *, #3575, .T. ) ; -#28483 = AXIS2_PLACEMENT_3D ( 'NONE', #20065, #14167, #17401 ) ; -#28484 = CARTESIAN_POINT ( 'NONE', ( -21.21281385531639430, 128.6733510584166140, 91.93807758298277122 ) ) ; -#28485 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17897, #18694, #30393, #40180, #9125, #14863, #3168, #5850, #27350, #15063 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28486 = CARTESIAN_POINT ( 'NONE', ( 36.20181100725926626, 191.4690138734401899, 103.8351635709739185 ) ) ; -#28487 = CARTESIAN_POINT ( 'NONE', ( -25.99978576141418429, 118.1122949349609286, 90.28348809642494643 ) ) ; -#28488 = AXIS2_PLACEMENT_3D ( 'NONE', #8070, #27109, #24648 ) ; -#28489 = ORIENTED_EDGE ( 'NONE', *, *, #33352, .T. ) ; -#28490 = LINE ( 'NONE', #2921, #25006 ) ; -#28491 = LINE ( 'NONE', #31769, #995 ) ; -#28492 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023852966 ) ) ; -#28493 = CARTESIAN_POINT ( 'NONE', ( -38.94661729375161485, 128.0727087836390865, 89.75751053642740374 ) ) ; -#28494 = ORIENTED_EDGE ( 'NONE', *, *, #4290, .F. ) ; -#28495 = CARTESIAN_POINT ( 'NONE', ( -25.50772789806992336, 207.4083919359153469, 77.09708259026270127 ) ) ; -#28496 = CARTESIAN_POINT ( 'NONE', ( 35.54494089926004108, 209.7096602146001487, 73.03703587511542139 ) ) ; -#28498 = CARTESIAN_POINT ( 'NONE', ( -2.935232621041004020, 190.8511156531020276, 106.7950609103722286 ) ) ; -#28497 = CARTESIAN_POINT ( 'NONE', ( -28.43520508893000098, 186.6528701677999891, 105.6701704825000121 ) ) ; -#28499 = VERTEX_POINT ( 'NONE', #38749 ) ; -#28500 = EDGE_CURVE ( 'NONE', #8772, #23153, #877, .T. ) ; -#28501 = LINE ( 'NONE', #9693, #21707 ) ; -#28502 = ORIENTED_EDGE ( 'NONE', *, *, #22684, .T. ) ; -#28503 = CARTESIAN_POINT ( 'NONE', ( -14.89266151782658021, 129.2859740412766882, 89.85203636143938866 ) ) ; -#28504 = VECTOR ( 'NONE', #38113, 1000.000000000000000 ) ; -#28505 = CARTESIAN_POINT ( 'NONE', ( 35.98181449372523844, 160.9880612539904234, 187.1235093347274017 ) ) ; -#28506 = CARTESIAN_POINT ( 'NONE', ( -6.035970131895957103, 136.6793194835712484, 94.29038707408911080 ) ) ; -#28507 = ORIENTED_EDGE ( 'NONE', *, *, #8065, .F. ) ; -#28508 = CIRCLE ( 'NONE', #29820, 22.00000000001089973 ) ; -#28509 = VECTOR ( 'NONE', #12389, 999.9999999999998863 ) ; -#28510 = ORIENTED_EDGE ( 'NONE', *, *, #36545, .T. ) ; -#28511 = LINE ( 'NONE', #15819, #14598 ) ; -#28512 = DIRECTION ( 'NONE', ( -0.0005884949961246006183, 0.2249510543439056653, -0.9743698870671265722 ) ) ; -#28513 = CARTESIAN_POINT ( 'NONE', ( 35.73033089362894543, 192.3272895366094986, 104.0378526287656342 ) ) ; -#28514 = ORIENTED_EDGE ( 'NONE', *, *, #20135, .F. ) ; -#28515 = ADVANCED_FACE ( 'NONE', ( #4613 ), #1549, .F. ) ; -#28516 = VERTEX_POINT ( 'NONE', #20349 ) ; -#28517 = CARTESIAN_POINT ( 'NONE', ( 43.54015349013348413, 114.1160320775752552, 121.8918845945049014 ) ) ; -#28518 = AXIS2_PLACEMENT_3D ( 'NONE', #34879, #25122, #37764 ) ; -#28519 = CARTESIAN_POINT ( 'NONE', ( -12.63727448935653186, 177.2390372512880958, 101.0505970525729680 ) ) ; -#28520 = CARTESIAN_POINT ( 'NONE', ( -3.501632090593860713, 185.3069955807334566, 105.1733482448064620 ) ) ; -#28521 = CYLINDRICAL_SURFACE ( 'NONE', #38574, 2.000000000000011546 ) ; -#28522 = ADVANCED_FACE ( 'NONE', ( #39359 ), #11072, .F. ) ; -#28523 = VERTEX_POINT ( 'NONE', #36709 ) ; -#28524 = CARTESIAN_POINT ( 'NONE', ( -23.89831259315023715, 121.1330467865301586, 177.8952988152876458 ) ) ; -#28525 = ORIENTED_EDGE ( 'NONE', *, *, #15088, .T. ) ; -#28526 = CARTESIAN_POINT ( 'NONE', ( -37.72956294166493052, 117.6505992105354750, 89.71937875289896169 ) ) ; -#28527 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #40099, #8647, #11498, #33362 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28528 = ADVANCED_FACE ( 'NONE', ( #8512 ), #30379, .F. ) ; -#28529 = CARTESIAN_POINT ( 'NONE', ( -15.99999342760827936, 185.2774429011668076, 102.4372551014714929 ) ) ; -#28530 = EDGE_CURVE ( 'NONE', #23376, #21600, #34557, .T. ) ; -#28531 = ORIENTED_EDGE ( 'NONE', *, *, #32621, .T. ) ; -#28532 = DIRECTION ( 'NONE', ( 0.0002393071182785211099, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#28533 = CARTESIAN_POINT ( 'NONE', ( 12.63852066807981345, 177.1933417902586427, 101.0667481637636627 ) ) ; -#28534 = DIRECTION ( 'NONE', ( 0.0005884949961289119482, -0.2249510543439059984, 0.9743698870671263501 ) ) ; -#28535 = AXIS2_PLACEMENT_3D ( 'NONE', #33607, #12155, #8892 ) ; -#28536 = ORIENTED_EDGE ( 'NONE', *, *, #25648, .T. ) ; -#28537 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7071067167009886800, -0.7071068456721004702 ) ) ; -#28538 = CARTESIAN_POINT ( 'NONE', ( 15.50147165697079465, 137.9484461010407870, 94.05722786790197176 ) ) ; -#28539 = VECTOR ( 'NONE', #17362, 1000.000000000000000 ) ; -#28540 = DIRECTION ( 'NONE', ( -0.6087614115774877543, 0.7730004600455409047, 0.1785492440296705396 ) ) ; -#28541 = CONICAL_SURFACE ( 'NONE', #17393, 2.503075499750329502, 0.7853981633711295540 ) ; -#28542 = CARTESIAN_POINT ( 'NONE', ( 42.56996684270875164, 189.7519616765065962, 106.3336315083538750 ) ) ; -#28543 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971563459 ) ) ; -#28544 = ORIENTED_EDGE ( 'NONE', *, *, #30184, .T. ) ; -#28545 = DIRECTION ( 'NONE', ( -0.0005884952295944862952, 0.2249510549294951034, -0.9743698869317914957 ) ) ; -#28546 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971555410 ) ) ; -#28547 = CARTESIAN_POINT ( 'NONE', ( 2.546082943913467123, 205.5673828937494534, 76.29867481864103240 ) ) ; -#28548 = ORIENTED_EDGE ( 'NONE', *, *, #31299, .T. ) ; -#28549 = CARTESIAN_POINT ( 'NONE', ( 0.05361349798586999976, 83.21792371834001756, 88.76775218440999993 ) ) ; -#28550 = ORIENTED_EDGE ( 'NONE', *, *, #22940, .F. ) ; -#28551 = CARTESIAN_POINT ( 'NONE', ( -38.20405560926187860, 218.5902260770999987, 76.08157892182251203 ) ) ; -#28552 = CARTESIAN_POINT ( 'NONE', ( -26.47524647853921209, 122.9562979991939784, 88.05560927516995662 ) ) ; -#28553 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#28554 = DIRECTION ( 'NONE', ( 0.0005884949961181157882, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#28555 = ORIENTED_EDGE ( 'NONE', *, *, #14999, .T. ) ; -#28556 = CARTESIAN_POINT ( 'NONE', ( 25.50051830703121780, 120.2145355607603534, 89.95699753438390189 ) ) ; -#28557 = ORIENTED_EDGE ( 'NONE', *, *, #11585, .T. ) ; -#28558 = ORIENTED_EDGE ( 'NONE', *, *, #2287, .T. ) ; -#28559 = CARTESIAN_POINT ( 'NONE', ( 37.17804754624985719, 145.4524169400428946, 280.9300640675564864 ) ) ; -#28560 = CARTESIAN_POINT ( 'NONE', ( 19.63521581173586483, 124.6513971846303548, 177.3953982281404080 ) ) ; -#28561 = CARTESIAN_POINT ( 'NONE', ( 39.74188351515407192, 169.2517364656017946, 164.2561587285271969 ) ) ; -#28562 = EDGE_CURVE ( 'NONE', #40342, #19998, #22200, .T. ) ; -#28563 = AXIS2_PLACEMENT_3D ( 'NONE', #21336, #19039, #30737 ) ; -#28564 = ORIENTED_EDGE ( 'NONE', *, *, #18889, .T. ) ; -#28565 = CARTESIAN_POINT ( 'NONE', ( -25.50991579498579398, 209.7152486954105086, 73.57374465072240355 ) ) ; -#28566 = DIRECTION ( 'NONE', ( -0.6983012566254244158, 0.000000000000000000, -0.7158039920225042207 ) ) ; -#28567 = ORIENTED_EDGE ( 'NONE', *, *, #22853, .F. ) ; -#28568 = DIRECTION ( 'NONE', ( -0.0006039748319391903498, -5.551115123125774025E-15, -0.9999998176071844824 ) ) ; -#28569 = CIRCLE ( 'NONE', #14186, 51.40509898897001761 ) ; -#28570 = EDGE_CURVE ( 'NONE', #89, #22666, #24870, .T. ) ; -#28571 = CARTESIAN_POINT ( 'NONE', ( -45.39754466565177182, 131.1270945138005573, 90.46656737203734622 ) ) ; -#28572 = ORIENTED_EDGE ( 'NONE', *, *, #18292, .T. ) ; -#28573 = CARTESIAN_POINT ( 'NONE', ( 21.05350619295907322, 128.5796794191466859, 92.23302540184623410 ) ) ; -#28574 = EDGE_CURVE ( 'NONE', #3175, #5370, #2854, .T. ) ; -#28575 = CARTESIAN_POINT ( 'NONE', ( 22.45660349583999960, 191.1065010712000003, 28.07991271570000080 ) ) ; -#28576 = CARTESIAN_POINT ( 'NONE', ( 41.29686553520478753, 130.6058778057362133, 336.5065907340476770 ) ) ; -#28577 = CYLINDRICAL_SURFACE ( 'NONE', #3285, 4.999999999999994671 ) ; -#28578 = EDGE_CURVE ( 'NONE', #24155, #9009, #24824, .T. ) ; -#28579 = CARTESIAN_POINT ( 'NONE', ( 4.030357199829833981, 135.8639809292952805, 91.01715860817544979 ) ) ; -#28580 = ADVANCED_FACE ( 'NONE', ( #21793 ), #2580, .F. ) ; -#28581 = ORIENTED_EDGE ( 'NONE', *, *, #30331, .T. ) ; -#28582 = CARTESIAN_POINT ( 'NONE', ( 16.22247671335948382, 122.0701589875174164, 174.5870958018068109 ) ) ; -#28583 = CARTESIAN_POINT ( 'NONE', ( 1.075851469382705705, 189.0669687373688532, 103.7034138247800144 ) ) ; -#28584 = CARTESIAN_POINT ( 'NONE', ( -20.89286847790088331, 136.3261294211067138, 91.13890976780785991 ) ) ; -#28585 = DIRECTION ( 'NONE', ( -0.0005884949961237983087, 0.2249510543439047772, -0.9743698870671267942 ) ) ; -#28586 = FACE_OUTER_BOUND ( 'NONE', #33727, .T. ) ; -#28587 = CARTESIAN_POINT ( 'NONE', ( 26.33447233267780163, 119.3314346165645361, 177.4911483211659800 ) ) ; -#28588 = CARTESIAN_POINT ( 'NONE', ( -3.168113297478124313, 183.4473166593645033, 105.0858980959790188 ) ) ; -#28589 = LINE ( 'NONE', #22860, #13915 ) ; -#28590 = ORIENTED_EDGE ( 'NONE', *, *, #5604, .T. ) ; -#28591 = CARTESIAN_POINT ( 'NONE', ( -25.67011802498781137, 190.9529943926732471, 106.4902118193780751 ) ) ; -#28592 = ORIENTED_EDGE ( 'NONE', *, *, #30352, .T. ) ; -#28593 = CONICAL_SURFACE ( 'NONE', #24697, 8.000001494568962812, 0.7853981633972983989 ) ; -#28594 = CONICAL_SURFACE ( 'NONE', #21431, 2.250000000041454840, 0.7853981633778843729 ) ; -#28595 = CARTESIAN_POINT ( 'NONE', ( -2.954012481561790970, 209.1419323005786737, 76.14255792608456375 ) ) ; -#28596 = LINE ( 'NONE', #7298, #6744 ) ; -#28597 = CARTESIAN_POINT ( 'NONE', ( 13.50000077923337649, 154.4078842014294537, 95.29263736447251176 ) ) ; -#28598 = CARTESIAN_POINT ( 'NONE', ( 20.07207848722921995, 127.4214942189600919, 89.13229914059456860 ) ) ; -#28599 = CARTESIAN_POINT ( 'NONE', ( 20.11467720513346435, 118.1092215096106912, 90.14282840794432161 ) ) ; -#28600 = CARTESIAN_POINT ( 'NONE', ( 23.68617478976915081, 127.9132360811641149, 92.25176250337622719 ) ) ; -#28601 = EDGE_LOOP ( 'NONE', ( #23316, #16686, #16889, #24601 ) ) ; -#28602 = CARTESIAN_POINT ( 'NONE', ( -0.01811060958565999940, 134.7313760321000018, 93.83703417463999585 ) ) ; -#28603 = CARTESIAN_POINT ( 'NONE', ( 4.035676231391283508, 136.7932109853815064, 93.79744583368700717 ) ) ; -#28604 = ADVANCED_FACE ( 'NONE', ( #5424 ), #18488, .T. ) ; -#28605 = ADVANCED_FACE ( 'NONE', ( #24469 ), #5841, .F. ) ; -#28606 = DIRECTION ( 'NONE', ( -0.7933530821293331980, -0.5932640870757640572, -0.1364866662427067778 ) ) ; -#28607 = EDGE_LOOP ( 'NONE', ( #14047, #31956, #37900 ) ) ; -#28608 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#28609 = EDGE_CURVE ( 'NONE', #29452, #38073, #11933, .T. ) ; -#28610 = ORIENTED_EDGE ( 'NONE', *, *, #4290, .T. ) ; -#28611 = ADVANCED_FACE ( 'NONE', ( #29472 ), #1242, .F. ) ; -#28612 = PLANE ( 'NONE', #24456 ) ; -#28613 = LINE ( 'NONE', #7324, #17550 ) ; -#28614 = CARTESIAN_POINT ( 'NONE', ( 4.034499242442382894, 168.3851528797071921, 99.03841376523669737 ) ) ; -#28615 = DIRECTION ( 'NONE', ( 0.0005884949961138158424, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#28616 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#28617 = AXIS2_PLACEMENT_3D ( 'NONE', #8768, #33682, #5690 ) ; -#28618 = LINE ( 'NONE', #34515, #18114 ) ; -#28619 = CARTESIAN_POINT ( 'NONE', ( -19.31979924309097996, 124.8061162773214079, 177.8324071844828893 ) ) ; -#28620 = VECTOR ( 'NONE', #2410, 1000.000000000000000 ) ; -#28621 = PLANE ( 'NONE', #7304 ) ; -#28622 = ORIENTED_EDGE ( 'NONE', *, *, #11032, .T. ) ; -#28623 = EDGE_CURVE ( 'NONE', #6712, #12315, #25066, .T. ) ; -#28624 = ORIENTED_EDGE ( 'NONE', *, *, #14306, .T. ) ; -#28625 = CARTESIAN_POINT ( 'NONE', ( 12.64524264573559265, 177.0869176997347552, 103.5651634678102937 ) ) ; -#28626 = CARTESIAN_POINT ( 'NONE', ( 42.81943401670074678, 120.8435851937607453, 92.41077006796218996 ) ) ; -#28627 = CARTESIAN_POINT ( 'NONE', ( -18.84740034850127444, 125.0255721163971714, 178.4920410802416200 ) ) ; -#28628 = CARTESIAN_POINT ( 'NONE', ( -37.22558238367000882, 191.5599626881000006, 104.5530307740000069 ) ) ; -#28629 = ORIENTED_EDGE ( 'NONE', *, *, #2893, .T. ) ; -#28630 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#28631 = ORIENTED_EDGE ( 'NONE', *, *, #26091, .F. ) ; -#28632 = CARTESIAN_POINT ( 'NONE', ( -40.45668859077597546, 220.4002261445999693, 73.08293890851697938 ) ) ; -#28633 = EDGE_CURVE ( 'NONE', #21532, #38161, #34429, .T. ) ; -#28634 = FACE_OUTER_BOUND ( 'NONE', #10287, .T. ) ; -#28635 = DIRECTION ( 'NONE', ( -0.9914446600486813699, -0.1273122826258633877, -0.02879355402771318836 ) ) ; -#28636 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #19581, #32077, #4234, #20175 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.570713693309743864, 2.960011224583242839 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.8455190531892258221, 0.8455190531892258221, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#28637 = CARTESIAN_POINT ( 'NONE', ( 30.06891677554877873, 175.2469091620284871, 100.6068511788076876 ) ) ; -#28638 = CIRCLE ( 'NONE', #11013, 1.999999999951510121 ) ; -#28639 = CARTESIAN_POINT ( 'NONE', ( -2.501018995718000237, 209.5694415279999987, 73.43744377689000657 ) ) ; -#28640 = CARTESIAN_POINT ( 'NONE', ( 38.65455852232000211, 118.3707348954999929, 89.51298033404999899 ) ) ; -#28641 = ORIENTED_EDGE ( 'NONE', *, *, #11037, .T. ) ; -#28642 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971573729 ) ) ; -#28643 = AXIS2_PLACEMENT_3D ( 'NONE', #22898, #22504, #38611 ) ; -#28644 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052565999616 ) ) ; -#28645 = CYLINDRICAL_SURFACE ( 'NONE', #34682, 3.000000000000000000 ) ; -#28646 = CONICAL_SURFACE ( 'NONE', #553, 2.503061127006177777, 0.7853981634091529163 ) ; -#28647 = CIRCLE ( 'NONE', #22762, 47.49999999998287592 ) ; -#28648 = LINE ( 'NONE', #7354, #2355 ) ; -#28649 = ORIENTED_EDGE ( 'NONE', *, *, #36059, .F. ) ; -#28650 = ORIENTED_EDGE ( 'NONE', *, *, #18107, .F. ) ; -#28651 = VERTEX_POINT ( 'NONE', #6424 ) ; -#28652 = CARTESIAN_POINT ( 'NONE', ( 20.50147137495634198, 190.9646546281344683, 106.2940065278771016 ) ) ; -#28653 = ADVANCED_FACE ( 'NONE', ( #1044 ), #31388, .T. ) ; -#28654 = ADVANCED_FACE ( 'NONE', ( #26014 ), #20879, .T. ) ; -#28655 = FACE_OUTER_BOUND ( 'NONE', #36634, .T. ) ; -#28656 = EDGE_CURVE ( 'NONE', #6112, #2318, #9791, .T. ) ; -#28657 = EDGE_CURVE ( 'NONE', #13040, #32811, #1447, .T. ) ; -#28658 = ORIENTED_EDGE ( 'NONE', *, *, #26259, .T. ) ; -#28659 = CARTESIAN_POINT ( 'NONE', ( -45.59279413748385679, 146.2345503595622347, 284.1924382399986939 ) ) ; -#28660 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#28661 = CARTESIAN_POINT ( 'NONE', ( -38.36815502355999996, 118.8281866406999967, 87.72028328499000338 ) ) ; -#28662 = DIRECTION ( 'NONE', ( 0.0005884949961247506718, -0.2249510543439066368, 0.9743698870671262391 ) ) ; -#28663 = ORIENTED_EDGE ( 'NONE', *, *, #32084, .T. ) ; -#28664 = EDGE_CURVE ( 'NONE', #30682, #7592, #20046, .T. ) ; -#28665 = CARTESIAN_POINT ( 'NONE', ( 15.95548590848913939, 122.4579714996872752, 172.0533845872113830 ) ) ; -#28666 = VERTEX_POINT ( 'NONE', #12563 ) ; -#28667 = CARTESIAN_POINT ( 'NONE', ( 37.42082352723856076, 132.6200669550715929, 336.9739440566017379 ) ) ; -#28668 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319114355331 ) ) ; -#28669 = ADVANCED_FACE ( 'NONE', ( #13532 ), #28326, .F. ) ; -#28670 = EDGE_LOOP ( 'NONE', ( #8245, #16335, #26658 ) ) ; -#28671 = CARTESIAN_POINT ( 'NONE', ( -14.89266160486395307, 136.5007287715515929, 91.51769391837629541 ) ) ; -#28672 = CARTESIAN_POINT ( 'NONE', ( 3.062676760987444347, 191.1124749746885811, 103.7728652716954514 ) ) ; -#28673 = CARTESIAN_POINT ( 'NONE', ( 43.11176529853025130, 93.58819903903858517, 291.5325055092823163 ) ) ; -#28674 = AXIS2_PLACEMENT_3D ( 'NONE', #14860, #6045, #21191 ) ; -#28675 = VECTOR ( 'NONE', #12302, 1000.000000000000114 ) ; -#28676 = ORIENTED_EDGE ( 'NONE', *, *, #32360, .T. ) ; -#28677 = CARTESIAN_POINT ( 'NONE', ( -21.17842536497620642, 213.4917284372353663, 73.07129532062806732 ) ) ; -#28678 = CARTESIAN_POINT ( 'NONE', ( 12.31735795870903161, 136.6817491452135016, 94.27986305550896873 ) ) ; -#28679 = ORIENTED_EDGE ( 'NONE', *, *, #30662, .T. ) ; -#28680 = CONICAL_SURFACE ( 'NONE', #3848, 7.999999999893429248, 0.7853981633973029508 ) ; -#28681 = LINE ( 'NONE', #22756, #24561 ) ; -#28682 = CARTESIAN_POINT ( 'NONE', ( 36.11816460276669716, 191.5234629219989131, 103.8477846469482415 ) ) ; -#28683 = CARTESIAN_POINT ( 'NONE', ( -25.95405152892999823, 121.2198833629000063, 90.60859627058000854 ) ) ; -#28684 = ORIENTED_EDGE ( 'NONE', *, *, #19167, .F. ) ; -#28685 = DIRECTION ( 'NONE', ( -0.0006039748319391919761, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#28686 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640315690, 0.2252353050503788645 ) ) ; -#28687 = CARTESIAN_POINT ( 'NONE', ( 38.64014645122774994, 77.14221734851339818, 291.0515339294258297 ) ) ; -#28688 = ORIENTED_EDGE ( 'NONE', *, *, #38066, .F. ) ; -#28689 = CARTESIAN_POINT ( 'NONE', ( 26.00396726516730084, 120.2363586782729925, 90.47612175240820420 ) ) ; -#28690 = FACE_OUTER_BOUND ( 'NONE', #19942, .T. ) ; -#28691 = CARTESIAN_POINT ( 'NONE', ( 35.71170796624453203, 209.7096579434202397, 73.20360198796264228 ) ) ; -#28693 = CARTESIAN_POINT ( 'NONE', ( -8.957660508846936764, 152.5474601094844900, 94.87668840795032565 ) ) ; -#28692 = CARTESIAN_POINT ( 'NONE', ( -12.63810004658400388, 184.1237364170421529, 102.1657915116017108 ) ) ; -#28694 = AXIS2_PLACEMENT_3D ( 'NONE', #10874, #35771, #4717 ) ; -#28695 = DIRECTION ( 'NONE', ( -0.0005884949961212385073, 0.2249510543439022514, -0.9743698870671273493 ) ) ; -#28696 = EDGE_LOOP ( 'NONE', ( #38228, #4702, #11706, #31482 ) ) ; -#28697 = CARTESIAN_POINT ( 'NONE', ( 15.59057381630712946, 147.4113417081824764, 179.2674225712011946 ) ) ; -#28698 = VECTOR ( 'NONE', #30137, 1000.000000000000114 ) ; -#28699 = CARTESIAN_POINT ( 'NONE', ( -31.70535868460997619, 226.4002260771022463, 73.57765341574507545 ) ) ; -#28700 = AXIS2_PLACEMENT_3D ( 'NONE', #2408, #33054, #14878 ) ; -#28701 = CARTESIAN_POINT ( 'NONE', ( 8.629804688381279121, 290.8783034154773759, 213.0387394798674165 ) ) ; -#28702 = EDGE_CURVE ( 'NONE', #28841, #37740, #37193, .T. ) ; -#28703 = EDGE_LOOP ( 'NONE', ( #16631, #4601, #11113, #38856 ) ) ; -#28704 = ADVANCED_FACE ( 'NONE', ( #18887 ), #6494, .T. ) ; -#28705 = VECTOR ( 'NONE', #22163, 999.9999999999998863 ) ; -#28706 = ORIENTED_EDGE ( 'NONE', *, *, #30053, .T. ) ; -#28707 = CARTESIAN_POINT ( 'NONE', ( 2.943104451508621544, 209.7096517725655644, 76.05672380837390278 ) ) ; -#28708 = DIRECTION ( 'NONE', ( -6.056093010559475298E-13, 0.9743700560245742714, 0.2249510922904529864 ) ) ; -#28709 = CARTESIAN_POINT ( 'NONE', ( -46.51510296192524407, 123.1642148636640570, 92.34525309360199685 ) ) ; -#28710 = CARTESIAN_POINT ( 'NONE', ( -2.814035348771000145, 190.9056005872000128, 106.6826603667999933 ) ) ; -#28711 = CARTESIAN_POINT ( 'NONE', ( 36.12231427442000609, 191.8632040566000114, 104.2147564600000038 ) ) ; -#28712 = ORIENTED_EDGE ( 'NONE', *, *, #22487, .T. ) ; -#28713 = EDGE_LOOP ( 'NONE', ( #20088, #19088, #32654, #34854 ) ) ; -#28714 = CARTESIAN_POINT ( 'NONE', ( -15.83142425403799969, 151.3373654620088757, 97.50908117948665677 ) ) ; -#28715 = CARTESIAN_POINT ( 'NONE', ( -5.639739516488999627, 174.3879284816999871, 152.4718672074000381 ) ) ; -#28716 = DIRECTION ( 'NONE', ( 0.6087613186456907188, -0.7729176985478710682, -0.1789074850089337476 ) ) ; -#28717 = FACE_OUTER_BOUND ( 'NONE', #32356, .T. ) ; -#28718 = ORIENTED_EDGE ( 'NONE', *, *, #19900, .T. ) ; -#28719 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265218904, -0.1368326740407753983 ) ) ; -#28720 = ORIENTED_EDGE ( 'NONE', *, *, #1637, .T. ) ; -#28721 = ORIENTED_EDGE ( 'NONE', *, *, #22841, .T. ) ; -#28722 = CARTESIAN_POINT ( 'NONE', ( -37.27437962779826108, 117.0177660251410430, 89.72826295827535148 ) ) ; -#28723 = CARTESIAN_POINT ( 'NONE', ( -15.99998654924659647, 185.5920200283469228, 102.5098809628851200 ) ) ; -#28724 = ORIENTED_EDGE ( 'NONE', *, *, #26919, .F. ) ; -#28725 = CARTESIAN_POINT ( 'NONE', ( 20.00153077817512326, 137.8436319123526914, 94.54354600521399732 ) ) ; -#28726 = AXIS2_PLACEMENT_3D ( 'NONE', #12672, #5936, #9820 ) ; -#28727 = EDGE_CURVE ( 'NONE', #10196, #34012, #9240, .T. ) ; -#28728 = CIRCLE ( 'NONE', #34032, 2.750000000059430239 ) ; -#28729 = CARTESIAN_POINT ( 'NONE', ( -1.750900962877000033, 189.6783647796999901, 105.7654186813000052 ) ) ; -#28730 = CARTESIAN_POINT ( 'NONE', ( -44.79177088925157335, 180.8389768040387366, 104.5088566725039527 ) ) ; -#28731 = AXIS2_PLACEMENT_3D ( 'NONE', #28353, #24494, #36954 ) ; -#28732 = ORIENTED_EDGE ( 'NONE', *, *, #22760, .T. ) ; -#28733 = PLANE ( 'NONE', #11237 ) ; -#28734 = AXIS2_PLACEMENT_3D ( 'NONE', #22473, #18564, #9392 ) ; -#28735 = LINE ( 'NONE', #3369, #29030 ) ; -#28736 = DIRECTION ( 'NONE', ( 0.0006039748319392047697, 1.154386647790520729E-15, 0.9999998176071845934 ) ) ; -#28737 = DIRECTION ( 'NONE', ( 1.026956297778271819E-13, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#28738 = CARTESIAN_POINT ( 'NONE', ( -40.67564690882122136, 188.1603015044537699, 107.8687550938168442 ) ) ; -#28739 = ORIENTED_EDGE ( 'NONE', *, *, #11562, .F. ) ; -#28740 = DIRECTION ( 'NONE', ( -0.0002393071182786160318, -0.2252352986010024705, 0.9743043687658494711 ) ) ; -#28741 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36034, #29924, #8247, #8668 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28742 = CARTESIAN_POINT ( 'NONE', ( -37.96017986806000266, 117.7251259182999945, 89.56172390870999322 ) ) ; -#28743 = ORIENTED_EDGE ( 'NONE', *, *, #36948, .T. ) ; -#28744 = ORIENTED_EDGE ( 'NONE', *, *, #23539, .T. ) ; -#28745 = CARTESIAN_POINT ( 'NONE', ( 10.97929769292734115, 158.8123032091548339, 96.31100024268565107 ) ) ; -#28746 = CARTESIAN_POINT ( 'NONE', ( -28.53208073851174476, 125.2791694434640135, 88.59312828080875590 ) ) ; -#28747 = CARTESIAN_POINT ( 'NONE', ( 23.69388335781209776, 131.0246890999723632, 89.88804818403849595 ) ) ; -#28748 = CARTESIAN_POINT ( 'NONE', ( -21.84296514512071852, 158.3842646686617854, 96.23200356538306721 ) ) ; -#28749 = ADVANCED_FACE ( 'NONE', ( #19833 ), #7781, .F. ) ; -#28750 = EDGE_CURVE ( 'NONE', #3973, #5945, #26413, .T. ) ; -#28751 = FACE_BOUND ( 'NONE', #15957, .T. ) ; -#28752 = EDGE_LOOP ( 'NONE', ( #33197, #2560, #5803, #16766 ) ) ; -#28753 = EDGE_LOOP ( 'NONE', ( #22551, #23641 ) ) ; -#28755 = CIRCLE ( 'NONE', #21595, 2.500000000050627946 ) ; -#28754 = CARTESIAN_POINT ( 'NONE', ( 2.559335146230606650, 190.6545083682405846, 106.2111020963487249 ) ) ; -#28756 = CIRCLE ( 'NONE', #18289, 4.500000002766396001 ) ; -#28757 = CARTESIAN_POINT ( 'NONE', ( -22.54153898917275711, 174.6477734237781476, 27.63001055752831547 ) ) ; -#28758 = AXIS2_PLACEMENT_3D ( 'NONE', #18176, #20436, #30069 ) ; -#28759 = ORIENTED_EDGE ( 'NONE', *, *, #3131, .F. ) ; -#28760 = LINE ( 'NONE', #16862, #21305 ) ; -#28761 = CONICAL_SURFACE ( 'NONE', #12413, 2.749999999950583973, 0.7853981633811774055 ) ; -#28762 = FACE_OUTER_BOUND ( 'NONE', #22019, .T. ) ; -#28763 = CARTESIAN_POINT ( 'NONE', ( 36.49000061041000009, 191.9055121536000001, 104.5102523057999946 ) ) ; -#28764 = ORIENTED_EDGE ( 'NONE', *, *, #10890, .F. ) ; -#28765 = CARTESIAN_POINT ( 'NONE', ( 39.06275665101696148, 183.6185769103316261, 102.5341710742749370 ) ) ; -#28766 = CARTESIAN_POINT ( 'NONE', ( 16.16550992384005170, 152.4595644213394223, 178.9888250856261607 ) ) ; -#28767 = VERTEX_POINT ( 'NONE', #21995 ) ; -#28768 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#28769 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#28770 = CARTESIAN_POINT ( 'NONE', ( 15.66829915461363143, 151.3691634012949692, 97.32665949641518921 ) ) ; -#28771 = CARTESIAN_POINT ( 'NONE', ( -25.99978576141418429, 118.1122949349609286, 90.28348809642494643 ) ) ; -#28772 = CARTESIAN_POINT ( 'NONE', ( -20.01736593119981222, 207.8686407175673594, 77.28911966098117148 ) ) ; -#28773 = VERTEX_POINT ( 'NONE', #25265 ) ; -#28774 = CARTESIAN_POINT ( 'NONE', ( -14.31599472567032549, 177.1946960966661777, 100.5701885340178450 ) ) ; -#28775 = ADVANCED_FACE ( 'NONE', ( #38263 ), #4099, .T. ) ; -#28776 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; -#28777 = CARTESIAN_POINT ( 'NONE', ( 94.27346847287640230, 222.2365666497040024, 195.1387431474686309 ) ) ; -#28778 = CARTESIAN_POINT ( 'NONE', ( -21.57450333036776513, 176.7766111650641676, 100.6491009196165436 ) ) ; -#28779 = ORIENTED_EDGE ( 'NONE', *, *, #33871, .F. ) ; -#28780 = CARTESIAN_POINT ( 'NONE', ( 38.45112143561028262, 119.0008945537455105, 90.24854934121363215 ) ) ; -#28781 = CARTESIAN_POINT ( 'NONE', ( -25.67828855867520232, 211.0902258593999932, 75.74375686936230068 ) ) ; -#28782 = CARTESIAN_POINT ( 'NONE', ( -26.00624846271685442, 190.8511609718977127, 106.8090059743847178 ) ) ; -#28783 = CARTESIAN_POINT ( 'NONE', ( 35.80518341334000354, 109.6131156991000069, 89.99615936003000627 ) ) ; -#28784 = CONICAL_SURFACE ( 'NONE', #5273, 2.502994749393338214, 0.7853981634319000538 ) ; -#28785 = CARTESIAN_POINT ( 'NONE', ( -31.91217790274522415, 174.0284854049060073, 102.4155994567338155 ) ) ; -#28786 = ORIENTED_EDGE ( 'NONE', *, *, #10705, .F. ) ; -#28787 = EDGE_CURVE ( 'NONE', #5771, #21181, #17376, .T. ) ; -#28788 = AXIS2_PLACEMENT_3D ( 'NONE', #28411, #19172, #15333 ) ; -#28789 = AXIS2_PLACEMENT_3D ( 'NONE', #18700, #34641, #34832 ) ; -#28790 = CARTESIAN_POINT ( 'NONE', ( 9.152368341089999859, 181.8773758343000395, 101.8936723023000042 ) ) ; -#28791 = EDGE_CURVE ( 'NONE', #33391, #11249, #23535, .T. ) ; -#28792 = CARTESIAN_POINT ( 'NONE', ( 16.29171451743032506, 127.7416981655566985, 175.3274352667909568 ) ) ; -#28793 = CARTESIAN_POINT ( 'NONE', ( 12.63969765807997625, 176.7434396814577440, 103.0154879366982641 ) ) ; -#28794 = CARTESIAN_POINT ( 'NONE', ( -25.99265238116858612, 191.7716299341333865, 103.9267712702834530 ) ) ; -#28795 = CARTESIAN_POINT ( 'NONE', ( 2.462157221798171314, 209.5677243469951634, 73.55701709285500556 ) ) ; -#28796 = CARTESIAN_POINT ( 'NONE', ( 36.06424597600000226, 192.4856413823000025, 105.0009491617999942 ) ) ; -#28797 = CARTESIAN_POINT ( 'NONE', ( 38.15044915630888767, 118.4868538170649970, 87.66883358155978101 ) ) ; -#28798 = EDGE_CURVE ( 'NONE', #38531, #29957, #39060, .T. ) ; -#28799 = EDGE_CURVE ( 'NONE', #31524, #11353, #39131, .T. ) ; -#28800 = FACE_OUTER_BOUND ( 'NONE', #17539, .T. ) ; -#28801 = ORIENTED_EDGE ( 'NONE', *, *, #18606, .T. ) ; -#28802 = ADVANCED_FACE ( 'NONE', ( #20671 ), #33262, .F. ) ; -#28803 = CARTESIAN_POINT ( 'NONE', ( -2.530585117517676785, 209.6188335209158424, 75.72670108198511230 ) ) ; -#28804 = ADVANCED_FACE ( 'NONE', ( #39669 ), #39801, .F. ) ; -#28805 = LINE ( 'NONE', #35307, #35967 ) ; -#28806 = FACE_OUTER_BOUND ( 'NONE', #2288, .T. ) ; -#28807 = VERTEX_POINT ( 'NONE', #33128 ) ; -#28808 = CARTESIAN_POINT ( 'NONE', ( 44.85744505170524832, 173.0251902600423932, 165.3610356716434922 ) ) ; -#28809 = AXIS2_PLACEMENT_3D ( 'NONE', #11832, #24514, #14701 ) ; -#28810 = ORIENTED_EDGE ( 'NONE', *, *, #34273, .T. ) ; -#28811 = CONICAL_SURFACE ( 'NONE', #35315, 3.500000265863834947, 0.7853981633209925484 ) ; -#28812 = VECTOR ( 'NONE', #3738, 1000.000000000000114 ) ; -#28813 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048993195, 181.0091974214194863, 104.5428127881379794 ) ) ; -#28814 = CARTESIAN_POINT ( 'NONE', ( -14.55129769576823939, 181.8820030174664737, 104.7313938035605787 ) ) ; -#28815 = DIRECTION ( 'NONE', ( 0.0005884949961248230966, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#28816 = AXIS2_PLACEMENT_3D ( 'NONE', #3244, #37595, #34707 ) ; -#28817 = VECTOR ( 'NONE', #19834, 1000.000000000000000 ) ; -#28818 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265227786, -0.1368326740407718733 ) ) ; -#28819 = CARTESIAN_POINT ( 'NONE', ( 44.72966403672144509, 105.5646547741824435, 174.3131243201257234 ) ) ; -#28820 = DIRECTION ( 'NONE', ( -0.7933308265452445607, -0.5932923437231208963, -0.1364932032467742196 ) ) ; -#28821 = VERTEX_POINT ( 'NONE', #8818 ) ; -#28822 = EDGE_LOOP ( 'NONE', ( #28759, #8350, #22775, #15450 ) ) ; -#28823 = CARTESIAN_POINT ( 'NONE', ( 37.18881986002047313, 185.3371258229277032, 105.5148290762721359 ) ) ; -#28824 = CARTESIAN_POINT ( 'NONE', ( -4.022778528374199247, 176.8352451414876043, 100.4809858824045961 ) ) ; -#28825 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#28826 = VERTEX_POINT ( 'NONE', #14546 ) ; -#28827 = CARTESIAN_POINT ( 'NONE', ( -37.98270182710000142, 190.9299589352999931, 103.6066259141999950 ) ) ; -#28828 = ORIENTED_EDGE ( 'NONE', *, *, #28799, .F. ) ; -#28829 = FACE_OUTER_BOUND ( 'NONE', #34019, .T. ) ; -#28830 = ORIENTED_EDGE ( 'NONE', *, *, #26064, .T. ) ; -#28831 = CARTESIAN_POINT ( 'NONE', ( 35.56284495376231547, 193.8169247290794601, 102.6814306726912776 ) ) ; -#28832 = ADVANCED_FACE ( 'NONE', ( #21293, #27030 ), #14947, .F. ) ; -#28833 = DIRECTION ( 'NONE', ( 0.0005884941600642186682, -0.2249510532593070877, 0.9743698873180307585 ) ) ; -#28834 = VECTOR ( 'NONE', #9263, 1000.000000000000114 ) ; -#28835 = CARTESIAN_POINT ( 'NONE', ( -12.63362340510167492, 177.0251879149293188, 103.4862258320118400 ) ) ; -#28836 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 134.8275956304323699, 92.30890876037859982 ) ) ; -#28837 = EDGE_CURVE ( 'NONE', #1363, #7316, #1864, .T. ) ; -#28838 = CIRCLE ( 'NONE', #3373, 2.000000001272049577 ) ; -#28839 = CARTESIAN_POINT ( 'NONE', ( 20.48060491281492546, 208.0678773903911178, 73.85355295145278376 ) ) ; -#28840 = CARTESIAN_POINT ( 'NONE', ( 38.66007910562999683, 118.3682276610000059, 89.51297402913000667 ) ) ; -#28841 = VERTEX_POINT ( 'NONE', #21083 ) ; -#28842 = EDGE_CURVE ( 'NONE', #8977, #14670, #35842, .T. ) ; -#28843 = FACE_OUTER_BOUND ( 'NONE', #21902, .T. ) ; -#28844 = CARTESIAN_POINT ( 'NONE', ( -36.61650759155055113, 191.3591673295911733, 106.3831752203444267 ) ) ; -#28845 = CARTESIAN_POINT ( 'NONE', ( -5.960622341254478762, 149.1452448442896923, 94.08941484461983862 ) ) ; -#28846 = CARTESIAN_POINT ( 'NONE', ( -20.50040440662989027, 193.7551219021977715, 103.6911811601128477 ) ) ; -#28847 = EDGE_LOOP ( 'NONE', ( #13394, #14372, #7162, #40023 ) ) ; -#28848 = ORIENTED_EDGE ( 'NONE', *, *, #28210, .T. ) ; -#28849 = EDGE_CURVE ( 'NONE', #17327, #22525, #30084, .T. ) ; -#28850 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3989, #19129, #4183, #35447 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28851 = ORIENTED_EDGE ( 'NONE', *, *, #26589, .T. ) ; -#28852 = DIRECTION ( 'NONE', ( 0.0005884949961265829735, -0.2249510543479622815, 0.9743698870661898770 ) ) ; -#28853 = CARTESIAN_POINT ( 'NONE', ( 15.50147165924775372, 160.1795853765612492, 99.18969171619460212 ) ) ; -#28854 = ORIENTED_EDGE ( 'NONE', *, *, #23687, .T. ) ; -#28855 = VERTEX_POINT ( 'NONE', #5324 ) ; -#28856 = FACE_BOUND ( 'NONE', #26605, .T. ) ; -#28857 = CARTESIAN_POINT ( 'NONE', ( -38.11719545559999744, 118.8155660612000020, 90.29080645717999687 ) ) ; -#28858 = CARTESIAN_POINT ( 'NONE', ( -38.12995955227000877, 119.0736919051999934, 87.44063144989000591 ) ) ; -#28859 = LINE ( 'NONE', #31940, #2781 ) ; -#28860 = VERTEX_POINT ( 'NONE', #23955 ) ; -#28861 = DIRECTION ( 'NONE', ( 0.0005884949961251158311, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#28862 = ORIENTED_EDGE ( 'NONE', *, *, #36736, .T. ) ; -#28863 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971556521 ) ) ; -#28864 = AXIS2_PLACEMENT_3D ( 'NONE', #29678, #1661, #7989 ) ; -#28865 = CARTESIAN_POINT ( 'NONE', ( 3.666638747417580557, 185.7959654145790864, 103.0582394725906568 ) ) ; -#28866 = VERTEX_POINT ( 'NONE', #39873 ) ; -#28867 = CARTESIAN_POINT ( 'NONE', ( -14.78542071362066679, 136.5876434558166750, 91.70874570386088465 ) ) ; -#28868 = CIRCLE ( 'NONE', #30833, 1.999999999975059284 ) ; -#28869 = CARTESIAN_POINT ( 'NONE', ( 36.06517739910999865, 192.1776130000999956, 106.5431043960000039 ) ) ; -#28870 = CARTESIAN_POINT ( 'NONE', ( 45.33292075665917054, 105.1136217838922988, 174.2090047145159701 ) ) ; -#28871 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6488, #8782, #9179, #9381 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28872 = ORIENTED_EDGE ( 'NONE', *, *, #37470, .T. ) ; -#28873 = CARTESIAN_POINT ( 'NONE', ( -25.50772789673414920, 207.4083919362629160, 77.09708259040941414 ) ) ; -#28874 = CARTESIAN_POINT ( 'NONE', ( -20.18676029030433838, 211.0871676712218630, 73.23727997610998841 ) ) ; -#28875 = ORIENTED_EDGE ( 'NONE', *, *, #2496, .F. ) ; -#28876 = CARTESIAN_POINT ( 'NONE', ( 3.062734419220130455, 191.5259964270285025, 103.8683342040099831 ) ) ; -#28877 = CARTESIAN_POINT ( 'NONE', ( 20.89286828480348035, 176.3842452922319524, 100.3618186666556369 ) ) ; -#28878 = CARTESIAN_POINT ( 'NONE', ( 16.41975760290100439, 151.3996119724024538, 184.5528527065874300 ) ) ; -#28879 = EDGE_CURVE ( 'NONE', #8051, #2542, #36413, .T. ) ; -#28880 = EDGE_CURVE ( 'NONE', #1598, #7297, #8417, .T. ) ; -#28881 = VERTEX_POINT ( 'NONE', #17583 ) ; -#28882 = EDGE_CURVE ( 'NONE', #31170, #31941, #34540, .T. ) ; -#28883 = CARTESIAN_POINT ( 'NONE', ( 2.548881393244593951, 189.3585829100690319, 106.4471705142469347 ) ) ; -#28884 = EDGE_CURVE ( 'NONE', #18267, #17189, #36529, .T. ) ; -#28885 = LINE ( 'NONE', #29089, #19260 ) ; -#28886 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#28887 = ORIENTED_EDGE ( 'NONE', *, *, #14389, .T. ) ; -#28888 = ORIENTED_EDGE ( 'NONE', *, *, #36939, .F. ) ; -#28889 = EDGE_CURVE ( 'NONE', #40149, #19772, #18585, .T. ) ; -#28890 = CARTESIAN_POINT ( 'NONE', ( 25.66702753569912332, 120.1660709880418096, 90.10665204569919240 ) ) ; -#28891 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #40256, #33517 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28892 = DIRECTION ( 'NONE', ( 0.0005884949961248781740, -0.2249510543439064425, 0.9743698870671262391 ) ) ; -#28894 = CARTESIAN_POINT ( 'NONE', ( -45.18925545272470856, 80.56898504508372127, 280.9798118546170258 ) ) ; -#28893 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673485204, 138.3983357652431039, 92.10969317386205546 ) ) ; -#28895 = VERTEX_POINT ( 'NONE', #40270 ) ; -#28896 = CIRCLE ( 'NONE', #5364, 4.499999998673683166 ) ; -#28897 = EDGE_CURVE ( 'NONE', #7776, #20110, #8737, .T. ) ; -#28898 = AXIS2_PLACEMENT_3D ( 'NONE', #34104, #12855, #37583 ) ; -#28899 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#28900 = EDGE_LOOP ( 'NONE', ( #11365, #14981, #12010, #26845 ) ) ; -#28901 = DIRECTION ( 'NONE', ( -0.6087614115774880874, 0.7730004600455407937, 0.1785492440296698458 ) ) ; -#28902 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927767006169, -0.0005734119022034026058 ) ) ; -#28903 = CARTESIAN_POINT ( 'NONE', ( 22.50029346827053089, 158.6816162529845826, 96.78702253161689839 ) ) ; -#28904 = ORIENTED_EDGE ( 'NONE', *, *, #16818, .T. ) ; -#28905 = VERTEX_POINT ( 'NONE', #28232 ) ; -#28906 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#28907 = EDGE_CURVE ( 'NONE', #15284, #17481, #30678, .T. ) ; -#28908 = CARTESIAN_POINT ( 'NONE', ( 43.18392532034716425, 82.25576545184350152, 280.9261012437979730 ) ) ; -#28909 = CARTESIAN_POINT ( 'NONE', ( -20.49970531676743235, 184.8492297950314480, 102.8542690818975132 ) ) ; -#28910 = CARTESIAN_POINT ( 'NONE', ( 36.08400100141000166, 192.2479736589999959, 104.3940943933999961 ) ) ; -#28911 = ORIENTED_EDGE ( 'NONE', *, *, #15806, .T. ) ; -#28912 = ORIENTED_EDGE ( 'NONE', *, *, #11115, .T. ) ; -#28913 = CARTESIAN_POINT ( 'NONE', ( 40.70212818817000766, 173.3563675979000323, 152.4718672074000381 ) ) ; -#28914 = CARTESIAN_POINT ( 'NONE', ( 20.31362792373948167, 209.7099901566150209, 73.37976260645619675 ) ) ; -#28915 = CARTESIAN_POINT ( 'NONE', ( -22.49852798328040038, 173.9502357504169936, 102.3918484913893252 ) ) ; -#28916 = DIRECTION ( 'NONE', ( -0.6087613512864371579, 0.7729391285148499158, 0.1788147667017893350 ) ) ; -#28917 = ORIENTED_EDGE ( 'NONE', *, *, #38473, .T. ) ; -#28918 = CARTESIAN_POINT ( 'NONE', ( 25.99886678296517672, 118.8155665066540934, 87.25209012101137773 ) ) ; -#28919 = ORIENTED_EDGE ( 'NONE', *, *, #39953, .F. ) ; -#28920 = AXIS2_PLACEMENT_3D ( 'NONE', #34605, #28902, #7210 ) ; -#28921 = CARTESIAN_POINT ( 'NONE', ( -36.99529868346930073, 116.5430723610914754, 89.73463934298317213 ) ) ; -#28922 = AXIS2_PLACEMENT_3D ( 'NONE', #28956, #10162, #22634 ) ; -#28923 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178915240083E-05, 0.0002331579774905574406 ) ) ; -#28924 = DIRECTION ( 'NONE', ( 0.7930615290754823299, -0.5935319944304117135, -0.1370152644339880932 ) ) ; -#28925 = VERTEX_POINT ( 'NONE', #33934 ) ; -#28926 = LINE ( 'NONE', #6427, #30809 ) ; -#28927 = CARTESIAN_POINT ( 'NONE', ( -45.59089670396822669, 145.5092601323765109, 287.3340147879176811 ) ) ; -#28928 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#28929 = ORIENTED_EDGE ( 'NONE', *, *, #13153, .F. ) ; -#28930 = FACE_OUTER_BOUND ( 'NONE', #37763, .T. ) ; -#28931 = EDGE_CURVE ( 'NONE', #906, #10693, #23497, .T. ) ; -#28932 = CARTESIAN_POINT ( 'NONE', ( -23.32853479928075657, 115.6131185455671044, 87.78168085064412196 ) ) ; -#28934 = ADVANCED_FACE ( 'NONE', ( #12888 ), #5740, .F. ) ; -#28933 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20998, #36941, #4830, #32847 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#28935 = CARTESIAN_POINT ( 'NONE', ( -3.893460979042727921, 148.0324882923159180, 129.7501302153316090 ) ) ; -#28936 = CARTESIAN_POINT ( 'NONE', ( -45.70040756943009086, 187.3695729804526309, 106.0171126674183739 ) ) ; -#28937 = DIRECTION ( 'NONE', ( -0.1305262373691799260, -0.9659798014921964215, -0.2232620085624539286 ) ) ; -#28938 = EDGE_LOOP ( 'NONE', ( #32228, #25987, #9964, #14164 ) ) ; -#28939 = CARTESIAN_POINT ( 'NONE', ( 33.59926631015442666, 82.65455085156807513, 286.9156910329689367 ) ) ; -#28940 = CARTESIAN_POINT ( 'NONE', ( -35.56888541235999668, 112.3660634750000042, 90.16795747465999966 ) ) ; -#28941 = VERTEX_POINT ( 'NONE', #15345 ) ; -#28942 = CARTESIAN_POINT ( 'NONE', ( -20.49846059232846684, 118.8155328640159070, 89.78014971369738362 ) ) ; -#28943 = CONICAL_SURFACE ( 'NONE', #3445, 2.503000000131598846, 0.7853981633979968402 ) ; -#28944 = ORIENTED_EDGE ( 'NONE', *, *, #27574, .F. ) ; -#28945 = CARTESIAN_POINT ( 'NONE', ( 10.60892767148880722, 158.9861580188522225, 96.35136148965206360 ) ) ; -#28946 = CARTESIAN_POINT ( 'NONE', ( -76.10925030609612918, 156.2403276578370708, 96.28296423947242033 ) ) ; -#28947 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; -#28948 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319368671214 ) ) ; -#28949 = CARTESIAN_POINT ( 'NONE', ( 30.05084667745524385, 127.2908262436609164, 89.53532598631991846 ) ) ; -#28951 = VERTEX_POINT ( 'NONE', #399 ) ; -#28950 = AXIS2_PLACEMENT_3D ( 'NONE', #7167, #29054, #21932 ) ; -#28952 = ORIENTED_EDGE ( 'NONE', *, *, #4597, .T. ) ; -#28953 = CARTESIAN_POINT ( 'NONE', ( -1.458415330454428283, 144.9404864492411207, 129.0359332385636151 ) ) ; -#28954 = EDGE_LOOP ( 'NONE', ( #11946, #32633, #33616, #24777 ) ) ; -#28955 = VERTEX_POINT ( 'NONE', #6522 ) ; -#28956 = CARTESIAN_POINT ( 'NONE', ( -13.49852954174652098, 151.4059594047230348, 97.18165546544217648 ) ) ; -#28957 = ADVANCED_FACE ( 'NONE', ( #6330 ), #199, .T. ) ; -#28958 = AXIS2_PLACEMENT_3D ( 'NONE', #34514, #9817, #40267 ) ; -#28959 = DIRECTION ( 'NONE', ( -0.0005884949961196883151, 0.2249510543439064425, -0.9743698870671262391 ) ) ; -#28960 = ORIENTED_EDGE ( 'NONE', *, *, #2171, .F. ) ; -#28961 = CARTESIAN_POINT ( 'NONE', ( -38.93778834861265636, 191.4135373867393355, 104.3808903904224508 ) ) ; -#28962 = CARTESIAN_POINT ( 'NONE', ( 20.31592050807716987, 207.5617839839853502, 77.13467258061730547 ) ) ; -#28963 = CARTESIAN_POINT ( 'NONE', ( 43.33738618907429441, 121.9452304551619193, 87.95443437753064586 ) ) ; -#28964 = CARTESIAN_POINT ( 'NONE', ( 2.952902371779212221, 209.6824931357368484, 76.05698180698200872 ) ) ; -#28965 = FACE_OUTER_BOUND ( 'NONE', #16169, .T. ) ; -#28966 = CARTESIAN_POINT ( 'NONE', ( 21.49855060081473468, 136.1244284095153603, 91.06673730668626376 ) ) ; -#28967 = ORIENTED_EDGE ( 'NONE', *, *, #674, .T. ) ; -#28968 = CARTESIAN_POINT ( 'NONE', ( 28.10661807784000032, 125.3262985144999959, 88.91197353779001844 ) ) ; -#28969 = CARTESIAN_POINT ( 'NONE', ( 47.95951205218858604, 80.18001836396577175, 297.5295786860745579 ) ) ; -#28970 = FACE_OUTER_BOUND ( 'NONE', #25970, .T. ) ; -#28971 = CARTESIAN_POINT ( 'NONE', ( 22.78222448925487953, 163.9654955388074029, 100.5724953333896536 ) ) ; -#28972 = CARTESIAN_POINT ( 'NONE', ( 3.549667999360065274, 137.0383104860663650, 91.28856432241404661 ) ) ; -#28973 = ORIENTED_EDGE ( 'NONE', *, *, #34537, .F. ) ; -#28974 = CARTESIAN_POINT ( 'NONE', ( 2.562147501752185086, 194.2771767929999953, 102.8967287192001692 ) ) ; -#28975 = CARTESIAN_POINT ( 'NONE', ( 0.7210351870193272283, 189.0061775126145278, 103.6849341927780728 ) ) ; -#28976 = CIRCLE ( 'NONE', #32249, 2.499999999942751128 ) ; -#28977 = AXIS2_PLACEMENT_3D ( 'NONE', #12859, #21471, #33911 ) ; -#28978 = CARTESIAN_POINT ( 'NONE', ( 36.50235068108981551, 191.7558943553050597, 104.3539645039292338 ) ) ; -#28979 = CARTESIAN_POINT ( 'NONE', ( 25.99883959725927340, 118.3495095284676779, 87.25212951290748720 ) ) ; -#28980 = ADVANCED_FACE ( 'NONE', ( #9616 ), #17616, .F. ) ; -#28981 = CARTESIAN_POINT ( 'NONE', ( -25.61365638992000271, 191.7614508023000042, 104.3047066533000020 ) ) ; -#28982 = EDGE_CURVE ( 'NONE', #34116, #40341, #30894, .T. ) ; -#28983 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971545696 ) ) ; -#28984 = CARTESIAN_POINT ( 'NONE', ( -37.17549197171149444, 71.97997760090089514, 323.0191280695677278 ) ) ; -#28985 = AXIS2_PLACEMENT_3D ( 'NONE', #21129, #11938, #8874 ) ; -#28986 = PLANE ( 'NONE', #14091 ) ; -#28987 = ORIENTED_EDGE ( 'NONE', *, *, #1313, .F. ) ; -#28988 = CARTESIAN_POINT ( 'NONE', ( 21.21457940375938378, 183.3621723504481906, 102.4857529904703028 ) ) ; -#28989 = ORIENTED_EDGE ( 'NONE', *, *, #33805, .T. ) ; -#28990 = PLANE ( 'NONE', #38758 ) ; -#28991 = CARTESIAN_POINT ( 'NONE', ( -35.95435800709800844, 218.5902260770999987, 75.58022006963935269 ) ) ; -#28992 = LINE ( 'NONE', #13461, #15013 ) ; -#28993 = CARTESIAN_POINT ( 'NONE', ( 36.06465993625999999, 192.4996331442999917, 105.6863068227000184 ) ) ; -#28994 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178539432571E-05, -0.0002331579774923554001 ) ) ; -#28995 = FACE_OUTER_BOUND ( 'NONE', #14882, .T. ) ; -#28996 = DIRECTION ( 'NONE', ( -2.498001805435684678E-14, 0.9743700557921592953, 0.2249510932971531540 ) ) ; -#28997 = ORIENTED_EDGE ( 'NONE', *, *, #7042, .T. ) ; -#28998 = ORIENTED_EDGE ( 'NONE', *, *, #21274, .F. ) ; -#28999 = CARTESIAN_POINT ( 'NONE', ( -2.372094540712000210, 209.5677221608999901, 75.55993681610999602 ) ) ; -#29000 = ADVANCED_FACE ( 'NONE', ( #18189 ), #18997, .F. ) ; -#29001 = CARTESIAN_POINT ( 'NONE', ( 10.89673787447373954, 188.3452299077503937, 103.1293446006402093 ) ) ; -#29002 = VECTOR ( 'NONE', #33954, 1000.000000000000227 ) ; -#29003 = DIRECTION ( 'NONE', ( -0.7075337269008550312, -8.731295299227720714E-15, -0.7066795775298634341 ) ) ; -#29004 = LINE ( 'NONE', #16125, #38937 ) ; -#29005 = VERTEX_POINT ( 'NONE', #12282 ) ; -#29006 = FACE_OUTER_BOUND ( 'NONE', #4614, .T. ) ; -#29007 = VECTOR ( 'NONE', #31922, 1000.000000000000000 ) ; -#29008 = ORIENTED_EDGE ( 'NONE', *, *, #18682, .T. ) ; -#29009 = CARTESIAN_POINT ( 'NONE', ( -3.316502142368714878, 129.4074268280347155, 89.53098268898165202 ) ) ; -#29010 = CYLINDRICAL_SURFACE ( 'NONE', #17676, 6.000000000000001776 ) ; -#29011 = EDGE_LOOP ( 'NONE', ( #39884, #20948, #779, #3757 ) ) ; -#29012 = CARTESIAN_POINT ( 'NONE', ( -37.83775869347861942, 191.4135374006265806, 104.3802260088867513 ) ) ; -#29013 = EDGE_CURVE ( 'NONE', #38943, #4296, #9, .T. ) ; -#29014 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498896523, 179.0675991014397255, 104.0619761092555535 ) ) ; -#29015 = LINE ( 'NONE', #19787, #32657 ) ; -#29016 = DIRECTION ( 'NONE', ( 0.6087614115774879764, -0.7730004600455407937, -0.1785492440296699013 ) ) ; -#29017 = VERTEX_POINT ( 'NONE', #34138 ) ; -#29018 = ADVANCED_FACE ( 'NONE', ( #38413 ), #16920, .F. ) ; -#29019 = CARTESIAN_POINT ( 'NONE', ( 16.56066969684213319, 151.5369496897081376, 184.4389257082733025 ) ) ; -#29020 = CARTESIAN_POINT ( 'NONE', ( 30.06999065270167293, 177.5155566641962821, 100.8568524939294662 ) ) ; -#29021 = PLANE ( 'NONE', #35143 ) ; -#29022 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9848, #22320, #9639, #38036 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.007059153986243680776, 0.007984364839272745790 ), - .UNSPECIFIED. ) ; -#29023 = CARTESIAN_POINT ( 'NONE', ( -37.66357074801999971, 191.5193100856000115, 104.5557267436000046 ) ) ; -#29024 = ORIENTED_EDGE ( 'NONE', *, *, #8310, .F. ) ; -#29025 = CARTESIAN_POINT ( 'NONE', ( 22.49964039506791380, 136.6763645039129074, 180.9867425820801259 ) ) ; -#29026 = EDGE_CURVE ( 'NONE', #14528, #10049, #15528, .T. ) ; -#29027 = EDGE_CURVE ( 'NONE', #18640, #9446, #5225, .T. ) ; -#29028 = ADVANCED_FACE ( 'NONE', ( #1397 ), #35874, .F. ) ; -#29029 = CARTESIAN_POINT ( 'NONE', ( 36.70965854364384739, 115.7295922440460743, 89.70117536820643522 ) ) ; -#29030 = VECTOR ( 'NONE', #27953, 1000.000000000000227 ) ; -#29031 = CIRCLE ( 'NONE', #12713, 2.499999999924464866 ) ; -#29032 = DIRECTION ( 'NONE', ( 2.710505431213760483E-20, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#29033 = PLANE ( 'NONE', #13894 ) ; -#29034 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #34204, #9899 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29035 = VECTOR ( 'NONE', #3380, 1000.000000000000000 ) ; -#29036 = LINE ( 'NONE', #31411, #38491 ) ; -#29037 = FACE_OUTER_BOUND ( 'NONE', #5693, .T. ) ; -#29038 = FACE_OUTER_BOUND ( 'NONE', #27756, .T. ) ; -#29039 = CARTESIAN_POINT ( 'NONE', ( 20.48164290558045053, 206.1980406404009329, 75.23207116101302461 ) ) ; -#29040 = CARTESIAN_POINT ( 'NONE', ( 38.66577705699000234, 118.3794861341999933, 89.51282126978000520 ) ) ; -#29041 = ORIENTED_EDGE ( 'NONE', *, *, #19133, .T. ) ; -#29042 = CARTESIAN_POINT ( 'NONE', ( 1.447658033344545903, 144.9407251398178005, 129.0349007176305065 ) ) ; -#29043 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; -#29044 = LINE ( 'NONE', #25990, #32093 ) ; -#29046 = ORIENTED_EDGE ( 'NONE', *, *, #23533, .T. ) ; -#29045 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; -#29047 = ORIENTED_EDGE ( 'NONE', *, *, #26244, .T. ) ; -#29048 = VERTEX_POINT ( 'NONE', #7329 ) ; -#29049 = LINE ( 'NONE', #38637, #35263 ) ; -#29050 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13526, #32528, #35982, #13723, #32137, #7578, #23134, #1037 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 4 ), - ( 1.176960980475848905E-15, 0.0004331621789878069002, 0.0008663243579744368990, 0.001732648715947696788 ), - .UNSPECIFIED. ) ; -#29051 = CARTESIAN_POINT ( 'NONE', ( 22.11658944985360264, 129.6856566903868213, 90.09300832417258675 ) ) ; -#29052 = EDGE_LOOP ( 'NONE', ( #7017, #29695, #31826, #19336 ) ) ; -#29053 = VECTOR ( 'NONE', #38520, 1000.000000000000114 ) ; -#29054 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -5.029100735414826696E-18, -0.0006039748319369899615 ) ) ; -#29055 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5844, #24270, #12376, #12191, #27742, #2182, #34046, #21604, #6039, #14653, #8725, #21186, #36515, #8517, #33644, #5639, #10126, #12789, #16239, #37715 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999667766, 0.1874999999999595879, 0.2187499999999551747, 0.2343749999999428513, 0.2499999999999305000, 0.4999999999999613642, 0.6249999999999771294, 0.6874999999999816813, 0.7187499999999844569, 0.7343749999999844569, 0.7499999999999843459, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29056 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -5.029098237799274788E-18, 0.0006039748319384018096 ) ) ; -#29057 = CARTESIAN_POINT ( 'NONE', ( -38.12719533885000089, 119.0721968347999962, 87.43909598028000119 ) ) ; -#29058 = CARTESIAN_POINT ( 'NONE', ( 6.034202883963867059, 175.3568768315410011, 100.1305289580489557 ) ) ; -#29059 = VECTOR ( 'NONE', #6374, 1000.000000000000227 ) ; -#29060 = VECTOR ( 'NONE', #352, 1000.000000000000114 ) ; -#29061 = CARTESIAN_POINT ( 'NONE', ( 22.50176656424163824, 160.0672683219272017, 99.67592654435250665 ) ) ; -#29062 = VERTEX_POINT ( 'NONE', #28819 ) ; -#29063 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#29064 = EDGE_CURVE ( 'NONE', #15381, #15846, #13878, .T. ) ; -#29065 = ORIENTED_EDGE ( 'NONE', *, *, #37612, .T. ) ; -#29066 = LINE ( 'NONE', #32139, #6363 ) ; -#29067 = AXIS2_PLACEMENT_3D ( 'NONE', #39853, #22971, #23171 ) ; -#29068 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.110223024625155594E-14 ) ) ; -#29069 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -2.938175737920237887E-14, 0.0006039748320101188559 ) ) ; -#29070 = CARTESIAN_POINT ( 'NONE', ( 76.10689632611000377, 156.0201458301999935, 97.16650080654000021 ) ) ; -#29071 = DIRECTION ( 'NONE', ( 0.0006039748319379876444, 1.544770086762009064E-14, 0.9999998176071845934 ) ) ; -#29072 = ORIENTED_EDGE ( 'NONE', *, *, #17029, .F. ) ; -#29073 = EDGE_CURVE ( 'NONE', #3788, #32791, #19839, .T. ) ; -#29074 = CARTESIAN_POINT ( 'NONE', ( -0.6295527621319999545, 188.7401429372000052, 103.3599632786999933 ) ) ; -#29075 = CARTESIAN_POINT ( 'NONE', ( 3.166350953592421025, 126.8041585549839709, 88.92605846951083493 ) ) ; -#29076 = DIRECTION ( 'NONE', ( -1.445602896664413772E-14, -1.000000000000000000, 0.000000000000000000 ) ) ; -#29077 = CARTESIAN_POINT ( 'NONE', ( 18.99282617352092828, 148.1950018063203913, 184.7146606765990100 ) ) ; -#29078 = EDGE_CURVE ( 'NONE', #1820, #37645, #9667, .T. ) ; -#29079 = EDGE_LOOP ( 'NONE', ( #9271, #8703, #30763, #2333 ) ) ; -#29080 = CARTESIAN_POINT ( 'NONE', ( -21.21281380558005125, 182.9066539643694966, 104.4588199671594850 ) ) ; -#29081 = CARTESIAN_POINT ( 'NONE', ( 22.53027613144000085, 173.3942358358999911, 152.4718672074000381 ) ) ; -#29082 = ADVANCED_FACE ( 'NONE', ( #31700 ), #38509, .F. ) ; -#29083 = ORIENTED_EDGE ( 'NONE', *, *, #16229, .T. ) ; -#29084 = ADVANCED_FACE ( 'NONE', ( #16732 ), #593, .F. ) ; -#29085 = ADVANCED_FACE ( 'NONE', ( #22891 ), #38010, .F. ) ; -#29086 = PLANE ( 'NONE', #32362 ) ; -#29087 = ORIENTED_EDGE ( 'NONE', *, *, #35597, .T. ) ; -#29088 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 130.2931719330194369, 89.72259846333660960 ) ) ; -#29089 = CARTESIAN_POINT ( 'NONE', ( 23.68596773153945989, 129.9751393263009334, 92.21150139171207627 ) ) ; -#29090 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#29091 = CARTESIAN_POINT ( 'NONE', ( 23.68783464955822637, 130.1000560662577641, 92.41140855418669275 ) ) ; -#29092 = AXIS2_PLACEMENT_3D ( 'NONE', #2743, #37281, #34003 ) ; -#29093 = ORIENTED_EDGE ( 'NONE', *, *, #4934, .T. ) ; -#29094 = VECTOR ( 'NONE', #20894, 1000.000000000000114 ) ; -#29095 = AXIS2_PLACEMENT_3D ( 'NONE', #19461, #6585, #37475 ) ; -#29096 = EDGE_LOOP ( 'NONE', ( #11634, #1940, #11055, #35574, #17822, #37501, #13903, #27816, #4279, #23867, #23544, #22251 ) ) ; -#29097 = CARTESIAN_POINT ( 'NONE', ( 25.50048144128237482, 120.2040495201863877, 89.94428625009325629 ) ) ; -#29098 = DIRECTION ( 'NONE', ( -0.0001408393175929667886, 0.2255194967740913881, -0.9742386446549157197 ) ) ; -#29099 = VECTOR ( 'NONE', #29570, 1000.000000000000000 ) ; -#29101 = CARTESIAN_POINT ( 'NONE', ( 12.63943526404941409, 181.6152899297528336, 104.1402435535042770 ) ) ; -#29100 = FACE_OUTER_BOUND ( 'NONE', #12847, .T. ) ; -#29102 = EDGE_LOOP ( 'NONE', ( #27219, #32682 ) ) ; -#29103 = CYLINDRICAL_SURFACE ( 'NONE', #1390, 22.50000000000000000 ) ; -#29104 = ORIENTED_EDGE ( 'NONE', *, *, #25236, .T. ) ; -#29105 = CARTESIAN_POINT ( 'NONE', ( -22.49823373578500707, 127.0679975458287885, 92.08138095398328460 ) ) ; -#29106 = LINE ( 'NONE', #4134, #24076 ) ; -#29107 = ORIENTED_EDGE ( 'NONE', *, *, #34859, .F. ) ; -#29108 = VERTEX_POINT ( 'NONE', #25766 ) ; -#29109 = CARTESIAN_POINT ( 'NONE', ( 38.76540524925999875, 119.1021110644999936, 90.11972037454999906 ) ) ; -#29110 = CARTESIAN_POINT ( 'NONE', ( -5.676543322760370991, 181.0132184317505448, 104.5254537842582323 ) ) ; -#29111 = FACE_OUTER_BOUND ( 'NONE', #28696, .T. ) ; -#29112 = CARTESIAN_POINT ( 'NONE', ( -45.63015653918211001, 123.6493010396682592, 93.26116892431079464 ) ) ; -#29113 = CARTESIAN_POINT ( 'NONE', ( -2.557265648198999930, 190.9740655001999983, 106.4346615696999976 ) ) ; -#29114 = CARTESIAN_POINT ( 'NONE', ( 36.24932317171001017, 191.9578045599000120, 104.3871094435999964 ) ) ; -#29115 = EDGE_CURVE ( 'NONE', #18050, #21146, #29015, .T. ) ; -#29116 = ORIENTED_EDGE ( 'NONE', *, *, #26446, .T. ) ; -#29117 = EDGE_CURVE ( 'NONE', #18594, #37750, #15938, .T. ) ; -#29118 = EDGE_LOOP ( 'NONE', ( #12506, #18570, #32483, #19778 ) ) ; -#29119 = VECTOR ( 'NONE', #33470, 999.9999999999998863 ) ; -#29120 = FACE_OUTER_BOUND ( 'NONE', #23426, .T. ) ; -#29121 = EDGE_CURVE ( 'NONE', #35627, #1984, #1297, .T. ) ; -#29122 = CARTESIAN_POINT ( 'NONE', ( -23.36287322752248485, 134.3886336262885663, 93.64575589608618600 ) ) ; -#29123 = AXIS2_PLACEMENT_3D ( 'NONE', #32511, #38039, #29451 ) ; -#29124 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673776705, 151.8594835319893548, 95.21744457848066645 ) ) ; -#29125 = VECTOR ( 'NONE', #962, 1000.000000000000227 ) ; -#29126 = ORIENTED_EDGE ( 'NONE', *, *, #24430, .F. ) ; -#29127 = VERTEX_POINT ( 'NONE', #4669 ) ; -#29128 = CARTESIAN_POINT ( 'NONE', ( -12.63048181974366990, 130.3451622633888576, 92.83206449613362565 ) ) ; -#29129 = ORIENTED_EDGE ( 'NONE', *, *, #29669, .F. ) ; -#29130 = AXIS2_PLACEMENT_3D ( 'NONE', #23212, #32997, #32418 ) ; -#29131 = EDGE_CURVE ( 'NONE', #2995, #9290, #36363, .T. ) ; -#29132 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#29133 = CARTESIAN_POINT ( 'NONE', ( 9.176516921554000561, 134.5452385099999901, 93.53193153540000537 ) ) ; -#29134 = EDGE_LOOP ( 'NONE', ( #23478, #26392, #28952, #30674, #24243, #10075 ) ) ; -#29135 = CARTESIAN_POINT ( 'NONE', ( -6.666724428068700803, 120.3902201003022583, 87.45121955335277164 ) ) ; -#29136 = ADVANCED_FACE ( 'NONE', ( #33078 ), #26140, .T. ) ; -#29137 = CARTESIAN_POINT ( 'NONE', ( -2.112662471484000104, 189.1905130851999957, 106.2660147881999961 ) ) ; -#29138 = CARTESIAN_POINT ( 'NONE', ( -32.37225756577250024, 137.6262283585609794, 94.52490471072836442 ) ) ; -#29139 = CARTESIAN_POINT ( 'NONE', ( 25.99018610745488900, 211.0908525021142168, 73.04280463953621449 ) ) ; -#29140 = ORIENTED_EDGE ( 'NONE', *, *, #12450, .T. ) ; -#29141 = CYLINDRICAL_SURFACE ( 'NONE', #29736, 2.500000000000002220 ) ; -#29142 = CYLINDRICAL_SURFACE ( 'NONE', #2924, 6.000000000000008882 ) ; -#29143 = CARTESIAN_POINT ( 'NONE', ( -3.669581222385334573, 184.0117732734999834, 102.6507570781000851 ) ) ; -#29144 = EDGE_CURVE ( 'NONE', #1021, #28145, #9163, .T. ) ; -#29145 = CARTESIAN_POINT ( 'NONE', ( 45.50974939072701630, 131.1361171346210313, 90.41374468093005135 ) ) ; -#29146 = ORIENTED_EDGE ( 'NONE', *, *, #6909, .F. ) ; -#29147 = CARTESIAN_POINT ( 'NONE', ( 25.50041447495308233, 118.1134306400200416, 89.75249416949174019 ) ) ; -#29148 = AXIS2_PLACEMENT_3D ( 'NONE', #26600, #20432, #8180 ) ; -#29149 = AXIS2_PLACEMENT_3D ( 'NONE', #28150, #37726, #34644 ) ; -#29150 = CARTESIAN_POINT ( 'NONE', ( -38.04444379205944671, 118.4867705051282627, 87.71485106921780073 ) ) ; -#29151 = EDGE_LOOP ( 'NONE', ( #34354, #35450, #16353, #1100 ) ) ; -#29152 = ORIENTED_EDGE ( 'NONE', *, *, #25536, .F. ) ; -#29153 = CARTESIAN_POINT ( 'NONE', ( 13.46612284730906950, 158.3062971533392158, 96.19268454968825210 ) ) ; -#29154 = CARTESIAN_POINT ( 'NONE', ( 35.33426620396411977, 88.25255173735948233, 281.9959031066233024 ) ) ; -#29155 = VECTOR ( 'NONE', #23794, 1000.000000000000227 ) ; -#29156 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; -#29157 = ORIENTED_EDGE ( 'NONE', *, *, #25103, .F. ) ; -#29158 = ORIENTED_EDGE ( 'NONE', *, *, #5968, .T. ) ; -#29159 = FACE_BOUND ( 'NONE', #9835, .T. ) ; -#29160 = ORIENTED_EDGE ( 'NONE', *, *, #17518, .F. ) ; -#29161 = ORIENTED_EDGE ( 'NONE', *, *, #26594, .T. ) ; -#29162 = ORIENTED_EDGE ( 'NONE', *, *, #171, .T. ) ; -#29163 = CARTESIAN_POINT ( 'NONE', ( 5.668006812857668386, 188.0198015040569999, 103.3352605442849210 ) ) ; -#29164 = CARTESIAN_POINT ( 'NONE', ( 2.480024872728376462, 190.3696323296966568, 106.1306803042403146 ) ) ; -#29165 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391915424 ) ) ; -#29166 = CARTESIAN_POINT ( 'NONE', ( -40.55693163771468335, 184.9318016480985136, 102.3722900139845251 ) ) ; -#29167 = EDGE_LOOP ( 'NONE', ( #6666, #5681, #11483, #33686 ) ) ; -#29168 = EDGE_CURVE ( 'NONE', #17312, #38732, #5065, .T. ) ; -#29169 = VERTEX_POINT ( 'NONE', #36145 ) ; -#29170 = CARTESIAN_POINT ( 'NONE', ( -25.50990988232443257, 208.8372429855093912, 73.63742171263974967 ) ) ; -#29171 = ADVANCED_FACE ( 'NONE', ( #2434 ), #23287, .F. ) ; -#29172 = CARTESIAN_POINT ( 'NONE', ( -26.00155756584835132, 118.8155666110999960, 87.28349583687662516 ) ) ; -#29173 = CARTESIAN_POINT ( 'NONE', ( 36.38410872893999937, 191.7179417355000055, 104.2356371314999990 ) ) ; -#29174 = EDGE_CURVE ( 'NONE', #5222, #19726, #4866, .T. ) ; -#29175 = CARTESIAN_POINT ( 'NONE', ( 2.977108692617461472, 209.6085488725653079, 76.05914829704735780 ) ) ; -#29176 = EDGE_LOOP ( 'NONE', ( #30617, #3284, #19966, #26982, #37103, #4432, #16929, #9916, #26319, #3542 ) ) ; -#29177 = CARTESIAN_POINT ( 'NONE', ( -14.55306118018871508, 176.9194272080598296, 100.5067835523781667 ) ) ; -#29178 = EDGE_LOOP ( 'NONE', ( #33810, #2183, #20779, #183, #2428, #6641, #26008, #8456, #28555, #38095 ) ) ; -#29179 = AXIS2_PLACEMENT_3D ( 'NONE', #20544, #23835, #26913 ) ; -#29180 = CARTESIAN_POINT ( 'NONE', ( 28.45934412591282126, 181.0176348879864747, 104.5058915996823004 ) ) ; -#29181 = CARTESIAN_POINT ( 'NONE', ( 24.25829023881467705, 115.9286911914962417, 87.75294826888874411 ) ) ; -#29182 = AXIS2_PLACEMENT_3D ( 'NONE', #40061, #12076, #1851 ) ; -#29183 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971519328 ) ) ; -#29184 = DIRECTION ( 'NONE', ( -0.6087611427424929333, -0.7731004630501246977, -0.1781166615410725018 ) ) ; -#29185 = AXIS2_PLACEMENT_3D ( 'NONE', #29200, #35092, #38387 ) ; -#29186 = ORIENTED_EDGE ( 'NONE', *, *, #38556, .T. ) ; -#29188 = EDGE_CURVE ( 'NONE', #22653, #28262, #39831, .T. ) ; -#29187 = DIRECTION ( 'NONE', ( -0.0006039748319110907569, -0.000000000000000000, -0.9999998176071845934 ) ) ; -#29189 = CARTESIAN_POINT ( 'NONE', ( 0.8300031732345369839, 189.0179702984774508, 103.6899947345402211 ) ) ; -#29190 = CARTESIAN_POINT ( 'NONE', ( -2.935232621041004020, 190.8511156531020276, 106.7950609103722286 ) ) ; -#29191 = AXIS2_PLACEMENT_3D ( 'NONE', #35408, #7414, #19881 ) ; -#29192 = CARTESIAN_POINT ( 'NONE', ( 12.64200339761032410, 130.3171527467937381, 92.76750990966068855 ) ) ; -#29193 = CARTESIAN_POINT ( 'NONE', ( -25.61308620896999955, 191.8364462360999880, 104.3104845255000015 ) ) ; -#29194 = DIRECTION ( 'NONE', ( 0.0005884949961273644664, -0.2249510543439051102, 0.9743698870671265722 ) ) ; -#29195 = CARTESIAN_POINT ( 'NONE', ( 20.89286828480348035, 176.3842452922319524, 100.3618186666556369 ) ) ; -#29196 = EDGE_CURVE ( 'NONE', #468, #35577, #1604, .T. ) ; -#29197 = CARTESIAN_POINT ( 'NONE', ( 41.88489195034309631, 131.9654069037970885, 291.5332465100412378 ) ) ; -#29198 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988483757628, 156.3551877983847476, 95.75036263592852492 ) ) ; -#29199 = VERTEX_POINT ( 'NONE', #23694 ) ; -#29200 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; -#29201 = VERTEX_POINT ( 'NONE', #14704 ) ; -#29202 = CARTESIAN_POINT ( 'NONE', ( -27.08876248542915377, 119.4912842839333535, 171.3567424277059956 ) ) ; -#29203 = LINE ( 'NONE', #38199, #918 ) ; -#29204 = AXIS2_PLACEMENT_3D ( 'NONE', #24737, #14911, #31056 ) ; -#29205 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#29206 = CARTESIAN_POINT ( 'NONE', ( 20.23265938097805261, 118.1109138226942576, 90.02470701647605722 ) ) ; -#29207 = DIRECTION ( 'NONE', ( -0.0006039748319381367221, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#29208 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; -#29209 = CARTESIAN_POINT ( 'NONE', ( 36.22735687070999688, 192.3421510775999934, 106.2514255960000042 ) ) ; -#29210 = AXIS2_PLACEMENT_3D ( 'NONE', #15853, #34840, #3780 ) ; -#29211 = ORIENTED_EDGE ( 'NONE', *, *, #16137, .F. ) ; -#29212 = CARTESIAN_POINT ( 'NONE', ( -2.690858666602926164, 209.6642433610929004, 75.89346406803156242 ) ) ; -#29213 = CARTESIAN_POINT ( 'NONE', ( -24.42776677020912146, 104.1131156706543095, 87.28253805075753746 ) ) ; -#29214 = CARTESIAN_POINT ( 'NONE', ( 14.78718341405425818, 175.4478817342403545, 102.7150877355488063 ) ) ; -#29215 = CARTESIAN_POINT ( 'NONE', ( 19.28996579701385272, 152.1764298578125647, 190.8161490377309235 ) ) ; -#29216 = ORIENTED_EDGE ( 'NONE', *, *, #27525, .T. ) ; -#29217 = CARTESIAN_POINT ( 'NONE', ( 6.035627073997911651, 177.4672258935703439, 100.8988463399265925 ) ) ; -#29218 = CARTESIAN_POINT ( 'NONE', ( 25.50045020523564077, 118.3474758881666560, 89.75243582336268844 ) ) ; -#29219 = EDGE_CURVE ( 'NONE', #38692, #35411, #40343, .T. ) ; -#29220 = ORIENTED_EDGE ( 'NONE', *, *, #17462, .F. ) ; -#29221 = LINE ( 'NONE', #10617, #10832 ) ; -#29222 = CARTESIAN_POINT ( 'NONE', ( -4.020898715903520326, 130.4236660157353072, 89.76602547266925569 ) ) ; -#29223 = VERTEX_POINT ( 'NONE', #8146 ) ; -#29224 = CARTESIAN_POINT ( 'NONE', ( 36.45704065391474558, 191.6277635170577867, 106.3741589157719289 ) ) ; -#29225 = CARTESIAN_POINT ( 'NONE', ( -35.43627711891984688, 192.7868339519407357, 106.8766537076977698 ) ) ; -#29226 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552156487, 3.781093664149108639E-12, 291.5584375788758393 ) ) ; -#29227 = CARTESIAN_POINT ( 'NONE', ( 20.49980344970378354, 118.1127835573565221, 87.75514417896067698 ) ) ; -#29228 = EDGE_LOOP ( 'NONE', ( #35579, #16500, #17861, #32187 ) ) ; -#29229 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#29230 = CARTESIAN_POINT ( 'NONE', ( -3.696943479721821024, 176.2105024722404494, 100.3365558499248635 ) ) ; -#29231 = FACE_OUTER_BOUND ( 'NONE', #29703, .T. ) ; -#29232 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34111, #28009, #6106, #37399 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29233 = VECTOR ( 'NONE', #26013, 999.9999999999998863 ) ; -#29234 = FACE_OUTER_BOUND ( 'NONE', #20789, .T. ) ; -#29235 = VERTEX_POINT ( 'NONE', #5268 ) ; -#29236 = ORIENTED_EDGE ( 'NONE', *, *, #24629, .T. ) ; -#29237 = DIRECTION ( 'NONE', ( -3.562554695809820367E-15, 0.9743043966640313469, 0.2252353050503801690 ) ) ; -#29238 = AXIS2_PLACEMENT_3D ( 'NONE', #23672, #1580, #33056 ) ; -#29239 = EDGE_CURVE ( 'NONE', #10957, #10196, #14089, .T. ) ; -#29240 = CARTESIAN_POINT ( 'NONE', ( -20.00025820447960001, 138.1823733798348428, 91.56700283718186029 ) ) ; -#29241 = DIRECTION ( 'NONE', ( 0.7933533416835694130, -0.5930537051408201199, -0.1373964266575329052 ) ) ; -#29242 = PLANE ( 'NONE', #25483 ) ; -#29243 = CARTESIAN_POINT ( 'NONE', ( 26.18925920981000388, 190.6440021692999949, 106.8645677889000041 ) ) ; -#29244 = CARTESIAN_POINT ( 'NONE', ( 38.70471324126999946, 118.8378872794999950, 87.80369324603999814 ) ) ; -#29245 = CARTESIAN_POINT ( 'NONE', ( -3.535839359701232087, 174.6735602432432586, 103.0605886135060700 ) ) ; -#29246 = CARTESIAN_POINT ( 'NONE', ( 38.48039504585000259, 118.5505675456000034, 89.80824134200000231 ) ) ; -#29247 = VERTEX_POINT ( 'NONE', #1811 ) ; -#29248 = ADVANCED_FACE ( 'NONE', ( #26567 ), #39010, .F. ) ; -#29249 = DIRECTION ( 'NONE', ( 3.092411411307044243E-16, -0.9743043966640313469, -0.2252353050503803911 ) ) ; -#29250 = CARTESIAN_POINT ( 'NONE', ( -36.19105143935069435, 191.8150791350400652, 106.4328427572402802 ) ) ; -#29251 = CARTESIAN_POINT ( 'NONE', ( -35.95668941153999754, 225.9002260768999975, 73.08022102179975832 ) ) ; -#29253 = VERTEX_POINT ( 'NONE', #2024 ) ; -#29252 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.110223024625155594E-14 ) ) ; -#29254 = ORIENTED_EDGE ( 'NONE', *, *, #33879, .T. ) ; -#29255 = ORIENTED_EDGE ( 'NONE', *, *, #39168, .T. ) ; -#29256 = ORIENTED_EDGE ( 'NONE', *, *, #31058, .T. ) ; -#29257 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#29258 = CONICAL_SURFACE ( 'NONE', #14877, 2.499999999928965710, 0.7853981633629654180 ) ; -#29259 = LINE ( 'NONE', #22929, #2422 ) ; -#29260 = EDGE_CURVE ( 'NONE', #6533, #26636, #5209, .T. ) ; -#29261 = ADVANCED_FACE ( 'NONE', ( #7940 ), #39411, .F. ) ; -#29262 = CONICAL_SURFACE ( 'NONE', #27333, 6.000000000011055157, 0.7853981633778703841 ) ; -#29263 = ORIENTED_EDGE ( 'NONE', *, *, #9878, .T. ) ; -#29264 = EDGE_CURVE ( 'NONE', #1201, #22101, #16942, .T. ) ; -#29265 = CARTESIAN_POINT ( 'NONE', ( -14.15070617995141511, 188.2799498060330166, 103.1293216427133501 ) ) ; -#29266 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.293414132305980107E-14, 0.9999998176071847045 ) ) ; -#29267 = LINE ( 'NONE', #1236, #24095 ) ; -#29268 = CARTESIAN_POINT ( 'NONE', ( -39.28820068017000011, 119.6036138029000142, 87.80684530786001574 ) ) ; -#29269 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624402326, 0.1792657018023851301 ) ) ; -#29270 = CARTESIAN_POINT ( 'NONE', ( -13.46321482478000142, 124.1316382070999964, 152.4718672074000381 ) ) ; -#29271 = ORIENTED_EDGE ( 'NONE', *, *, #37597, .T. ) ; -#29272 = CARTESIAN_POINT ( 'NONE', ( -2.435723678148116633, 191.9759150222000130, 106.4229192757972271 ) ) ; -#29273 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624403437, 0.1792657018023851578 ) ) ; -#29274 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.274821093756980468E-14, 0.9999998176071847045 ) ) ; -#29275 = DIRECTION ( 'NONE', ( -0.6087611434179118763, 0.7728348325624406767, 0.1792657018023830207 ) ) ; -#29276 = PLANE ( 'NONE', #11845 ) ; -#29277 = FACE_OUTER_BOUND ( 'NONE', #7496, .T. ) ; -#29278 = VERTEX_POINT ( 'NONE', #39214 ) ; -#29279 = VERTEX_POINT ( 'NONE', #9366 ) ; -#29280 = CARTESIAN_POINT ( 'NONE', ( 13.47343164508975377, 158.6809479346725595, 96.79232023565108989 ) ) ; -#29281 = CARTESIAN_POINT ( 'NONE', ( 3.333113635449135970, 126.7663220037077139, 89.08827443880241503 ) ) ; -#29282 = CARTESIAN_POINT ( 'NONE', ( 15.75014751337000263, 167.5737453454999866, 98.58743350925999493 ) ) ; -#29283 = EDGE_LOOP ( 'NONE', ( #9035, #20694, #13019 ) ) ; -#29284 = CARTESIAN_POINT ( 'NONE', ( -20.50037936456179821, 118.1134456052949560, 87.78011095654957785 ) ) ; -#29285 = LINE ( 'NONE', #16981, #23282 ) ; -#29286 = ORIENTED_EDGE ( 'NONE', *, *, #10086, .T. ) ; -#29287 = VECTOR ( 'NONE', #17685, 1000.000000000000114 ) ; -#29288 = ORIENTED_EDGE ( 'NONE', *, *, #30703, .T. ) ; -#29289 = ORIENTED_EDGE ( 'NONE', *, *, #32583, .T. ) ; -#29290 = CARTESIAN_POINT ( 'NONE', ( -27.25979547307461104, 188.5120705772432643, 103.1908285165064285 ) ) ; -#29291 = CARTESIAN_POINT ( 'NONE', ( 20.48555995111231809, 211.0898943587194481, 73.54694346759191603 ) ) ; -#29292 = VECTOR ( 'NONE', #34413, 1000.000000000000114 ) ; -#29293 = CARTESIAN_POINT ( 'NONE', ( -26.01062451896041949, 209.7096538831000032, 78.07421475979387537 ) ) ; -#29294 = ORIENTED_EDGE ( 'NONE', *, *, #33856, .F. ) ; -#29295 = EDGE_CURVE ( 'NONE', #36184, #13881, #4276, .T. ) ; -#29296 = CARTESIAN_POINT ( 'NONE', ( 26.00255769141890383, 120.1016707076159946, 90.44558059243480841 ) ) ; -#29297 = CARTESIAN_POINT ( 'NONE', ( -39.67864439245563801, 110.6878145009781207, 169.3185036007950828 ) ) ; -#29299 = CARTESIAN_POINT ( 'NONE', ( -37.29141526061891199, 118.0180923441248666, 123.5799244855521835 ) ) ; -#29298 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#29300 = EDGE_CURVE ( 'NONE', #37405, #25158, #38900, .T. ) ; -#29301 = CARTESIAN_POINT ( 'NONE', ( 0.5984374266184000479, 209.0000000000000000, 162.9824824849000322 ) ) ; -#29302 = ORIENTED_EDGE ( 'NONE', *, *, #3086, .T. ) ; -#29303 = CARTESIAN_POINT ( 'NONE', ( -16.78856485531536080, 122.2590524011903881, 174.8714234134831429 ) ) ; -#29304 = CARTESIAN_POINT ( 'NONE', ( -20.51998460911297784, 211.0905570173818546, 73.57089872868714053 ) ) ; -#29305 = ORIENTED_EDGE ( 'NONE', *, *, #26083, .T. ) ; -#29306 = EDGE_CURVE ( 'NONE', #32791, #3536, #3261, .T. ) ; -#29307 = EDGE_CURVE ( 'NONE', #20919, #9311, #2823, .T. ) ; -#29308 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3539, #19081, #686, #19683 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29309 = ORIENTED_EDGE ( 'NONE', *, *, #38782, .F. ) ; -#29310 = EDGE_CURVE ( 'NONE', #11222, #32939, #8216, .T. ) ; -#29311 = LINE ( 'NONE', #26252, #20469 ) ; -#29312 = AXIS2_PLACEMENT_3D ( 'NONE', #14138, #5516, #30486 ) ; -#29313 = EDGE_CURVE ( 'NONE', #28523, #16013, #31103, .T. ) ; -#29314 = FACE_OUTER_BOUND ( 'NONE', #9079, .T. ) ; -#29315 = CARTESIAN_POINT ( 'NONE', ( -2.557037456827000010, 190.9411552911000172, 106.4259169352999947 ) ) ; -#29316 = ORIENTED_EDGE ( 'NONE', *, *, #13568, .T. ) ; -#29317 = EDGE_LOOP ( 'NONE', ( #20386, #22330, #22012, #15670 ) ) ; -#29318 = AXIS2_PLACEMENT_3D ( 'NONE', #15160, #15738, #205 ) ; -#29319 = ORIENTED_EDGE ( 'NONE', *, *, #34537, .T. ) ; -#29320 = AXIS2_PLACEMENT_3D ( 'NONE', #263, #25643, #6400 ) ; -#29321 = CARTESIAN_POINT ( 'NONE', ( -12.63718745341644301, 177.5174336403395898, 100.8766356206245689 ) ) ; -#29322 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971565402 ) ) ; -#29323 = AXIS2_PLACEMENT_3D ( 'NONE', #14401, #38521, #32594 ) ; -#29324 = ORIENTED_EDGE ( 'NONE', *, *, #27809, .F. ) ; -#29325 = VERTEX_POINT ( 'NONE', #8769 ) ; -#29326 = CARTESIAN_POINT ( 'NONE', ( 30.06681124672108396, 135.0171899757494032, 90.93488900863064828 ) ) ; -#29327 = CARTESIAN_POINT ( 'NONE', ( -45.37719536161908707, 116.4273876275239701, 122.4606002128412285 ) ) ; -#29328 = ORIENTED_EDGE ( 'NONE', *, *, #1816, .F. ) ; -#29329 = CARTESIAN_POINT ( 'NONE', ( 39.70509503528159456, 119.3565270907554208, 89.75033746721189232 ) ) ; -#29330 = EDGE_CURVE ( 'NONE', #28905, #14957, #12616, .T. ) ; -#29331 = DIRECTION ( 'NONE', ( -0.1305262051655330657, 0.9658997629102444860, 0.2236080449693589878 ) ) ; -#29332 = PLANE ( 'NONE', #24170 ) ; -#29333 = CARTESIAN_POINT ( 'NONE', ( 32.61880616768083740, 141.6762977345059653, 282.0021323259457517 ) ) ; -#29334 = ORIENTED_EDGE ( 'NONE', *, *, #4217, .F. ) ; -#29335 = FACE_OUTER_BOUND ( 'NONE', #33464, .T. ) ; -#29336 = PLANE ( 'NONE', #21215 ) ; -#29337 = CARTESIAN_POINT ( 'NONE', ( 20.99281265120761830, 212.6262136629989925, 75.54565946750157934 ) ) ; -#29338 = AXIS2_PLACEMENT_3D ( 'NONE', #8558, #11407, #11214 ) ; -#29339 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21501, #6, #15734, #2692 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29340 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; -#29341 = ORIENTED_EDGE ( 'NONE', *, *, #9689, .F. ) ; -#29342 = EDGE_CURVE ( 'NONE', #24276, #33109, #20361, .T. ) ; -#29343 = VECTOR ( 'NONE', #6630, 1000.000000000000000 ) ; -#29344 = AXIS2_PLACEMENT_3D ( 'NONE', #7610, #10696, #26849 ) ; -#29345 = CARTESIAN_POINT ( 'NONE', ( -35.93638238082318992, 190.3639747181505584, 106.7025276796465221 ) ) ; -#29346 = VECTOR ( 'NONE', #18854, 999.9999999999998863 ) ; -#29347 = CARTESIAN_POINT ( 'NONE', ( -37.37212863889000403, 118.2131122468999962, 90.44578357401999824 ) ) ; -#29349 = ORIENTED_EDGE ( 'NONE', *, *, #14361, .T. ) ; -#29348 = EDGE_CURVE ( 'NONE', #17763, #8665, #31355, .T. ) ; -#29350 = CARTESIAN_POINT ( 'NONE', ( -4.036264727041273481, 174.7924093549539180, 102.5751288760997966 ) ) ; -#29351 = ORIENTED_EDGE ( 'NONE', *, *, #5767, .F. ) ; -#29352 = CARTESIAN_POINT ( 'NONE', ( -12.63809828823728232, 131.0198806733800438, 89.90888323108799796 ) ) ; -#29353 = ADVANCED_FACE ( 'NONE', ( #15497 ), #27989, .F. ) ; -#29354 = CARTESIAN_POINT ( 'NONE', ( -94.39863492640319009, 220.5914987861245038, 200.8703399042459807 ) ) ; -#29355 = CARTESIAN_POINT ( 'NONE', ( -20.00152015007030215, 160.4187917561418146, 96.70059905290261781 ) ) ; -#29356 = ORIENTED_EDGE ( 'NONE', *, *, #29751, .T. ) ; -#29357 = ORIENTED_EDGE ( 'NONE', *, *, #18908, .F. ) ; -#29358 = CARTESIAN_POINT ( 'NONE', ( -4.410460075269428515, 181.9951793858723761, 101.6724849349506741 ) ) ; -#29359 = ORIENTED_EDGE ( 'NONE', *, *, #31171, .F. ) ; -#29360 = ORIENTED_EDGE ( 'NONE', *, *, #12540, .F. ) ; -#29362 = EDGE_CURVE ( 'NONE', #23733, #11837, #11835, .T. ) ; -#29361 = CARTESIAN_POINT ( 'NONE', ( 5.667566726500820273, 188.1583619933900877, 103.2486785480823528 ) ) ; -#29363 = CARTESIAN_POINT ( 'NONE', ( -28.55615809014881989, 225.5077044902887735, 74.57575155991852967 ) ) ; -#29364 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#29365 = CARTESIAN_POINT ( 'NONE', ( 36.06343484178082548, 196.1181868591233410, 103.6579563381249471 ) ) ; -#29366 = ORIENTED_EDGE ( 'NONE', *, *, #12879, .F. ) ; -#29367 = CARTESIAN_POINT ( 'NONE', ( 23.36190162741788967, 177.7945445883550519, 100.6858769593398080 ) ) ; -#29368 = CARTESIAN_POINT ( 'NONE', ( 37.31808587042999648, 118.5177498127000035, 87.11908126231999461 ) ) ; -#29369 = DIRECTION ( 'NONE', ( -1.318389841742375916E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#29370 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23924, #5492, #5908, #8585 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29371 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474981270974893, 155.7928101626038426, 98.18628735352585579 ) ) ; -#29372 = AXIS2_PLACEMENT_3D ( 'NONE', #14851, #15048, #33840 ) ; -#29373 = ORIENTED_EDGE ( 'NONE', *, *, #4112, .F. ) ; -#29374 = CARTESIAN_POINT ( 'NONE', ( -28.45663166759245399, 131.0177812377234545, 89.91795229967709702 ) ) ; -#29375 = ORIENTED_EDGE ( 'NONE', *, *, #9047, .T. ) ; -#29376 = CONICAL_SURFACE ( 'NONE', #31976, 2.503152139042832847, 0.7853981633518120065 ) ; -#29377 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.110223024625155594E-14, 1.000000000000000000 ) ) ; -#29378 = CONICAL_SURFACE ( 'NONE', #18902, 2.503114778588952483, 0.7853981634133299083 ) ; -#29379 = DIRECTION ( 'NONE', ( -0.0004161288024540961568, -0.5299192578740949955, -0.8480479980348919478 ) ) ; -#29380 = CYLINDRICAL_SURFACE ( 'NONE', #15073, 4.000000000000000000 ) ; -#29381 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22822, #23017, #35250, #323 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29382 = CARTESIAN_POINT ( 'NONE', ( 45.34049352841594782, 186.1006523922279143, 106.0989781906799294 ) ) ; -#29383 = ORIENTED_EDGE ( 'NONE', *, *, #3066, .T. ) ; -#29384 = LINE ( 'NONE', #28974, #1738 ) ; -#29385 = CARTESIAN_POINT ( 'NONE', ( 0.8771784711739323281, 189.0248903872490018, 103.6920662537458355 ) ) ; -#29386 = DIRECTION ( 'NONE', ( -0.0005884949961238380989, 0.2249510543439045829, -0.9743698870671267942 ) ) ; -#29387 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 110.4872222533748243, 170.3180069646643915 ) ) ; -#29388 = EDGE_LOOP ( 'NONE', ( #26832, #14631, #16163, #22784 ) ) ; -#29389 = CARTESIAN_POINT ( 'NONE', ( -25.61331352295000130, 191.7885398544999873, 104.3073041621000101 ) ) ; -#29390 = CARTESIAN_POINT ( 'NONE', ( 13.50176809758824703, 126.1286536816045327, 91.84597050332364176 ) ) ; -#29391 = FACE_OUTER_BOUND ( 'NONE', #6551, .T. ) ; -#29392 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #29994, #8529, #27356, #11800 ), - ( #33653, #6052, #30808, #12387 ), - ( #30606, #2789, #18305, #21807 ), - ( #36938, #34056, #3171, #2600 ), - ( #5441, #36725, #115, #5654 ), - ( #18100, #40384, #39991, #12202 ), - ( #24884, #15652, #39784, #12577 ), - ( #9331, #37134, #28148, #27955 ), - ( #37336, #33451, #21414, #33850 ), - ( #5854, #34245, #6244, #15068 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.01471884533601999952, 0.000000000000000000, 0.2499920972522000073, 0.4999842007554999856, 0.7499763042585999573, 0.9999683887995000076, 1.000000000000000000, 1.015331287128000026 ), - ( 3.901540937544999784E-08, 1.000006391878000001 ), - .UNSPECIFIED. ) ; -#29393 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#29394 = EDGE_CURVE ( 'NONE', #2007, #38021, #14515, .T. ) ; -#29395 = ORIENTED_EDGE ( 'NONE', *, *, #28332, .T. ) ; -#29396 = CARTESIAN_POINT ( 'NONE', ( -15.66641274222027214, 174.4419466282511166, 100.2776428363426362 ) ) ; -#29397 = EDGE_CURVE ( 'NONE', #12309, #21808, #35472, .T. ) ; -#29398 = EDGE_CURVE ( 'NONE', #18716, #29610, #9824, .T. ) ; -#29399 = DIRECTION ( 'NONE', ( -6.938893903636092940E-15, -0.9743700557921582961, -0.2249510932971574007 ) ) ; -#29400 = AXIS2_PLACEMENT_3D ( 'NONE', #544, #10178, #19745 ) ; -#29401 = VECTOR ( 'NONE', #3748, 1000.000000000000000 ) ; -#29402 = CARTESIAN_POINT ( 'NONE', ( -20.49823408210000153, 188.6991459859000031, 106.3088473569000030 ) ) ; -#29403 = CARTESIAN_POINT ( 'NONE', ( 3.667423414729050535, 183.7129785219334224, 103.9457492209319014 ) ) ; -#29404 = EDGE_CURVE ( 'NONE', #38536, #10351, #14370, .T. ) ; -#29405 = AXIS2_PLACEMENT_3D ( 'NONE', #4178, #13014, #28947 ) ; -#29406 = CARTESIAN_POINT ( 'NONE', ( 36.26185541537999768, 190.7902229992999992, 106.9071729905000154 ) ) ; -#29407 = CARTESIAN_POINT ( 'NONE', ( -20.34738573694473729, 105.2139170220266777, 87.78007369431503548 ) ) ; -#29408 = AXIS2_PLACEMENT_3D ( 'NONE', #20207, #17745, #8578 ) ; -#29409 = CARTESIAN_POINT ( 'NONE', ( -43.57149710298272538, 121.9974123356087858, 87.84455874305574241 ) ) ; -#29410 = CYLINDRICAL_SURFACE ( 'NONE', #13554, 9.999999999999996447 ) ; -#29411 = PLANE ( 'NONE', #25619 ) ; -#29412 = LINE ( 'NONE', #22476, #27857 ) ; -#29413 = VERTEX_POINT ( 'NONE', #34678 ) ; -#29414 = ADVANCED_FACE ( 'NONE', ( #13037 ), #25518, .T. ) ; -#29415 = CARTESIAN_POINT ( 'NONE', ( -2.552137162834999806, 209.5516823602000045, 75.72668698761999906 ) ) ; -#29416 = CARTESIAN_POINT ( 'NONE', ( 35.55352078495887724, 112.9281706801280194, 87.24630913759760631 ) ) ; -#29417 = CARTESIAN_POINT ( 'NONE', ( 20.25014673412999855, 145.1862164384000096, 93.41614637723000669 ) ) ; -#29418 = ORIENTED_EDGE ( 'NONE', *, *, #7780, .F. ) ; -#29419 = CARTESIAN_POINT ( 'NONE', ( -39.42639396830977461, 119.7153704062085353, 90.39411697856569106 ) ) ; -#29420 = ORIENTED_EDGE ( 'NONE', *, *, #18634, .T. ) ; -#29421 = DIRECTION ( 'NONE', ( -0.6188015000093128881, 0.7855473910504855439, 0.000000000000000000 ) ) ; -#29422 = ORIENTED_EDGE ( 'NONE', *, *, #35628, .T. ) ; -#29423 = CARTESIAN_POINT ( 'NONE', ( 36.07534003772678233, 192.4911781188437487, 106.3697569404252334 ) ) ; -#29424 = CARTESIAN_POINT ( 'NONE', ( 45.27414284685049495, 117.1178614856958831, 122.5863626319347759 ) ) ; -#29425 = DIRECTION ( 'NONE', ( -0.6087611434178765712, -0.7731004625452565504, -0.1781166614241066204 ) ) ; -#29426 = CARTESIAN_POINT ( 'NONE', ( -43.94897559508903839, 113.3760414474846669, 85.85438606565890041 ) ) ; -#29427 = CARTESIAN_POINT ( 'NONE', ( -22.59416765712766306, 154.4034534036981654, 95.31341440929543296 ) ) ; -#29428 = ORIENTED_EDGE ( 'NONE', *, *, #3131, .T. ) ; -#29429 = VECTOR ( 'NONE', #6426, 1000.000000000000114 ) ; -#29430 = CARTESIAN_POINT ( 'NONE', ( 17.25783797889552673, 152.2862265970470617, 183.5735822442753147 ) ) ; -#29431 = AXIS2_PLACEMENT_3D ( 'NONE', #10760, #35268, #29566 ) ; -#29432 = PLANE ( 'NONE', #3559 ) ; -#29433 = LINE ( 'NONE', #11030, #13637 ) ; -#29434 = AXIS2_PLACEMENT_3D ( 'NONE', #23727, #27628, #33113 ) ; -#29435 = AXIS2_PLACEMENT_3D ( 'NONE', #22809, #22011, #19315 ) ; -#29436 = DIRECTION ( 'NONE', ( 0.0005884949961240561319, -0.2249510543439064147, 0.9743698870671262391 ) ) ; -#29437 = ORIENTED_EDGE ( 'NONE', *, *, #18499, .F. ) ; -#29438 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; -#29439 = DIRECTION ( 'NONE', ( -0.4300430038311932601, 0.3870104123855429012, 0.8156506332744531962 ) ) ; -#29440 = FACE_OUTER_BOUND ( 'NONE', #18802, .T. ) ; -#29441 = ADVANCED_FACE ( 'NONE', ( #35276 ), #1967, .F. ) ; -#29442 = CARTESIAN_POINT ( 'NONE', ( 18.72203975115986552, 148.1637263778248723, 183.9835433754430198 ) ) ; -#29443 = CARTESIAN_POINT ( 'NONE', ( 25.63308425969000126, 191.5931614552000042, 106.5131989830999970 ) ) ; -#29444 = LINE ( 'NONE', #11440, #4842 ) ; -#29445 = CARTESIAN_POINT ( 'NONE', ( 38.31967541772999652, 118.7379564658999982, 90.10272892278000256 ) ) ; -#29446 = ORIENTED_EDGE ( 'NONE', *, *, #4586, .F. ) ; -#29447 = DIRECTION ( 'NONE', ( -0.0005884949961204158147, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#29448 = DIRECTION ( 'NONE', ( -0.0005884949961246006183, 0.2249510543439056653, -0.9743698870671265722 ) ) ; -#29449 = LINE ( 'NONE', #22918, #22177 ) ; -#29450 = DIRECTION ( 'NONE', ( 0.0006039748319381690314, -1.159276051261448636E-15, 0.9999998176071845934 ) ) ; -#29451 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; -#29452 = VERTEX_POINT ( 'NONE', #22650 ) ; -#29453 = VERTEX_POINT ( 'NONE', #4012 ) ; -#29454 = AXIS2_PLACEMENT_3D ( 'NONE', #7557, #38632, #16948 ) ; -#29455 = ORIENTED_EDGE ( 'NONE', *, *, #6799, .T. ) ; -#29456 = FACE_OUTER_BOUND ( 'NONE', #24880, .T. ) ; -#29457 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25427, #16396, #31762, #31550 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29458 = AXIS2_PLACEMENT_3D ( 'NONE', #22441, #37966, #9562 ) ; -#29459 = CARTESIAN_POINT ( 'NONE', ( 5.658901668160544851, 123.6924101227050699, 91.28505159842420369 ) ) ; -#29460 = ORIENTED_EDGE ( 'NONE', *, *, #39082, .T. ) ; -#29461 = DIRECTION ( 'NONE', ( 5.165621017347116159E-14, -0.9743700557921582961, -0.2249510932971570121 ) ) ; -#29462 = EDGE_CURVE ( 'NONE', #5073, #4624, #19572, .T. ) ; -#29463 = CARTESIAN_POINT ( 'NONE', ( -38.50399426135000169, 118.5032430122000022, 89.70860371832000624 ) ) ; -#29464 = CARTESIAN_POINT ( 'NONE', ( -38.24270320005000201, 119.4332578602000154, 87.31799352362999400 ) ) ; -#29465 = CARTESIAN_POINT ( 'NONE', ( 1.752039179668178903, 151.6655327357930219, 130.5892088565730091 ) ) ; -#29466 = CARTESIAN_POINT ( 'NONE', ( -15.49852919459145184, 184.4001630190128367, 104.8001769099776652 ) ) ; -#29467 = EDGE_LOOP ( 'NONE', ( #24640, #13135, #32429, #18596 ) ) ; -#29468 = CARTESIAN_POINT ( 'NONE', ( -38.11441020723251683, 171.2555900315151121, 164.7874451303060823 ) ) ; -#29469 = VERTEX_POINT ( 'NONE', #7081 ) ; -#29470 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474974024143720, 155.7928101624922590, 98.18628735357600590 ) ) ; -#29471 = CARTESIAN_POINT ( 'NONE', ( 5.672806455269946646, 130.3093209897733971, 92.76044916600127976 ) ) ; -#29472 = FACE_OUTER_BOUND ( 'NONE', #21411, .T. ) ; -#29473 = CARTESIAN_POINT ( 'NONE', ( -3.169881913554984720, 185.9062129263137138, 102.5746722649703315 ) ) ; -#29474 = CARTESIAN_POINT ( 'NONE', ( -29.94659852274801892, 109.6131156702000027, 89.78587174306085217 ) ) ; -#29475 = ORIENTED_EDGE ( 'NONE', *, *, #27942, .T. ) ; -#29476 = CARTESIAN_POINT ( 'NONE', ( -1.067264757979980105, 188.6621860948839924, 103.2069977215000023 ) ) ; -#29477 = CARTESIAN_POINT ( 'NONE', ( -14.78542069845082807, 129.1241041573916561, 89.98565157148227911 ) ) ; -#29478 = CARTESIAN_POINT ( 'NONE', ( 2.685831263600999996, 190.9632241143999920, 106.4286715060000148 ) ) ; -#29479 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4001, #28962, #7069, #9962 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29480 = EDGE_LOOP ( 'NONE', ( #14838, #7596, #14216, #12606 ) ) ; -#29481 = CIRCLE ( 'NONE', #28809, 6.500000000066433969 ) ; -#29482 = DIRECTION ( 'NONE', ( 0.0005884949961256158652, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#29483 = DIRECTION ( 'NONE', ( 0.0001408404346092576671, -0.2255194953558363191, 0.9742386449830560124 ) ) ; -#29484 = VERTEX_POINT ( 'NONE', #1153 ) ; -#29485 = CIRCLE ( 'NONE', #12485, 2.250000000020509816 ) ; -#29486 = ORIENTED_EDGE ( 'NONE', *, *, #32516, .T. ) ; -#29487 = VERTEX_POINT ( 'NONE', #26120 ) ; -#29488 = EDGE_CURVE ( 'NONE', #30170, #14055, #11109, .T. ) ; -#29489 = ADVANCED_FACE ( 'NONE', ( #31649 ), #5902, .F. ) ; -#29490 = CARTESIAN_POINT ( 'NONE', ( 12.63825826683999942, 182.0651920360970735, 102.1915037817528997 ) ) ; -#29491 = CARTESIAN_POINT ( 'NONE', ( 76.10630783110904929, 156.2450968845086550, 96.19213091948995498 ) ) ; -#29492 = ORIENTED_EDGE ( 'NONE', *, *, #20859, .T. ) ; -#29493 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19366, #13638, #28778, #23052 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999992928508356638 ), - .UNSPECIFIED. ) ; -#29494 = CARTESIAN_POINT ( 'NONE', ( -5.670689818969662177, 181.8882185760199093, 101.9226644025294490 ) ) ; -#29495 = VERTEX_POINT ( 'NONE', #10375 ) ; -#29496 = ADVANCED_FACE ( 'NONE', ( #950 ), #28577, .T. ) ; -#29497 = CARTESIAN_POINT ( 'NONE', ( 25.66769799861999957, 120.2588969794000064, 90.13975766321000549 ) ) ; -#29498 = DIRECTION ( 'NONE', ( 0.7072735235932094966, 0.6508952249435893123, 0.2758615032397236932 ) ) ; -#29500 = CARTESIAN_POINT ( 'NONE', ( 13.46793942647703801, 157.6314446051065943, 99.11578051374280562 ) ) ; -#29499 = CARTESIAN_POINT ( 'NONE', ( 20.50029387904210765, 120.2778657767349841, 87.92202505056270923 ) ) ; -#29501 = ORIENTED_EDGE ( 'NONE', *, *, #1642, .F. ) ; -#29502 = ORIENTED_EDGE ( 'NONE', *, *, #10888, .T. ) ; -#29503 = LINE ( 'NONE', #26046, #1199 ) ; -#29504 = ORIENTED_EDGE ( 'NONE', *, *, #26089, .F. ) ; -#29506 = VECTOR ( 'NONE', #5483, 1000.000000000000114 ) ; -#29505 = CYLINDRICAL_SURFACE ( 'NONE', #38728, 1.749999999999998446 ) ; -#29507 = EDGE_CURVE ( 'NONE', #35411, #10050, #15022, .T. ) ; -#29508 = VECTOR ( 'NONE', #17294, 1000.000000000000000 ) ; -#29509 = DIRECTION ( 'NONE', ( -3.469446951894384145E-15, 0.9743700557921587402, 0.2249510932971553745 ) ) ; -#29510 = CARTESIAN_POINT ( 'NONE', ( -46.21296508723837348, 123.3002630821660404, 92.78578120404377216 ) ) ; -#29511 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 1.005820108796730516E-17, 0.0006039748319389842430 ) ) ; -#29512 = EDGE_LOOP ( 'NONE', ( #16233, #10134, #11422, #30370 ) ) ; -#29513 = VERTEX_POINT ( 'NONE', #9975 ) ; -#29514 = DIRECTION ( 'NONE', ( -0.5987322044655852826, -0.8009492788783697526, 0.000000000000000000 ) ) ; -#29515 = EDGE_LOOP ( 'NONE', ( #391, #4906, #11093, #8439 ) ) ; -#29516 = VERTEX_POINT ( 'NONE', #16088 ) ; -#29517 = CARTESIAN_POINT ( 'NONE', ( 30.06443600138266703, 134.9229365128052507, 90.78414315763292564 ) ) ; -#29518 = CARTESIAN_POINT ( 'NONE', ( -37.85149864583512169, 117.8012976905560123, 89.71727313126454817 ) ) ; -#29519 = EDGE_CURVE ( 'NONE', #17526, #32940, #32034, .T. ) ; -#29520 = CARTESIAN_POINT ( 'NONE', ( -13.49852954173086417, 173.9514271942828145, 102.3866877817021503 ) ) ; -#29521 = CARTESIAN_POINT ( 'NONE', ( 2.731001113970879857, 190.9650871812991397, 106.4758074628583842 ) ) ; -#29522 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10780, #14250, #4422, #26724 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29523 = ORIENTED_EDGE ( 'NONE', *, *, #34490, .F. ) ; -#29524 = DIRECTION ( 'NONE', ( 0.9999998268367795706, 0.0001323825607408260941, -0.0005734119534792807889 ) ) ; -#29525 = ADVANCED_FACE ( 'NONE', ( #23238 ), #26930, .T. ) ; -#29526 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 132.9679238121742912, 90.36185680194377312 ) ) ; -#29527 = CARTESIAN_POINT ( 'NONE', ( 22.50176470574409393, 137.8371495728137575, 94.54045718443185820 ) ) ; -#29528 = LINE ( 'NONE', #1301, #31954 ) ; -#29529 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39695, #3091, #21108, #2715 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0006506470571234205429, 0.001755109801005554342 ), - .UNSPECIFIED. ) ; -#29530 = VERTEX_POINT ( 'NONE', #5023 ) ; -#29532 = EDGE_CURVE ( 'NONE', #38952, #6177, #17892, .T. ) ; -#29531 = CARTESIAN_POINT ( 'NONE', ( -23.65566532903961772, 115.6781942705080297, 87.78188130487900764 ) ) ; -#29533 = CIRCLE ( 'NONE', #6664, 2.499999999747368307 ) ; -#29534 = EDGE_CURVE ( 'NONE', #38443, #929, #28755, .T. ) ; -#29535 = CARTESIAN_POINT ( 'NONE', ( -44.46121984373956337, 189.2577286604973210, 103.8865186576782804 ) ) ; -#29536 = CARTESIAN_POINT ( 'NONE', ( -12.63088703835403237, 131.0198726340251199, 89.90887950976862442 ) ) ; -#29537 = EDGE_CURVE ( 'NONE', #27254, #35918, #1833, .T. ) ; -#29538 = CIRCLE ( 'NONE', #23679, 2.250000000020509816 ) ; -#29539 = EDGE_CURVE ( 'NONE', #31100, #36542, #8660, .T. ) ; -#29540 = AXIS2_PLACEMENT_3D ( 'NONE', #23070, #32670, #25951 ) ; -#29541 = VERTEX_POINT ( 'NONE', #7890 ) ; -#29542 = LINE ( 'NONE', #29345, #24758 ) ; -#29543 = CARTESIAN_POINT ( 'NONE', ( -35.30542352610000023, 113.0281073712999955, 90.42665468874000112 ) ) ; -#29544 = ORIENTED_EDGE ( 'NONE', *, *, #11777, .T. ) ; -#29545 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#29546 = ORIENTED_EDGE ( 'NONE', *, *, #2265, .F. ) ; -#29547 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#29548 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26421, #4724, #38865, #23349 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29549 = CARTESIAN_POINT ( 'NONE', ( 37.59860802954651149, 190.9741169367089242, 106.2840917320254732 ) ) ; -#29550 = DIRECTION ( 'NONE', ( -0.0006039748319380813194, -1.041532381956747772E-14, -0.9999998176071845934 ) ) ; -#29551 = EDGE_LOOP ( 'NONE', ( #38156, #15897, #17535, #18654 ) ) ; -#29552 = ORIENTED_EDGE ( 'NONE', *, *, #354, .T. ) ; -#29553 = CARTESIAN_POINT ( 'NONE', ( -37.31403596624686969, 185.5641699427571893, 107.6478458894942065 ) ) ; -#29554 = EDGE_LOOP ( 'NONE', ( #21743, #35702, #34060, #5879 ) ) ; -#29555 = ORIENTED_EDGE ( 'NONE', *, *, #35683, .T. ) ; -#29556 = ORIENTED_EDGE ( 'NONE', *, *, #6307, .T. ) ; -#29557 = DIRECTION ( 'NONE', ( 0.0006039748319481906373, 1.291365685536980129E-14, 0.9999998176071845934 ) ) ; -#29558 = EDGE_CURVE ( 'NONE', #32274, #30770, #18909, .T. ) ; -#29559 = PLANE ( 'NONE', #37854 ) ; -#29560 = ORIENTED_EDGE ( 'NONE', *, *, #3029, .T. ) ; -#29561 = EDGE_LOOP ( 'NONE', ( #19741, #28558, #2767, #10557 ) ) ; -#29562 = CARTESIAN_POINT ( 'NONE', ( -20.51880467302672173, 211.0905570380611493, 75.57084890002228406 ) ) ; -#29563 = CARTESIAN_POINT ( 'NONE', ( 38.06915235233999795, 118.5704106966999944, 87.56905173524000929 ) ) ; -#29565 = CIRCLE ( 'NONE', #5389, 3.500000000064008354 ) ; -#29564 = CARTESIAN_POINT ( 'NONE', ( 36.35611649474000018, 191.4884628071999941, 103.9475963394999951 ) ) ; -#29566 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#29567 = CARTESIAN_POINT ( 'NONE', ( 40.54675149425525404, 217.7719116180000185, 76.03401540786036605 ) ) ; -#29568 = EDGE_LOOP ( 'NONE', ( #26977, #37007, #8291, #14525, #250, #9534, #29921, #16652, #11308, #1718, #15499, #17218, #12068 ) ) ; -#29569 = AXIS2_PLACEMENT_3D ( 'NONE', #4115, #10687, #32162 ) ; -#29570 = DIRECTION ( 'NONE', ( 0.7933535325932939974, -0.5931614258681802143, -0.1369295263402624252 ) ) ; -#29571 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319364147923 ) ) ; -#29572 = ORIENTED_EDGE ( 'NONE', *, *, #28345, .F. ) ; -#29573 = EDGE_CURVE ( 'NONE', #7173, #15039, #39363, .T. ) ; -#29574 = CARTESIAN_POINT ( 'NONE', ( -6.038584421608743646, 134.3886675673123534, 93.63723382949044094 ) ) ; -#29575 = FACE_OUTER_BOUND ( 'NONE', #28149, .T. ) ; -#29576 = CARTESIAN_POINT ( 'NONE', ( 20.50028285398298777, 191.4126458000098978, 104.3447517631808097 ) ) ; -#29577 = FACE_OUTER_BOUND ( 'NONE', #39277, .T. ) ; -#29578 = ORIENTED_EDGE ( 'NONE', *, *, #11434, .T. ) ; -#29579 = DIRECTION ( 'NONE', ( -0.7933532970003751572, -0.5930762008556708098, -0.1372995488602872238 ) ) ; -#29580 = EDGE_CURVE ( 'NONE', #10930, #6111, #1331, .T. ) ; -#29581 = PLANE ( 'NONE', #37549 ) ; -#29582 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; -#29583 = ADVANCED_FACE ( 'NONE', ( #23440 ), #29380, .F. ) ; -#29584 = ORIENTED_EDGE ( 'NONE', *, *, #18358, .T. ) ; -#29585 = CARTESIAN_POINT ( 'NONE', ( -15.81543425933796065, 123.2981470472886656, 173.7034767455141662 ) ) ; -#29586 = VERTEX_POINT ( 'NONE', #23852 ) ; -#29587 = CARTESIAN_POINT ( 'NONE', ( -25.88994835531000049, 191.4519696899999985, 103.9944507113000043 ) ) ; -#29588 = FACE_OUTER_BOUND ( 'NONE', #22622, .T. ) ; -#29589 = CARTESIAN_POINT ( 'NONE', ( -19.99984748064912665, 127.7403057018771904, 89.15611954941233819 ) ) ; -#29590 = EDGE_CURVE ( 'NONE', #30729, #1120, #20805, .T. ) ; -#29591 = AXIS2_PLACEMENT_3D ( 'NONE', #16600, #20283, #19476 ) ; -#29592 = CARTESIAN_POINT ( 'NONE', ( 18.98780079260364317, 148.3242069017240681, 184.1917624428014904 ) ) ; -#29593 = ORIENTED_EDGE ( 'NONE', *, *, #13474, .T. ) ; -#29594 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041179293725575E-05, 0.0002331579774892958087 ) ) ; -#29595 = AXIS2_PLACEMENT_3D ( 'NONE', #36697, #30775, #25052 ) ; -#29596 = CARTESIAN_POINT ( 'NONE', ( 2.713260901989404950, 207.5618069885142347, 77.14516539463954814 ) ) ; -#29597 = VECTOR ( 'NONE', #11817, 1000.000000000000000 ) ; -#29598 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989907490, -0.1373964268091706076 ) ) ; -#29599 = CARTESIAN_POINT ( 'NONE', ( -3.740984982057359964, 137.3073912455885761, 91.56380801151034632 ) ) ; -#29600 = CARTESIAN_POINT ( 'NONE', ( -23.33152358916000324, 172.5096616001999905, 152.4718672074000381 ) ) ; -#29601 = DIRECTION ( 'NONE', ( 0.6087614115774889756, 0.7729348350621332298, 0.1788331191967985345 ) ) ; -#29602 = CARTESIAN_POINT ( 'NONE', ( -25.49601843126475487, 191.0768224934509192, 106.3476355555037571 ) ) ; -#29603 = FACE_OUTER_BOUND ( 'NONE', #5783, .T. ) ; -#29604 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22751, #7384, #10879, #38070 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29605 = CARTESIAN_POINT ( 'NONE', ( 20.07344744512846546, 117.3560877785396173, 90.25566097994942538 ) ) ; -#29606 = ORIENTED_EDGE ( 'NONE', *, *, #37957, .F. ) ; -#29607 = CARTESIAN_POINT ( 'NONE', ( -4.036264726651273449, 143.6503695269377943, 95.38542116098325607 ) ) ; -#29608 = CARTESIAN_POINT ( 'NONE', ( -15.49852919464750833, 127.1814504007330839, 91.59019381971197049 ) ) ; -#29609 = CARTESIAN_POINT ( 'NONE', ( 27.38172910116941949, 155.9316580491613706, 179.7942429727659146 ) ) ; -#29610 = VERTEX_POINT ( 'NONE', #1346 ) ; -#29611 = FACE_OUTER_BOUND ( 'NONE', #28670, .T. ) ; -#29612 = CARTESIAN_POINT ( 'NONE', ( 28.46384604140097352, 128.5894095540852504, 89.32293395223631194 ) ) ; -#29613 = EDGE_LOOP ( 'NONE', ( #14209, #33059, #26853, #5560 ) ) ; -#29614 = CARTESIAN_POINT ( 'NONE', ( 24.24964982527031054, 213.2746822943149425, 73.54367273967973517 ) ) ; -#29615 = ORIENTED_EDGE ( 'NONE', *, *, #15798, .F. ) ; -#29616 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#29617 = AXIS2_PLACEMENT_3D ( 'NONE', #1423, #16208, #13904 ) ; -#29618 = EDGE_CURVE ( 'NONE', #20941, #8704, #36095, .T. ) ; -#29619 = EDGE_CURVE ( 'NONE', #25425, #30682, #2783, .T. ) ; -#29620 = CARTESIAN_POINT ( 'NONE', ( 30.06891677554796161, 137.2464769733099104, 91.83375853871403649 ) ) ; -#29621 = ADVANCED_FACE ( 'NONE', ( #33031 ), #27137, .F. ) ; -#29622 = CARTESIAN_POINT ( 'NONE', ( -26.00142186005520983, 120.7678123865047297, 87.55007858260474052 ) ) ; -#29623 = AXIS2_PLACEMENT_3D ( 'NONE', #35761, #20441, #23734 ) ; -#29624 = EDGE_CURVE ( 'NONE', #127, #14712, #7613, .T. ) ; -#29625 = CARTESIAN_POINT ( 'NONE', ( -12.17913406779514496, 125.0348195299330030, 178.7841644720564602 ) ) ; -#29626 = DIRECTION ( 'NONE', ( -0.5989082241854605249, 0.8008175873178844384, 0.0003617255600147427190 ) ) ; -#29627 = ORIENTED_EDGE ( 'NONE', *, *, #25259, .F. ) ; -#29628 = ORIENTED_EDGE ( 'NONE', *, *, #28130, .F. ) ; -#29629 = CARTESIAN_POINT ( 'NONE', ( 17.25788389583062354, 152.5143575514096597, 182.5876268288973847 ) ) ; -#29630 = VECTOR ( 'NONE', #14231, 1000.000000000000000 ) ; -#29631 = CARTESIAN_POINT ( 'NONE', ( 29.40653848676928916, 157.5555674720174579, 201.9044920761300546 ) ) ; -#29632 = FACE_OUTER_BOUND ( 'NONE', #7391, .T. ) ; -#29633 = EDGE_CURVE ( 'NONE', #28118, #35790, #301, .T. ) ; -#29634 = VERTEX_POINT ( 'NONE', #28138 ) ; -#29635 = CARTESIAN_POINT ( 'NONE', ( -45.30255556275930928, 123.8777291761282129, 93.38906572069882372 ) ) ; -#29636 = ORIENTED_EDGE ( 'NONE', *, *, #11982, .F. ) ; -#29637 = ORIENTED_EDGE ( 'NONE', *, *, #20540, .F. ) ; -#29638 = CARTESIAN_POINT ( 'NONE', ( -20.00029466087617180, 160.7280592933503556, 96.77210435901376684 ) ) ; -#29639 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#29640 = CARTESIAN_POINT ( 'NONE', ( 16.16445611536306259, 152.0055496971487514, 180.9366119946107858 ) ) ; -#29641 = ADVANCED_FACE ( 'NONE', ( #25069 ), #27741, .T. ) ; -#29642 = CARTESIAN_POINT ( 'NONE', ( -21.21399079302519652, 183.3565551017309190, 102.5100844002234197 ) ) ; -#29643 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #5594, #18452 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29644 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#29645 = FACE_OUTER_BOUND ( 'NONE', #8912, .T. ) ; -#29646 = ADVANCED_FACE ( 'NONE', ( #15054 ), #5240, .F. ) ; -#29647 = CARTESIAN_POINT ( 'NONE', ( 4.035676231980001027, 136.7932109853310010, 93.79744583390555590 ) ) ; -#29648 = CARTESIAN_POINT ( 'NONE', ( 3.166265796306132696, 183.9718521032420711, 102.1242597203226836 ) ) ; -#29649 = AXIS2_PLACEMENT_3D ( 'NONE', #30705, #18595, #36824 ) ; -#29650 = AXIS2_PLACEMENT_3D ( 'NONE', #9166, #21642, #8972 ) ; -#29651 = ORIENTED_EDGE ( 'NONE', *, *, #27201, .F. ) ; -#29652 = FACE_OUTER_BOUND ( 'NONE', #22477, .T. ) ; -#29653 = CARTESIAN_POINT ( 'NONE', ( 37.65039792813953312, 188.7571058070083154, 106.2871081217155904 ) ) ; -#29654 = CARTESIAN_POINT ( 'NONE', ( 43.18716009838831127, 118.0176470502005941, 104.8323746835856838 ) ) ; -#29655 = LINE ( 'NONE', #7967, #26116 ) ; -#29656 = VECTOR ( 'NONE', #27868, 1000.000000000000114 ) ; -#29657 = CARTESIAN_POINT ( 'NONE', ( 28.46384604140102681, 184.1285027467652355, 102.1451462731230322 ) ) ; -#29658 = EDGE_LOOP ( 'NONE', ( #28376, #10738, #36033, #25667, #11481 ) ) ; -#29659 = VERTEX_POINT ( 'NONE', #30593 ) ; -#29660 = ORIENTED_EDGE ( 'NONE', *, *, #37288, .T. ) ; -#29661 = CARTESIAN_POINT ( 'NONE', ( -45.70040756943009086, 187.3695729804526309, 106.0171126674183739 ) ) ; -#29662 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001722, 123.6868832756584027, 91.30891139640375798 ) ) ; -#29663 = ORIENTED_EDGE ( 'NONE', *, *, #26544, .T. ) ; -#29664 = FACE_BOUND ( 'NONE', #8554, .T. ) ; -#29665 = LINE ( 'NONE', #30267, #23410 ) ; -#29666 = CARTESIAN_POINT ( 'NONE', ( 16.56169987041441161, 121.8384666780658563, 177.5555275195565059 ) ) ; -#29667 = VERTEX_POINT ( 'NONE', #6233 ) ; -#29668 = CARTESIAN_POINT ( 'NONE', ( -39.71442208983258837, 169.2236437704519574, 164.3192996581971101 ) ) ; -#29669 = EDGE_CURVE ( 'NONE', #11904, #25314, #2677, .T. ) ; -#29670 = EDGE_LOOP ( 'NONE', ( #22205, #3405, #22629, #17069 ) ) ; -#29672 = EDGE_CURVE ( 'NONE', #16662, #28384, #31528, .T. ) ; -#29671 = CARTESIAN_POINT ( 'NONE', ( 5.666470275070142115, 124.7419549499387159, 88.96160009709909389 ) ) ; -#29673 = FACE_OUTER_BOUND ( 'NONE', #13386, .T. ) ; -#29674 = EDGE_CURVE ( 'NONE', #34614, #25997, #9118, .T. ) ; -#29675 = CARTESIAN_POINT ( 'NONE', ( -14.78424366467106665, 136.1377412980438351, 93.65748546644259420 ) ) ; -#29676 = CARTESIAN_POINT ( 'NONE', ( 5.667647268251000625, 124.2920528385285053, 90.91033986944312062 ) ) ; -#29677 = CARTESIAN_POINT ( 'NONE', ( -20.49852807266789867, 190.9630690214611946, 106.3183227610936541 ) ) ; -#29678 = CARTESIAN_POINT ( 'NONE', ( -22.82602396999000405, 180.7017300104000128, 28.07991271570000080 ) ) ; -#29679 = ORIENTED_EDGE ( 'NONE', *, *, #3084, .F. ) ; -#29680 = ORIENTED_EDGE ( 'NONE', *, *, #10844, .F. ) ; -#29681 = CARTESIAN_POINT ( 'NONE', ( -1.679261953508219829, 188.9060477537240104, 103.2635922829680055 ) ) ; -#29682 = CARTESIAN_POINT ( 'NONE', ( 47.97518411862906618, 74.18940180350469404, 323.4777850570266082 ) ) ; -#29683 = AXIS2_PLACEMENT_3D ( 'NONE', #29438, #23493, #29237 ) ; -#29684 = CIRCLE ( 'NONE', #12062, 9.999999999999992895 ) ; -#29685 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#29686 = CARTESIAN_POINT ( 'NONE', ( 24.53348384866002974, 103.6131156702165157, 87.75296677365770392 ) ) ; -#29687 = EDGE_CURVE ( 'NONE', #32437, #8293, #21402, .T. ) ; -#29688 = AXIS2_PLACEMENT_3D ( 'NONE', #35343, #19812, #7349 ) ; -#29689 = EDGE_LOOP ( 'NONE', ( #33064, #7794, #22950, #5578 ) ) ; -#29690 = CARTESIAN_POINT ( 'NONE', ( 35.54748837207993262, 207.8686442303677211, 77.25557267504142089 ) ) ; -#29691 = CARTESIAN_POINT ( 'NONE', ( -25.93820646888479686, 211.8747973169839725, 76.07188810541477153 ) ) ; -#29692 = ORIENTED_EDGE ( 'NONE', *, *, #30053, .F. ) ; -#29693 = ORIENTED_EDGE ( 'NONE', *, *, #20847, .F. ) ; -#29694 = ADVANCED_FACE ( 'NONE', ( #33842 ), #34433, .T. ) ; -#29695 = ORIENTED_EDGE ( 'NONE', *, *, #21427, .F. ) ; -#29696 = ORIENTED_EDGE ( 'NONE', *, *, #5766, .F. ) ; -#29697 = CARTESIAN_POINT ( 'NONE', ( 3.064236136099508290, 190.8512031035150471, 106.7914583158460573 ) ) ; -#29698 = CARTESIAN_POINT ( 'NONE', ( -28.52494867685999935, 186.7521474632000036, 105.8641953606999948 ) ) ; -#29699 = CYLINDRICAL_SURFACE ( 'NONE', #23475, 2.250000000000011102 ) ; -#29700 = ADVANCED_FACE ( 'NONE', ( #18490 ), #7873, .F. ) ; -#29701 = VERTEX_POINT ( 'NONE', #40175 ) ; -#29702 = CARTESIAN_POINT ( 'NONE', ( -5.669730063980141566, 182.0627683792234848, 102.2020018026141486 ) ) ; -#29703 = EDGE_LOOP ( 'NONE', ( #39662, #31521, #8758, #28688 ) ) ; -#29704 = CARTESIAN_POINT ( 'NONE', ( 27.65426534970599803, 123.9758217684860000, 91.34070308701521412 ) ) ; -#29705 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9849, #18414, #220, #12700 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.004046376536929338630, 0.01004638012039786414 ), - .UNSPECIFIED. ) ; -#29706 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; -#29708 = CARTESIAN_POINT ( 'NONE', ( 39.42035703641028022, 114.3667165859880015, 151.6079144922757109 ) ) ; -#29707 = CARTESIAN_POINT ( 'NONE', ( 31.79365004200798595, 115.2698610323616890, 176.5535528959301530 ) ) ; -#29709 = AXIS2_PLACEMENT_3D ( 'NONE', #29992, #27354, #26732 ) ; -#29710 = ORIENTED_EDGE ( 'NONE', *, *, #1637, .F. ) ; -#29711 = FACE_OUTER_BOUND ( 'NONE', #29151, .T. ) ; -#29712 = ORIENTED_EDGE ( 'NONE', *, *, #32837, .F. ) ; -#29713 = AXIS2_PLACEMENT_3D ( 'NONE', #3578, #10151, #727 ) ; -#29714 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #36988, #12047, #15697, #11850 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.698067942813251685, 1.698162583727800268 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999992535913984, 0.9999999992535913984, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#29715 = ORIENTED_EDGE ( 'NONE', *, *, #21024, .T. ) ; -#29716 = CARTESIAN_POINT ( 'NONE', ( 9.153839578580999614, 181.3149981983999908, 104.3295970199999942 ) ) ; -#29717 = FACE_OUTER_BOUND ( 'NONE', #15612, .T. ) ; -#29718 = LINE ( 'NONE', #11925, #34388 ) ; -#29719 = CARTESIAN_POINT ( 'NONE', ( 20.50029382911849041, 160.6303866027595575, 97.23813965018092631 ) ) ; -#29720 = ORIENTED_EDGE ( 'NONE', *, *, #19800, .T. ) ; -#29721 = ORIENTED_EDGE ( 'NONE', *, *, #37717, .T. ) ; -#29722 = ORIENTED_EDGE ( 'NONE', *, *, #3846, .T. ) ; -#29723 = ADVANCED_FACE ( 'NONE', ( #21185 ), #11790, .F. ) ; -#29724 = DIRECTION ( 'NONE', ( 0.7933532411131102302, 0.5932638852154232811, 0.1364866195435443241 ) ) ; -#29725 = EDGE_CURVE ( 'NONE', #26291, #5530, #14952, .T. ) ; -#29726 = CARTESIAN_POINT ( 'NONE', ( 25.99912381358999980, 120.7769352125000069, 87.52069434298999795 ) ) ; -#29727 = ORIENTED_EDGE ( 'NONE', *, *, #4366, .T. ) ; -#29728 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#29729 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13821, #29783, #19940, #14240 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29730 = EDGE_CURVE ( 'NONE', #23378, #11983, #12375, .T. ) ; -#29731 = CARTESIAN_POINT ( 'NONE', ( 3.075283362363695705, 190.8485236763429782, 106.8022027959297446 ) ) ; -#29732 = ORIENTED_EDGE ( 'NONE', *, *, #7322, .F. ) ; -#29733 = LINE ( 'NONE', #1719, #13176 ) ; -#29734 = CIRCLE ( 'NONE', #27157, 2.749999999886777236 ) ; -#29735 = LINE ( 'NONE', #17437, #34297 ) ; -#29736 = AXIS2_PLACEMENT_3D ( 'NONE', #1508, #10728, #13592 ) ; -#29737 = CARTESIAN_POINT ( 'NONE', ( -41.34206624736095392, 120.4517752878489318, 90.39423589739264742 ) ) ; -#29738 = CARTESIAN_POINT ( 'NONE', ( 89.82620651468094763, 73.45072472530432606, 291.5042911573538618 ) ) ; -#29739 = ORIENTED_EDGE ( 'NONE', *, *, #29633, .F. ) ; -#29740 = AXIS2_PLACEMENT_3D ( 'NONE', #15810, #19074, #680 ) ; -#29741 = CARTESIAN_POINT ( 'NONE', ( 3.700917157829753279, 137.3198398098652433, 91.52446586985966803 ) ) ; -#29742 = CARTESIAN_POINT ( 'NONE', ( 19.73921667059327234, 149.8473492619755802, 180.1939462582248836 ) ) ; -#29743 = ADVANCED_FACE ( 'NONE', ( #10331 ), #30747, .F. ) ; -#29744 = ORIENTED_EDGE ( 'NONE', *, *, #15412, .T. ) ; -#29745 = CARTESIAN_POINT ( 'NONE', ( 33.24153725755936506, 80.65949370439929567, 289.2744314884981804 ) ) ; -#29747 = CARTESIAN_POINT ( 'NONE', ( -23.36173673102033632, 135.2906635749613997, 91.41449413045401684 ) ) ; -#29746 = DIRECTION ( 'NONE', ( 0.0005884949961231939744, -0.2249510543439056098, 0.9743698870671265722 ) ) ; -#29748 = EDGE_LOOP ( 'NONE', ( #31902, #32604, #38492, #26939 ) ) ; -#29749 = EDGE_LOOP ( 'NONE', ( #3139, #11081, #22305, #33578, #13076, #7083, #17566, #4868 ) ) ; -#29750 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825958228653913, 0.0005734119015069124312 ) ) ; -#29751 = EDGE_CURVE ( 'NONE', #30770, #15161, #24219, .T. ) ; -#29752 = CONICAL_SURFACE ( 'NONE', #14185, 2.503011032745954267, 0.7853981633441630139 ) ; -#29753 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921577410, 0.2249510932971590937 ) ) ; -#29754 = DIRECTION ( 'NONE', ( -0.1389764456053318442, -0.3254809698329895751, 0.9352794693798666126 ) ) ; -#29755 = CARTESIAN_POINT ( 'NONE', ( 16.29163119234463508, 147.3214335078221779, 179.2465642266784585 ) ) ; -#29756 = CARTESIAN_POINT ( 'NONE', ( -20.00029466087617180, 160.7280592933503556, 96.77210435901376684 ) ) ; -#29757 = VERTEX_POINT ( 'NONE', #26068 ) ; -#29758 = VERTEX_POINT ( 'NONE', #25268 ) ; -#29759 = FACE_OUTER_BOUND ( 'NONE', #12126, .T. ) ; -#29760 = ORIENTED_EDGE ( 'NONE', *, *, #2980, .F. ) ; -#29761 = CONICAL_SURFACE ( 'NONE', #3618, 7.999999999997401190, 0.7853981633973092791 ) ; -#29762 = VERTEX_POINT ( 'NONE', #22197 ) ; -#29763 = ORIENTED_EDGE ( 'NONE', *, *, #3889, .T. ) ; -#29764 = FACE_OUTER_BOUND ( 'NONE', #19079, .T. ) ; -#29765 = EDGE_CURVE ( 'NONE', #26024, #34687, #38128, .T. ) ; -#29766 = FACE_OUTER_BOUND ( 'NONE', #408, .T. ) ; -#29767 = CARTESIAN_POINT ( 'NONE', ( -2.851226056375999907, 209.7096532013000001, 76.06022722036999539 ) ) ; -#29768 = VECTOR ( 'NONE', #7723, 1000.000000000000000 ) ; -#29769 = ORIENTED_EDGE ( 'NONE', *, *, #31070, .T. ) ; -#29770 = CARTESIAN_POINT ( 'NONE', ( -5.669580876059291619, 126.6891943625079762, 89.41800251076365669 ) ) ; -#29771 = AXIS2_PLACEMENT_3D ( 'NONE', #35665, #17681, #33431 ) ; -#29773 = EDGE_CURVE ( 'NONE', #5743, #39814, #808, .T. ) ; -#29772 = CARTESIAN_POINT ( 'NONE', ( -18.98884698902605450, 125.5257020437638147, 175.6370175312684978 ) ) ; -#29774 = CARTESIAN_POINT ( 'NONE', ( -35.27986735535999685, 192.2622337511000126, 103.7793111048000014 ) ) ; -#29775 = CARTESIAN_POINT ( 'NONE', ( 37.74174011798000095, 190.9299051180000220, 103.5602631483999971 ) ) ; -#29776 = EDGE_CURVE ( 'NONE', #24276, #629, #19697, .T. ) ; -#29777 = FACE_OUTER_BOUND ( 'NONE', #25105, .T. ) ; -#29778 = ADVANCED_FACE ( 'NONE', ( #34630 ), #9928, .T. ) ; -#29779 = EDGE_LOOP ( 'NONE', ( #25039, #36710, #14073, #33132 ) ) ; -#29780 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -6.705467647123323749E-18, -0.0006039748319385910029 ) ) ; -#29781 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27187, #29427, #8147, #17533 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29782 = CARTESIAN_POINT ( 'NONE', ( 3.062029414146148376, 193.8169247290955752, 102.7010603508831252 ) ) ; -#29783 = CARTESIAN_POINT ( 'NONE', ( 19.99979080445197610, 118.3402007382070309, 87.25534304740426705 ) ) ; -#29784 = VERTEX_POINT ( 'NONE', #10529 ) ; -#29785 = CARTESIAN_POINT ( 'NONE', ( 0.5744871300181850771, 188.6022961663466617, 103.1948475296316587 ) ) ; -#29786 = CYLINDRICAL_SURFACE ( 'NONE', #33830, 2.000000000000014655 ) ; -#29787 = CARTESIAN_POINT ( 'NONE', ( 20.50053403162508658, 194.6757035433049055, 105.5170475396686811 ) ) ; -#29788 = CARTESIAN_POINT ( 'NONE', ( 19.06749373967776862, 124.7645831343390483, 178.7458660396097230 ) ) ; -#29789 = ORIENTED_EDGE ( 'NONE', *, *, #35365, .T. ) ; -#29790 = CARTESIAN_POINT ( 'NONE', ( -3.169881662145332513, 128.5839160399947332, 89.34077473205128683 ) ) ; -#29791 = CARTESIAN_POINT ( 'NONE', ( -0.03848092455648834120, -31.54510897440487938, 136.4474729010643159 ) ) ; -#29792 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971546806 ) ) ; -#29793 = ORIENTED_EDGE ( 'NONE', *, *, #14407, .T. ) ; -#29794 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#29795 = ORIENTED_EDGE ( 'NONE', *, *, #28394, .F. ) ; -#29796 = CARTESIAN_POINT ( 'NONE', ( 44.09418427031000220, 97.50014108196999985, 154.5673021613000060 ) ) ; -#29797 = DIRECTION ( 'NONE', ( 0.0005884949961244758266, -0.2249510546964108848, 0.9743698869857442268 ) ) ; -#29798 = CIRCLE ( 'NONE', #13479, 2.000000000000011546 ) ; -#29799 = CARTESIAN_POINT ( 'NONE', ( 25.92984058226999977, 191.3539199937000035, 103.9362281880000154 ) ) ; -#29800 = CARTESIAN_POINT ( 'NONE', ( 0.0003589606774950931402, 137.3532831589782575, 178.0585834213011083 ) ) ; -#29801 = CARTESIAN_POINT ( 'NONE', ( -26.71487369399972067, 123.8654304295266115, 90.83140486997200469 ) ) ; -#29802 = ORIENTED_EDGE ( 'NONE', *, *, #31677, .F. ) ; -#29803 = CONICAL_SURFACE ( 'NONE', #16065, 2.503171273173633082, 0.7853981633585357391 ) ; -#29804 = AXIS2_PLACEMENT_3D ( 'NONE', #38067, #28471, #10068 ) ; -#29805 = DIRECTION ( 'NONE', ( 0.6087614115774527823, 0.7729348350621608743, 0.1788331191968013101 ) ) ; -#29806 = CARTESIAN_POINT ( 'NONE', ( -26.00133086711789687, 118.1131156701862892, 87.28349311522542564 ) ) ; -#29807 = LINE ( 'NONE', #20171, #6806 ) ; -#29808 = ADVANCED_FACE ( 'NONE', ( #19101 ), #13746, .F. ) ; -#29809 = CARTESIAN_POINT ( 'NONE', ( 36.75673095752000563, 191.5503568576000362, 106.2292217633000035 ) ) ; -#29810 = CARTESIAN_POINT ( 'NONE', ( -15.99825050089035550, 126.1262029676268668, 91.86002998339648684 ) ) ; -#29811 = DIRECTION ( 'NONE', ( -0.9914447795421228449, -0.1272537940604324957, -0.02904687618137882441 ) ) ; -#29812 = CARTESIAN_POINT ( 'NONE', ( -38.51027449227886734, 118.9650952051504902, 87.72826332570426189 ) ) ; -#29813 = ORIENTED_EDGE ( 'NONE', *, *, #18123, .T. ) ; -#29814 = CARTESIAN_POINT ( 'NONE', ( 3.652177024044888309, 144.1910916277216472, 93.06085627818802664 ) ) ; -#29815 = EDGE_CURVE ( 'NONE', #36762, #24313, #31594, .T. ) ; -#29816 = PLANE ( 'NONE', #26846 ) ; -#29817 = AXIS2_PLACEMENT_3D ( 'NONE', #40442, #21859, #24943 ) ; -#29818 = VERTEX_POINT ( 'NONE', #31998 ) ; -#29819 = CARTESIAN_POINT ( 'NONE', ( 35.18456992010624163, 82.61260495581380781, 284.2600058304622053 ) ) ; -#29820 = AXIS2_PLACEMENT_3D ( 'NONE', #28457, #8705, #21163 ) ; -#29821 = EDGE_CURVE ( 'NONE', #37725, #29530, #30723, .T. ) ; -#29822 = VERTEX_POINT ( 'NONE', #3553 ) ; -#29823 = AXIS2_PLACEMENT_3D ( 'NONE', #39234, #36167, #1831 ) ; -#29824 = EDGE_CURVE ( 'NONE', #16409, #26164, #25878, .T. ) ; -#29825 = EDGE_CURVE ( 'NONE', #75, #5645, #18821, .T. ) ; -#29826 = DIRECTION ( 'NONE', ( 0.7855473026356903921, 0.6188014303620728018, -0.0004744508866335532646 ) ) ; -#29827 = VERTEX_POINT ( 'NONE', #3362 ) ; -#29828 = CARTESIAN_POINT ( 'NONE', ( 12.66848887859000072, 172.5096616001999905, 152.4718672074000381 ) ) ; -#29829 = AXIS2_PLACEMENT_3D ( 'NONE', #21949, #34393, #19249 ) ; -#29830 = CARTESIAN_POINT ( 'NONE', ( -14.78502443122015286, 175.7439026860171509, 101.4328847155116762 ) ) ; -#29831 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; -#29832 = AXIS2_PLACEMENT_3D ( 'NONE', #3813, #9369, #25521 ) ; -#29833 = CARTESIAN_POINT ( 'NONE', ( 3.668109984895000508, 129.8600137445999962, 92.71016498503001912 ) ) ; -#29834 = DIRECTION ( 'NONE', ( 0.0005884949961138158424, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#29835 = VERTEX_POINT ( 'NONE', #702 ) ; -#29836 = CARTESIAN_POINT ( 'NONE', ( -19.40198027091592081, 124.9165765156423760, 177.8474014814652264 ) ) ; -#29837 = CARTESIAN_POINT ( 'NONE', ( 12.63825826684001719, 182.0651920382574076, 102.1915037821187440 ) ) ; -#29838 = DIRECTION ( 'NONE', ( -0.0006039748319386693907, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#29839 = CARTESIAN_POINT ( 'NONE', ( 14.86381945347172895, 10.02083688679028661, 291.5495665607396063 ) ) ; -#29840 = EDGE_LOOP ( 'NONE', ( #16852, #26257, #16024, #36734 ) ) ; -#29841 = CYLINDRICAL_SURFACE ( 'NONE', #15317, 3.000000000000001332 ) ; -#29842 = CARTESIAN_POINT ( 'NONE', ( 23.00039803961572460, 115.6131156701970895, 89.75408929892711285 ) ) ; -#29843 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#29844 = CARTESIAN_POINT ( 'NONE', ( -30.11673734781999912, 185.5712258908999956, 102.7701824946000073 ) ) ; -#29845 = CARTESIAN_POINT ( 'NONE', ( 3.166377416628577190, 128.5876387387983186, 89.33781556475464924 ) ) ; -#29846 = CARTESIAN_POINT ( 'NONE', ( 24.95681190508087965, 159.0107988627873397, 180.5054692823873097 ) ) ; -#29847 = VECTOR ( 'NONE', #18882, 1000.000000000000000 ) ; -#29848 = CYLINDRICAL_SURFACE ( 'NONE', #39279, 2.000000000000014655 ) ; -#29849 = AXIS2_PLACEMENT_3D ( 'NONE', #38406, #34905, #13272 ) ; -#29850 = CARTESIAN_POINT ( 'NONE', ( 41.33957401875372284, 109.4463674645799500, 169.0514110310531919 ) ) ; -#29851 = VECTOR ( 'NONE', #39734, 1000.000000000000000 ) ; -#29852 = DIRECTION ( 'NONE', ( 0.0005884949961222661141, -0.2249510543439069699, 0.9743698870671262391 ) ) ; -#29853 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#29854 = CARTESIAN_POINT ( 'NONE', ( 38.63960300981000273, 118.6927473727999995, 89.80843469027999504 ) ) ; -#29855 = VERTEX_POINT ( 'NONE', #1102 ) ; -#29856 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#29857 = CARTESIAN_POINT ( 'NONE', ( -44.34810901449250764, 188.6498613026045064, 105.9697747766177258 ) ) ; -#29858 = ADVANCED_FACE ( 'NONE', ( #12989 ), #9180, .F. ) ; -#29859 = DIRECTION ( 'NONE', ( -0.6087614115774527823, 0.7730004600455669950, 0.1785492440296760075 ) ) ; -#29860 = CARTESIAN_POINT ( 'NONE', ( -23.00078011532012212, 115.1133396198523968, 87.28167119284988473 ) ) ; -#29861 = ADVANCED_FACE ( 'NONE', ( #18893 ), #666, .T. ) ; -#29862 = CARTESIAN_POINT ( 'NONE', ( -38.11718854129877343, 118.8155790694493561, 90.29079743518840928 ) ) ; -#29863 = ORIENTED_EDGE ( 'NONE', *, *, #22620, .F. ) ; -#29864 = ORIENTED_EDGE ( 'NONE', *, *, #32533, .T. ) ; -#29865 = ADVANCED_FACE ( 'NONE', ( #15834 ), #3961, .F. ) ; -#29866 = ORIENTED_EDGE ( 'NONE', *, *, #3288, .F. ) ; -#29867 = DIRECTION ( 'NONE', ( 0.0005884949961197505483, -0.2249510543439084409, 0.9743698870671257950 ) ) ; -#29868 = ADVANCED_FACE ( 'NONE', ( #13190 ), #22602, .T. ) ; -#29869 = CARTESIAN_POINT ( 'NONE', ( 18.76312242143445275, 124.3781087017529217, 178.6564478547896329 ) ) ; -#29870 = ORIENTED_EDGE ( 'NONE', *, *, #32532, .T. ) ; -#29871 = PLANE ( 'NONE', #29623 ) ; -#29872 = EDGE_CURVE ( 'NONE', #6999, #24745, #5674, .T. ) ; -#29873 = CARTESIAN_POINT ( 'NONE', ( 22.99138912207082441, 214.0899462551063266, 73.04463992848049259 ) ) ; -#29874 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927776843677, 0.0005734119022075554253 ) ) ; -#29875 = CARTESIAN_POINT ( 'NONE', ( -35.40078786029999947, 114.5765172629999995, 87.14831916340999385 ) ) ; -#29876 = EDGE_LOOP ( 'NONE', ( #32679, #18477, #22621, #4364, #8720, #18071, #31637, #14852 ) ) ; -#29877 = CARTESIAN_POINT ( 'NONE', ( -19.21669706698516222, 125.4524192385917729, 177.5306020213529337 ) ) ; -#29878 = AXIS2_PLACEMENT_3D ( 'NONE', #31140, #3109, #12510 ) ; -#29879 = VERTEX_POINT ( 'NONE', #35620 ) ; -#29880 = CARTESIAN_POINT ( 'NONE', ( -15.91977242095778422, 175.2217652188366799, 100.1156701095006269 ) ) ; -#29881 = CARTESIAN_POINT ( 'NONE', ( 5.335352931311528657, 188.3446295391898389, 103.1324850470098653 ) ) ; -#29882 = CARTESIAN_POINT ( 'NONE', ( 35.62841261737278131, 113.6507261092753680, 90.24626617076017965 ) ) ; -#29883 = AXIS2_PLACEMENT_3D ( 'NONE', #23563, #36441, #11710 ) ; -#29884 = CARTESIAN_POINT ( 'NONE', ( -12.63758390637487139, 181.3626882069777082, 104.3104898290644940 ) ) ; -#29885 = ORIENTED_EDGE ( 'NONE', *, *, #26446, .F. ) ; -#29886 = CARTESIAN_POINT ( 'NONE', ( -2.714642339597999943, 190.4530878461000043, 103.7849384411999978 ) ) ; -#29887 = CARTESIAN_POINT ( 'NONE', ( 0.6498165197299999862, 188.7395310661999872, 103.3612335093000212 ) ) ; -#29888 = CARTESIAN_POINT ( 'NONE', ( 28.33637912711604656, 124.4911283627940435, 91.45576088605962184 ) ) ; -#29889 = ORIENTED_EDGE ( 'NONE', *, *, #8520, .T. ) ; -#29890 = CARTESIAN_POINT ( 'NONE', ( 22.68744430041023818, 154.4094416041085367, 95.28744793558422543 ) ) ; -#29891 = EDGE_LOOP ( 'NONE', ( #891, #36003, #6822, #27933, #21237 ) ) ; -#29892 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12917, #6756, #3692, #34750 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.002118074346442883234 ), - .UNSPECIFIED. ) ; -#29893 = ORIENTED_EDGE ( 'NONE', *, *, #24062, .F. ) ; -#29894 = ORIENTED_EDGE ( 'NONE', *, *, #29064, .T. ) ; -#29895 = EDGE_LOOP ( 'NONE', ( #35633, #36471, #27885, #38308 ) ) ; -#29896 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#29897 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#29898 = EDGE_LOOP ( 'NONE', ( #10764, #23914, #19668, #7720 ) ) ; -#29899 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319377938974 ) ) ; -#29900 = ORIENTED_EDGE ( 'NONE', *, *, #37153, .F. ) ; -#29901 = EDGE_CURVE ( 'NONE', #14103, #7935, #20309, .T. ) ; -#29902 = CARTESIAN_POINT ( 'NONE', ( 26.12848274264259985, 121.2572229188339890, 90.71399663803099145 ) ) ; -#29903 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21819, #12597, #36741, #24703, #9146, #15477, #21629, #34260, #8753, #34070, #6067, #27766, #40404, #28357, #24496, #36956, #15663, #15864, #22027, #24906, #25099, #2994, #18924 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000002776, 0.1874999999999990841, 0.2187499999999993894, 0.2343749999999986955, 0.2499999999999979738, 0.3749999999999905076, 0.4374999999999874545, 0.4687499999999834022, 0.4999999999999792388, 0.6249999999999779066, 0.6874999999999801270, 0.7187499999999840128, 0.7499999999999880096, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29904 = EDGE_CURVE ( 'NONE', #28499, #410, #23524, .T. ) ; -#29905 = CONICAL_SURFACE ( 'NONE', #31210, 2.503003566838541527, 0.7853570728499476017 ) ; -#29906 = CARTESIAN_POINT ( 'NONE', ( 40.79660045530999923, 219.0860688542000219, 75.78386445958000195 ) ) ; -#29907 = EDGE_CURVE ( 'NONE', #12388, #3510, #1499, .T. ) ; -#29908 = CONICAL_SURFACE ( 'NONE', #1823, 8.000001721232548491, 0.7853981633972927368 ) ; -#29910 = CARTESIAN_POINT ( 'NONE', ( 40.22341809199669882, 84.46459415942207727, 281.4571872699962682 ) ) ; -#29909 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319391912172 ) ) ; -#29911 = ORIENTED_EDGE ( 'NONE', *, *, #11982, .T. ) ; -#29912 = DIRECTION ( 'NONE', ( -0.0005884949961246437695, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#29913 = ORIENTED_EDGE ( 'NONE', *, *, #23908, .F. ) ; -#29914 = EDGE_CURVE ( 'NONE', #18505, #16566, #35259, .T. ) ; -#29915 = VERTEX_POINT ( 'NONE', #14599 ) ; -#29916 = CARTESIAN_POINT ( 'NONE', ( 43.65682646703121605, 93.15907832361875762, 291.5321763059946534 ) ) ; -#29917 = EDGE_CURVE ( 'NONE', #19724, #30529, #26667, .T. ) ; -#29918 = CARTESIAN_POINT ( 'NONE', ( -12.63767699504066577, 177.1899956602251507, 101.0812418388079834 ) ) ; -#29919 = CARTESIAN_POINT ( 'NONE', ( -28.25571780481785567, 186.4543157461568228, 105.2821206686522686 ) ) ; -#29920 = CARTESIAN_POINT ( 'NONE', ( 36.22641505778000237, 191.6139406055999928, 104.0139690017000191 ) ) ; -#29921 = ORIENTED_EDGE ( 'NONE', *, *, #27905, .F. ) ; -#29922 = ORIENTED_EDGE ( 'NONE', *, *, #2812, .T. ) ; -#29923 = ORIENTED_EDGE ( 'NONE', *, *, #16229, .F. ) ; -#29924 = CARTESIAN_POINT ( 'NONE', ( 20.16839244953768073, 190.8891819486728139, 106.6188877771056127 ) ) ; -#29925 = CARTESIAN_POINT ( 'NONE', ( 25.74260163869999829, 121.8290458033000050, 88.10601801296999724 ) ) ; -#29926 = ORIENTED_EDGE ( 'NONE', *, *, #13335, .T. ) ; -#29927 = EDGE_LOOP ( 'NONE', ( #3044, #20356, #6768, #30104 ) ) ; -#29928 = CARTESIAN_POINT ( 'NONE', ( -35.93453016941000300, 192.5815800178999950, 106.4047550415999979 ) ) ; -#29929 = AXIS2_PLACEMENT_3D ( 'NONE', #19744, #155, #28185 ) ; -#29930 = EDGE_LOOP ( 'NONE', ( #8497, #20652 ) ) ; -#29931 = CARTESIAN_POINT ( 'NONE', ( -22.78251873534900440, 164.0719396662763074, 100.1114352475750309 ) ) ; -#29932 = CARTESIAN_POINT ( 'NONE', ( 19.99999382154498662, 120.3902235794415816, 87.43511282661482653 ) ) ; -#29933 = CARTESIAN_POINT ( 'NONE', ( 15.83342446817142068, 126.7663492669746717, 89.08073393852320976 ) ) ; -#29934 = FACE_OUTER_BOUND ( 'NONE', #12339, .T. ) ; -#29935 = DIRECTION ( 'NONE', ( 0.6337575784460532935, -0.7735316317038959388, -0.0003827736967368305454 ) ) ; -#29936 = ORIENTED_EDGE ( 'NONE', *, *, #36315, .F. ) ; -#29937 = CYLINDRICAL_SURFACE ( 'NONE', #4907, 4.999999999999990230 ) ; -#29938 = CARTESIAN_POINT ( 'NONE', ( 30.18297412318279171, 127.2294757820334752, 89.35003157987318900 ) ) ; -#29939 = ORIENTED_EDGE ( 'NONE', *, *, #12694, .T. ) ; -#29940 = CARTESIAN_POINT ( 'NONE', ( 32.65325603764978979, 78.97532739632895016, 290.6005298003525468 ) ) ; -#29941 = EDGE_CURVE ( 'NONE', #14788, #28866, #16827, .T. ) ; -#29943 = ADVANCED_FACE ( 'NONE', ( #14391 ), #7493, .F. ) ; -#29942 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10339, #22410, #9732, #22211 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29944 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #24246, #28260, #18070, #12920 ), - .UNSPECIFIED., .F., .F. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.583410654013528429, 4.583439918374093480 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999286330876, 0.9999999999286330876, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#29945 = CARTESIAN_POINT ( 'NONE', ( -44.12605770667196481, 189.0087315190842503, 103.3156785504129118 ) ) ; -#29946 = ORIENTED_EDGE ( 'NONE', *, *, #36265, .F. ) ; -#29947 = AXIS2_PLACEMENT_3D ( 'NONE', #3054, #15148, #24360 ) ; -#29948 = ORIENTED_EDGE ( 'NONE', *, *, #10579, .T. ) ; -#29949 = CARTESIAN_POINT ( 'NONE', ( 76.10777906861902409, 155.6981007157128829, 98.63160672925188521 ) ) ; -#29950 = EDGE_LOOP ( 'NONE', ( #8288, #22283, #20543, #28828 ) ) ; -#29951 = CARTESIAN_POINT ( 'NONE', ( 2.333463758010000166, 209.5293504425999913, 75.42172714685999324 ) ) ; -#29952 = AXIS2_PLACEMENT_3D ( 'NONE', #9573, #17941, #14901 ) ; -#29953 = CARTESIAN_POINT ( 'NONE', ( 14.93318671104674777, 124.4798289405424612, 171.6828735292820625 ) ) ; -#29954 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#29955 = CONICAL_SURFACE ( 'NONE', #5126, 2.502999999931229791, 0.7853981633952228369 ) ; -#29956 = CARTESIAN_POINT ( 'NONE', ( 12.63986376608903406, 174.6822240277132039, 103.0527707682702783 ) ) ; -#29957 = VERTEX_POINT ( 'NONE', #2737 ) ; -#29958 = VERTEX_POINT ( 'NONE', #27693 ) ; -#29959 = CARTESIAN_POINT ( 'NONE', ( 13.76428958128341584, 125.4663756326080346, 174.1938355030713694 ) ) ; -#29960 = VERTEX_POINT ( 'NONE', #33991 ) ; -#29961 = EDGE_LOOP ( 'NONE', ( #16191, #9065, #15135, #4951 ) ) ; -#29962 = CARTESIAN_POINT ( 'NONE', ( 25.50879993301148829, 196.1181868571946438, 103.6643310760977670 ) ) ; -#29963 = CARTESIAN_POINT ( 'NONE', ( 36.03687122555673739, 218.5902260770998282, 61.03673652647002257 ) ) ; -#29964 = ORIENTED_EDGE ( 'NONE', *, *, #14580, .F. ) ; -#29965 = CARTESIAN_POINT ( 'NONE', ( 31.79421363390792266, 220.4002260770999726, 73.53930126515697907 ) ) ; -#29966 = CARTESIAN_POINT ( 'NONE', ( -35.89395010493000626, 191.7067202632000260, 104.0335547037000055 ) ) ; -#29967 = CARTESIAN_POINT ( 'NONE', ( 36.86023212634999879, 191.7079963920000125, 104.5047224584999981 ) ) ; -#29968 = ORIENTED_EDGE ( 'NONE', *, *, #19591, .T. ) ; -#29969 = CARTESIAN_POINT ( 'NONE', ( -25.66877846115464123, 120.6335317947693540, 87.84733053400728409 ) ) ; -#29970 = ADVANCED_FACE ( 'NONE', ( #22196 ), #6624, .T. ) ; -#29971 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#29972 = ORIENTED_EDGE ( 'NONE', *, *, #21342, .T. ) ; -#29973 = CARTESIAN_POINT ( 'NONE', ( -20.49852833730357560, 151.4051363130266168, 97.18569325580692464 ) ) ; -#29974 = CARTESIAN_POINT ( 'NONE', ( -23.35938884972302532, 176.8157736797523683, 103.1595155122197980 ) ) ; -#29975 = ORIENTED_EDGE ( 'NONE', *, *, #9588, .T. ) ; -#29976 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37643, #40101, #34166, #12913 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#29977 = CARTESIAN_POINT ( 'NONE', ( 0.6690589101043880049, 188.6123594706415076, 103.1971137079293470 ) ) ; -#29978 = CARTESIAN_POINT ( 'NONE', ( 23.65359131764347822, 115.6781963768868593, 87.75330774182334892 ) ) ; -#29979 = DIRECTION ( 'NONE', ( -0.0005884949961259158639, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#29980 = CARTESIAN_POINT ( 'NONE', ( 35.55533445286192062, 109.6131156991000069, 90.24631030788441421 ) ) ; -#29981 = ORIENTED_EDGE ( 'NONE', *, *, #5244, .F. ) ; -#29982 = CARTESIAN_POINT ( 'NONE', ( -35.45484958738647663, 205.1071295951935838, 76.12626288493709126 ) ) ; -#29983 = AXIS2_PLACEMENT_3D ( 'NONE', #10221, #22691, #16515 ) ; -#29984 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319387908213 ) ) ; -#29985 = LINE ( 'NONE', #14046, #33233 ) ; -#29986 = AXIS2_PLACEMENT_3D ( 'NONE', #32450, #29386, #29792 ) ; -#29987 = ORIENTED_EDGE ( 'NONE', *, *, #24435, .T. ) ; -#29988 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#29989 = EDGE_LOOP ( 'NONE', ( #16583, #2701, #12141, #10872 ) ) ; -#29990 = CONICAL_SURFACE ( 'NONE', #6472, 2.502994266666827894, 0.7853981634117951360 ) ; -#29991 = CARTESIAN_POINT ( 'NONE', ( 8.330750845879437705, 150.6663524668997809, 97.16877009602183080 ) ) ; -#29992 = CARTESIAN_POINT ( 'NONE', ( 22.78222448783905918, 163.9654960800027652, 100.5724929892154620 ) ) ; -#29993 = AXIS2_PLACEMENT_3D ( 'NONE', #9479, #31558, #6997 ) ; -#29994 = CARTESIAN_POINT ( 'NONE', ( 35.42095112463999840, 112.3598550145000132, 90.38140071967001177 ) ) ; -#29995 = CARTESIAN_POINT ( 'NONE', ( 6.030013099936853749, 134.9861680000014701, 90.90411879691632180 ) ) ; -#29996 = ORIENTED_EDGE ( 'NONE', *, *, #30096, .F. ) ; -#29997 = EDGE_CURVE ( 'NONE', #25850, #4106, #6583, .T. ) ; -#29998 = EDGE_CURVE ( 'NONE', #12730, #8754, #2705, .T. ) ; -#29999 = CARTESIAN_POINT ( 'NONE', ( -6.037582702418865743, 135.2929569925057365, 91.40456025213514124 ) ) ; -#30000 = DIRECTION ( 'NONE', ( 0.0006039748319391906751, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#30001 = CARTESIAN_POINT ( 'NONE', ( 20.00182604067493131, 190.8514159882993511, 106.7812686061269716 ) ) ; -#30002 = EDGE_CURVE ( 'NONE', #19471, #17466, #4630, .T. ) ; -#30003 = DIRECTION ( 'NONE', ( -0.0005884949961243157984, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#30004 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; -#30005 = CARTESIAN_POINT ( 'NONE', ( 40.67183997101093951, 184.9339790117970210, 102.3237318327851710 ) ) ; -#30006 = CARTESIAN_POINT ( 'NONE', ( -38.36470799546496835, 118.8248470719471612, 87.72050125755728800 ) ) ; -#30007 = ORIENTED_EDGE ( 'NONE', *, *, #28288, .F. ) ; -#30009 = AXIS2_PLACEMENT_3D ( 'NONE', #36091, #8093, #7681 ) ; -#30008 = DIRECTION ( 'NONE', ( 1.294744789823872573E-10, -0.9743700558212509133, -0.2249510931711427575 ) ) ; -#30010 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385906776 ) ) ; -#30011 = VECTOR ( 'NONE', #33390, 1000.000000000000114 ) ; -#30012 = ORIENTED_EDGE ( 'NONE', *, *, #16731, .F. ) ; -#30013 = CARTESIAN_POINT ( 'NONE', ( 14.55485738440738963, 181.8858882541513537, 104.7147121319332825 ) ) ; -#30014 = CIRCLE ( 'NONE', #4542, 2.000000002172721558 ) ; -#30015 = VECTOR ( 'NONE', #27860, 1000.000000000000227 ) ; -#30016 = EDGE_LOOP ( 'NONE', ( #38664, #17852, #36659, #32057 ) ) ; -#30017 = EDGE_CURVE ( 'NONE', #35255, #572, #35619, .T. ) ; -#30018 = CARTESIAN_POINT ( 'NONE', ( 25.84397327880365935, 191.4423330798549898, 106.7096297072122013 ) ) ; -#30019 = FACE_OUTER_BOUND ( 'NONE', #26373, .T. ) ; -#30020 = CARTESIAN_POINT ( 'NONE', ( -18.61117187107760884, 125.1353300184083253, 178.8218272577300354 ) ) ; -#30021 = ORIENTED_EDGE ( 'NONE', *, *, #24214, .T. ) ; -#30022 = CARTESIAN_POINT ( 'NONE', ( 36.06506570308751947, 192.5918829023582930, 106.3581458348548807 ) ) ; -#30023 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927766006264, 0.0005734119022010027242 ) ) ; -#30024 = CARTESIAN_POINT ( 'NONE', ( -13.46635853387000026, 147.8787825985000097, 152.4718672074000381 ) ) ; -#30025 = CARTESIAN_POINT ( 'NONE', ( -12.63516111085457716, 130.0934455189878634, 92.42935276955371648 ) ) ; -#30026 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #24265, #18287, #12562, #2775 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.800309848272725333, 3.800390736461993324 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999994547583704, 0.9999999994547583704, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#30027 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#30028 = FACE_OUTER_BOUND ( 'NONE', #34883, .T. ) ; -#30029 = ORIENTED_EDGE ( 'NONE', *, *, #20732, .T. ) ; -#30030 = EDGE_LOOP ( 'NONE', ( #33416, #19044, #40348, #23684 ) ) ; -#30031 = CARTESIAN_POINT ( 'NONE', ( 30.05352354161590966, 104.1131156705860690, 87.24963271661329145 ) ) ; -#30032 = CARTESIAN_POINT ( 'NONE', ( -13.66810824591000006, 176.6274814210999864, 103.5177582616999956 ) ) ; -#30033 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#30034 = ADVANCED_FACE ( 'NONE', ( #897 ), #22284, .T. ) ; -#30035 = CARTESIAN_POINT ( 'NONE', ( -10.03773492422901370, 168.4955924422791043, 98.55925788090297601 ) ) ; -#30036 = ORIENTED_EDGE ( 'NONE', *, *, #10347, .F. ) ; -#30037 = CARTESIAN_POINT ( 'NONE', ( -23.85050479439979654, 156.8744767616792615, 186.1578534662776292 ) ) ; -#30038 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23350, #30090, #5535, #32740, #4928, #2080, #2487, #1666, #14555, #35779, #39469, #4725, #14761, #26827, #36418, #8424, #17385, #27245, #20882, #14346, #39676, #8624, #29888, #17181 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 4.334733740157455816E-05, 8.669467480314911633E-05, 0.0001733893496063294577, 0.0003467786992127401763, 0.0006935573984255927844, 0.001387114796851327816, 0.002774229593702839947, 0.003467786992128592868, 0.004161344390554346656, 0.004854901788980100011, 0.005548459187405853366 ), - .UNSPECIFIED. ) ; -#30039 = CARTESIAN_POINT ( 'NONE', ( -41.20667332552599760, 120.5418273977710868, 90.58599501078802518 ) ) ; -#30040 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; -#30041 = CARTESIAN_POINT ( 'NONE', ( -42.48820456521394817, 182.6260049196332602, 137.7617708393588885 ) ) ; -#30042 = LINE ( 'NONE', #20629, #19014 ) ; -#30043 = AXIS2_PLACEMENT_3D ( 'NONE', #4416, #37971, #35075 ) ; -#30044 = EDGE_CURVE ( 'NONE', #31534, #33783, #19349, .T. ) ; -#30045 = AXIS2_PLACEMENT_3D ( 'NONE', #24810, #39915, #46 ) ; -#30046 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#30047 = CIRCLE ( 'NONE', #28731, 2.000000000000011546 ) ; -#30048 = CARTESIAN_POINT ( 'NONE', ( -28.46560972492484609, 127.9063310723858535, 92.28167137666822839 ) ) ; -#30049 = AXIS2_PLACEMENT_3D ( 'NONE', #27198, #30040, #29843 ) ; -#30050 = EDGE_CURVE ( 'NONE', #34375, #1422, #5271, .T. ) ; -#30051 = EDGE_CURVE ( 'NONE', #35141, #27835, #12755, .T. ) ; -#30052 = CARTESIAN_POINT ( 'NONE', ( -21.25263179906144728, 151.3572514703366778, 27.73455668113730965 ) ) ; -#30053 = EDGE_CURVE ( 'NONE', #24492, #37430, #12059, .T. ) ; -#30054 = LINE ( 'NONE', #33704, #26559 ) ; -#30055 = EDGE_CURVE ( 'NONE', #34777, #650, #24743, .T. ) ; -#30056 = CARTESIAN_POINT ( 'NONE', ( 38.17628665576000913, 118.2980305818999938, 87.79568836177999458 ) ) ; -#30057 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825965039104825, 0.0005734119013517169133 ) ) ; -#30058 = CARTESIAN_POINT ( 'NONE', ( 38.94288640132000268, 118.9460699731999966, 89.82301361787001781 ) ) ; -#30059 = VERTEX_POINT ( 'NONE', #10578 ) ; -#30060 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#30061 = CARTESIAN_POINT ( 'NONE', ( -23.36147737338983177, 177.1885760160717211, 101.0873909945826341 ) ) ; -#30062 = FACE_OUTER_BOUND ( 'NONE', #30087, .T. ) ; -#30063 = CARTESIAN_POINT ( 'NONE', ( 35.67174478196999843, 112.8596397694000188, 87.36414130154000190 ) ) ; -#30064 = CARTESIAN_POINT ( 'NONE', ( -5.509042010817696955, 134.9596946440107956, 180.7415265967344169 ) ) ; -#30065 = ORIENTED_EDGE ( 'NONE', *, *, #36022, .T. ) ; -#30066 = ORIENTED_EDGE ( 'NONE', *, *, #28452, .F. ) ; -#30067 = CARTESIAN_POINT ( 'NONE', ( -2.915586116141384743, 190.7752836099844274, 103.6986292183714227 ) ) ; -#30068 = ORIENTED_EDGE ( 'NONE', *, *, #4798, .T. ) ; -#30069 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825908426682013, 0.0005734119026547008927 ) ) ; -#30070 = DIRECTION ( 'NONE', ( -1.001359783477163956E-17, 0.9743043966640315690, 0.2252353050503800580 ) ) ; -#30071 = ORIENTED_EDGE ( 'NONE', *, *, #15141, .T. ) ; -#30072 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#30073 = AXIS2_PLACEMENT_3D ( 'NONE', #29931, #7636, #17023 ) ; -#30074 = ADVANCED_FACE ( 'NONE', ( #33226 ), #35887, .F. ) ; -#30075 = AXIS2_PLACEMENT_3D ( 'NONE', #3597, #16079, #28568 ) ; -#30076 = CARTESIAN_POINT ( 'NONE', ( -39.44282146501851116, 161.9553710365894119, 194.9383616928014646 ) ) ; -#30077 = CARTESIAN_POINT ( 'NONE', ( -13.49688601046059588, 187.5020877889633653, 105.8020847638134256 ) ) ; -#30078 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989907490, -0.1373964268091705798 ) ) ; -#30079 = ORIENTED_EDGE ( 'NONE', *, *, #19367, .T. ) ; -#30080 = DIRECTION ( 'NONE', ( 0.0006039748319375912600, 1.387265140328410610E-14, 0.9999998176071847045 ) ) ; -#30081 = AXIS2_PLACEMENT_3D ( 'NONE', #21539, #40112, #5368 ) ; -#30082 = ORIENTED_EDGE ( 'NONE', *, *, #19769, .F. ) ; -#30083 = FACE_OUTER_BOUND ( 'NONE', #2397, .T. ) ; -#30084 = LINE ( 'NONE', #5113, #26748 ) ; -#30085 = CARTESIAN_POINT ( 'NONE', ( -19.37104535314951903, 147.8320913697636172, 183.5553890942303497 ) ) ; -#30086 = ORIENTED_EDGE ( 'NONE', *, *, #21529, .F. ) ; -#30087 = EDGE_LOOP ( 'NONE', ( #32779, #35461, #4190, #13418 ) ) ; -#30088 = CARTESIAN_POINT ( 'NONE', ( -26.08849602176999838, 190.2333037056999956, 103.7122373673999931 ) ) ; -#30089 = CARTESIAN_POINT ( 'NONE', ( 0.5732490465848030237, 188.9966601621639768, 103.7032449934750105 ) ) ; -#30090 = CARTESIAN_POINT ( 'NONE', ( 25.99312043943056594, 120.1143596994206177, 90.44671930700148721 ) ) ; -#30091 = ADVANCED_FACE ( 'NONE', ( #1765 ), #1154, .T. ) ; -#30092 = ORIENTED_EDGE ( 'NONE', *, *, #40057, .F. ) ; -#30093 = LINE ( 'NONE', #26628, #881 ) ; -#30094 = EDGE_LOOP ( 'NONE', ( #27462, #36648, #17882, #1244 ) ) ; -#30095 = EDGE_CURVE ( 'NONE', #37167, #7200, #39891, .T. ) ; -#30096 = EDGE_CURVE ( 'NONE', #16955, #25532, #30597, .T. ) ; -#30097 = EDGE_LOOP ( 'NONE', ( #1844, #18661, #30187, #14251, #10419, #21270, #19758, #25211, #33512, #23885 ) ) ; -#30098 = VERTEX_POINT ( 'NONE', #29980 ) ; -#30099 = CARTESIAN_POINT ( 'NONE', ( 3.061557430615667652, 191.9759150222000130, 101.9195982364086888 ) ) ; -#30100 = LINE ( 'NONE', #14565, #36527 ) ; -#30101 = EDGE_CURVE ( 'NONE', #3073, #31048, #31034, .T. ) ; -#30102 = CARTESIAN_POINT ( 'NONE', ( -25.99154556069859012, 196.5784392978119968, 103.8908015619487060 ) ) ; -#30103 = AXIS2_PLACEMENT_3D ( 'NONE', #20225, #6956, #20027 ) ; -#30104 = ORIENTED_EDGE ( 'NONE', *, *, #40206, .T. ) ; -#30105 = CARTESIAN_POINT ( 'NONE', ( -20.49842948179519553, 118.5814959395139283, 89.78014270750621506 ) ) ; -#30106 = ORIENTED_EDGE ( 'NONE', *, *, #17551, .F. ) ; -#30107 = VECTOR ( 'NONE', #22431, 1000.000000000000000 ) ; -#30108 = CARTESIAN_POINT ( 'NONE', ( 26.06569843707619683, 120.9038867973739855, 90.63414402004558212 ) ) ; -#30109 = AXIS2_PLACEMENT_3D ( 'NONE', #22745, #31946, #9870 ) ; -#30110 = FACE_OUTER_BOUND ( 'NONE', #30789, .T. ) ; -#30112 = DIRECTION ( 'NONE', ( 0.0004161288024522937249, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#30111 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#30113 = ORIENTED_EDGE ( 'NONE', *, *, #14905, .T. ) ; -#30114 = ORIENTED_EDGE ( 'NONE', *, *, #18481, .F. ) ; -#30115 = ORIENTED_EDGE ( 'NONE', *, *, #15055, .T. ) ; -#30116 = DIRECTION ( 'NONE', ( -0.0006039748319382907873, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#30117 = CARTESIAN_POINT ( 'NONE', ( 30.06995708077950269, 134.8478347379656270, 93.33259620158477787 ) ) ; -#30118 = LINE ( 'NONE', #18229, #21563 ) ; -#30119 = CARTESIAN_POINT ( 'NONE', ( 36.42656940490999773, 191.8204547590999880, 104.3694610780000005 ) ) ; -#30120 = ORIENTED_EDGE ( 'NONE', *, *, #24629, .F. ) ; -#30121 = ORIENTED_EDGE ( 'NONE', *, *, #27633, .F. ) ; -#30122 = LINE ( 'NONE', #1708, #20727 ) ; -#30123 = AXIS2_PLACEMENT_3D ( 'NONE', #24101, #2820, #8561 ) ; -#30124 = CARTESIAN_POINT ( 'NONE', ( 27.86721609982999937, 124.8039940644000012, 88.44928661843999862 ) ) ; -#30125 = AXIS2_PLACEMENT_3D ( 'NONE', #35231, #7234, #17025 ) ; -#30126 = ORIENTED_EDGE ( 'NONE', *, *, #21053, .F. ) ; -#30127 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#30128 = CIRCLE ( 'NONE', #32719, 59.40509898897001051 ) ; -#30129 = ADVANCED_FACE ( 'NONE', ( #29577 ), #23441, .T. ) ; -#30130 = EDGE_LOOP ( 'NONE', ( #941, #9903, #29889, #38485 ) ) ; -#30131 = ADVANCED_FACE ( 'NONE', ( #17280 ), #36096, .F. ) ; -#30132 = CARTESIAN_POINT ( 'NONE', ( 36.04562886062198857, 218.5902260770999987, 75.53673388173362468 ) ) ; -#30133 = ORIENTED_EDGE ( 'NONE', *, *, #12967, .T. ) ; -#30134 = CARTESIAN_POINT ( 'NONE', ( -16.26709548105753811, 147.3187592549000158, 179.2581322910629069 ) ) ; -#30135 = CARTESIAN_POINT ( 'NONE', ( -46.08467315290042876, 125.4204749030748758, 88.80740376148220605 ) ) ; -#30136 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825920524828662, 0.0005734119023723335557 ) ) ; -#30137 = DIRECTION ( 'NONE', ( 0.0005559617645653921157, -0.3907311284892677761, 0.9205046855589706922 ) ) ; -#30138 = EDGE_CURVE ( 'NONE', #31409, #37905, #18315, .T. ) ; -#30139 = ORIENTED_EDGE ( 'NONE', *, *, #30327, .F. ) ; -#30140 = CARTESIAN_POINT ( 'NONE', ( 25.99063927089856563, 207.3563238408722782, 73.60442922372433827 ) ) ; -#30141 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23666, #26951, #4836, #21005 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30142 = CARTESIAN_POINT ( 'NONE', ( -22.63609548443118413, 177.7106153948775500, 100.6943230432614342 ) ) ; -#30143 = CARTESIAN_POINT ( 'NONE', ( 25.50924745143719718, 191.9344736266071436, 104.4056993596765039 ) ) ; -#30144 = EDGE_CURVE ( 'NONE', #36696, #16013, #7225, .T. ) ; -#30145 = VERTEX_POINT ( 'NONE', #26121 ) ; -#30146 = LINE ( 'NONE', #27098, #3180 ) ; -#30148 = FACE_OUTER_BOUND ( 'NONE', #5966, .T. ) ; -#30147 = CARTESIAN_POINT ( 'NONE', ( 14.27573290317919330, 135.8449083118874228, 91.00656752237129865 ) ) ; -#30149 = ORIENTED_EDGE ( 'NONE', *, *, #35590, .T. ) ; -#30150 = CIRCLE ( 'NONE', #27590, 2.499999999556782981 ) ; -#30151 = ADVANCED_FACE ( 'NONE', ( #11364 ), #35933, .F. ) ; -#30152 = ORIENTED_EDGE ( 'NONE', *, *, #13550, .T. ) ; -#30153 = AXIS2_PLACEMENT_3D ( 'NONE', #38144, #26843, #33556 ) ; -#30154 = CARTESIAN_POINT ( 'NONE', ( 38.65087382282330708, 118.5394481973313816, 89.66228983010682896 ) ) ; -#30155 = VERTEX_POINT ( 'NONE', #32640 ) ; -#30156 = CARTESIAN_POINT ( 'NONE', ( 15.99974815555098218, 138.5019114137554936, 91.61902897505088106 ) ) ; -#30157 = DIRECTION ( 'NONE', ( -0.0004161288024658205565, 0.8480480897788525985, -0.5299191110530538928 ) ) ; -#30158 = CARTESIAN_POINT ( 'NONE', ( 37.09326454176861176, 191.1521966848744398, 106.3078452960112656 ) ) ; -#30159 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554023 ) ) ; -#30160 = ORIENTED_EDGE ( 'NONE', *, *, #12409, .F. ) ; -#30161 = EDGE_LOOP ( 'NONE', ( #1909, #37369, #18844, #23577 ) ) ; -#30162 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#30163 = ORIENTED_EDGE ( 'NONE', *, *, #12396, .T. ) ; -#30164 = ORIENTED_EDGE ( 'NONE', *, *, #10432, .F. ) ; -#30165 = CARTESIAN_POINT ( 'NONE', ( 36.06343484149106615, 196.1181868591261264, 103.6579563381262972 ) ) ; -#30166 = CARTESIAN_POINT ( 'NONE', ( -20.00011757681407687, 142.7751936262870629, 92.62737297394311042 ) ) ; -#30167 = CARTESIAN_POINT ( 'NONE', ( 2.781577460637000065, 209.6623454612000330, 73.22349077734000389 ) ) ; -#30168 = CARTESIAN_POINT ( 'NONE', ( -2.954045212696999823, 209.2037278823000293, 76.12424252725000429 ) ) ; -#30169 = ORIENTED_EDGE ( 'NONE', *, *, #24337, .T. ) ; -#30170 = VERTEX_POINT ( 'NONE', #18296 ) ; -#30171 = FACE_OUTER_BOUND ( 'NONE', #752, .T. ) ; -#30172 = CARTESIAN_POINT ( 'NONE', ( -36.28576886329999951, 191.9717759737999927, 104.5605806779000204 ) ) ; -#30173 = CARTESIAN_POINT ( 'NONE', ( 36.96191343238999849, 191.2461813283000254, 103.8994397653000021 ) ) ; -#30174 = ORIENTED_EDGE ( 'NONE', *, *, #29306, .T. ) ; -#30175 = CARTESIAN_POINT ( 'NONE', ( -25.66780912439000062, 120.7136169122999974, 87.87971206257999768 ) ) ; -#30176 = ORIENTED_EDGE ( 'NONE', *, *, #40004, .F. ) ; -#30177 = ORIENTED_EDGE ( 'NONE', *, *, #21429, .T. ) ; -#30178 = DIRECTION ( 'NONE', ( -1.183724029337065647E-10, -0.9743700557655629035, -0.2249510934123543637 ) ) ; -#30179 = CARTESIAN_POINT ( 'NONE', ( -23.35635573182313607, 131.0183818788550241, 89.91503395410319399 ) ) ; -#30180 = EDGE_LOOP ( 'NONE', ( #3260, #5647, #17249, #3325 ) ) ; -#30181 = CARTESIAN_POINT ( 'NONE', ( -14.21481790486992658, 199.9748479675046440, 27.79156831219690815 ) ) ; -#30182 = EDGE_CURVE ( 'NONE', #22954, #29758, #37395, .T. ) ; -#30183 = VECTOR ( 'NONE', #13487, 1000.000000000000227 ) ; -#30184 = EDGE_CURVE ( 'NONE', #30155, #14229, #18089, .T. ) ; -#30185 = CARTESIAN_POINT ( 'NONE', ( 37.99861263456919147, 119.0703074402329946, 87.24831694550429972 ) ) ; -#30186 = CARTESIAN_POINT ( 'NONE', ( -3.535986895436823207, 167.8052092920482039, 101.4748507491612912 ) ) ; -#30187 = ORIENTED_EDGE ( 'NONE', *, *, #31911, .T. ) ; -#30188 = AXIS2_PLACEMENT_3D ( 'NONE', #4093, #10468, #6767 ) ; -#30189 = CARTESIAN_POINT ( 'NONE', ( -35.93819496000456581, 196.1181868592477144, 103.7014435179352603 ) ) ; -#30190 = CARTESIAN_POINT ( 'NONE', ( 2.219713491779890635, 189.8798548279868328, 103.9373167649446401 ) ) ; -#30191 = LINE ( 'NONE', #16879, #22815 ) ; -#30192 = APPROVAL ( #15127, '未' ) ; -#30193 = EDGE_LOOP ( 'NONE', ( #17254, #32552, #17848, #7347 ) ) ; -#30194 = CARTESIAN_POINT ( 'NONE', ( 37.28139524443679420, 185.5739301951794289, 107.6056048166977916 ) ) ; -#30195 = ORIENTED_EDGE ( 'NONE', *, *, #39857, .T. ) ; -#30196 = EDGE_LOOP ( 'NONE', ( #20968, #15659, #11417, #24546 ) ) ; -#30197 = CARTESIAN_POINT ( 'NONE', ( 8.471855203514563115, 150.6175905705881064, 96.98637658383512417 ) ) ; -#30198 = CARTESIAN_POINT ( 'NONE', ( -2.449345313868760865, 209.1926399313205422, 73.58232963557692585 ) ) ; -#30199 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#30200 = LINE ( 'NONE', #2196, #1682 ) ; -#30201 = ORIENTED_EDGE ( 'NONE', *, *, #24391, .F. ) ; -#30202 = CARTESIAN_POINT ( 'NONE', ( 15.99998384348811875, 126.8035267017516787, 88.91816380576780432 ) ) ; -#30203 = ADVANCED_FACE ( 'NONE', ( #39771 ), #5926, .F. ) ; -#30204 = CYLINDRICAL_SURFACE ( 'NONE', #6145, 7.000000000000007994 ) ; -#30205 = CARTESIAN_POINT ( 'NONE', ( -3.707115906001695382, 137.3147537657612816, 91.53070687509357128 ) ) ; -#30206 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32019, #40397, #18710, #38722, #23209, #38934, #35643, #20117, #12160, #17454, #14409, #26895, #30154, #14617, #11550, #36477, #16012, #13169 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.007812500000031027264, 0.01562500000006205453, 0.03125000000009766493, 0.06250000000008840151, 0.1250000000000698885, 0.2500000000000857092, 0.5000000000000646150, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30207 = CARTESIAN_POINT ( 'NONE', ( 19.46069570751975064, 126.1537043193212071, 176.3650766102145155 ) ) ; -#30208 = CARTESIAN_POINT ( 'NONE', ( 32.54675005397223231, 175.7420487377131906, 100.2065144811790418 ) ) ; -#30209 = CARTESIAN_POINT ( 'NONE', ( -14.55306309020423505, 135.7870933973037211, 91.01063163966807679 ) ) ; -#30210 = CARTESIAN_POINT ( 'NONE', ( 20.00245300826521344, 117.7233654573207673, 90.25570385881030688 ) ) ; -#30211 = VERTEX_POINT ( 'NONE', #27138 ) ; -#30212 = CARTESIAN_POINT ( 'NONE', ( 39.06524929025407999, 190.3639766107277751, 106.6572273908310677 ) ) ; -#30213 = VECTOR ( 'NONE', #17397, 1000.000000000000114 ) ; -#30214 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#30215 = ORIENTED_EDGE ( 'NONE', *, *, #20087, .F. ) ; -#30216 = FACE_OUTER_BOUND ( 'NONE', #13549, .T. ) ; -#30217 = ORIENTED_EDGE ( 'NONE', *, *, #675, .T. ) ; -#30218 = CARTESIAN_POINT ( 'NONE', ( -39.09419349104000219, 119.9285908000999967, 87.53984484766000662 ) ) ; -#30219 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.894780628693970840E-14, -0.9999998176071847045 ) ) ; -#30220 = ORIENTED_EDGE ( 'NONE', *, *, #6261, .T. ) ; -#30221 = CARTESIAN_POINT ( 'NONE', ( 35.72162228762299208, 191.8765893896865862, 106.8996286655296331 ) ) ; -#30222 = CARTESIAN_POINT ( 'NONE', ( 4.035087735728000169, 137.3597734203999892, 92.90194316321000656 ) ) ; -#30223 = DIRECTION ( 'NONE', ( -7.723605449956060566E-15, -1.000000000000000000, 7.732940816592896770E-15 ) ) ; -#30224 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19403, #31904, #3063, #22699 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 4.581999207909093208, 4.582002206190092686 ), - .UNSPECIFIED. ) ; -#30225 = EDGE_CURVE ( 'NONE', #23133, #21095, #39839, .T. ) ; -#30226 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22769, #1071, #29299, #19477 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 3.911707216971325806E-06, 0.001107709280090561979 ), - .UNSPECIFIED. ) ; -#30227 = EDGE_CURVE ( 'NONE', #11066, #16199, #13996, .T. ) ; -#30228 = CARTESIAN_POINT ( 'NONE', ( -22.53834600676000477, 152.8497889692000058, 28.07991271570000080 ) ) ; -#30229 = CARTESIAN_POINT ( 'NONE', ( 29.75539532201830895, 185.8818174615954035, 102.8912523119488043 ) ) ; -#30230 = ORIENTED_EDGE ( 'NONE', *, *, #33974, .F. ) ; -#30231 = CARTESIAN_POINT ( 'NONE', ( 38.67185976444999795, 118.8147476325000156, 87.79798927129999697 ) ) ; -#30232 = CARTESIAN_POINT ( 'NONE', ( 76.10748482112096269, 155.8105762428848209, 98.14442178571832187 ) ) ; -#30233 = CARTESIAN_POINT ( 'NONE', ( 26.00773787884236654, 191.9759150222000130, 101.9057393183920510 ) ) ; -#30234 = CARTESIAN_POINT ( 'NONE', ( -20.18406416472224052, 207.7152079537316069, 77.22406492501946218 ) ) ; -#30235 = ORIENTED_EDGE ( 'NONE', *, *, #25674, .T. ) ; -#30236 = CIRCLE ( 'NONE', #12595, 6.000000000000001776 ) ; -#30237 = CARTESIAN_POINT ( 'NONE', ( -20.50650306240503440, 198.0404403167238740, 94.04479409490431863 ) ) ; -#30238 = CARTESIAN_POINT ( 'NONE', ( -42.84416203867576911, 121.1162828388086155, 91.10151243711948155 ) ) ; -#30239 = CARTESIAN_POINT ( 'NONE', ( 6.034689397599763083, 134.7209248247105506, 93.42369219423338222 ) ) ; -#30240 = CARTESIAN_POINT ( 'NONE', ( -28.02720713106999995, 124.8179244407999988, 91.17684134897000092 ) ) ; -#30241 = AXIS2_PLACEMENT_3D ( 'NONE', #35177, #32543, #1452 ) ; -#30242 = CARTESIAN_POINT ( 'NONE', ( -24.42746481139502279, 103.6131156702177094, 87.78253795974556795 ) ) ; -#30243 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; -#30244 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3391, #31026, #37353, #6459 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30245 = CARTESIAN_POINT ( 'NONE', ( -25.73720508646628957, 209.7105442809424005, 73.34683674680479726 ) ) ; -#30246 = DIRECTION ( 'NONE', ( 0.0004161288024444326629, -0.8480480898058072592, 0.5299191110099175095 ) ) ; -#30247 = CALENDAR_DATE ( 2025, 24, 6 ) ; -#30248 = CARTESIAN_POINT ( 'NONE', ( 38.91850419312000042, 118.6194549561000002, 89.51573056895999514 ) ) ; -#30249 = CARTESIAN_POINT ( 'NONE', ( 15.93615458542151764, 126.1689532666872253, 88.77169389726503823 ) ) ; -#30250 = CARTESIAN_POINT ( 'NONE', ( 16.94389310934299786, 122.7108572845141907, 172.1118440547324724 ) ) ; -#30251 = CARTESIAN_POINT ( 'NONE', ( -13.49987458195000123, 124.7394176561793273, 88.97259030854483797 ) ) ; -#30252 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#30253 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971542088 ) ) ; -#30254 = ORIENTED_EDGE ( 'NONE', *, *, #19216, .T. ) ; -#30255 = ORIENTED_EDGE ( 'NONE', *, *, #16319, .T. ) ; -#30256 = CARTESIAN_POINT ( 'NONE', ( -2.803546274881732803, 190.2883312291301081, 103.5861397132776887 ) ) ; -#30257 = ORIENTED_EDGE ( 'NONE', *, *, #1407, .T. ) ; -#30258 = CARTESIAN_POINT ( 'NONE', ( 39.06385346271000714, 191.4135373863498444, 104.3337793579115100 ) ) ; -#30259 = CONICAL_SURFACE ( 'NONE', #216, 3.003184325552035627, 0.7853589132226472813 ) ; -#30260 = EDGE_CURVE ( 'NONE', #37740, #15715, #11582, .T. ) ; -#30261 = CARTESIAN_POINT ( 'NONE', ( -75.44083865550381063, 196.3268239558178152, 191.1601047369532580 ) ) ; -#30262 = AXIS2_PLACEMENT_3D ( 'NONE', #25856, #6412, #35214 ) ; -#30263 = EDGE_LOOP ( 'NONE', ( #29418, #27893, #31629, #11478 ) ) ; -#30264 = PLANE ( 'NONE', #2879 ) ; -#30265 = EDGE_CURVE ( 'NONE', #1820, #20853, #24058, .T. ) ; -#30266 = AXIS2_PLACEMENT_3D ( 'NONE', #23284, #34912, #6929 ) ; -#30267 = CARTESIAN_POINT ( 'NONE', ( 43.53522454855391999, 122.0089639019850409, 87.79461535567980945 ) ) ; -#30268 = CARTESIAN_POINT ( 'NONE', ( -20.18442483482148120, 205.2604112295805692, 76.18245618944183661 ) ) ; -#30269 = ORIENTED_EDGE ( 'NONE', *, *, #42, .T. ) ; -#30270 = DIRECTION ( 'NONE', ( -0.1305263947813612435, -0.9659212020967549162, -0.2235153050807486830 ) ) ; -#30271 = EDGE_LOOP ( 'NONE', ( #19038, #12275, #23834, #3794 ) ) ; -#30272 = CARTESIAN_POINT ( 'NONE', ( 5.015777457169973808, 188.2825131376439742, 103.1183373587086152 ) ) ; -#30273 = EDGE_CURVE ( 'NONE', #7388, #7259, #36928, .T. ) ; -#30274 = ADVANCED_FACE ( 'NONE', ( #21798 ), #33843, .F. ) ; -#30275 = CARTESIAN_POINT ( 'NONE', ( -39.77033354370986729, 163.8648153409711199, 187.7699382718473089 ) ) ; -#30276 = CARTESIAN_POINT ( 'NONE', ( 12.31576967652000043, 135.2953866536457781, 91.39403621976647685 ) ) ; -#30277 = CARTESIAN_POINT ( 'NONE', ( -12.63752829087790452, 181.3391861866521708, 104.3251754955068549 ) ) ; -#30278 = ORIENTED_EDGE ( 'NONE', *, *, #8236, .T. ) ; -#30279 = EDGE_CURVE ( 'NONE', #7552, #35389, #29055, .T. ) ; -#30280 = ORIENTED_EDGE ( 'NONE', *, *, #31760, .T. ) ; -#30281 = CARTESIAN_POINT ( 'NONE', ( -28.27857295063000009, 187.7633331748000103, 102.8796472078000050 ) ) ; -#30282 = CARTESIAN_POINT ( 'NONE', ( 0.5626226327078748257, 189.0115755308770531, 103.6989479033729680 ) ) ; -#30283 = CARTESIAN_POINT ( 'NONE', ( -36.31535185967262436, 190.8511613781771530, 106.8152324789805903 ) ) ; -#30284 = ORIENTED_EDGE ( 'NONE', *, *, #30906, .T. ) ; -#30285 = VERTEX_POINT ( 'NONE', #28725 ) ; -#30286 = LINE ( 'NONE', #15357, #17217 ) ; -#30287 = VERTEX_POINT ( 'NONE', #25070 ) ; -#30288 = AXIS2_PLACEMENT_3D ( 'NONE', #39174, #20775, #5432 ) ; -#30289 = VECTOR ( 'NONE', #29447, 1000.000000000000000 ) ; -#30290 = ORIENTED_EDGE ( 'NONE', *, *, #8913, .T. ) ; -#30291 = ORIENTED_EDGE ( 'NONE', *, *, #5684, .F. ) ; -#30292 = AXIS2_PLACEMENT_3D ( 'NONE', #25914, #18578, #6323 ) ; -#30293 = CARTESIAN_POINT ( 'NONE', ( -37.93481815207000807, 190.9222121061999928, 106.5159675105000048 ) ) ; -#30294 = CARTESIAN_POINT ( 'NONE', ( -6.679083190205946056E-14, 155.6803346354327289, 98.67347229705578115 ) ) ; -#30295 = CARTESIAN_POINT ( 'NONE', ( 39.76265845619285244, 165.1578649273459973, 181.9301569360012252 ) ) ; -#30296 = VECTOR ( 'NONE', #5732, 1000.000000000000114 ) ; -#30297 = EDGE_CURVE ( 'NONE', #626, #27523, #27535, .T. ) ; -#30298 = ORIENTED_EDGE ( 'NONE', *, *, #31895, .F. ) ; -#30299 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178587041921E-05, -0.0002331579774917524482 ) ) ; -#30300 = ORIENTED_EDGE ( 'NONE', *, *, #5815, .F. ) ; -#30301 = CARTESIAN_POINT ( 'NONE', ( 25.89572839478000077, 120.9676170113999945, 90.47270357463001744 ) ) ; -#30302 = FACE_OUTER_BOUND ( 'NONE', #9260, .T. ) ; -#30303 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26949, #5448, #33051, #5038 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30305 = CARTESIAN_POINT ( 'NONE', ( -38.98349917073630166, 208.8862087839809476, 28.69844958122075340 ) ) ; -#30304 = CARTESIAN_POINT ( 'NONE', ( -25.51008961762496341, 210.1735744387999887, 73.57367795469900784 ) ) ; -#30306 = EDGE_LOOP ( 'NONE', ( #24510, #37190, #26333, #29628 ) ) ; -#30307 = ORIENTED_EDGE ( 'NONE', *, *, #23682, .F. ) ; -#30308 = EDGE_CURVE ( 'NONE', #3137, #29487, #28926, .T. ) ; -#30309 = DIRECTION ( 'NONE', ( -0.0006039748319384701143, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#30310 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32674, #980, #38403, #10608 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 1.482755031588850025, 1.482761572412980344 ), - .UNSPECIFIED. ) ; -#30311 = ORIENTED_EDGE ( 'NONE', *, *, #2167, .F. ) ; -#30312 = CARTESIAN_POINT ( 'NONE', ( -13.47112979352495543, 158.6774517721759139, 96.80778692315055878 ) ) ; -#30313 = EDGE_CURVE ( 'NONE', #13401, #3242, #37518, .T. ) ; -#30314 = CARTESIAN_POINT ( 'NONE', ( -15.99998354555182090, 127.4301387325058812, 89.08215018471784674 ) ) ; -#30315 = DIRECTION ( 'NONE', ( 0.0006039748319389841346, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#30316 = CARTESIAN_POINT ( 'NONE', ( 12.63733492464552910, 130.8755352229478603, 89.98668270653696766 ) ) ; -#30317 = ORIENTED_EDGE ( 'NONE', *, *, #5237, .F. ) ; -#30318 = CIRCLE ( 'NONE', #10732, 6.500001283309376099 ) ; -#30319 = VECTOR ( 'NONE', #36337, 1000.000000000000114 ) ; -#30320 = EDGE_CURVE ( 'NONE', #16053, #24926, #21762, .T. ) ; -#30321 = ORIENTED_EDGE ( 'NONE', *, *, #20856, .F. ) ; -#30322 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #40262, #23949, #30268, #2065 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30323 = EDGE_LOOP ( 'NONE', ( #5195, #25609, #34555, #7768 ) ) ; -#30324 = CARTESIAN_POINT ( 'NONE', ( -2.389131445052671499, 190.4669456657243245, 104.1095116572825248 ) ) ; -#30325 = CARTESIAN_POINT ( 'NONE', ( -59.17051632422617757, 248.4236826516141718, 201.1548740838363187 ) ) ; -#30326 = AXIS2_PLACEMENT_3D ( 'NONE', #18759, #18366, #31065 ) ; -#30327 = EDGE_CURVE ( 'NONE', #3435, #26700, #22199, .T. ) ; -#30328 = CARTESIAN_POINT ( 'NONE', ( 26.81146780509000038, 123.8575906589999960, 88.40256404721999672 ) ) ; -#30329 = VERTEX_POINT ( 'NONE', #34434 ) ; -#30330 = CARTESIAN_POINT ( 'NONE', ( 35.85095044413336041, 209.7096532900772559, 75.73246956629850501 ) ) ; -#30331 = EDGE_CURVE ( 'NONE', #24195, #14326, #12473, .T. ) ; -#30332 = CARTESIAN_POINT ( 'NONE', ( 0.7554937491704000196, 188.5901081920000024, 106.0612825900000047 ) ) ; -#30333 = CARTESIAN_POINT ( 'NONE', ( 5.667266162990448386, 130.4719365712317654, 90.24229930473130423 ) ) ; -#30334 = CARTESIAN_POINT ( 'NONE', ( 13.49909370106398576, 124.5554084217246213, 88.65691245320910241 ) ) ; -#30335 = CARTESIAN_POINT ( 'NONE', ( -3.668109984895000508, 124.1783413802999974, 91.40287821750001740 ) ) ; -#30336 = CARTESIAN_POINT ( 'NONE', ( 4.988793577564046622, 148.2075385567467833, 93.86631507789503814 ) ) ; -#30337 = ORIENTED_EDGE ( 'NONE', *, *, #27675, .T. ) ; -#30338 = CARTESIAN_POINT ( 'NONE', ( 25.99030105615392827, 209.7097546603872900, 73.04280869622928662 ) ) ; -#30339 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709481474, 92.27946979429643193, 322.5205145037750754 ) ) ; -#30340 = CARTESIAN_POINT ( 'NONE', ( -44.80682199002519894, 71.18588162383781537, 322.8408877984866763 ) ) ; -#30341 = LOCAL_TIME ( 14, 25, 27.00000000000000000, #3034 ) ; -#30342 = AXIS2_PLACEMENT_3D ( 'NONE', #38763, #22460, #28983 ) ; -#30343 = AXIS2_PLACEMENT_3D ( 'NONE', #2596, #11798, #24279 ) ; -#30344 = EDGE_LOOP ( 'NONE', ( #11995, #16552, #20084, #15023 ) ) ; -#30345 = DIRECTION ( 'NONE', ( -0.7066775280858015318, -9.360549773363750444E-05, 0.7075357676729508993 ) ) ; -#30346 = ORIENTED_EDGE ( 'NONE', *, *, #21145, .T. ) ; -#30347 = AXIS2_PLACEMENT_3D ( 'NONE', #19717, #31622, #34653 ) ; -#30348 = CARTESIAN_POINT ( 'NONE', ( -37.29435884442529670, 164.6092402323636463, 198.2106787237848948 ) ) ; -#30349 = EDGE_LOOP ( 'NONE', ( #36086, #27248 ) ) ; -#30350 = ORIENTED_EDGE ( 'NONE', *, *, #2090, .F. ) ; -#30351 = EDGE_LOOP ( 'NONE', ( #15431, #27434, #4236, #14486 ) ) ; -#30352 = EDGE_CURVE ( 'NONE', #12627, #40149, #22313, .T. ) ; -#30353 = LINE ( 'NONE', #2349, #18593 ) ; -#30354 = ADVANCED_FACE ( 'NONE', ( #32000 ), #13241, .F. ) ; -#30355 = DIRECTION ( 'NONE', ( 1.355448645614934247E-15, 0.9743700557918348881, 0.2249510932985576139 ) ) ; -#30356 = FACE_OUTER_BOUND ( 'NONE', #11492, .T. ) ; -#30357 = EDGE_CURVE ( 'NONE', #19028, #6998, #26230, .T. ) ; -#30358 = FACE_OUTER_BOUND ( 'NONE', #10913, .T. ) ; -#30359 = VERTEX_POINT ( 'NONE', #34631 ) ; -#30360 = VERTEX_POINT ( 'NONE', #3163 ) ; -#30361 = FACE_OUTER_BOUND ( 'NONE', #14159, .T. ) ; -#30362 = ORIENTED_EDGE ( 'NONE', *, *, #11777, .F. ) ; -#30363 = ORIENTED_EDGE ( 'NONE', *, *, #25511, .F. ) ; -#30364 = DIRECTION ( 'NONE', ( 0.0005884949961232180437, -0.2249510543439044996, 0.9743698870671267942 ) ) ; -#30365 = EDGE_CURVE ( 'NONE', #9881, #4160, #25681, .T. ) ; -#30366 = DIRECTION ( 'NONE', ( 0.7933533411653070910, 0.5931840316265236668, 0.1368326740407682096 ) ) ; -#30367 = CARTESIAN_POINT ( 'NONE', ( -23.36589107377781005, 134.9158523539519194, 90.81477344275025132 ) ) ; -#30368 = ADVANCED_FACE ( 'NONE', ( #31596 ), #3555, .F. ) ; -#30369 = ORIENTED_EDGE ( 'NONE', *, *, #9925, .T. ) ; -#30370 = ORIENTED_EDGE ( 'NONE', *, *, #15378, .T. ) ; -#30371 = CARTESIAN_POINT ( 'NONE', ( 24.57257244294000031, 109.6131156702000027, 152.4718672074000381 ) ) ; -#30372 = CARTESIAN_POINT ( 'NONE', ( -35.93694266037999796, 191.6740185698999994, 104.0281987147999985 ) ) ; -#30373 = CARTESIAN_POINT ( 'NONE', ( -26.00154085324000164, 120.8070833447000041, 87.55874384822999446 ) ) ; -#30374 = CIRCLE ( 'NONE', #16633, 6.000000000000007994 ) ; -#30375 = EDGE_CURVE ( 'NONE', #22363, #9812, #34824, .T. ) ; -#30376 = ORIENTED_EDGE ( 'NONE', *, *, #36407, .F. ) ; -#30377 = CARTESIAN_POINT ( 'NONE', ( -77.86614104348858234, 192.3476576144325350, 194.3451165138085912 ) ) ; -#30378 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049006696, 187.6642686534657969, 106.0792573255290279 ) ) ; -#30379 = PLANE ( 'NONE', #40440 ) ; -#30380 = ORIENTED_EDGE ( 'NONE', *, *, #18837, .T. ) ; -#30381 = AXIS2_PLACEMENT_3D ( 'NONE', #37327, #9523, #10334 ) ; -#30382 = CARTESIAN_POINT ( 'NONE', ( 2.856426491790444722, 190.1159510835748563, 103.5429241319047122 ) ) ; -#30383 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38532, #9747, #6855, #16455 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0001360695803370404959, 0.001188674531724661070 ), - .UNSPECIFIED. ) ; -#30384 = CONICAL_SURFACE ( 'NONE', #3594, 51.90509899251598824, 0.7853981633973070586 ) ; -#30385 = CARTESIAN_POINT ( 'NONE', ( 0.5623190733617040582, 188.6124699482102756, 103.1972064621602527 ) ) ; -#30386 = CARTESIAN_POINT ( 'NONE', ( 39.43357611201896873, 119.6599139514868000, 90.33369661064041622 ) ) ; -#30387 = EDGE_LOOP ( 'NONE', ( #24299, #31539, #30725, #26964 ) ) ; -#30388 = EDGE_CURVE ( 'NONE', #21808, #13881, #39765, .T. ) ; -#30389 = CARTESIAN_POINT ( 'NONE', ( -19.35108328216286466, 125.8813528276864986, 176.2931328289076873 ) ) ; -#30390 = CARTESIAN_POINT ( 'NONE', ( 2.527886776962242177, 190.6140954227784619, 104.1491054897084751 ) ) ; -#30391 = CARTESIAN_POINT ( 'NONE', ( -13.49684457966274920, 188.3420920579488040, 103.1432733986002006 ) ) ; -#30392 = ORIENTED_EDGE ( 'NONE', *, *, #29115, .F. ) ; -#30393 = CARTESIAN_POINT ( 'NONE', ( 25.92457966006830361, 117.3337153156629853, 90.25212704270869324 ) ) ; -#30394 = VERTEX_POINT ( 'NONE', #7842 ) ; -#30395 = CARTESIAN_POINT ( 'NONE', ( 40.92026568130903286, 127.3697701065169525, 89.54698672993396258 ) ) ; -#30396 = CARTESIAN_POINT ( 'NONE', ( -2.455535015344930905, 209.0643992532682489, 73.60343043103465277 ) ) ; -#30397 = DIRECTION ( 'NONE', ( -0.0005884950603321816021, 0.2249510543244929717, -0.9743698870715694627 ) ) ; -#30398 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#30399 = CARTESIAN_POINT ( 'NONE', ( -38.94544030374902377, 127.6228066749847159, 91.70625031055864440 ) ) ; -#30400 = ORIENTED_EDGE ( 'NONE', *, *, #912, .T. ) ; -#30401 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#30402 = VECTOR ( 'NONE', #36015, 1000.000000000000114 ) ; -#30403 = AXIS2_PLACEMENT_3D ( 'NONE', #24432, #6000, #21759 ) ; -#30404 = DIRECTION ( 'NONE', ( 0.7933308265452475583, 0.5932923437231171215, 0.1364932032467733869 ) ) ; -#30405 = CARTESIAN_POINT ( 'NONE', ( -2.938441476483304005, 191.9759150222000130, 101.9232220854011928 ) ) ; -#30406 = VECTOR ( 'NONE', #8010, 999.9999999999998863 ) ; -#30407 = CIRCLE ( 'NONE', #14748, 2.749999999872844381 ) ; -#30408 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#30410 = AXIS2_PLACEMENT_3D ( 'NONE', #36509, #8923, #5212 ) ; -#30409 = LINE ( 'NONE', #2987, #2930 ) ; -#30411 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #12402, #3387 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30412 = ADVANCED_FACE ( 'NONE', ( #23592 ), #35832, .F. ) ; -#30413 = CARTESIAN_POINT ( 'NONE', ( -20.80881105757926619, 183.3190328663897901, 104.5537767167631813 ) ) ; -#30414 = DIRECTION ( 'NONE', ( 1.908195823574476760E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#30415 = CARTESIAN_POINT ( 'NONE', ( -37.03430921788798003, 164.9912417531061806, 195.6638442139325207 ) ) ; -#30416 = ADVANCED_FACE ( 'NONE', ( #22997 ), #8603, .T. ) ; -#30417 = CIRCLE ( 'NONE', #38888, 1.999999999912203341 ) ; -#30418 = CARTESIAN_POINT ( 'NONE', ( 41.20592959029892199, 166.0079942228585708, 183.1534114321898130 ) ) ; -#30419 = EDGE_CURVE ( 'NONE', #27010, #23072, #28245, .T. ) ; -#30420 = CARTESIAN_POINT ( 'NONE', ( -35.60463239281441616, 192.3272979397512188, 104.0809358108204350 ) ) ; -#30421 = ORIENTED_EDGE ( 'NONE', *, *, #21201, .F. ) ; -#30422 = VERTEX_POINT ( 'NONE', #7639 ) ; -#30423 = CARTESIAN_POINT ( 'NONE', ( 26.96435332582821687, 119.8033593921229425, 171.4421629884936067 ) ) ; -#30424 = CARTESIAN_POINT ( 'NONE', ( -32.48647373867155608, 136.7094953407745095, 91.23441627737952331 ) ) ; -#30425 = ADVANCED_FACE ( 'NONE', ( #17230 ), #4565, .T. ) ; -#30426 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20044, #23340, #2479, #20667 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0001754148665578480321, 0.0002047026810873128701 ), - .UNSPECIFIED. ) ; -#30427 = ORIENTED_EDGE ( 'NONE', *, *, #1479, .F. ) ; -#30428 = CARTESIAN_POINT ( 'NONE', ( -38.86369644165072401, 118.8228811219059793, 89.72077589445396484 ) ) ; -#30429 = CARTESIAN_POINT ( 'NONE', ( -19.99970941558080284, 118.1131156714892114, 90.27986793006986943 ) ) ; -#30430 = ORIENTED_EDGE ( 'NONE', *, *, #10656, .F. ) ; -#30431 = CARTESIAN_POINT ( 'NONE', ( -39.69380504816999888, 119.8651302025999996, 87.86311136131999433 ) ) ; -#30432 = EDGE_CURVE ( 'NONE', #3941, #20872, #37322, .T. ) ; -#30433 = CARTESIAN_POINT ( 'NONE', ( 16.24136348069641045, 152.0504431525023676, 181.0538646986893809 ) ) ; -#30434 = CARTESIAN_POINT ( 'NONE', ( 36.66403270979058249, 190.6919956248356982, 106.7344084553361512 ) ) ; -#30435 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265228896, 0.1368326740407719011 ) ) ; -#30436 = EDGE_LOOP ( 'NONE', ( #29492, #4959, #14663, #15302 ) ) ; -#30437 = LINE ( 'NONE', #18133, #23580 ) ; -#30438 = AXIS2_PLACEMENT_3D ( 'NONE', #29965, #11159, #33425 ) ; -#30439 = LINE ( 'NONE', #12613, #20491 ) ; -#30440 = CARTESIAN_POINT ( 'NONE', ( 36.06476242627000062, 193.5538913732000026, 105.8560347722000046 ) ) ; -#30441 = EDGE_CURVE ( 'NONE', #24020, #29762, #26869, .T. ) ; -#30442 = CIRCLE ( 'NONE', #12140, 2.000000000000011546 ) ; -#30443 = CARTESIAN_POINT ( 'NONE', ( -14.38825339673138259, 10.02132158114557114, 291.5672340797456172 ) ) ; -#30444 = LINE ( 'NONE', #12236, #11947 ) ; -#30445 = VECTOR ( 'NONE', #17706, 1000.000000000000000 ) ; -#30446 = VERTEX_POINT ( 'NONE', #10931 ) ; -#30447 = CARTESIAN_POINT ( 'NONE', ( 39.54773932386999746, 120.6021275922999934, 87.32418019465001180 ) ) ; -#30448 = CARTESIAN_POINT ( 'NONE', ( 25.74196636718000164, 210.3999399800999868, 75.79295708133000176 ) ) ; -#30449 = DIRECTION ( 'NONE', ( 0.6087608094795160518, -0.7729396873201688223, -0.1788141957654486303 ) ) ; -#30450 = CARTESIAN_POINT ( 'NONE', ( 21.57626858038420181, 182.0286742890524181, 104.5723846802734300 ) ) ; -#30451 = CONICAL_SURFACE ( 'NONE', #16701, 5.000000000038869352, 0.7853981633647073579 ) ; -#30452 = ORIENTED_EDGE ( 'NONE', *, *, #34529, .T. ) ; -#30453 = CARTESIAN_POINT ( 'NONE', ( 22.07808152764010856, 150.7554441681027129, 27.80156222623680762 ) ) ; -#30454 = CARTESIAN_POINT ( 'NONE', ( -41.44595535608001313, 120.6173858629433369, 90.60358358051291816 ) ) ; -#30455 = LINE ( 'NONE', #23706, #32666 ) ; -#30456 = FACE_OUTER_BOUND ( 'NONE', #9158, .T. ) ; -#30457 = CARTESIAN_POINT ( 'NONE', ( 13.67163921588000086, 181.5029510073999859, 104.6268367889000075 ) ) ; -#30458 = CARTESIAN_POINT ( 'NONE', ( 22.31312662366504540, 116.2335386298891393, 182.3227435278615474 ) ) ; -#30459 = CARTESIAN_POINT ( 'NONE', ( -21.21399091018682981, 129.1232532189451376, 89.98933777676734280 ) ) ; -#30460 = CARTESIAN_POINT ( 'NONE', ( -37.17455842349777129, 80.91246596882704978, 284.1870184124936145 ) ) ; -#30461 = CALENDAR_DATE ( 2025, 24, 6 ) ; -#30462 = CARTESIAN_POINT ( 'NONE', ( 38.75341522189999921, 118.7918142041999943, 89.81188645496000333 ) ) ; -#30463 = CARTESIAN_POINT ( 'NONE', ( 30.05084665326030446, 185.2025551396338585, 102.9053044902910869 ) ) ; -#30464 = CARTESIAN_POINT ( 'NONE', ( 17.19707752705298276, 122.6006626263945947, 172.0864319364189612 ) ) ; -#30465 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825942860899101, 0.0005734119018572840726 ) ) ; -#30466 = CONICAL_SURFACE ( 'NONE', #25246, 5.999999999758601099, 0.7853981633778982507 ) ; -#30467 = LINE ( 'NONE', #9196, #9769 ) ; -#30468 = CARTESIAN_POINT ( 'NONE', ( 36.20192395120999862, 112.8316120500000039, 87.89471584367001356 ) ) ; -#30469 = EDGE_CURVE ( 'NONE', #32409, #16053, #10722, .T. ) ; -#30470 = AXIS2_PLACEMENT_3D ( 'NONE', #8954, #12017, #28168 ) ; -#30471 = CARTESIAN_POINT ( 'NONE', ( 13.46857904157075403, 158.4311794591165494, 96.39256747411997139 ) ) ; -#30472 = VECTOR ( 'NONE', #37137, 1000.000000000000114 ) ; -#30473 = ORIENTED_EDGE ( 'NONE', *, *, #32302, .T. ) ; -#30474 = EDGE_LOOP ( 'NONE', ( #17260, #37621, #3704, #30430 ) ) ; -#30475 = ORIENTED_EDGE ( 'NONE', *, *, #11330, .T. ) ; -#30476 = LINE ( 'NONE', #19872, #10798 ) ; -#30477 = ORIENTED_EDGE ( 'NONE', *, *, #32669, .T. ) ; -#30478 = CARTESIAN_POINT ( 'NONE', ( 20.46042542853685120, 126.8635651546206020, 91.53723576583463739 ) ) ; -#30479 = CIRCLE ( 'NONE', #2398, 2.499999999985527577 ) ; -#30480 = CARTESIAN_POINT ( 'NONE', ( 16.04422245830440374, 152.0461280324277311, 184.5382697652126467 ) ) ; -#30481 = FACE_OUTER_BOUND ( 'NONE', #32227, .T. ) ; -#30482 = CONICAL_SURFACE ( 'NONE', #33724, 3.499999999950266005, 0.7853981633778703841 ) ; -#30483 = EDGE_CURVE ( 'NONE', #30145, #40336, #23191, .T. ) ; -#30484 = EDGE_LOOP ( 'NONE', ( #31311, #15349, #14342, #3001 ) ) ; -#30485 = CARTESIAN_POINT ( 'NONE', ( 15.50029467836134778, 127.6324160061193567, 89.62297635127647766 ) ) ; -#30486 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323826000612104178, 0.0005734119005250372597 ) ) ; -#30487 = CARTESIAN_POINT ( 'NONE', ( -18.79252570011861678, 125.8499160133713133, 175.1155745579973484 ) ) ; -#30488 = ORIENTED_EDGE ( 'NONE', *, *, #29872, .F. ) ; -#30489 = FACE_OUTER_BOUND ( 'NONE', #2535, .T. ) ; -#30490 = LINE ( 'NONE', #6131, #27327 ) ; -#30491 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971557631 ) ) ; -#30492 = CARTESIAN_POINT ( 'NONE', ( -3.787588882752000341, 140.7274741751000136, 92.40128261844999713 ) ) ; -#30493 = CARTESIAN_POINT ( 'NONE', ( -3.336546828080732663, 186.7822604252457097, 102.7770212601688655 ) ) ; -#30494 = CARTESIAN_POINT ( 'NONE', ( -20.39708600605234068, 212.6012170711696001, 76.07084295526449580 ) ) ; -#30495 = ORIENTED_EDGE ( 'NONE', *, *, #26643, .T. ) ; -#30496 = ORIENTED_EDGE ( 'NONE', *, *, #16975, .T. ) ; -#30497 = EDGE_CURVE ( 'NONE', #12419, #29005, #13987, .T. ) ; -#30498 = CARTESIAN_POINT ( 'NONE', ( -26.18286805740000034, 188.6943569864000381, 103.8843509396999991 ) ) ; -#30499 = CARTESIAN_POINT ( 'NONE', ( 0.9447797691695138944, 189.0460019304039747, 103.7072988499540003 ) ) ; -#30500 = CARTESIAN_POINT ( 'NONE', ( -35.51435415167420473, 192.1311557781389467, 106.9413281154107551 ) ) ; -#30501 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27915, #40339, #12342, #24845 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30502 = CIRCLE ( 'NONE', #32438, 40.50000000001669065 ) ; -#30503 = ORIENTED_EDGE ( 'NONE', *, *, #33229, .F. ) ; -#30504 = CARTESIAN_POINT ( 'NONE', ( -3.536105410441011010, 136.6754134117661863, 94.28792821396773149 ) ) ; -#30505 = AXIS2_PLACEMENT_3D ( 'NONE', #17055, #14223, #23827 ) ; -#30506 = ORIENTED_EDGE ( 'NONE', *, *, #34450, .T. ) ; -#30507 = CIRCLE ( 'NONE', #33752, 2.000002475912143751 ) ; -#30508 = FACE_OUTER_BOUND ( 'NONE', #29052, .T. ) ; -#30509 = VECTOR ( 'NONE', #17214, 1000.000000000000227 ) ; -#30510 = EDGE_CURVE ( 'NONE', #1901, #20812, #33388, .T. ) ; -#30511 = ORIENTED_EDGE ( 'NONE', *, *, #11721, .F. ) ; -#30512 = ORIENTED_EDGE ( 'NONE', *, *, #31446, .F. ) ; -#30513 = CARTESIAN_POINT ( 'NONE', ( -36.55077431165999968, 191.6726824183000133, 104.1988125334000017 ) ) ; -#30514 = CARTESIAN_POINT ( 'NONE', ( -20.01880829891733171, 206.1769743876099312, 74.49881186909658481 ) ) ; -#30515 = CARTESIAN_POINT ( 'NONE', ( -37.19949496103398445, 191.0620094574575774, 106.3403951867547335 ) ) ; -#30516 = ORIENTED_EDGE ( 'NONE', *, *, #12280, .F. ) ; -#30517 = LINE ( 'NONE', #2502, #2330 ) ; -#30518 = ORIENTED_EDGE ( 'NONE', *, *, #16786, .T. ) ; -#30519 = CARTESIAN_POINT ( 'NONE', ( 25.76080190021000504, 121.9504149108000064, 90.35745116152999401 ) ) ; -#30520 = CARTESIAN_POINT ( 'NONE', ( -35.43806428669827824, 192.3002664666033468, 103.9163745585288297 ) ) ; -#30521 = EDGE_CURVE ( 'NONE', #37452, #27517, #29733, .T. ) ; -#30523 = CARTESIAN_POINT ( 'NONE', ( 37.59407280179000566, 112.0479120775361821, 151.0714151308390854 ) ) ; -#30522 = DIRECTION ( 'NONE', ( 0.0005884949927976746440, -0.2249510782047483837, 0.9743698815584175277 ) ) ; -#30524 = VERTEX_POINT ( 'NONE', #30134 ) ; -#30525 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38808, #30234, #36154, #20832 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30526 = VERTEX_POINT ( 'NONE', #27503 ) ; -#30527 = EDGE_CURVE ( 'NONE', #38835, #7316, #33381, .T. ) ; -#30528 = VECTOR ( 'NONE', #13755, 1000.000000000000227 ) ; -#30529 = VERTEX_POINT ( 'NONE', #40127 ) ; -#30530 = CARTESIAN_POINT ( 'NONE', ( 38.94172870169000333, 119.2287965852000013, 90.13226831520999838 ) ) ; -#30531 = CARTESIAN_POINT ( 'NONE', ( 19.98232544185748694, 209.7096131673859816, 76.04619115725449774 ) ) ; -#30532 = CARTESIAN_POINT ( 'NONE', ( 13.00137693451448584, 181.6895106735664172, 101.5913994261357942 ) ) ; -#30533 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971579558 ) ) ; -#30534 = CARTESIAN_POINT ( 'NONE', ( -25.49121842733731569, 191.8361208170296379, 104.4329317390898950 ) ) ; -#30535 = CARTESIAN_POINT ( 'NONE', ( 12.63887439035699956, 130.9170872642954748, 89.96071735129629587 ) ) ; -#30536 = CARTESIAN_POINT ( 'NONE', ( -38.98458235476000056, 201.0912482656999885, 26.89884147244999824 ) ) ; -#30537 = VERTEX_POINT ( 'NONE', #21553 ) ; -#30538 = EDGE_LOOP ( 'NONE', ( #34499, #4912, #10360, #36674, #12036, #11728, #14221, #32546, #11311, #20288, #37159, #3294, #33566, #26021 ) ) ; -#30539 = DIRECTION ( 'NONE', ( -0.000000000000000000, -1.000000000000000000, -0.000000000000000000 ) ) ; -#30540 = CARTESIAN_POINT ( 'NONE', ( 25.57814583233000505, 121.8237546048000013, 88.27603067743000054 ) ) ; -#30541 = ORIENTED_EDGE ( 'NONE', *, *, #24527, .T. ) ; -#30542 = CARTESIAN_POINT ( 'NONE', ( -25.49121842733731569, 191.8361208170296379, 104.4329317390898950 ) ) ; -#30543 = CARTESIAN_POINT ( 'NONE', ( 0.5641662327143323052, 188.3672386194435262, 106.2403187889907770 ) ) ; -#30544 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; -#30545 = PLANE ( 'NONE', #16666 ) ; -#30546 = DIRECTION ( 'NONE', ( -0.0005884949961254158299, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#30547 = CARTESIAN_POINT ( 'NONE', ( -31.91335489270172232, 174.4783875135883875, 100.4668596826281970 ) ) ; -#30548 = ORIENTED_EDGE ( 'NONE', *, *, #24197, .T. ) ; -#30549 = CYLINDRICAL_SURFACE ( 'NONE', #38844, 17.00000000000406430 ) ; -#30550 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23751, #18592, #12475, #40079 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.001042251736472776759, 0.001064276280997240517 ), - .UNSPECIFIED. ) ; -#30551 = VECTOR ( 'NONE', #19971, 1000.000000000000114 ) ; -#30552 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; -#30553 = EDGE_CURVE ( 'NONE', #2503, #39956, #35999, .T. ) ; -#30554 = ORIENTED_EDGE ( 'NONE', *, *, #33494, .F. ) ; -#30555 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14816, #9080, #31164, #21764 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 5.250277230495868265E-07, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30556 = FACE_OUTER_BOUND ( 'NONE', #595, .T. ) ; -#30557 = ORIENTED_EDGE ( 'NONE', *, *, #405, .T. ) ; -#30558 = ADVANCED_FACE ( 'NONE', ( #5792 ), #25586, .F. ) ; -#30559 = EDGE_CURVE ( 'NONE', #16409, #1699, #35835, .T. ) ; -#30560 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#30561 = EDGE_CURVE ( 'NONE', #27781, #1537, #18374, .T. ) ; -#30562 = VERTEX_POINT ( 'NONE', #2916 ) ; -#30563 = ORIENTED_EDGE ( 'NONE', *, *, #29398, .T. ) ; -#30564 = CARTESIAN_POINT ( 'NONE', ( 22.50176470575384613, 184.2926722047558030, 105.2655616184450196 ) ) ; -#30565 = EDGE_CURVE ( 'NONE', #1021, #13145, #5145, .T. ) ; -#30566 = ORIENTED_EDGE ( 'NONE', *, *, #17436, .T. ) ; -#30567 = CARTESIAN_POINT ( 'NONE', ( 2.608838527522000295, 209.5011064695000016, 75.68136822124000673 ) ) ; -#30568 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18917, #2796, #36949, #24694 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30569 = CARTESIAN_POINT ( 'NONE', ( -22.78251873534911098, 147.5076487179167657, 96.28726666134990353 ) ) ; -#30570 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#30571 = ORIENTED_EDGE ( 'NONE', *, *, #36322, .F. ) ; -#30572 = VERTEX_POINT ( 'NONE', #18246 ) ; -#30573 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319403346168 ) ) ; -#30574 = VERTEX_POINT ( 'NONE', #39516 ) ; -#30575 = ORIENTED_EDGE ( 'NONE', *, *, #22625, .T. ) ; -#30576 = DIRECTION ( 'NONE', ( 0.7075337269008549201, 8.710880586812428391E-15, 0.7066795775298635451 ) ) ; -#30577 = DIRECTION ( 'NONE', ( 0.0002393071182786160318, 0.2252352986010024705, -0.9743043687658494711 ) ) ; -#30578 = CYLINDRICAL_SURFACE ( 'NONE', #19963, 2.500000000000000888 ) ; -#30579 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#30580 = CARTESIAN_POINT ( 'NONE', ( 2.620676500973129208, 209.6192316634764268, 73.39025550097103689 ) ) ; -#30581 = ORIENTED_EDGE ( 'NONE', *, *, #1490, .T. ) ; -#30582 = EDGE_LOOP ( 'NONE', ( #14684, #5174, #23235, #35731 ) ) ; -#30583 = DIRECTION ( 'NONE', ( -2.168404344927432685E-16, -1.000000000000000000, 6.938893903767784591E-15 ) ) ; -#30584 = CARTESIAN_POINT ( 'NONE', ( -36.08623042272999726, 192.5000881635999974, 104.5331338456000054 ) ) ; -#30585 = VERTEX_POINT ( 'NONE', #11940 ) ; -#30586 = CARTESIAN_POINT ( 'NONE', ( -25.83472006383999897, 120.7707320335999981, 87.72146630243001653 ) ) ; -#30587 = ORIENTED_EDGE ( 'NONE', *, *, #24623, .T. ) ; -#30588 = ORIENTED_EDGE ( 'NONE', *, *, #307, .T. ) ; -#30589 = EDGE_CURVE ( 'NONE', #8704, #33884, #24628, .T. ) ; -#30590 = DIRECTION ( 'NONE', ( 0.0002393071182786170076, 0.2252352986010032476, -0.9743043687658492491 ) ) ; -#30591 = CARTESIAN_POINT ( 'NONE', ( -40.76671320591064784, 189.8685293510188501, 106.8201389809352690 ) ) ; -#30592 = VERTEX_POINT ( 'NONE', #27901 ) ; -#30593 = CARTESIAN_POINT ( 'NONE', ( 30.17614589098232258, 126.7625099796061932, 88.90012650384656467 ) ) ; -#30594 = CARTESIAN_POINT ( 'NONE', ( 39.53555642364394629, 119.7153706430301554, 90.34642614193101906 ) ) ; -#30595 = DIRECTION ( 'NONE', ( 0.7933533411653341805, -0.5930537057989598848, -0.1373964268091485141 ) ) ; -#30596 = FACE_OUTER_BOUND ( 'NONE', #3532, .T. ) ; -#30597 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4417, #38968, #32445, #1979 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30598 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989907490, -0.1373964268091706076 ) ) ; -#30599 = EDGE_CURVE ( 'NONE', #24414, #11920, #5583, .T. ) ; -#30600 = ORIENTED_EDGE ( 'NONE', *, *, #26306, .T. ) ; -#30601 = CARTESIAN_POINT ( 'NONE', ( -37.26053171017113641, 182.4107432069956474, 119.7485912024541506 ) ) ; -#30602 = ORIENTED_EDGE ( 'NONE', *, *, #8007, .F. ) ; -#30603 = VERTEX_POINT ( 'NONE', #8259 ) ; -#30604 = DIRECTION ( 'NONE', ( 1.026956297800417606E-13, 0.9743700557921590732, 0.2249510932971540700 ) ) ; -#30605 = LINE ( 'NONE', #3370, #17947 ) ; -#30606 = CARTESIAN_POINT ( 'NONE', ( 35.41497335244000055, 113.0343134727000205, 90.38372467985999492 ) ) ; -#30607 = ADVANCED_FACE ( 'NONE', ( #36461 ), #28811, .F. ) ; -#30608 = DIRECTION ( 'NONE', ( -0.7857167656192536320, 0.6185862421878159934, 0.0004745532380132037723 ) ) ; -#30609 = CARTESIAN_POINT ( 'NONE', ( 6.033127994686249274, 135.1723769864917415, 91.20211310550756423 ) ) ; -#30610 = ORIENTED_EDGE ( 'NONE', *, *, #4865, .T. ) ; -#30611 = EDGE_CURVE ( 'NONE', #1021, #10263, #17834, .T. ) ; -#30612 = AXIS2_PLACEMENT_3D ( 'NONE', #24974, #34521, #19002 ) ; -#30613 = AXIS2_PLACEMENT_3D ( 'NONE', #3083, #15558, #12482 ) ; -#30614 = CARTESIAN_POINT ( 'NONE', ( -6.038838517186622568, 135.1212689757913950, 91.12980290360583524 ) ) ; -#30615 = EDGE_CURVE ( 'NONE', #11261, #27866, #16801, .T. ) ; -#30616 = FACE_OUTER_BOUND ( 'NONE', #34391, .T. ) ; -#30617 = ORIENTED_EDGE ( 'NONE', *, *, #30599, .F. ) ; -#30618 = DIRECTION ( 'NONE', ( 0.0005884949961203373185, -0.2249510543439093846, 0.9743698870671255730 ) ) ; -#30619 = CARTESIAN_POINT ( 'NONE', ( 22.50071842841086678, 154.4094130781474803, 95.28756121982962668 ) ) ; -#30620 = CARTESIAN_POINT ( 'NONE', ( 26.00889011773534065, 191.8021148264478768, 103.9029935424293853 ) ) ; -#30621 = DIRECTION ( 'NONE', ( 1.561251128379117234E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#30622 = DIRECTION ( 'NONE', ( 0.0005884949961229807118, -0.2249510543439059429, 0.9743698870671263501 ) ) ; -#30623 = CARTESIAN_POINT ( 'NONE', ( -3.669581222385323027, 126.6894591277999922, 89.41685568642002124 ) ) ; -#30624 = ORIENTED_EDGE ( 'NONE', *, *, #1096, .T. ) ; -#30625 = VERTEX_POINT ( 'NONE', #31907 ) ; -#30626 = CARTESIAN_POINT ( 'NONE', ( 0.6795524081307224851, 188.9999999395514862, 105.7358963014655728 ) ) ; -#30627 = CARTESIAN_POINT ( 'NONE', ( 13.47345847663963880, 153.8080446478709575, 95.66732164731912746 ) ) ; -#30628 = ORIENTED_EDGE ( 'NONE', *, *, #12148, .F. ) ; -#30629 = CARTESIAN_POINT ( 'NONE', ( -23.36256910961311206, 135.1032017342878078, 91.11449304548321493 ) ) ; -#30630 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8097, #16681, #29978, #29181, #35671, #14243, #1152, #23045, #23437, #23643 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30631 = ORIENTED_EDGE ( 'NONE', *, *, #34371, .F. ) ; -#30632 = CARTESIAN_POINT ( 'NONE', ( -38.29920341924000127, 119.0013441654000133, 87.58334976871999800 ) ) ; -#30633 = AXIS2_PLACEMENT_3D ( 'NONE', #32050, #22643, #7274 ) ; -#30634 = CARTESIAN_POINT ( 'NONE', ( -3.677662715490698453, 143.5677092796093177, 95.73393933775022902 ) ) ; -#30635 = FACE_OUTER_BOUND ( 'NONE', #18097, .T. ) ; -#30636 = EDGE_LOOP ( 'NONE', ( #26699, #22893, #33636, #39075 ) ) ; -#30637 = CYLINDRICAL_SURFACE ( 'NONE', #30123, 9.999999999999996447 ) ; -#30638 = VECTOR ( 'NONE', #353, 1000.000000000000114 ) ; -#30639 = CARTESIAN_POINT ( 'NONE', ( 3.655486316165832417, 167.8522820322272082, 101.3586486882937692 ) ) ; -#30640 = CARTESIAN_POINT ( 'NONE', ( -25.61982903191000105, 190.9959539028000393, 106.4567112378999951 ) ) ; -#30641 = CARTESIAN_POINT ( 'NONE', ( -24.48834041483651447, 115.4756765368858566, 90.28257518319199448 ) ) ; -#30642 = CONICAL_SURFACE ( 'NONE', #584, 30.49999999999573319, 0.7853981633972993981 ) ; -#30643 = CARTESIAN_POINT ( 'NONE', ( -5.675054657474391639, 124.3656264979204167, 88.36836997283377571 ) ) ; -#30644 = ORIENTED_EDGE ( 'NONE', *, *, #16683, .F. ) ; -#30645 = CARTESIAN_POINT ( 'NONE', ( 2.563028759935935597, 191.4135359453850072, 104.3558246061316339 ) ) ; -#30646 = FACE_OUTER_BOUND ( 'NONE', #1265, .T. ) ; -#30647 = CARTESIAN_POINT ( 'NONE', ( 36.58205298002189920, 191.7114058399030512, 104.3498827429378935 ) ) ; -#30648 = ADVANCED_FACE ( 'NONE', ( #20003 ), #6938, .T. ) ; -#30649 = ADVANCED_FACE ( 'NONE', ( #29234 ), #10024, .T. ) ; -#30650 = CARTESIAN_POINT ( 'NONE', ( -17.26273596142550204, 152.7387145730194504, 181.5933280602652076 ) ) ; -#30651 = ORIENTED_EDGE ( 'NONE', *, *, #30320, .T. ) ; -#30652 = EDGE_CURVE ( 'NONE', #410, #24414, #19262, .T. ) ; -#30653 = EDGE_LOOP ( 'NONE', ( #29948, #7985, #22318, #7251 ) ) ; -#30654 = DIRECTION ( 'NONE', ( 0.4261581047166934644, -0.4480007095713214871, -0.7859291533006447228 ) ) ; -#30655 = CYLINDRICAL_SURFACE ( 'NONE', #23225, 2.250000000000011102 ) ; -#30656 = CARTESIAN_POINT ( 'NONE', ( 19.45332703025135146, 148.3679948532157482, 180.6096929009134158 ) ) ; -#30657 = CARTESIAN_POINT ( 'NONE', ( -36.05505683567000119, 191.5962994020999872, 104.0132945296000031 ) ) ; -#30658 = CARTESIAN_POINT ( 'NONE', ( -23.02059183176825741, 214.0904033191889084, 73.07235108223721909 ) ) ; -#30659 = EDGE_CURVE ( 'NONE', #9058, #4088, #25977, .T. ) ; -#30660 = CARTESIAN_POINT ( 'NONE', ( -25.98804079021204672, 209.7098732596503794, 73.09630377377690991 ) ) ; -#30661 = CARTESIAN_POINT ( 'NONE', ( 29.62444488996374403, 185.2955461510884732, 104.9796392865966652 ) ) ; -#30662 = EDGE_CURVE ( 'NONE', #28666, #18813, #37974, .T. ) ; -#30663 = VECTOR ( 'NONE', #32341, 1000.000000000000000 ) ; -#30664 = CARTESIAN_POINT ( 'NONE', ( 38.50589746725999873, 118.6516391838000004, 87.79297567035000327 ) ) ; -#30665 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; -#30666 = LINE ( 'NONE', #34109, #39603 ) ; -#30667 = DIRECTION ( 'NONE', ( -0.9999998268366268039, -0.0001323826607561396436, 0.0005734121968886058199 ) ) ; -#30668 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#30669 = AXIS2_PLACEMENT_3D ( 'NONE', #24878, #8522, #36931 ) ; -#30670 = CARTESIAN_POINT ( 'NONE', ( 25.49993254952412514, 120.4394916964541551, 88.98262338670512861 ) ) ; -#30671 = CARTESIAN_POINT ( 'NONE', ( 37.18383917477999745, 191.3394645145000084, 104.9785211344999993 ) ) ; -#30672 = AXIS2_PLACEMENT_3D ( 'NONE', #3329, #35193, #260 ) ; -#30673 = CARTESIAN_POINT ( 'NONE', ( 36.67096985404000264, 191.2363461959999995, 106.4436279980999984 ) ) ; -#30674 = ORIENTED_EDGE ( 'NONE', *, *, #28339, .T. ) ; -#30675 = ORIENTED_EDGE ( 'NONE', *, *, #30659, .T. ) ; -#30676 = ADVANCED_FACE ( 'NONE', ( #22505 ), #15958, .F. ) ; -#30677 = CARTESIAN_POINT ( 'NONE', ( -6.045835231059395021, 134.9182589738620095, 90.80491324842614631 ) ) ; -#30678 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34516, #2691, #3059, #15541, #40073, #28035 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30679 = ORIENTED_EDGE ( 'NONE', *, *, #25675, .F. ) ; -#30680 = CARTESIAN_POINT ( 'NONE', ( -23.36090843875937395, 177.5203768732290257, 100.8800585087934394 ) ) ; -#30681 = CARTESIAN_POINT ( 'NONE', ( -20.00006126831510400, 120.3902141372887087, 87.45929000627990035 ) ) ; -#30682 = VERTEX_POINT ( 'NONE', #38613 ) ; -#30683 = CARTESIAN_POINT ( 'NONE', ( -39.27942170210999961, 119.7579698461999982, 90.54247500236000690 ) ) ; -#30684 = PLANE ( 'NONE', #12664 ) ; -#30685 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#30686 = FACE_OUTER_BOUND ( 'NONE', #23522, .T. ) ; -#30687 = ORIENTED_EDGE ( 'NONE', *, *, #18705, .F. ) ; -#30688 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28496, #28691, #31563, #471 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30689 = CARTESIAN_POINT ( 'NONE', ( -43.21068176890801027, 118.0105506722982369, 104.8630716126889126 ) ) ; -#30690 = CARTESIAN_POINT ( 'NONE', ( 23.36441916942174402, 176.9663247858313753, 103.3637569773408842 ) ) ; -#30691 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #28264, #6966 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30692 = DIRECTION ( 'NONE', ( -0.0005884965853139737055, 0.2249510543436361309, -0.9743698870662287348 ) ) ; -#30693 = CARTESIAN_POINT ( 'NONE', ( -3.470756533003450439, 187.1137718651480668, 102.8536377798947967 ) ) ; -#30694 = CARTESIAN_POINT ( 'NONE', ( 43.18716009838831127, 118.0176470502005941, 104.8323746835856838 ) ) ; -#30695 = VERTEX_POINT ( 'NONE', #7335 ) ; -#30696 = VERTEX_POINT ( 'NONE', #19794 ) ; -#30697 = VECTOR ( 'NONE', #9567, 1000.000000000000114 ) ; -#30698 = CARTESIAN_POINT ( 'NONE', ( -25.62560591737999971, 191.4791926512000089, 104.2632692198000086 ) ) ; -#30699 = AXIS2_PLACEMENT_3D ( 'NONE', #31179, #21981, #24860 ) ; -#30700 = CARTESIAN_POINT ( 'NONE', ( 2.027256735944490629, 189.6370327888450049, 103.8799177752640190 ) ) ; -#30701 = CARTESIAN_POINT ( 'NONE', ( -22.49962777877401265, 154.4034663070004285, 95.31336199324331915 ) ) ; -#30702 = CONICAL_SURFACE ( 'NONE', #16937, 2.502997798619384540, 0.7853981633682427521 ) ; -#30703 = EDGE_CURVE ( 'NONE', #12815, #5743, #20724, .T. ) ; -#30704 = ORIENTED_EDGE ( 'NONE', *, *, #39073, .T. ) ; -#30705 = CARTESIAN_POINT ( 'NONE', ( 35.56237297027564637, 191.9759150222000130, 101.8999685582079593 ) ) ; -#30706 = ADVANCED_FACE ( 'NONE', ( #26178 ), #15778, .T. ) ; -#30707 = ORIENTED_EDGE ( 'NONE', *, *, #3997, .F. ) ; -#30708 = AXIS2_PLACEMENT_3D ( 'NONE', #36783, #13598, #31613 ) ; -#30709 = CARTESIAN_POINT ( 'NONE', ( -43.57149722038838036, 121.9974985178074434, 87.84418581487720701 ) ) ; -#30710 = PLANE ( 'NONE', #26231 ) ; -#30711 = CARTESIAN_POINT ( 'NONE', ( -37.60461463224000056, 190.9112647455999934, 106.5131070789000063 ) ) ; -#30712 = DIRECTION ( 'NONE', ( -0.6087614810001780175, 0.7729390313185915407, 0.1788147452386051883 ) ) ; -#30713 = DIRECTION ( 'NONE', ( 0.7075227810178097432, -0.1590644159616022568, 0.6885564798298096090 ) ) ; -#30714 = ORIENTED_EDGE ( 'NONE', *, *, #6994, .T. ) ; -#30715 = CARTESIAN_POINT ( 'NONE', ( 46.08149850379091106, 185.2364904696372037, 105.4692177053970852 ) ) ; -#30716 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386905326 ) ) ; -#30717 = CARTESIAN_POINT ( 'NONE', ( -25.66663111670890984, 118.8155669158736174, 89.94995278256749316 ) ) ; -#30718 = ORIENTED_EDGE ( 'NONE', *, *, #19856, .T. ) ; -#30719 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#30720 = DIRECTION ( 'NONE', ( -0.0002393071182785116774, -0.2252352986010041080, 0.9743043687658491381 ) ) ; -#30722 = CARTESIAN_POINT ( 'NONE', ( -6.045835231059395021, 134.9182589738620095, 90.80491324842614631 ) ) ; -#30721 = CARTESIAN_POINT ( 'NONE', ( 39.05501141494404038, 128.0727085485270038, 89.71040052552025656 ) ) ; -#30723 = CIRCLE ( 'NONE', #39186, 10.00000000000000533 ) ; -#30724 = EDGE_CURVE ( 'NONE', #2177, #30359, #39018, .T. ) ; -#30725 = ORIENTED_EDGE ( 'NONE', *, *, #20856, .T. ) ; -#30726 = VECTOR ( 'NONE', #14270, 1000.000000000000114 ) ; -#30727 = CARTESIAN_POINT ( 'NONE', ( 20.17891932135707833, 117.0898005074367063, 87.25559673040211806 ) ) ; -#30728 = AXIS2_PLACEMENT_3D ( 'NONE', #30951, #27507, #30136 ) ; -#30729 = VERTEX_POINT ( 'NONE', #33489 ) ; -#30730 = CARTESIAN_POINT ( 'NONE', ( -30.18611280629168903, 127.2214839853137107, 89.38464791844357649 ) ) ; -#30731 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; -#30732 = CARTESIAN_POINT ( 'NONE', ( 30.83664601630805180, 129.3587224879779853, 89.49911075836023144 ) ) ; -#30733 = CYLINDRICAL_SURFACE ( 'NONE', #30081, 4.999999999999990230 ) ; -#30734 = DIRECTION ( 'NONE', ( -0.0005884949961248538879, 0.2249510543439045551, -0.9743698870671267942 ) ) ; -#30735 = ORIENTED_EDGE ( 'NONE', *, *, #25634, .F. ) ; -#30736 = VERTEX_POINT ( 'NONE', #14296 ) ; -#30737 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319391919761 ) ) ; -#30738 = DIRECTION ( 'NONE', ( -0.0005884949952376201335, 0.2255194585879184699, -0.9742384859323988122 ) ) ; -#30739 = ORIENTED_EDGE ( 'NONE', *, *, #32360, .F. ) ; -#30740 = CARTESIAN_POINT ( 'NONE', ( -35.93599395966710119, 191.2079282146110302, 106.8919311732110060 ) ) ; -#30741 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12979, #10113, #32190, #25462, #3753, #22788, #26058, #34812, #25256, #22188 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999501510, 0.3749999999999252265, 0.4374999999999437117, 0.4999999999999622524, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30742 = FACE_OUTER_BOUND ( 'NONE', #39930, .T. ) ; -#30743 = EDGE_CURVE ( 'NONE', #32426, #9253, #36380, .T. ) ; -#30744 = CARTESIAN_POINT ( 'NONE', ( 0.5638623032898999465, 189.0000161160999994, 105.7369849321000004 ) ) ; -#30745 = EDGE_CURVE ( 'NONE', #13713, #17189, #116, .T. ) ; -#30746 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971550969 ) ) ; -#30747 = CONICAL_SURFACE ( 'NONE', #24867, 2.499995733429277056, 0.7853981633661824002 ) ; -#30748 = VECTOR ( 'NONE', #10520, 1000.000000000000227 ) ; -#30749 = CARTESIAN_POINT ( 'NONE', ( 3.045988519791387628, 209.1419319775010877, 76.13893608185537687 ) ) ; -#30750 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -5.046468293990521964E-15, -0.0006039748319388752807 ) ) ; -#30751 = CARTESIAN_POINT ( 'NONE', ( 3.927688557146990167, 146.4071203614214767, 93.45129659090066809 ) ) ; -#30752 = VECTOR ( 'NONE', #22124, 1000.000000000000000 ) ; -#30753 = VERTEX_POINT ( 'NONE', #13888 ) ; -#30754 = CARTESIAN_POINT ( 'NONE', ( 25.99034337665942118, 208.7353210334150617, 73.11451777455893364 ) ) ; -#30755 = AXIS2_PLACEMENT_3D ( 'NONE', #1750, #20751, #33207 ) ; -#30756 = CYLINDRICAL_SURFACE ( 'NONE', #17977, 9.000000000000003553 ) ; -#30757 = DIRECTION ( 'NONE', ( 0.0001408410614214824043, -0.2255194958243955106, 0.9742386448745018468 ) ) ; -#30758 = ORIENTED_EDGE ( 'NONE', *, *, #2644, .T. ) ; -#30759 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; -#30760 = EDGE_LOOP ( 'NONE', ( #7428, #25086, #11822, #17783 ) ) ; -#30762 = CARTESIAN_POINT ( 'NONE', ( -16.42286345479342913, 121.5140989012041359, 177.3183312225191059 ) ) ; -#30761 = CARTESIAN_POINT ( 'NONE', ( -15.49852919254797179, 185.3436308334966895, 105.0179936564814511 ) ) ; -#30763 = ORIENTED_EDGE ( 'NONE', *, *, #27586, .F. ) ; -#30764 = ORIENTED_EDGE ( 'NONE', *, *, #14918, .F. ) ; -#30765 = ORIENTED_EDGE ( 'NONE', *, *, #24793, .T. ) ; -#30766 = CARTESIAN_POINT ( 'NONE', ( 2.581782723837000137, 209.5968814416000328, 75.67889051560000269 ) ) ; -#30767 = CARTESIAN_POINT ( 'NONE', ( 3.417962904437000127, 127.0758678244000066, 91.81096914418000665 ) ) ; -#30768 = DIRECTION ( 'NONE', ( 0.6087611434178765712, 0.7731004625452565504, 0.1781166614241066204 ) ) ; -#30769 = CARTESIAN_POINT ( 'NONE', ( 12.64110264230791181, 177.6556643415725318, 100.7778556750161982 ) ) ; -#30770 = VERTEX_POINT ( 'NONE', #39224 ) ; -#30771 = AXIS2_PLACEMENT_3D ( 'NONE', #26165, #29616, #4666 ) ; -#30772 = ORIENTED_EDGE ( 'NONE', *, *, #11161, .T. ) ; -#30773 = EDGE_LOOP ( 'NONE', ( #38547, #25833, #16870, #36879 ) ) ; -#30774 = VERTEX_POINT ( 'NONE', #23702 ) ; -#30776 = VECTOR ( 'NONE', #39313, 1000.000000000000227 ) ; -#30775 = DIRECTION ( 'NONE', ( -0.0005884949961208581692, 0.2249510543439069699, -0.9743698870671261281 ) ) ; -#30777 = AXIS2_PLACEMENT_3D ( 'NONE', #25699, #38149, #10148 ) ; -#30778 = PLANE ( 'NONE', #19990 ) ; -#30779 = CARTESIAN_POINT ( 'NONE', ( -16.53681909317384324, 122.5194902194745055, 174.6067105814985609 ) ) ; -#30780 = EDGE_LOOP ( 'NONE', ( #11579, #14336, #28239, #13761 ) ) ; -#30781 = ORIENTED_EDGE ( 'NONE', *, *, #36774, .F. ) ; -#30782 = AXIS2_PLACEMENT_3D ( 'NONE', #36745, #27174, #17519 ) ; -#30783 = VERTEX_POINT ( 'NONE', #20204 ) ; -#30784 = CARTESIAN_POINT ( 'NONE', ( -5.673458782793131761, 123.7518939737303327, 91.25343359375852970 ) ) ; -#30785 = AXIS2_PLACEMENT_3D ( 'NONE', #15534, #388, #19181 ) ; -#30786 = CARTESIAN_POINT ( 'NONE', ( 20.48123591540864652, 210.6297143866032400, 75.54543465911078215 ) ) ; -#30787 = CARTESIAN_POINT ( 'NONE', ( -28.12721690162999977, 125.1825297727000077, 88.74162087477000682 ) ) ; -#30788 = EDGE_CURVE ( 'NONE', #39273, #10263, #36371, .T. ) ; -#30789 = EDGE_LOOP ( 'NONE', ( #13911, #32087, #29793, #15681 ) ) ; -#30790 = DIRECTION ( 'NONE', ( -0.0008702530711002103318, 0.2253087760482092305, -0.9742870203873447155 ) ) ; -#30791 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9334763082618803276, -0.3586390691402302489 ) ) ; -#30792 = ORIENTED_EDGE ( 'NONE', *, *, #8601, .F. ) ; -#30793 = EDGE_CURVE ( 'NONE', #14254, #25874, #18748, .T. ) ; -#30794 = CARTESIAN_POINT ( 'NONE', ( -77.87588430178237786, 193.2350846156091109, 190.4447722601752844 ) ) ; -#30795 = EDGE_CURVE ( 'NONE', #34342, #33812, #26253, .T. ) ; -#30796 = DIRECTION ( 'NONE', ( 0.0005884949961222661141, -0.2249510543439069699, 0.9743698870671262391 ) ) ; -#30797 = EDGE_CURVE ( 'NONE', #33368, #27481, #30525, .T. ) ; -#30798 = ADVANCED_FACE ( 'NONE', ( #7740 ), #2089, .F. ) ; -#30799 = CARTESIAN_POINT ( 'NONE', ( -39.59665107658459959, 119.3565288389648629, 89.79823649497362226 ) ) ; -#30800 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178536755269E-05, 0.0002331579774905574406 ) ) ; -#30801 = ORIENTED_EDGE ( 'NONE', *, *, #27962, .T. ) ; -#30802 = CARTESIAN_POINT ( 'NONE', ( -32.37402305108282263, 174.4007230276914697, 99.93605550448263841 ) ) ; -#30803 = VERTEX_POINT ( 'NONE', #35728 ) ; -#30804 = ORIENTED_EDGE ( 'NONE', *, *, #22812, .F. ) ; -#30805 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#30806 = VECTOR ( 'NONE', #12130, 1000.000000000000114 ) ; -#30807 = DIRECTION ( 'NONE', ( -0.7075337269147008445, -1.085056246983001043E-14, -0.7066795775160008564 ) ) ; -#30808 = CARTESIAN_POINT ( 'NONE', ( 35.93394892565999754, 112.3993893374999971, 89.86828732537999542 ) ) ; -#30809 = VECTOR ( 'NONE', #6831, 1000.000000000000000 ) ; -#30810 = AXIS2_PLACEMENT_3D ( 'NONE', #6058, #2977, #40390 ) ; -#30811 = FACE_OUTER_BOUND ( 'NONE', #2354, .T. ) ; -#30812 = ORIENTED_EDGE ( 'NONE', *, *, #38352, .T. ) ; -#30813 = DIRECTION ( 'NONE', ( -1.786199550476174780E-15, 0.9743043966640313469, 0.2252353050503801690 ) ) ; -#30814 = FACE_OUTER_BOUND ( 'NONE', #17379, .T. ) ; -#30815 = VERTEX_POINT ( 'NONE', #32695 ) ; -#30816 = DIRECTION ( 'NONE', ( -0.0004161288024553938926, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#30817 = CARTESIAN_POINT ( 'NONE', ( 26.03373140117899709, 191.5260202047026041, 103.8544635878054976 ) ) ; -#30818 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749907037, 179.6299767372991312, 101.6260513917314796 ) ) ; -#30819 = LINE ( 'NONE', #11609, #34435 ) ; -#30820 = CARTESIAN_POINT ( 'NONE', ( 26.03550245107076933, 190.8511564191358900, 106.7775725292634945 ) ) ; -#30821 = ORIENTED_EDGE ( 'NONE', *, *, #34688, .T. ) ; -#30822 = LINE ( 'NONE', #24910, #4744 ) ; -#30823 = FACE_OUTER_BOUND ( 'NONE', #8175, .T. ) ; -#30824 = ADVANCED_FACE ( 'NONE', ( #39419 ), #4676, .F. ) ; -#30825 = ORIENTED_EDGE ( 'NONE', *, *, #20380, .F. ) ; -#30826 = LINE ( 'NONE', #37551, #10911 ) ; -#30827 = CARTESIAN_POINT ( 'NONE', ( -34.95638760652211374, 220.4002260770999726, 73.57961695561236581 ) ) ; -#30828 = AXIS2_PLACEMENT_3D ( 'NONE', #7941, #39011, #20615 ) ; -#30829 = ORIENTED_EDGE ( 'NONE', *, *, #35590, .F. ) ; -#30830 = DIRECTION ( 'NONE', ( -0.0005884949961233868539, 0.2249510543439054988, -0.9743698870671265722 ) ) ; -#30831 = AXIS2_PLACEMENT_3D ( 'NONE', #14711, #11640, #24114 ) ; -#30832 = EDGE_CURVE ( 'NONE', #32868, #35062, #14100, .T. ) ; -#30833 = AXIS2_PLACEMENT_3D ( 'NONE', #1319, #22222, #13407 ) ; -#30834 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#30835 = ORIENTED_EDGE ( 'NONE', *, *, #4582, .T. ) ; -#30836 = CYLINDRICAL_SURFACE ( 'NONE', #24923, 9.000000000000003553 ) ; -#30837 = EDGE_CURVE ( 'NONE', #6247, #3459, #781, .T. ) ; -#30838 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15116, #1163, #15893, #28588 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30839 = DIRECTION ( 'NONE', ( 0.0005884949961259158639, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#30840 = CARTESIAN_POINT ( 'NONE', ( -25.60907744188000379, 191.2754202488000033, 106.5082922742000022 ) ) ; -#30841 = CARTESIAN_POINT ( 'NONE', ( 25.49921952841093642, 118.5814822561333415, 87.75235346248901180 ) ) ; -#30842 = EDGE_CURVE ( 'NONE', #23779, #5998, #21248, .T. ) ; -#30843 = CARTESIAN_POINT ( 'NONE', ( -5.670781729043352648, 124.5528706720611183, 88.66790470360065513 ) ) ; -#30844 = ORIENTED_EDGE ( 'NONE', *, *, #18656, .F. ) ; -#30845 = ADVANCED_FACE ( 'NONE', ( #27996 ), #9175, .T. ) ; -#30846 = VERTEX_POINT ( 'NONE', #40430 ) ; -#30847 = CARTESIAN_POINT ( 'NONE', ( 15.12415969602515986, 146.0659008074709106, 180.8278994957862551 ) ) ; -#30848 = DIRECTION ( 'NONE', ( 0.7069870866307323976, -0.6508451585901298131, -0.2767125564140127114 ) ) ; -#30849 = CARTESIAN_POINT ( 'NONE', ( 22.49960432933178822, 158.3069096095373993, 96.18736459073451783 ) ) ; -#30850 = DIRECTION ( 'NONE', ( -0.6087611434179104331, -0.7731004625452351231, -0.1781166614240846935 ) ) ; -#30851 = ORIENTED_EDGE ( 'NONE', *, *, #34137, .T. ) ; -#30852 = ORIENTED_EDGE ( 'NONE', *, *, #858, .F. ) ; -#30853 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#30854 = DIRECTION ( 'NONE', ( -0.0006039748319386906410, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#30855 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#30856 = PLANE ( 'NONE', #4111 ) ; -#30857 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971565125 ) ) ; -#30858 = VECTOR ( 'NONE', #11614, 1000.000000000000114 ) ; -#30859 = AXIS2_PLACEMENT_3D ( 'NONE', #25884, #6632, #16243 ) ; -#30860 = CARTESIAN_POINT ( 'NONE', ( -5.668107805537519361, 123.6871559675325898, 91.29388376821638929 ) ) ; -#30861 = CIRCLE ( 'NONE', #7994, 2.000000000000011546 ) ; -#30862 = CARTESIAN_POINT ( 'NONE', ( -3.418257151934999793, 184.3972769734000394, 105.0487905064999978 ) ) ; -#30863 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; -#30864 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2252353050503803633, 0.9743043966640312359 ) ) ; -#30865 = DIRECTION ( 'NONE', ( 0.7066795774896457161, -3.556111233149506773E-18, -0.7075337269410242325 ) ) ; -#30866 = CYLINDRICAL_SURFACE ( 'NONE', #17851, 6.000000000000001776 ) ; -#30867 = LINE ( 'NONE', #31257, #12691 ) ; -#30868 = CARTESIAN_POINT ( 'NONE', ( -41.93243227727202793, 132.0857236358559135, 291.5838700735885709 ) ) ; -#30869 = CARTESIAN_POINT ( 'NONE', ( 37.96500113043519775, 190.9605824516280279, 106.2964067674099908 ) ) ; -#30870 = ORIENTED_EDGE ( 'NONE', *, *, #17436, .F. ) ; -#30871 = CARTESIAN_POINT ( 'NONE', ( 36.24487234395000002, 190.8173657113999866, 106.9127831590000000 ) ) ; -#30872 = ORIENTED_EDGE ( 'NONE', *, *, #25259, .T. ) ; -#30873 = VERTEX_POINT ( 'NONE', #5894 ) ; -#30874 = ORIENTED_EDGE ( 'NONE', *, *, #32216, .F. ) ; -#30875 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; -#30876 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5883, #17931, #18336, #14893 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.002841761714416722335 ), - .UNSPECIFIED. ) ; -#30877 = DIRECTION ( 'NONE', ( 9.113420628105814676E-11, 0.9743700558127087463, 0.2249510932081433268 ) ) ; -#30878 = EDGE_CURVE ( 'NONE', #23019, #39678, #33902, .T. ) ; -#30879 = EDGE_CURVE ( 'NONE', #982, #3120, #13203, .T. ) ; -#30880 = CARTESIAN_POINT ( 'NONE', ( -40.95578253733000196, 217.7719116638000401, 74.58324062236999907 ) ) ; -#30881 = EDGE_CURVE ( 'NONE', #11228, #24036, #28218, .T. ) ; -#30882 = EDGE_CURVE ( 'NONE', #31599, #16953, #27407, .T. ) ; -#30883 = ORIENTED_EDGE ( 'NONE', *, *, #25340, .T. ) ; -#30884 = DIRECTION ( 'NONE', ( 0.9999998184837881610, 0.000000000000000000, -0.0006025216930823954712 ) ) ; -#30885 = LINE ( 'NONE', #18773, #14280 ) ; -#30886 = CARTESIAN_POINT ( 'NONE', ( 47.33272938907029470, 69.51964883234494152, 321.8667867251971302 ) ) ; -#30887 = AXIS2_PLACEMENT_3D ( 'NONE', #4388, #35648, #7661 ) ; -#30888 = ORIENTED_EDGE ( 'NONE', *, *, #18944, .T. ) ; -#30889 = EDGE_CURVE ( 'NONE', #9009, #6112, #18404, .T. ) ; -#30890 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; -#30891 = CARTESIAN_POINT ( 'NONE', ( -45.39773774286052088, 124.2994142384970218, 88.45363130071420699 ) ) ; -#30892 = DIRECTION ( 'NONE', ( 0.7075229215369458480, 9.360719862056602573E-05, 0.7066903895890456200 ) ) ; -#30893 = AXIS2_PLACEMENT_3D ( 'NONE', #21979, #21585, #21166 ) ; -#30894 = LINE ( 'NONE', #22294, #11099 ) ; -#30895 = CARTESIAN_POINT ( 'NONE', ( -23.01879311717446086, 214.0903458147471383, 76.07243274013872281 ) ) ; -#30896 = ADVANCED_FACE ( 'NONE', ( #8777 ), #24523, .T. ) ; -#30897 = ORIENTED_EDGE ( 'NONE', *, *, #18798, .T. ) ; -#30898 = CARTESIAN_POINT ( 'NONE', ( -28.40995515711000152, 186.9781618348000052, 103.2258058761999990 ) ) ; -#30899 = CONICAL_SURFACE ( 'NONE', #13287, 2.499999999755544877, 0.7853981633651736516 ) ; -#30900 = CARTESIAN_POINT ( 'NONE', ( 2.840598881635000073, 190.4675684574999934, 103.7878333129000055 ) ) ; -#30901 = CARTESIAN_POINT ( 'NONE', ( 3.047144816660192657, 209.7096538831000032, 78.05666459524968559 ) ) ; -#30902 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27573, #39999, #8950, #9342 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999909300445012361 ), - .UNSPECIFIED. ) ; -#30903 = VERTEX_POINT ( 'NONE', #27794 ) ; -#30904 = LINE ( 'NONE', #2876, #20519 ) ; -#30905 = EDGE_LOOP ( 'NONE', ( #32148, #33966, #40080, #38252 ) ) ; -#30906 = EDGE_CURVE ( 'NONE', #15817, #8959, #26531, .T. ) ; -#30907 = LINE ( 'NONE', #28439, #7340 ) ; -#30908 = CARTESIAN_POINT ( 'NONE', ( -37.93624021805000268, 191.4653865237999923, 104.1593327167000069 ) ) ; -#30909 = LINE ( 'NONE', #18208, #33240 ) ; -#30910 = CARTESIAN_POINT ( 'NONE', ( 20.50153854971994960, 118.8155953598612484, 89.75541792533370256 ) ) ; -#30911 = ORIENTED_EDGE ( 'NONE', *, *, #123, .T. ) ; -#30912 = CARTESIAN_POINT ( 'NONE', ( -20.89111388057672158, 175.7038788979348283, 103.3088927995675590 ) ) ; -#30913 = CARTESIAN_POINT ( 'NONE', ( -1.216627282320019932, 189.1585234522316341, 105.7841143928696823 ) ) ; -#30914 = CIRCLE ( 'NONE', #36109, 8.000000000000007105 ) ; -#30915 = EDGE_LOOP ( 'NONE', ( #20717, #21634, #16242, #28801, #11711, #27220, #15293, #5144 ) ) ; -#30916 = CARTESIAN_POINT ( 'NONE', ( 28.52919418227002879, 125.2871234584923883, 88.56050369811191558 ) ) ; -#30917 = CARTESIAN_POINT ( 'NONE', ( 37.63914288645734274, 212.5463740004862245, 75.70243813626552765 ) ) ; -#30918 = CARTESIAN_POINT ( 'NONE', ( -15.74838202838000178, 184.8155507445000012, 105.1528037194999996 ) ) ; -#30919 = VECTOR ( 'NONE', #27273, 1000.000000000000000 ) ; -#30921 = CARTESIAN_POINT ( 'NONE', ( 16.22118037345659403, 122.3444927893303174, 173.3954680681185039 ) ) ; -#30920 = CARTESIAN_POINT ( 'NONE', ( 28.46561152642233949, 127.9145563745610872, 92.24604368512542862 ) ) ; -#30922 = VECTOR ( 'NONE', #23960, 999.9999999999998863 ) ; -#30923 = VERTEX_POINT ( 'NONE', #37182 ) ; -#30924 = EDGE_CURVE ( 'NONE', #31880, #14883, #20201, .T. ) ; -#30925 = CARTESIAN_POINT ( 'NONE', ( -13.49852954173680430, 160.1760870560666774, 99.20639934581299713 ) ) ; -#30926 = EDGE_CURVE ( 'NONE', #6128, #8723, #27053, .T. ) ; -#30927 = ADVANCED_FACE ( 'NONE', ( #15693 ), #34189, .F. ) ; -#30928 = ORIENTED_EDGE ( 'NONE', *, *, #32607, .T. ) ; -#30929 = CARTESIAN_POINT ( 'NONE', ( -26.07387125551695561, 121.1687737160897740, 90.72159716644539174 ) ) ; -#30930 = CARTESIAN_POINT ( 'NONE', ( 14.02725226625147847, 182.0693359945237546, 101.6784694239287319 ) ) ; -#30931 = CARTESIAN_POINT ( 'NONE', ( 36.04442091094806244, 218.5902260770999987, 73.53673424655958968 ) ) ; -#30932 = CARTESIAN_POINT ( 'NONE', ( 29.52631484424119890, 130.7952929006900717, 89.83156063865355634 ) ) ; -#30933 = CARTESIAN_POINT ( 'NONE', ( -34.95668960139003900, 225.9002260769516965, 73.07961704682827531 ) ) ; -#30934 = VERTEX_POINT ( 'NONE', #32061 ) ; -#30935 = ORIENTED_EDGE ( 'NONE', *, *, #15898, .T. ) ; -#30936 = PLANE ( 'NONE', #26615 ) ; -#30937 = FACE_OUTER_BOUND ( 'NONE', #24912, .T. ) ; -#30938 = DIRECTION ( 'NONE', ( 0.1305262373691798983, -0.9659583596717404852, -0.2233547598295697878 ) ) ; -#30939 = EDGE_CURVE ( 'NONE', #2592, #8692, #25600, .T. ) ; -#30940 = EDGE_LOOP ( 'NONE', ( #39305, #15275 ) ) ; -#30941 = CARTESIAN_POINT ( 'NONE', ( 15.53173119598054264, 162.3883494940283185, 152.4706590695620605 ) ) ; -#30942 = AXIS2_PLACEMENT_3D ( 'NONE', #3316, #6986, #25627 ) ; -#30943 = VECTOR ( 'NONE', #11654, 1000.000000000000000 ) ; -#30944 = LINE ( 'NONE', #2914, #29287 ) ; -#30945 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #14363, #38879 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30946 = VECTOR ( 'NONE', #11061, 1000.000000000000114 ) ; -#30947 = CARTESIAN_POINT ( 'NONE', ( 2.880315910408000057, 190.5847237225000299, 106.5537292353999987 ) ) ; -#30948 = CARTESIAN_POINT ( 'NONE', ( -94.40216589637994105, 221.9412051121879301, 195.0241205818432491 ) ) ; -#30949 = ADVANCED_FACE ( 'NONE', ( #31450 ), #23647, .F. ) ; -#30950 = DIRECTION ( 'NONE', ( 0.0005884949961241158715, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#30951 = CARTESIAN_POINT ( 'NONE', ( 23.36337295639098244, 183.5654497021793645, 104.5839965068618227 ) ) ; -#30952 = CARTESIAN_POINT ( 'NONE', ( -20.89285664280696864, 129.6089482465050366, 89.58812326051432251 ) ) ; -#30953 = ORIENTED_EDGE ( 'NONE', *, *, #14592, .F. ) ; -#30954 = CARTESIAN_POINT ( 'NONE', ( 25.99887565026168090, 119.3449815503509228, 87.25209341632874782 ) ) ; -#30955 = CARTESIAN_POINT ( 'NONE', ( 21.70190315701263017, 123.1837599801819465, 176.5257127422096914 ) ) ; -#30956 = LINE ( 'NONE', #27908, #3211 ) ; -#30957 = ORIENTED_EDGE ( 'NONE', *, *, #15816, .T. ) ; -#30958 = CARTESIAN_POINT ( 'NONE', ( -5.662686464640452222, 188.3429660633563287, 103.1387990589197869 ) ) ; -#30959 = ORIENTED_EDGE ( 'NONE', *, *, #24156, .T. ) ; -#30961 = CARTESIAN_POINT ( 'NONE', ( 35.58101881484880380, 192.1430711721313855, 103.8930328919773274 ) ) ; -#30960 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566790 ) ) ; -#30962 = ORIENTED_EDGE ( 'NONE', *, *, #22432, .F. ) ; -#30963 = ORIENTED_EDGE ( 'NONE', *, *, #11825, .T. ) ; -#30964 = AXIS2_PLACEMENT_3D ( 'NONE', #4061, #16532, #1006 ) ; -#30965 = CONICAL_SURFACE ( 'NONE', #6777, 5.999999999929134908, 0.7853981633778842619 ) ; -#30966 = ORIENTED_EDGE ( 'NONE', *, *, #7321, .T. ) ; -#30967 = CARTESIAN_POINT ( 'NONE', ( -23.36160748208693150, 137.2394037007878183, 91.86439624240760793 ) ) ; -#30968 = CARTESIAN_POINT ( 'NONE', ( -45.03708708209951084, 124.0713768683079081, 93.45577792510331960 ) ) ; -#30969 = CARTESIAN_POINT ( 'NONE', ( -12.63793204807000770, 135.2920832175974510, 91.40834497109533174 ) ) ; -#30970 = EDGE_CURVE ( 'NONE', #37138, #13070, #6513, .T. ) ; -#30971 = EDGE_LOOP ( 'NONE', ( #26971, #28322, #35481, #23253 ) ) ; -#30973 = ADVANCED_FACE ( 'NONE', ( #3415 ), #34704, .F. ) ; -#30972 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6790, #19060, #31557, #19257 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#30974 = EDGE_LOOP ( 'NONE', ( #15329, #9458, #4952, #111 ) ) ; -#30975 = ORIENTED_EDGE ( 'NONE', *, *, #20468, .F. ) ; -#30976 = DIRECTION ( 'NONE', ( 0.0005884949961216158097, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#30977 = CARTESIAN_POINT ( 'NONE', ( 4.035087735728000169, 174.6768175980000137, 101.5172632219999969 ) ) ; -#30978 = DIRECTION ( 'NONE', ( 0.0005884956407902205500, -0.2249510534665960237, 0.9743698872692800883 ) ) ; -#30979 = DIRECTION ( 'NONE', ( -0.0005884949961224158425, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#30980 = FACE_OUTER_BOUND ( 'NONE', #217, .T. ) ; -#30981 = ORIENTED_EDGE ( 'NONE', *, *, #19991, .T. ) ; -#30982 = VERTEX_POINT ( 'NONE', #10586 ) ; -#30983 = FACE_OUTER_BOUND ( 'NONE', #2130, .T. ) ; -#30984 = DIRECTION ( 'NONE', ( -0.1305262453914154686, 0.9659761156053645603, 0.2232779508683992165 ) ) ; -#30985 = CARTESIAN_POINT ( 'NONE', ( 39.74198101999568422, 169.1998828075846575, 164.4809833079056887 ) ) ; -#30986 = CARTESIAN_POINT ( 'NONE', ( -26.66109084696000053, 123.9341801008000061, 88.62365338252001834 ) ) ; -#30987 = ORIENTED_EDGE ( 'NONE', *, *, #17309, .F. ) ; -#30988 = ORIENTED_EDGE ( 'NONE', *, *, #35597, .F. ) ; -#30989 = CARTESIAN_POINT ( 'NONE', ( 20.05333031552076051, 184.3083097996710933, 105.2176979012920697 ) ) ; -#30990 = CARTESIAN_POINT ( 'NONE', ( 20.48580071746687281, 209.7097554882793702, 78.04612426987789320 ) ) ; -#30991 = CARTESIAN_POINT ( 'NONE', ( -40.91725980310987865, 188.6757777993018692, 107.4960952986480152 ) ) ; -#30992 = ORIENTED_EDGE ( 'NONE', *, *, #29078, .T. ) ; -#30993 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#30994 = CARTESIAN_POINT ( 'NONE', ( 14.55306318046054592, 176.9232825744718411, 100.4900915860747403 ) ) ; -#30995 = VECTOR ( 'NONE', #20218, 1000.000000000000000 ) ; -#30996 = EDGE_CURVE ( 'NONE', #21098, #39629, #10457, .T. ) ; -#30997 = DIRECTION ( 'NONE', ( -0.0005884949961239134509, 0.2249510543439059707, -0.9743698870671263501 ) ) ; -#30998 = AXIS2_PLACEMENT_3D ( 'NONE', #13248, #16295, #26730 ) ; -#30999 = AXIS2_PLACEMENT_3D ( 'NONE', #30232, #5274, #2232 ) ; -#31000 = FACE_OUTER_BOUND ( 'NONE', #25626, .T. ) ; -#31001 = ORIENTED_EDGE ( 'NONE', *, *, #4215, .F. ) ; -#31002 = LINE ( 'NONE', #11796, #2114 ) ; -#31003 = CONICAL_SURFACE ( 'NONE', #4172, 6.502999999940457521, 0.7853981633531327278 ) ; -#31004 = CARTESIAN_POINT ( 'NONE', ( 36.55249482085380208, 80.25314331434174164, 289.8258038402724992 ) ) ; -#31005 = CARTESIAN_POINT ( 'NONE', ( -37.63159775036000099, 118.5781719367000022, 87.39224945975999503 ) ) ; -#31006 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#31007 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#31008 = VERTEX_POINT ( 'NONE', #6683 ) ; -#31009 = CARTESIAN_POINT ( 'NONE', ( -43.19369327228462652, 172.6130766527593892, 183.6332436169467712 ) ) ; -#31010 = ORIENTED_EDGE ( 'NONE', *, *, #26416, .T. ) ; -#31011 = EDGE_CURVE ( 'NONE', #7592, #7007, #25616, .T. ) ; -#31012 = CARTESIAN_POINT ( 'NONE', ( -38.37822306518999937, 118.5483362540999934, 89.85072421485999428 ) ) ; -#31013 = EDGE_LOOP ( 'NONE', ( #25139, #6241, #7763, #8741 ) ) ; -#31014 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930882562 ) ) ; -#31015 = CARTESIAN_POINT ( 'NONE', ( -32.65040898612480191, 153.0051697192221241, 291.5764532040477093 ) ) ; -#31016 = CARTESIAN_POINT ( 'NONE', ( 18.00147123749098554, 179.1800746285791206, 103.5747911657629601 ) ) ; -#31017 = CARTESIAN_POINT ( 'NONE', ( 23.36273455199158278, 177.2438047235408760, 101.0299531551032146 ) ) ; -#31018 = EDGE_CURVE ( 'NONE', #26136, #13855, #29493, .T. ) ; -#31019 = ADVANCED_FACE ( 'NONE', ( #35083 ), #13045, .T. ) ; -#31020 = CARTESIAN_POINT ( 'NONE', ( 31.84188692585000169, 220.4002260771000010, 152.4718672074000381 ) ) ; -#31021 = VERTEX_POINT ( 'NONE', #25733 ) ; -#31022 = AXIS2_PLACEMENT_3D ( 'NONE', #4575, #13993, #17442 ) ; -#31023 = EDGE_CURVE ( 'NONE', #5506, #26460, #38375, .T. ) ; -#31024 = ORIENTED_EDGE ( 'NONE', *, *, #19759, .F. ) ; -#31025 = CARTESIAN_POINT ( 'NONE', ( -19.70060805389840297, 149.2630956751775955, 182.5538467380586098 ) ) ; -#31026 = CARTESIAN_POINT ( 'NONE', ( -32.66145081237952041, 191.5260128943200471, 103.8899145187908175 ) ) ; -#31027 = CIRCLE ( 'NONE', #36203, 2.500000000045985438 ) ; -#31028 = FACE_OUTER_BOUND ( 'NONE', #18462, .T. ) ; -#31029 = AXIS2_PLACEMENT_3D ( 'NONE', #903, #13390, #38323 ) ; -#31030 = ORIENTED_EDGE ( 'NONE', *, *, #33811, .T. ) ; -#31031 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; -#31032 = VECTOR ( 'NONE', #6450, 1000.000000000000114 ) ; -#31033 = ORIENTED_EDGE ( 'NONE', *, *, #6121, .F. ) ; -#31035 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524157562, 149.3470289647612219, 130.0514119197758305 ) ) ; -#31034 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #14246, #10976, #13829, #16685 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 6.160373448998780255, 6.403395894008630407 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9950843936374926813, 0.9950843936374926813, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#31036 = LINE ( 'NONE', #9359, #26722 ) ; -#31037 = ORIENTED_EDGE ( 'NONE', *, *, #26154, .T. ) ; -#31038 = CARTESIAN_POINT ( 'NONE', ( -38.82926470596208901, 119.3584309079524246, 90.32664788632943953 ) ) ; -#31039 = CARTESIAN_POINT ( 'NONE', ( 3.760861305702880131, 167.8747276737439620, 101.2555565256170951 ) ) ; -#31040 = CARTESIAN_POINT ( 'NONE', ( -25.35577217468999933, 191.5262698070999932, 106.2802080165999996 ) ) ; -#31041 = CARTESIAN_POINT ( 'NONE', ( 30.07825772506129525, 177.1204444582162409, 103.6051399121813859 ) ) ; -#31042 = CARTESIAN_POINT ( 'NONE', ( 4.017041573755003370, 124.9646835441209021, 88.50086511966965475 ) ) ; -#31043 = ORIENTED_EDGE ( 'NONE', *, *, #10960, .T. ) ; -#31044 = CARTESIAN_POINT ( 'NONE', ( 21.59709472431439181, 115.2762503876805624, 188.9250028067568508 ) ) ; -#31045 = CARTESIAN_POINT ( 'NONE', ( 37.32096841862673386, 164.8291704540998523, 197.3151593714009380 ) ) ; -#31046 = CARTESIAN_POINT ( 'NONE', ( -15.94435338216056230, 121.6615746736106303, 175.4535042054991436 ) ) ; -#31047 = CARTESIAN_POINT ( 'NONE', ( -45.82946015665383754, 124.9267195748215755, 91.89216530322958931 ) ) ; -#31048 = VERTEX_POINT ( 'NONE', #6481 ) ; -#31049 = ORIENTED_EDGE ( 'NONE', *, *, #7413, .T. ) ; -#31050 = CARTESIAN_POINT ( 'NONE', ( 38.22623376675434059, 118.8155667128057615, 90.24469678293085906 ) ) ; -#31051 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26771, #11225, #36152, #8150 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31052 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#31053 = PLANE ( 'NONE', #4573 ) ; -#31054 = AXIS2_PLACEMENT_3D ( 'NONE', #28465, #21737, #21938 ) ; -#31055 = CONICAL_SURFACE ( 'NONE', #12116, 2.499999999913497195, 0.7853981633683820851 ) ; -#31056 = DIRECTION ( 'NONE', ( -0.7933533411653045375, 0.5930537057989968552, 0.1373964268091591723 ) ) ; -#31057 = CARTESIAN_POINT ( 'NONE', ( -26.03762553832000037, 190.4430459227999961, 106.7148042862000068 ) ) ; -#31058 = EDGE_CURVE ( 'NONE', #29757, #19715, #13246, .T. ) ; -#31059 = AXIS2_PLACEMENT_3D ( 'NONE', #35499, #38402, #6707 ) ; -#31060 = CARTESIAN_POINT ( 'NONE', ( 6.035817316620117445, 176.7425654412684537, 103.0192746809948403 ) ) ; -#31061 = EDGE_CURVE ( 'NONE', #12211, #4391, #13842, .T. ) ; -#31062 = APPROVAL_ROLE ( '' ) ; -#31063 = CARTESIAN_POINT ( 'NONE', ( 20.50029381459107825, 138.3995138255986603, 92.10573732912574485 ) ) ; -#31064 = PLANE ( 'NONE', #28977 ) ; -#31065 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921571859, -0.2249510932971622024 ) ) ; -#31066 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11902, #9030, #39687, #33757 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999909299021982889 ), - .UNSPECIFIED. ) ; -#31067 = FACE_OUTER_BOUND ( 'NONE', #22964, .T. ) ; -#31068 = CARTESIAN_POINT ( 'NONE', ( 36.18931259780619314, 192.0080012320809999, 104.3455603723210174 ) ) ; -#31069 = EDGE_CURVE ( 'NONE', #36902, #604, #32111, .T. ) ; -#31070 = EDGE_CURVE ( 'NONE', #39281, #20961, #26324, .T. ) ; -#31071 = ORIENTED_EDGE ( 'NONE', *, *, #558, .F. ) ; -#31073 = EDGE_LOOP ( 'NONE', ( #17569, #35729, #34726, #35374 ) ) ; -#31072 = CARTESIAN_POINT ( 'NONE', ( 36.82112145928000047, 191.5024862555000027, 106.2217677218000063 ) ) ; -#31074 = ORIENTED_EDGE ( 'NONE', *, *, #8645, .F. ) ; -#31075 = EDGE_LOOP ( 'NONE', ( #32745, #15391, #26258, #11695 ) ) ; -#31076 = EDGE_CURVE ( 'NONE', #604, #24326, #5228, .T. ) ; -#31077 = CARTESIAN_POINT ( 'NONE', ( 31.54582148684999865, 177.9538242463000302, 164.9590253462000362 ) ) ; -#31078 = ADVANCED_FACE ( 'NONE', ( #4625 ), #16881, .T. ) ; -#31079 = CARTESIAN_POINT ( 'NONE', ( -20.24140383769758955, 184.9064092065293892, 102.6020569953306705 ) ) ; -#31080 = VECTOR ( 'NONE', #21276, 1000.000000000000227 ) ; -#31081 = CARTESIAN_POINT ( 'NONE', ( -32.50869459978976295, 175.9851385237510328, 100.3019280490168512 ) ) ; -#31082 = AXIS2_PLACEMENT_3D ( 'NONE', #18812, #15567, #28255 ) ; -#31083 = ORIENTED_EDGE ( 'NONE', *, *, #8308, .F. ) ; -#31084 = VECTOR ( 'NONE', #14054, 1000.000000000000114 ) ; -#31085 = CARTESIAN_POINT ( 'NONE', ( 42.93478411035056297, 121.9318606513537020, 87.77717731540884927 ) ) ; -#31086 = CARTESIAN_POINT ( 'NONE', ( 3.667815741532966189, 126.2406713581920599, 91.36142183184406917 ) ) ; -#31087 = PLANE ( 'NONE', #6604 ) ; -#31088 = VERTEX_POINT ( 'NONE', #11180 ) ; -#31089 = AXIS2_PLACEMENT_3D ( 'NONE', #3049, #9603, #18768 ) ; -#31090 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825948087824765, 0.0005734119017360681013 ) ) ; -#31091 = DIRECTION ( 'NONE', ( -0.000000000000000000, -1.000000000000000000, 0.000000000000000000 ) ) ; -#31092 = AXIS2_PLACEMENT_3D ( 'NONE', #30990, #39763, #2956 ) ; -#31093 = CARTESIAN_POINT ( 'NONE', ( -20.00004361580415591, 118.8155695144462669, 87.27991261026372172 ) ) ; -#31094 = CARTESIAN_POINT ( 'NONE', ( -24.42746481139502279, 103.6131156702177094, 87.78253795974556795 ) ) ; -#31095 = EDGE_LOOP ( 'NONE', ( #14655, #22281, #24239, #4456 ) ) ; -#31096 = CARTESIAN_POINT ( 'NONE', ( 16.00151820029350702, 137.8265450205371394, 94.54185288967525480 ) ) ; -#31097 = CARTESIAN_POINT ( 'NONE', ( 2.553143702803999826, 190.9977876359000106, 104.2699393190000023 ) ) ; -#31098 = CARTESIAN_POINT ( 'NONE', ( 16.24603267945985507, 152.0453547567774706, 181.0525560685096593 ) ) ; -#31099 = EDGE_LOOP ( 'NONE', ( #12024, #6014, #32924, #7140, #8031, #19619 ) ) ; -#31100 = VERTEX_POINT ( 'NONE', #23654 ) ; -#31101 = CARTESIAN_POINT ( 'NONE', ( -38.45417236430746755, 119.6409147006968823, 87.33694759259822149 ) ) ; -#31102 = ORIENTED_EDGE ( 'NONE', *, *, #25439, .F. ) ; -#31103 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31442, #6084, #15881, #34282, #24318, #40423, #18536, #12235, #6278, #31041 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000001353917, 0.3750000000002030598, 0.4375000000002060019, 0.5000000000002089440, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31104 = ADVANCED_FACE ( 'NONE', ( #20780 ), #22347, .F. ) ; -#31105 = VECTOR ( 'NONE', #1336, 999.9999999999998863 ) ; -#31106 = EDGE_CURVE ( 'NONE', #3689, #21726, #12915, .T. ) ; -#31107 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #5223, #24475, #2184, #14858 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.609997058757503652, 4.712388980384670134 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9012658660484214046, 0.9012658660484214046, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#31108 = VECTOR ( 'NONE', #35959, 1000.000000000000000 ) ; -#31109 = CARTESIAN_POINT ( 'NONE', ( 12.31198009898977297, 134.9205818654068025, 90.79431936396761671 ) ) ; -#31110 = VECTOR ( 'NONE', #7441, 1000.000000000000000 ) ; -#31111 = CARTESIAN_POINT ( 'NONE', ( -37.21730312380855565, 191.0563982775359477, 106.3396948499198658 ) ) ; -#31112 = EDGE_CURVE ( 'NONE', #12877, #35118, #26942, .T. ) ; -#31113 = CARTESIAN_POINT ( 'NONE', ( 3.578322037524656274, 149.3470289647502511, 130.0514119197545142 ) ) ; -#31114 = CARTESIAN_POINT ( 'NONE', ( -5.670666054933423794, 181.8752443071280709, 101.9019012075243609 ) ) ; -#31115 = CARTESIAN_POINT ( 'NONE', ( -2.371600584370171738, 190.4347757011841509, 106.1523463772184215 ) ) ; -#31116 = VERTEX_POINT ( 'NONE', #14661 ) ; -#31117 = AXIS2_PLACEMENT_3D ( 'NONE', #32280, #13075, #9809 ) ; -#31118 = EDGE_CURVE ( 'NONE', #24370, #39941, #6009, .T. ) ; -#31119 = CYLINDRICAL_SURFACE ( 'NONE', #9405, 6.000000000000008882 ) ; -#31120 = CARTESIAN_POINT ( 'NONE', ( 37.56516904143808233, 212.6956748481447335, 75.86914951168479604 ) ) ; -#31121 = DIRECTION ( 'NONE', ( -0.7933532970003740470, -0.5930762008556723641, -0.1372995488602875569 ) ) ; -#31123 = CARTESIAN_POINT ( 'NONE', ( 36.05382442437669965, 112.9281706447458760, 87.74600877593400128 ) ) ; -#31122 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 1.739499925770551072E-30, 0.0006039748319385906776 ) ) ; -#31124 = ORIENTED_EDGE ( 'NONE', *, *, #35974, .F. ) ; -#31125 = EDGE_CURVE ( 'NONE', #3122, #22426, #2752, .T. ) ; -#31126 = ORIENTED_EDGE ( 'NONE', *, *, #25537, .T. ) ; -#31127 = DIRECTION ( 'NONE', ( 0.0004161288024631969499, -0.8480480897833772014, 0.5299191110458129073 ) ) ; -#31128 = LINE ( 'NONE', #3098, #5415 ) ; -#31129 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2431, #27394, #24315, #24721, #40025, #24921 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 4.416197448658278450E-07, 0.001508600510335431381, 0.003016759400925997196 ), - .UNSPECIFIED. ) ; -#31130 = ORIENTED_EDGE ( 'NONE', *, *, #25306, .T. ) ; -#31131 = CARTESIAN_POINT ( 'NONE', ( -39.69723568842041317, 114.7507352566516943, 151.7663457455989544 ) ) ; -#31132 = DIRECTION ( 'NONE', ( -2.775557561558865794E-15, -0.9743700557921587402, -0.2249510932971555965 ) ) ; -#31133 = CARTESIAN_POINT ( 'NONE', ( 15.83500089607693617, 184.3280936476482452, 105.1067149263252105 ) ) ; -#31134 = DIRECTION ( 'NONE', ( -6.681078215644284579E-11, 0.9743700557771369786, 0.2249510933622214381 ) ) ; -#31135 = ORIENTED_EDGE ( 'NONE', *, *, #17794, .F. ) ; -#31136 = LINE ( 'NONE', #25811, #14719 ) ; -#31137 = VERTEX_POINT ( 'NONE', #36102 ) ; -#31138 = AXIS2_PLACEMENT_3D ( 'NONE', #6222, #31182, #21392 ) ; -#31139 = CARTESIAN_POINT ( 'NONE', ( 5.663463790603415760, 124.4575615037363860, 88.50647768129195470 ) ) ; -#31140 = CARTESIAN_POINT ( 'NONE', ( -1.762796035792233207, 151.6652447683722471, 130.5904578368917441 ) ) ; -#31141 = AXIS2_PLACEMENT_3D ( 'NONE', #14741, #8609, #5729 ) ; -#31142 = FACE_OUTER_BOUND ( 'NONE', #34662, .T. ) ; -#31143 = CARTESIAN_POINT ( 'NONE', ( -13.49836187949013322, 187.2925309095741113, 105.4667247238223524 ) ) ; -#31144 = ORIENTED_EDGE ( 'NONE', *, *, #28656, .F. ) ; -#31145 = LINE ( 'NONE', #30941, #16067 ) ; -#31146 = CARTESIAN_POINT ( 'NONE', ( 0.7586617867642599933, 188.6208944900433835, 103.1990300548870181 ) ) ; -#31147 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 132.9726895863779532, 90.34121396988804520 ) ) ; -#31148 = EDGE_LOOP ( 'NONE', ( #21686, #33286 ) ) ; -#31149 = CARTESIAN_POINT ( 'NONE', ( 2.729957264165000286, 190.8363048546000016, 106.4417122540999969 ) ) ; -#31150 = CARTESIAN_POINT ( 'NONE', ( 13.49481983871936386, 124.3681642032378534, 88.35737770391504853 ) ) ; -#31151 = CARTESIAN_POINT ( 'NONE', ( 36.28566749807773562, 191.4195153028702236, 103.8236852762196492 ) ) ; -#31152 = CARTESIAN_POINT ( 'NONE', ( -25.36508458611999828, 120.1656809584000030, 89.83749781794000455 ) ) ; -#31153 = EDGE_CURVE ( 'NONE', #24029, #20341, #10781, .T. ) ; -#31154 = EDGE_CURVE ( 'NONE', #25978, #23623, #30150, .T. ) ; -#31155 = ORIENTED_EDGE ( 'NONE', *, *, #20608, .T. ) ; -#31156 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557843820720, -0.2249510933308394578 ) ) ; -#31157 = EDGE_CURVE ( 'NONE', #12808, #33829, #35336, .T. ) ; -#31158 = CARTESIAN_POINT ( 'NONE', ( -16.54012570822575157, 121.8328361328813543, 177.5596287226420316 ) ) ; -#31159 = EDGE_CURVE ( 'NONE', #796, #39798, #36683, .T. ) ; -#31160 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -7.515125404477462028E-16, 0.0006039748319388944710 ) ) ; -#31161 = CARTESIAN_POINT ( 'NONE', ( -20.11801462494291215, 127.0926108250165498, 91.96276686944507617 ) ) ; -#31162 = VERTEX_POINT ( 'NONE', #39178 ) ; -#31163 = AXIS2_PLACEMENT_3D ( 'NONE', #15017, #39942, #8784 ) ; -#31164 = CARTESIAN_POINT ( 'NONE', ( 32.36006137438955221, 209.7096916965322180, 73.03895941624857358 ) ) ; -#31165 = ORIENTED_EDGE ( 'NONE', *, *, #29618, .T. ) ; -#31166 = VECTOR ( 'NONE', #32282, 1000.000000000000114 ) ; -#31167 = CIRCLE ( 'NONE', #2454, 1.999999999953854024 ) ; -#31169 = CARTESIAN_POINT ( 'NONE', ( 0.5623190733617040582, 188.6124699482102756, 103.1972064621602527 ) ) ; -#31168 = DIRECTION ( 'NONE', ( 0.0005884949961237983087, -0.2249510543439047772, 0.9743698870671267942 ) ) ; -#31170 = VERTEX_POINT ( 'NONE', #35894 ) ; -#31171 = EDGE_CURVE ( 'NONE', #11449, #39475, #7695, .T. ) ; -#31172 = EDGE_LOOP ( 'NONE', ( #32299, #14199, #17131, #16861 ) ) ; -#31173 = CARTESIAN_POINT ( 'NONE', ( 2.835810955472000572, 209.6480747013999917, 75.93553738705000455 ) ) ; -#31174 = DIRECTION ( 'NONE', ( -0.0005884949961206489182, 0.2249510543439051102, -0.9743698870671265722 ) ) ; -#31175 = VERTEX_POINT ( 'NONE', #29387 ) ; -#31176 = ORIENTED_EDGE ( 'NONE', *, *, #6264, .F. ) ; -#31177 = CARTESIAN_POINT ( 'NONE', ( 35.04524256069624499, 220.4002260770989778, 73.53733772514158318 ) ) ; -#31178 = FACE_OUTER_BOUND ( 'NONE', #20981, .T. ) ; -#31179 = CARTESIAN_POINT ( 'NONE', ( 29.05442967595000070, 110.6131156702000027, 88.75023641814000541 ) ) ; -#31180 = ORIENTED_EDGE ( 'NONE', *, *, #22077, .F. ) ; -#31181 = ORIENTED_EDGE ( 'NONE', *, *, #21051, .F. ) ; -#31182 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#31183 = CARTESIAN_POINT ( 'NONE', ( -30.07038801301974473, 136.6761377446392487, 94.30416869774899169 ) ) ; -#31184 = CARTESIAN_POINT ( 'NONE', ( -26.52264724072000135, 123.9893196918000058, 88.80742175707999309 ) ) ; -#31185 = ORIENTED_EDGE ( 'NONE', *, *, #17296, .F. ) ; -#31186 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749898865, 177.4376441116277761, 101.1199114316599577 ) ) ; -#31187 = CARTESIAN_POINT ( 'NONE', ( 40.86755754141834274, 188.5902530340942178, 107.5428458308915509 ) ) ; -#31188 = VERTEX_POINT ( 'NONE', #19952 ) ; -#31189 = VECTOR ( 'NONE', #27282, 1000.000000000000114 ) ; -#31190 = CARTESIAN_POINT ( 'NONE', ( 39.01707480719999666, 142.5739022138000109, 26.89884147244999824 ) ) ; -#31191 = CARTESIAN_POINT ( 'NONE', ( -38.90215727773150434, 162.5678425802583433, 197.7383679064734565 ) ) ; -#31192 = AXIS2_PLACEMENT_3D ( 'NONE', #20174, #17509, #26151 ) ; -#31193 = CARTESIAN_POINT ( 'NONE', ( -45.05010495504543400, 181.2316974417921074, 101.8628679662392642 ) ) ; -#31194 = CARTESIAN_POINT ( 'NONE', ( 27.78438839505666991, 188.0117751643121267, 103.0420822765563855 ) ) ; -#31195 = ORIENTED_EDGE ( 'NONE', *, *, #814, .T. ) ; -#31196 = CARTESIAN_POINT ( 'NONE', ( 12.63825826684001719, 182.0651920382574076, 102.1915037821187440 ) ) ; -#31197 = VERTEX_POINT ( 'NONE', #1355 ) ; -#31198 = ADVANCED_FACE ( 'NONE', ( #8108 ), #9942, .F. ) ; -#31199 = CARTESIAN_POINT ( 'NONE', ( -23.36170564740040234, 182.0604262685139361, 102.2121465934016129 ) ) ; -#31200 = EDGE_CURVE ( 'NONE', #11920, #11101, #40196, .T. ) ; -#31201 = FACE_OUTER_BOUND ( 'NONE', #27334, .T. ) ; -#31202 = CARTESIAN_POINT ( 'NONE', ( -14.29753817416625061, 182.6906998136370532, 102.1811316074132350 ) ) ; -#31203 = CARTESIAN_POINT ( 'NONE', ( 45.10956928938049515, 115.5709318062878168, 128.3132131271731851 ) ) ; -#31204 = ORIENTED_EDGE ( 'NONE', *, *, #35082, .F. ) ; -#31205 = FACE_OUTER_BOUND ( 'NONE', #23277, .T. ) ; -#31206 = ORIENTED_EDGE ( 'NONE', *, *, #14956, .T. ) ; -#31207 = CARTESIAN_POINT ( 'NONE', ( 47.95567328239271632, 139.9374889060051146, 291.1737358715798791 ) ) ; -#31208 = EDGE_LOOP ( 'NONE', ( #13512, #38159, #7820, #20580 ) ) ; -#31209 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971598709 ) ) ; -#31210 = AXIS2_PLACEMENT_3D ( 'NONE', #35769, #13930, #26411 ) ; -#31211 = CARTESIAN_POINT ( 'NONE', ( 22.53675382576999908, 124.4626272919999934, 152.4718672074000381 ) ) ; -#31212 = CARTESIAN_POINT ( 'NONE', ( -37.09602284966847208, 164.9667323745490251, 195.9811478980911374 ) ) ; -#31213 = DIRECTION ( 'NONE', ( 0.6087613186456907188, 0.7730177010543248795, 0.1784749023741044327 ) ) ; -#31214 = CARTESIAN_POINT ( 'NONE', ( 45.25615125966712782, 130.4019898035445522, 92.63912118957520647 ) ) ; -#31215 = CONICAL_SURFACE ( 'NONE', #13587, 2.749999999892358549, 0.7853981634430725611 ) ; -#31216 = ORIENTED_EDGE ( 'NONE', *, *, #26188, .T. ) ; -#31217 = EDGE_LOOP ( 'NONE', ( #13912, #5615, #19973, #27433, #22793, #20918, #7455, #13004 ) ) ; -#31218 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; -#31219 = CARTESIAN_POINT ( 'NONE', ( 1.273934745427919069, 189.1300036437734207, 105.7744582827584310 ) ) ; -#31220 = ADVANCED_FACE ( 'NONE', ( #5031 ), #15647, .F. ) ; -#31221 = CARTESIAN_POINT ( 'NONE', ( -37.39932010222903358, 212.8449755639020111, 76.08109288175667473 ) ) ; -#31222 = VERTEX_POINT ( 'NONE', #31196 ) ; -#31223 = CARTESIAN_POINT ( 'NONE', ( -23.36258829528358660, 135.1161733599290642, 91.13525200680678040 ) ) ; -#31224 = ORIENTED_EDGE ( 'NONE', *, *, #10166, .F. ) ; -#31225 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596101196, 128.5887768395678563, 89.32567453973172178 ) ) ; -#31226 = CARTESIAN_POINT ( 'NONE', ( -5.668459040265249271, 130.7309778812349350, 90.08599464117959599 ) ) ; -#31227 = VERTEX_POINT ( 'NONE', #2968 ) ; -#31228 = CARTESIAN_POINT ( 'NONE', ( 28.52226708450999837, 125.2835602215999984, 88.55890939917999560 ) ) ; -#31229 = CARTESIAN_POINT ( 'NONE', ( 25.57447242411126709, 211.0902261055813085, 73.45914216482992742 ) ) ; -#31230 = CARTESIAN_POINT ( 'NONE', ( -25.64662748966999928, 190.7220139133999908, 106.3869458739000038 ) ) ; -#31231 = CARTESIAN_POINT ( 'NONE', ( 45.31782503891692926, 120.7229189729074363, 105.4582906007348271 ) ) ; -#31232 = LINE ( 'NONE', #21645, #37389 ) ; -#31233 = ORIENTED_EDGE ( 'NONE', *, *, #16786, .F. ) ; -#31234 = CARTESIAN_POINT ( 'NONE', ( -35.43878503052407325, 193.8169247181471349, 102.7243139024822511 ) ) ; -#31235 = CARTESIAN_POINT ( 'NONE', ( -37.89691480486764164, 119.0726142382651886, 87.29510449627004220 ) ) ; -#31236 = LINE ( 'NONE', #12622, #14962 ) ; -#31237 = AXIS2_PLACEMENT_3D ( 'NONE', #26514, #17275, #5021 ) ; -#31238 = CARTESIAN_POINT ( 'NONE', ( 21.83140111251249493, 182.3124853075107978, 104.2956521028678054 ) ) ; -#31239 = EDGE_LOOP ( 'NONE', ( #18521, #37417, #1343, #5312 ) ) ; -#31240 = EDGE_CURVE ( 'NONE', #39849, #37286, #28896, .T. ) ; -#31241 = ORIENTED_EDGE ( 'NONE', *, *, #38519, .T. ) ; -#31242 = LINE ( 'NONE', #34884, #34893 ) ; -#31243 = ADVANCED_FACE ( 'NONE', ( #21804 ), #7990, .F. ) ; -#31244 = CARTESIAN_POINT ( 'NONE', ( 3.045964837637491485, 205.1071438019466484, 76.10297588903854660 ) ) ; -#31245 = VECTOR ( 'NONE', #20079, 1000.000000000000227 ) ; -#31246 = DIRECTION ( 'NONE', ( 0.0006039748319377988848, 1.383702340315400350E-14, 0.9999998176071845934 ) ) ; -#31247 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#31248 = ORIENTED_EDGE ( 'NONE', *, *, #2590, .F. ) ; -#31249 = CARTESIAN_POINT ( 'NONE', ( -25.83629999435114044, 190.9265745077870520, 106.6552633789108313 ) ) ; -#31250 = EDGE_LOOP ( 'NONE', ( #35157, #17211, #16661, #17614, #32026 ) ) ; -#31251 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19585, #4239, #4653, #19976, #34903, #6917, #19390, #31883, #16715, #13268, #32473, #10808, #784, #4448, #25754, #38207, #22686, #16904, #29416 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999980849, 0.1875000000000007772, 0.2187499999999994171, 0.2499999999999980571, 0.3749999999999963363, 0.4999999999999946709, 0.6249999999999930056, 0.6874999999999921174, 0.7499999999999912292, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31252 = DIRECTION ( 'NONE', ( 0.0005884949961256158652, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#31253 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#31254 = DIRECTION ( 'NONE', ( -3.092411411307044243E-16, 0.9743043966640313469, 0.2252353050503803911 ) ) ; -#31255 = EDGE_LOOP ( 'NONE', ( #25821, #29739, #35668, #30821 ) ) ; -#31256 = DIRECTION ( 'NONE', ( -0.0005884949961223030854, 0.2249510543439056098, -0.9743698870671265722 ) ) ; -#31257 = CARTESIAN_POINT ( 'NONE', ( -39.33474900027506749, 121.5592670194013181, 123.6449446999658335 ) ) ; -#31258 = CARTESIAN_POINT ( 'NONE', ( -31.70384873206000265, 225.9002260769261738, 76.07765295985980458 ) ) ; -#31259 = CARTESIAN_POINT ( 'NONE', ( 36.19055948864460959, 192.0350829726729955, 106.4100390531919942 ) ) ; -#31260 = ORIENTED_EDGE ( 'NONE', *, *, #9211, .T. ) ; -#31261 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16219, #16611, #25250, #28707 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31262 = CARTESIAN_POINT ( 'NONE', ( 36.51684498022000014, 190.9760849982000082, 106.6659581011000029 ) ) ; -#31263 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #13263, #9443, #24798, #3833 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.841040618783368998, 4.841135276510147634 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999992533261661, 0.9999999992533261661, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#31264 = EDGE_LOOP ( 'NONE', ( #36253, #20029, #30149, #40284, #27280, #3351, #38309, #31548, #33085 ) ) ; -#31265 = ORIENTED_EDGE ( 'NONE', *, *, #20859, .F. ) ; -#31267 = AXIS2_PLACEMENT_3D ( 'NONE', #15387, #2723, #37455 ) ; -#31266 = DIRECTION ( 'NONE', ( -0.0005884949961246157971, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#31268 = EDGE_CURVE ( 'NONE', #5125, #12157, #39690, .T. ) ; -#31269 = CARTESIAN_POINT ( 'NONE', ( 20.48079242901865982, 211.0898936264048587, 74.87825877592972290 ) ) ; -#31270 = AXIS2_PLACEMENT_3D ( 'NONE', #26574, #23905, #17738 ) ; -#31271 = CYLINDRICAL_SURFACE ( 'NONE', #6976, 1.749999999999998446 ) ; -#31272 = AXIS2_PLACEMENT_3D ( 'NONE', #20111, #14210, #11137 ) ; -#31273 = CIRCLE ( 'NONE', #20825, 2.499999999963690378 ) ; -#31274 = ORIENTED_EDGE ( 'NONE', *, *, #24037, .F. ) ; -#31275 = LINE ( 'NONE', #28225, #22491 ) ; -#31276 = CARTESIAN_POINT ( 'NONE', ( 17.14832387282329407, 126.1996735828056728, 179.0783422476870044 ) ) ; -#31277 = CARTESIAN_POINT ( 'NONE', ( 22.00487102077426371, 128.4742142609961775, 175.4981782972427595 ) ) ; -#31278 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; -#31279 = EDGE_LOOP ( 'NONE', ( #31799, #21776, #14351, #25812 ) ) ; -#31280 = CARTESIAN_POINT ( 'NONE', ( -18.76885123896627050, 125.8224625306723112, 175.1047239809785765 ) ) ; -#31281 = EDGE_CURVE ( 'NONE', #5648, #34131, #32388, .T. ) ; -#31282 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26629, #38663, #10883, #1056, #17185, #35573, #20262, #29691, #10683, #38466 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31283 = CARTESIAN_POINT ( 'NONE', ( 41.44965782246524810, 121.0516445706251289, 87.74591107882081076 ) ) ; -#31284 = CYLINDRICAL_SURFACE ( 'NONE', #14098, 1.999999999999989342 ) ; -#31285 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 82.27946979429631824, 312.5857197240630967 ) ) ; -#31286 = EDGE_LOOP ( 'NONE', ( #39203, #26577, #31949, #27052 ) ) ; -#31287 = EDGE_LOOP ( 'NONE', ( #34370, #1252, #29939, #10651 ) ) ; -#31288 = EDGE_CURVE ( 'NONE', #8100, #13786, #15790, .T. ) ; -#31289 = CARTESIAN_POINT ( 'NONE', ( 12.64067740912175708, 176.9725557677797099, 103.3821496526897761 ) ) ; -#31290 = CARTESIAN_POINT ( 'NONE', ( 2.549404638957319502, 190.8267260001289856, 104.2255130234709952 ) ) ; -#31291 = CARTESIAN_POINT ( 'NONE', ( -22.78469271946612196, 158.3009118758265004, 96.21332883968871386 ) ) ; -#31292 = EDGE_CURVE ( 'NONE', #18171, #19279, #37733, .T. ) ; -#31293 = ORIENTED_EDGE ( 'NONE', *, *, #23313, .T. ) ; -#31294 = LINE ( 'NONE', #25577, #269 ) ; -#31295 = ORIENTED_EDGE ( 'NONE', *, *, #11918, .T. ) ; -#31296 = EDGE_CURVE ( 'NONE', #9326, #25855, #8934, .T. ) ; -#31297 = EDGE_CURVE ( 'NONE', #37905, #38246, #18095, .T. ) ; -#31298 = AXIS2_PLACEMENT_3D ( 'NONE', #14034, #10570, #11167 ) ; -#31299 = EDGE_CURVE ( 'NONE', #20395, #29818, #24881, .T. ) ; -#31300 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5115, #24771, #18586, #30494, #3258, #15347, #21892, #24571, #14949, #30895 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.0005627318540861992423, 0.2504220488905646302, 0.5002813659270430868, 0.7501406829635215434, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31301 = CARTESIAN_POINT ( 'NONE', ( -20.51978786315646630, 209.7094320854081104, 73.57086927696296641 ) ) ; -#31302 = CIRCLE ( 'NONE', #10410, 6.500000000082215124 ) ; -#31303 = VECTOR ( 'NONE', #20072, 1000.000000000000000 ) ; -#31304 = CARTESIAN_POINT ( 'NONE', ( 20.48253891412411321, 207.4083879957671002, 77.06951181954761410 ) ) ; -#31305 = AXIS2_PLACEMENT_3D ( 'NONE', #23363, #14168, #38475 ) ; -#31306 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971565125 ) ) ; -#31307 = CARTESIAN_POINT ( 'NONE', ( -3.336448430802661402, 185.8690661594090159, 102.7372488050839507 ) ) ; -#31308 = CARTESIAN_POINT ( 'NONE', ( -21.09369801935529765, 136.1618710054223982, 91.10110626354527597 ) ) ; -#31309 = CARTESIAN_POINT ( 'NONE', ( -12.64175801402573995, 134.2925017664874190, 93.70056500962402879 ) ) ; -#31310 = CARTESIAN_POINT ( 'NONE', ( -2.148764250739064074, 189.9651423557504870, 106.0171960769523878 ) ) ; -#31311 = ORIENTED_EDGE ( 'NONE', *, *, #10532, .T. ) ; -#31312 = PLANE ( 'NONE', #3506 ) ; -#31313 = CARTESIAN_POINT ( 'NONE', ( 39.04675176836854433, 209.7096538831000316, 76.03492163576670748 ) ) ; -#31314 = PLANE ( 'NONE', #2678 ) ; -#31315 = DIRECTION ( 'NONE', ( 0.0006039748319387072293, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#31316 = ORIENTED_EDGE ( 'NONE', *, *, #9879, .F. ) ; -#31317 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #14059, #23459, #20170, #32852 ), - ( #39190, #17299, #21309, #24388 ), - ( #33347, #15364, #9236, #18406 ), - ( #33756, #24785, #17799, #5544 ), - ( #37235, #11697, #36835, #21711 ), - ( #6148, #21515, #39889, #8840 ), - ( #30513, #9029, #5755, #27469 ), - ( #11901, #18206, #40090, #8638 ), - ( #5345, #36630, #21099, #30711 ), - ( #30908, #12100, #27858, #30293 ), - ( #15170, #2703, #34154, #18004 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.06423221000888999777, 0.000000000000000000, 0.1249986728208000025, 0.2499983718750999895, 0.3749980709294999937, 0.4999977699838000222, 0.7499971680925999751, 1.000000000000000000, 1.044138764985000023 ), - ( -0.0006364018616687999860, 0.9999999836310999868 ), - .UNSPECIFIED. ) ; -#31318 = EDGE_LOOP ( 'NONE', ( #21091, #17969, #21106, #28454 ) ) ; -#31319 = CARTESIAN_POINT ( 'NONE', ( 20.50411903244052780, 118.8156269615539742, 94.25541629140380451 ) ) ; -#31320 = LINE ( 'NONE', #33618, #21337 ) ; -#31321 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #16810, #21070, #29303, #5307, #5505, #35399, #20855 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 4 ), - ( -0.001262858050230576809, 0.000000000000000000, 2.768544891470852386E-05 ), - .UNSPECIFIED. ) ; -#31322 = ORIENTED_EDGE ( 'NONE', *, *, #9281, .T. ) ; -#31323 = ORIENTED_EDGE ( 'NONE', *, *, #21799, .F. ) ; -#31324 = CARTESIAN_POINT ( 'NONE', ( 35.04524255441999969, 226.4002260771000010, 73.53733772517999512 ) ) ; -#31325 = VECTOR ( 'NONE', #2072, 1000.000000000000114 ) ; -#31326 = CARTESIAN_POINT ( 'NONE', ( 23.67925056556238772, 134.2473364980823476, 93.71096924780141535 ) ) ; -#31327 = CARTESIAN_POINT ( 'NONE', ( -3.169906973560626895, 184.1222312815566795, 102.1628149875517408 ) ) ; -#31328 = CARTESIAN_POINT ( 'NONE', ( -12.63885304198008086, 135.0706950218433633, 91.05405041975734548 ) ) ; -#31329 = EDGE_LOOP ( 'NONE', ( #23330, #25365, #40015, #17674 ) ) ; -#31330 = CARTESIAN_POINT ( 'NONE', ( 17.27169409178496551, 122.3510092884824729, 172.9162538931327902 ) ) ; -#31331 = EDGE_CURVE ( 'NONE', #31589, #25100, #28485, .T. ) ; -#31332 = CIRCLE ( 'NONE', #10440, 6.000000000012134294 ) ; -#31333 = ORIENTED_EDGE ( 'NONE', *, *, #38109, .T. ) ; -#31334 = CIRCLE ( 'NONE', #13065, 5.499999999599896938 ) ; -#31335 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971558741 ) ) ; -#31336 = CARTESIAN_POINT ( 'NONE', ( 26.00773787888504529, 191.9759150222000130, 101.9057393184010323 ) ) ; -#31337 = AXIS2_PLACEMENT_3D ( 'NONE', #3675, #31501, #31306 ) ; -#31338 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971549582 ) ) ; -#31339 = VERTEX_POINT ( 'NONE', #27560 ) ; -#31340 = EDGE_CURVE ( 'NONE', #4072, #13020, #31002, .T. ) ; -#31341 = CARTESIAN_POINT ( 'NONE', ( 20.31560735737901524, 205.4141931770509473, 76.22222318449824741 ) ) ; -#31342 = CARTESIAN_POINT ( 'NONE', ( 1.143504943582302813, 188.6809584813572371, 103.2126644868193068 ) ) ; -#31343 = CARTESIAN_POINT ( 'NONE', ( -23.36229215089216993, 181.4106142796427719, 104.2858048007022944 ) ) ; -#31344 = EDGE_CURVE ( 'NONE', #23170, #6189, #19709, .T. ) ; -#31345 = ORIENTED_EDGE ( 'NONE', *, *, #13841, .T. ) ; -#31346 = LINE ( 'NONE', #12731, #34185 ) ; -#31347 = ORIENTED_EDGE ( 'NONE', *, *, #1800, .T. ) ; -#31348 = ADVANCED_FACE ( 'NONE', ( #33650 ), #2593, .F. ) ; -#31349 = LINE ( 'NONE', #9472, #21284 ) ; -#31350 = CARTESIAN_POINT ( 'NONE', ( 36.49036606398971827, 191.3180990208740582, 103.8001478455694979 ) ) ; -#31351 = CARTESIAN_POINT ( 'NONE', ( 16.14865643636807846, 151.1202562712145152, 184.8374432047714606 ) ) ; -#31352 = VERTEX_POINT ( 'NONE', #24481 ) ; -#31353 = CARTESIAN_POINT ( 'NONE', ( -28.25571780481785567, 186.4543157461568228, 105.2821206686522686 ) ) ; -#31354 = CARTESIAN_POINT ( 'NONE', ( -4.410790214992264424, 124.6726707417136879, 88.43853883911272362 ) ) ; -#31355 = CIRCLE ( 'NONE', #32001, 2.750000000059430239 ) ; -#31356 = CONICAL_SURFACE ( 'NONE', #36579, 2.500000095127406841, 0.7853981633778667204 ) ; -#31357 = ORIENTED_EDGE ( 'NONE', *, *, #40229, .F. ) ; -#31358 = AXIS2_PLACEMENT_3D ( 'NONE', #16260, #22422, #38152 ) ; -#31359 = AXIS2_PLACEMENT_3D ( 'NONE', #8471, #5386, #40129 ) ; -#31360 = CARTESIAN_POINT ( 'NONE', ( -39.58538553044007102, 75.03979799197465184, 323.7269989125918528 ) ) ; -#31361 = CYLINDRICAL_SURFACE ( 'NONE', #25731, 51.40509898897001761 ) ; -#31363 = CARTESIAN_POINT ( 'NONE', ( 15.94108644203163294, 147.2333410478985911, 179.8333394151990490 ) ) ; -#31362 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250615212, 179.6252109630535472, 101.6466942236910569 ) ) ; -#31364 = ORIENTED_EDGE ( 'NONE', *, *, #24946, .T. ) ; -#31365 = CARTESIAN_POINT ( 'NONE', ( 14.93318671017543231, 151.7188427972803311, 177.9798661502222217 ) ) ; -#31366 = ORIENTED_EDGE ( 'NONE', *, *, #25354, .T. ) ; -#31367 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#31368 = DIRECTION ( 'NONE', ( 0.7942820423213362568, 0.5918950211223029667, 0.1370267171630251968 ) ) ; -#31369 = ORIENTED_EDGE ( 'NONE', *, *, #23260, .F. ) ; -#31370 = ORIENTED_EDGE ( 'NONE', *, *, #24089, .F. ) ; -#31371 = FACE_OUTER_BOUND ( 'NONE', #10078, .T. ) ; -#31372 = CARTESIAN_POINT ( 'NONE', ( -35.44716532913142260, 113.1977046342314708, 87.28919349165808228 ) ) ; -#31373 = CARTESIAN_POINT ( 'NONE', ( 22.78078928741000198, 153.8098031069565650, 95.66210622461615287 ) ) ; -#31374 = CARTESIAN_POINT ( 'NONE', ( 2.939226598809902669, 209.7173956323443917, 73.05673022523419036 ) ) ; -#31375 = EDGE_CURVE ( 'NONE', #27269, #18813, #2641, .T. ) ; -#31376 = ORIENTED_EDGE ( 'NONE', *, *, #10745, .F. ) ; -#31377 = ADVANCED_FACE ( 'NONE', ( #28930 ), #28733, .T. ) ; -#31378 = EDGE_LOOP ( 'NONE', ( #11916, #22014, #39042, #39326, #28987 ) ) ; -#31379 = CARTESIAN_POINT ( 'NONE', ( 25.99026500172996990, 210.1701206109333384, 73.04280661359497628 ) ) ; -#31380 = EDGE_CURVE ( 'NONE', #30585, #8845, #13395, .T. ) ; -#31381 = CARTESIAN_POINT ( 'NONE', ( 20.15421560565993531, 128.2853077194433524, 89.25774530750982194 ) ) ; -#31382 = ADVANCED_FACE ( 'NONE', ( #9729 ), #24978, .F. ) ; -#31383 = FACE_OUTER_BOUND ( 'NONE', #36242, .T. ) ; -#31384 = AXIS2_PLACEMENT_3D ( 'NONE', #30132, #4563, #20096 ) ; -#31385 = ORIENTED_EDGE ( 'NONE', *, *, #3031, .F. ) ; -#31386 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 92.27946979429643193, 322.5967026918627312 ) ) ; -#31387 = CARTESIAN_POINT ( 'NONE', ( -23.02004673814065683, 213.5902071504527839, 73.57250091739375364 ) ) ; -#31388 = PLANE ( 'NONE', #22836 ) ; -#31389 = AXIS2_PLACEMENT_3D ( 'NONE', #29371, #10171, #31845 ) ; -#31390 = EDGE_LOOP ( 'NONE', ( #12255, #36293, #627, #12114 ) ) ; -#31391 = ADVANCED_FACE ( 'NONE', ( #18901 ), #25687, .T. ) ; -#31392 = VECTOR ( 'NONE', #30768, 1000.000000000000114 ) ; -#31393 = CONICAL_SURFACE ( 'NONE', #26818, 2.249999999984611421, 0.7853981634347277918 ) ; -#31394 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921578520, 0.2249510932971594823 ) ) ; -#31395 = CARTESIAN_POINT ( 'NONE', ( 16.67763860462360981, 127.2204759592696917, 176.3528348589679524 ) ) ; -#31396 = EDGE_CURVE ( 'NONE', #20878, #31222, #19311, .T. ) ; -#31397 = CARTESIAN_POINT ( 'NONE', ( -0.3312283176345999780, 188.8545265543999960, 105.8569945315000069 ) ) ; -#31398 = DIRECTION ( 'NONE', ( -0.1634997390362193104, 0.3413656262119397766, -0.9256010720477901854 ) ) ; -#31399 = VERTEX_POINT ( 'NONE', #3563 ) ; -#31400 = CARTESIAN_POINT ( 'NONE', ( -42.83981852382991917, 113.7604137494400476, 123.0507168651698038 ) ) ; -#31401 = FACE_OUTER_BOUND ( 'NONE', #13927, .T. ) ; -#31402 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1115, #17604, #10541, #30102 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31403 = DIRECTION ( 'NONE', ( 0.6337890847338583100, -0.7735059121120007042, 0.000000000000000000 ) ) ; -#31404 = CARTESIAN_POINT ( 'NONE', ( 30.06995708078038376, 134.8478347390543490, 93.33259620325232220 ) ) ; -#31405 = EDGE_CURVE ( 'NONE', #23621, #18764, #24590, .T. ) ; -#31406 = DIRECTION ( 'NONE', ( -0.7855473026356898369, -0.6188014303620734680, 0.0004744508866335558125 ) ) ; -#31407 = VERTEX_POINT ( 'NONE', #35029 ) ; -#31408 = LINE ( 'NONE', #314, #28509 ) ; -#31409 = VERTEX_POINT ( 'NONE', #31600 ) ; -#31410 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 5.029100215316657124E-18, 0.0006039748319386160479 ) ) ; -#31411 = CARTESIAN_POINT ( 'NONE', ( 25.49273537670188361, 207.4083917605166789, 77.06627999559708542 ) ) ; -#31412 = CARTESIAN_POINT ( 'NONE', ( -38.35588822081000160, 118.5258381726000181, 89.84986101129000247 ) ) ; -#31413 = CIRCLE ( 'NONE', #18985, 22.50000000000898837 ) ; -#31414 = ORIENTED_EDGE ( 'NONE', *, *, #1415, .T. ) ; -#31415 = DIRECTION ( 'NONE', ( 0.6088160902985568779, -0.7729595817128234181, -0.1785397805306046526 ) ) ; -#31416 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1505, #23194, #29737, #4158 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31417 = VECTOR ( 'NONE', #36959, 1000.000000000000227 ) ; -#31418 = CARTESIAN_POINT ( 'NONE', ( 39.06422788861904394, 183.0561992322088543, 104.9700959750892366 ) ) ; -#31419 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; -#31420 = AXIS2_PLACEMENT_3D ( 'NONE', #26760, #10619, #4664 ) ; -#31421 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825977240376177, 0.0005734119010670563803 ) ) ; -#31422 = CARTESIAN_POINT ( 'NONE', ( 12.59458203848999958, 191.9910753069000293, 28.07991271570000080 ) ) ; -#31423 = LINE ( 'NONE', #30623, #34971 ) ; -#31424 = EDGE_LOOP ( 'NONE', ( #16121, #13189, #12499 ) ) ; -#31425 = EDGE_LOOP ( 'NONE', ( #20527, #21939, #34986, #20886, #33422, #8731, #4524 ) ) ; -#31426 = ORIENTED_EDGE ( 'NONE', *, *, #13926, .F. ) ; -#31427 = FACE_OUTER_BOUND ( 'NONE', #30653, .T. ) ; -#31428 = CARTESIAN_POINT ( 'NONE', ( -2.695352837891999975, 201.9934155195000187, 90.48001809261999995 ) ) ; -#31429 = VERTEX_POINT ( 'NONE', #31808 ) ; -#31430 = CARTESIAN_POINT ( 'NONE', ( -13.84340190104143353, 154.7500563556122017, 161.1767822654394422 ) ) ; -#31431 = EDGE_CURVE ( 'NONE', #26477, #9324, #23627, .T. ) ; -#31432 = ADVANCED_FACE ( 'NONE', ( #9935 ), #7308, .F. ) ; -#31433 = EDGE_LOOP ( 'NONE', ( #8214, #8148, #1255, #17 ) ) ; -#31434 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#31435 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#31436 = ORIENTED_EDGE ( 'NONE', *, *, #29174, .T. ) ; -#31437 = CARTESIAN_POINT ( 'NONE', ( 20.95020508879656163, 128.6695385774041256, 92.42488413635012989 ) ) ; -#31438 = ADVANCED_FACE ( 'NONE', ( #7039 ), #32006, .T. ) ; -#31439 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#31440 = CARTESIAN_POINT ( 'NONE', ( -5.663464557155529988, 131.0206703453534374, 89.90489628355439322 ) ) ; -#31441 = CIRCLE ( 'NONE', #11862, 5.000000000028509639 ) ; -#31442 = CARTESIAN_POINT ( 'NONE', ( 30.07023774425934803, 176.7457471811506764, 103.0054930552473564 ) ) ; -#31443 = CARTESIAN_POINT ( 'NONE', ( 44.24772793393911030, 122.2367175089034959, 90.92567871579780103 ) ) ; -#31444 = ORIENTED_EDGE ( 'NONE', *, *, #7321, .F. ) ; -#31446 = EDGE_CURVE ( 'NONE', #1973, #30753, #13196, .T. ) ; -#31445 = CARTESIAN_POINT ( 'NONE', ( -13.00577321180114865, 177.7894282964912804, 100.7067019652760678 ) ) ; -#31447 = AXIS2_PLACEMENT_3D ( 'NONE', #32510, #7157, #34941 ) ; -#31448 = CARTESIAN_POINT ( 'NONE', ( -37.84078032415512638, 119.0089722949934696, 87.29331153112032382 ) ) ; -#31449 = PLANE ( 'NONE', #22176 ) ; -#31450 = FACE_OUTER_BOUND ( 'NONE', #32777, .T. ) ; -#31451 = EDGE_LOOP ( 'NONE', ( #30718, #6959, #580, #10542 ) ) ; -#31452 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; -#31453 = CARTESIAN_POINT ( 'NONE', ( 19.43523103776308503, 149.2156397595460930, 181.3139216008023880 ) ) ; -#31454 = CARTESIAN_POINT ( 'NONE', ( -34.05013329931477273, 81.71494582553067687, 291.5791093625203985 ) ) ; -#31455 = LINE ( 'NONE', #3620, #20305 ) ; -#31456 = EDGE_CURVE ( 'NONE', #15358, #3283, #29538, .T. ) ; -#31457 = CARTESIAN_POINT ( 'NONE', ( 43.33709577780441435, 121.3453068284270699, 90.54570139316727762 ) ) ; -#31458 = CARTESIAN_POINT ( 'NONE', ( -26.29133475941970133, 188.3528585319050137, 105.7175370394109848 ) ) ; -#31459 = ORIENTED_EDGE ( 'NONE', *, *, #26361, .F. ) ; -#31460 = CARTESIAN_POINT ( 'NONE', ( -16.53001031479427141, 121.8780329720448066, 177.6173573199974953 ) ) ; -#31461 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548258502, 171.7660675377210282, 184.4841745997615021 ) ) ; -#31462 = VERTEX_POINT ( 'NONE', #9526 ) ; -#31463 = CARTESIAN_POINT ( 'NONE', ( -10.03596943924095797, 143.5372728157101676, 95.87608654283346254 ) ) ; -#31464 = CARTESIAN_POINT ( 'NONE', ( 20.33446643993600134, 127.3604678021566201, 89.38718315066802234 ) ) ; -#31465 = CARTESIAN_POINT ( 'NONE', ( 37.68745077890000772, 191.4215636083000049, 104.2998648217000124 ) ) ; -#31466 = CARTESIAN_POINT ( 'NONE', ( 36.09277602024999965, 191.9597434480999993, 106.5195528529000057 ) ) ; -#31467 = ORIENTED_EDGE ( 'NONE', *, *, #17259, .F. ) ; -#31468 = ORIENTED_EDGE ( 'NONE', *, *, #16990, .T. ) ; -#31469 = VECTOR ( 'NONE', #40227, 1000.000000000000114 ) ; -#31470 = DIRECTION ( 'NONE', ( 0.6096989917424270322, -0.7722987078273715333, -0.1783867858235026471 ) ) ; -#31471 = AXIS2_PLACEMENT_3D ( 'NONE', #30862, #31253, #12642 ) ; -#31472 = CARTESIAN_POINT ( 'NONE', ( 30.05382551810999914, 103.6131156702000027, 87.74963262557000121 ) ) ; -#31473 = CARTESIAN_POINT ( 'NONE', ( -23.36013624460098725, 136.6770260652199624, 94.30032095887112575 ) ) ; -#31474 = ORIENTED_EDGE ( 'NONE', *, *, #14785, .T. ) ; -#31475 = DIRECTION ( 'NONE', ( -0.0005884949961217841863, 0.2249510543439048882, -0.9743698870671267942 ) ) ; -#31476 = EDGE_CURVE ( 'NONE', #20455, #30422, #5070, .T. ) ; -#31478 = ADVANCED_FACE ( 'NONE', ( #37721 ), #26278, .F. ) ; -#31477 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32649, #20783, #5232, #14866 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31479 = ORIENTED_EDGE ( 'NONE', *, *, #24534, .T. ) ; -#31480 = CARTESIAN_POINT ( 'NONE', ( 39.77041188632269098, 161.5626287739675888, 197.5124357450602588 ) ) ; -#31481 = CARTESIAN_POINT ( 'NONE', ( 12.64209925790531308, 131.0231129754641302, 89.89439459407216759 ) ) ; -#31482 = ORIENTED_EDGE ( 'NONE', *, *, #2216, .F. ) ; -#31483 = CARTESIAN_POINT ( 'NONE', ( -18.79252570011861678, 125.8499160133713133, 175.1155745579973484 ) ) ; -#31484 = DIRECTION ( 'NONE', ( 0.1695469893270771522, -1.252670582138759957E-14, -0.9855221044756550253 ) ) ; -#31485 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; -#31486 = CARTESIAN_POINT ( 'NONE', ( 23.67925056556238772, 134.2473364980823476, 93.71096924780141535 ) ) ; -#31487 = ORIENTED_EDGE ( 'NONE', *, *, #31240, .F. ) ; -#31488 = ORIENTED_EDGE ( 'NONE', *, *, #3985, .F. ) ; -#31489 = CARTESIAN_POINT ( 'NONE', ( -25.50922756583905837, 191.3757872987501969, 104.3640622938216183 ) ) ; -#31490 = CARTESIAN_POINT ( 'NONE', ( 1.316320443139440188, 189.1529878064920069, 103.7382684573219933 ) ) ; -#31491 = CARTESIAN_POINT ( 'NONE', ( -22.49967939491756752, 153.8038087509543743, 95.68807059495395606 ) ) ; -#31492 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #23923, #30459 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31493 = ORIENTED_EDGE ( 'NONE', *, *, #7014, .T. ) ; -#31494 = VERTEX_POINT ( 'NONE', #27490 ) ; -#31495 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748615741, 179.1800746285439345, 103.5747911658197893 ) ) ; -#31496 = ORIENTED_EDGE ( 'NONE', *, *, #30970, .F. ) ; -#31497 = CIRCLE ( 'NONE', #13857, 6.000000000128157041 ) ; -#31498 = AXIS2_PLACEMENT_3D ( 'NONE', #27375, #11813, #17511 ) ; -#31499 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566235 ) ) ; -#31500 = DIRECTION ( 'NONE', ( -0.0005884949961204411851, 0.2249510543439063592, -0.9743698870671264611 ) ) ; -#31501 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#31502 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #33429, #1545, #20141, #17476 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.570796326794964726, 3.376412948467386599 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.7462717963450533620, 0.7462717963450533620, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#31503 = CARTESIAN_POINT ( 'NONE', ( -39.73142568412256992, 175.7232364642230777, 136.1664758066176830 ) ) ; -#31504 = CARTESIAN_POINT ( 'NONE', ( -3.088327906531000089, 208.7573243651999917, 73.01289067924000165 ) ) ; -#31505 = CARTESIAN_POINT ( 'NONE', ( -1.935624522227932909, 189.6762913120315943, 105.9337518142968975 ) ) ; -#31506 = VERTEX_POINT ( 'NONE', #8865 ) ; -#31507 = EDGE_CURVE ( 'NONE', #5465, #23779, #18028, .T. ) ; -#31508 = CARTESIAN_POINT ( 'NONE', ( -35.95487748704000097, 206.4002260771000010, 76.08022047462002035 ) ) ; -#31509 = CARTESIAN_POINT ( 'NONE', ( -36.58309918135517336, 191.3840766415999042, 106.3867753853837712 ) ) ; -#31510 = CARTESIAN_POINT ( 'NONE', ( -45.15281646518302239, 105.2939582111126242, 174.2284691125232143 ) ) ; -#31511 = CARTESIAN_POINT ( 'NONE', ( -2.455538055765680738, 209.0000002601700544, 73.61629604161946361 ) ) ; -#31512 = ORIENTED_EDGE ( 'NONE', *, *, #33213, .T. ) ; -#31513 = EDGE_CURVE ( 'NONE', #31352, #8754, #40313, .T. ) ; -#31514 = ORIENTED_EDGE ( 'NONE', *, *, #18529, .T. ) ; -#31515 = CARTESIAN_POINT ( 'NONE', ( 25.53626815854681098, 191.3673954314083119, 104.3312944428767253 ) ) ; -#31516 = CIRCLE ( 'NONE', #7360, 51.40509898897001051 ) ; -#31517 = CARTESIAN_POINT ( 'NONE', ( 22.61860768848664449, 115.1133264115357377, 87.25412321976182284 ) ) ; -#31518 = DIRECTION ( 'NONE', ( 0.9914447019871154287, -0.1270494721560660734, -0.02993049492649695054 ) ) ; -#31519 = FACE_OUTER_BOUND ( 'NONE', #18531, .T. ) ; -#31520 = EDGE_CURVE ( 'NONE', #18145, #19730, #16723, .T. ) ; -#31521 = ORIENTED_EDGE ( 'NONE', *, *, #17029, .T. ) ; -#31522 = AXIS2_PLACEMENT_3D ( 'NONE', #25519, #22250, #22847 ) ; -#31523 = EDGE_CURVE ( 'NONE', #28425, #7038, #2725, .T. ) ; -#31524 = VERTEX_POINT ( 'NONE', #25207 ) ; -#31525 = EDGE_CURVE ( 'NONE', #7165, #17944, #15771, .T. ) ; -#31526 = CARTESIAN_POINT ( 'NONE', ( 12.63633280683901106, 127.9124608697227927, 92.25512031180861072 ) ) ; -#31527 = AXIS2_PLACEMENT_3D ( 'NONE', #24982, #31500, #5951 ) ; -#31528 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18295, #2963, #12566, #24471, #37516, #14855, #2583, #24875, #21997, #27553 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999779066, 0.3749999999999668598, 0.4374999999999613642, 0.4999999999999558131, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31529 = CARTESIAN_POINT ( 'NONE', ( -20.33397659309266814, 196.2711692071578682, 103.7581375276250242 ) ) ; -#31530 = CARTESIAN_POINT ( 'NONE', ( -35.95425951663850839, 207.4083918145487075, 77.10339231471580490 ) ) ; -#31531 = CARTESIAN_POINT ( 'NONE', ( 21.21457940375938378, 183.3621723504481906, 102.4857529904703028 ) ) ; -#31532 = VERTEX_POINT ( 'NONE', #21119 ) ; -#31533 = CARTESIAN_POINT ( 'NONE', ( -45.92783482638418491, 124.8424006619797098, 91.58171271578800088 ) ) ; -#31534 = VERTEX_POINT ( 'NONE', #6372 ) ; -#31535 = ORIENTED_EDGE ( 'NONE', *, *, #40461, .T. ) ; -#31536 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#31537 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#31538 = CARTESIAN_POINT ( 'NONE', ( 42.51832847222295442, 128.8459892653891075, 92.45259438658834483 ) ) ; -#31539 = ORIENTED_EDGE ( 'NONE', *, *, #9784, .F. ) ; -#31540 = CARTESIAN_POINT ( 'NONE', ( -2.436965057049000016, 190.9999858852999921, 104.2634334619999947 ) ) ; -#31541 = CARTESIAN_POINT ( 'NONE', ( 3.064870483804259305, 190.8403612114580028, 103.7100415233180826 ) ) ; -#31542 = CARTESIAN_POINT ( 'NONE', ( -26.00969531629161224, 206.5435593458424535, 74.17353529082527075 ) ) ; -#31543 = LINE ( 'NONE', #9669, #7702 ) ; -#31544 = ORIENTED_EDGE ( 'NONE', *, *, #39138, .T. ) ; -#31545 = EDGE_LOOP ( 'NONE', ( #9504, #2766, #28274, #8156, #11149, #8574 ) ) ; -#31546 = PLANE ( 'NONE', #9401 ) ; -#31547 = CARTESIAN_POINT ( 'NONE', ( 42.97429946896744468, 67.83849343097567441, 322.0145824706445978 ) ) ; -#31548 = ORIENTED_EDGE ( 'NONE', *, *, #2120, .T. ) ; -#31549 = LINE ( 'NONE', #22556, #36950 ) ; -#31550 = CARTESIAN_POINT ( 'NONE', ( -25.99225322733968113, 193.8169247290872761, 102.7186084094945926 ) ) ; -#31551 = CARTESIAN_POINT ( 'NONE', ( -25.62183731277999854, 120.1108274837000209, 90.08866940772999499 ) ) ; -#31552 = AXIS2_PLACEMENT_3D ( 'NONE', #32171, #32367, #4127 ) ; -#31553 = ORIENTED_EDGE ( 'NONE', *, *, #7861, .F. ) ; -#31554 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319387908213 ) ) ; -#31555 = VECTOR ( 'NONE', #37307, 1000.000000000000227 ) ; -#31556 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #64, #5994 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31557 = CARTESIAN_POINT ( 'NONE', ( 26.00061531446862517, 118.3483399336666793, 90.25208111907872421 ) ) ; -#31558 = DIRECTION ( 'NONE', ( -0.0005884949961189803310, 0.2249510543439054433, -0.9743698870671265722 ) ) ; -#31559 = CIRCLE ( 'NONE', #13257, 2.499999999488756064 ) ; -#31560 = EDGE_LOOP ( 'NONE', ( #17440, #23140, #33137, #12355, #39249, #4649, #10972, #24497 ) ) ; -#31561 = ADVANCED_FACE ( 'NONE', ( #18825 ), #16445, .F. ) ; -#31562 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554578 ) ) ; -#31563 = CARTESIAN_POINT ( 'NONE', ( 35.87847517210509096, 209.7096558782537556, 73.37016786902755427 ) ) ; -#31565 = DIRECTION ( 'NONE', ( 0.6087613186456907188, 0.7730177010543248795, 0.1784749023741044327 ) ) ; -#31564 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775456658 ) ) ; -#31566 = VERTEX_POINT ( 'NONE', #12314 ) ; -#31567 = ADVANCED_FACE ( 'NONE', ( #21735 ), #33979, .T. ) ; -#31568 = ORIENTED_EDGE ( 'NONE', *, *, #28907, .T. ) ; -#31569 = CARTESIAN_POINT ( 'NONE', ( -35.95517947438523976, 209.7096537232000344, 75.58022056590567672 ) ) ; -#31570 = EDGE_CURVE ( 'NONE', #17481, #31838, #27499, .T. ) ; -#31571 = CARTESIAN_POINT ( 'NONE', ( 39.11549366608129930, 162.5504968431983457, 191.0044786453397307 ) ) ; -#31572 = LINE ( 'NONE', #30969, #1852 ) ; -#31573 = EDGE_LOOP ( 'NONE', ( #4263, #6141, #2969, #8394, #32579, #320, #25107 ) ) ; -#31574 = EDGE_CURVE ( 'NONE', #24177, #32425, #40115, .T. ) ; -#31575 = ORIENTED_EDGE ( 'NONE', *, *, #19557, .F. ) ; -#31576 = ADVANCED_FACE ( 'NONE', ( #9457 ), #28074, .T. ) ; -#31577 = CARTESIAN_POINT ( 'NONE', ( 44.93626489333781393, 188.5078210156812304, 105.6925916894777799 ) ) ; -#31578 = EDGE_CURVE ( 'NONE', #3435, #2188, #15389, .T. ) ; -#31579 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#31580 = LINE ( 'NONE', #25456, #20685 ) ; -#31581 = CARTESIAN_POINT ( 'NONE', ( 33.54411937952203715, 218.5902260770999987, 73.03824427483441184 ) ) ; -#31582 = AXIS2_PLACEMENT_3D ( 'NONE', #8387, #20845, #29856 ) ; -#31583 = VERTEX_POINT ( 'NONE', #9056 ) ; -#31584 = EDGE_LOOP ( 'NONE', ( #5632, #21696, #13614, #18805, #39653 ) ) ; -#31585 = CARTESIAN_POINT ( 'NONE', ( -8.048542123480551425, 150.7617452742509556, 97.54278737913534769 ) ) ; -#31586 = CARTESIAN_POINT ( 'NONE', ( 20.41579965800398000, 128.8293016962263380, 89.38317824560692770 ) ) ; -#31587 = AXIS2_PLACEMENT_3D ( 'NONE', #34954, #6368, #19437 ) ; -#31588 = CARTESIAN_POINT ( 'NONE', ( -20.49874983313576848, 118.1134457197417902, 89.11340909896085805 ) ) ; -#31589 = VERTEX_POINT ( 'NONE', #37457 ) ; -#31590 = ORIENTED_EDGE ( 'NONE', *, *, #11233, .T. ) ; -#31591 = CONICAL_SURFACE ( 'NONE', #4122, 6.499999999937051243, 0.7853981633647675320 ) ; -#31592 = CARTESIAN_POINT ( 'NONE', ( 26.00820986244454858, 193.8169247290949784, 102.6872014327978775 ) ) ; -#31593 = ORIENTED_EDGE ( 'NONE', *, *, #39682, .F. ) ; -#31594 = LINE ( 'NONE', #13385, #4599 ) ; -#31595 = ORIENTED_EDGE ( 'NONE', *, *, #26500, .T. ) ; -#31596 = FACE_OUTER_BOUND ( 'NONE', #4245, .T. ) ; -#31597 = CARTESIAN_POINT ( 'NONE', ( -26.00143740904770695, 120.6419526453365165, 87.52101428342558620 ) ) ; -#31598 = CARTESIAN_POINT ( 'NONE', ( 16.99952089899044694, 136.5640433068810182, 181.4726123975704297 ) ) ; -#31599 = VERTEX_POINT ( 'NONE', #21935 ) ; -#31600 = CARTESIAN_POINT ( 'NONE', ( -35.43806428669827824, 192.3002664666033468, 103.9163745585288297 ) ) ; -#31601 = DIRECTION ( 'NONE', ( -0.7933533411653073131, 0.5930537057989939687, 0.1373964268091565077 ) ) ; -#31602 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #10101, #873 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31603 = CARTESIAN_POINT ( 'NONE', ( 19.98430243908310899, 211.4692376108927760, 73.04643406448599308 ) ) ; -#31604 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250612370, 132.8554482850432237, 90.84904174543585498 ) ) ; -#31605 = CARTESIAN_POINT ( 'NONE', ( -24.42746480248211682, 109.6131156702000027, 87.78253795969705209 ) ) ; -#31606 = ORIENTED_EDGE ( 'NONE', *, *, #34752, .T. ) ; -#31607 = AXIS2_PLACEMENT_3D ( 'NONE', #8426, #37233, #5751 ) ; -#31608 = AXIS2_PLACEMENT_3D ( 'NONE', #14286, #24104, #23480 ) ; -#31609 = CARTESIAN_POINT ( 'NONE', ( -30.07831637853678686, 134.9151858147922667, 90.81876078434068233 ) ) ; -#31610 = EDGE_CURVE ( 'NONE', #16151, #40272, #4041, .T. ) ; -#31611 = ORIENTED_EDGE ( 'NONE', *, *, #6390, .F. ) ; -#31612 = ADVANCED_FACE ( 'NONE', ( #22133 ), #27612, .F. ) ; -#31614 = ADVANCED_FACE ( 'NONE', ( #32334 ), #22540, .F. ) ; -#31613 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319387940739 ) ) ; -#31615 = AXIS2_PLACEMENT_3D ( 'NONE', #9037, #24991, #34544 ) ; -#31616 = CARTESIAN_POINT ( 'NONE', ( 21.70246180708700123, 182.6954656095747396, 102.1604887804233641 ) ) ; -#31618 = ORIENTED_EDGE ( 'NONE', *, *, #9588, .F. ) ; -#31617 = EDGE_CURVE ( 'NONE', #11920, #22363, #15805, .T. ) ; -#31619 = FACE_OUTER_BOUND ( 'NONE', #23723, .T. ) ; -#31620 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#31621 = ORIENTED_EDGE ( 'NONE', *, *, #33114, .T. ) ; -#31622 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#31623 = EDGE_CURVE ( 'NONE', #32971, #34336, #18671, .T. ) ; -#31624 = FACE_OUTER_BOUND ( 'NONE', #23521, .T. ) ; -#31625 = FACE_OUTER_BOUND ( 'NONE', #2858, .T. ) ; -#31626 = CARTESIAN_POINT ( 'NONE', ( -21.61917713407146380, 158.4572069570291148, 96.24870846027548055 ) ) ; -#31627 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #3880, #13905 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31628 = DIRECTION ( 'NONE', ( -0.0006039748319383739456, 3.094196748328522329E-15, -0.9999998176071845934 ) ) ; -#31629 = ORIENTED_EDGE ( 'NONE', *, *, #19046, .F. ) ; -#31630 = ORIENTED_EDGE ( 'NONE', *, *, #39389, .T. ) ; -#31631 = EDGE_CURVE ( 'NONE', #4072, #36231, #34956, .T. ) ; -#31632 = PLANE ( 'NONE', #34136 ) ; -#31633 = CARTESIAN_POINT ( 'NONE', ( -45.25641640995738868, 187.0376772300918162, 105.9402203223797585 ) ) ; -#31634 = VERTEX_POINT ( 'NONE', #22935 ) ; -#31635 = CARTESIAN_POINT ( 'NONE', ( -38.93802797675191840, 191.1637323145700122, 103.9811187850653340 ) ) ; -#31636 = DIRECTION ( 'NONE', ( 0.0006039748319385305044, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#31637 = ORIENTED_EDGE ( 'NONE', *, *, #39187, .T. ) ; -#31638 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319385907860 ) ) ; -#31639 = ADVANCED_FACE ( 'NONE', ( #16771 ), #20388, .F. ) ; -#31640 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#31641 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825930922507203, 0.0005734119021363929484 ) ) ; -#31642 = ORIENTED_EDGE ( 'NONE', *, *, #28380, .F. ) ; -#31643 = CARTESIAN_POINT ( 'NONE', ( 28.08889367328000120, 125.1496492417999917, 88.70009216949001996 ) ) ; -#31644 = VECTOR ( 'NONE', #33899, 1000.000000000000000 ) ; -#31645 = AXIS2_PLACEMENT_3D ( 'NONE', #18135, #33887, #15097 ) ; -#31646 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971537924 ) ) ; -#31647 = CARTESIAN_POINT ( 'NONE', ( 30.02511232208999914, 191.9910753069000293, 28.07991271570000080 ) ) ; -#31648 = AXIS2_PLACEMENT_3D ( 'NONE', #34895, #19379, #31874 ) ; -#31649 = FACE_OUTER_BOUND ( 'NONE', #9341, .T. ) ; -#31650 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319379894875 ) ) ; -#31651 = VERTEX_POINT ( 'NONE', #9865 ) ; -#31652 = FACE_OUTER_BOUND ( 'NONE', #10686, .T. ) ; -#31653 = CARTESIAN_POINT ( 'NONE', ( 1.085475968734386676, 189.0695496040855517, 103.7041505517462241 ) ) ; -#31654 = CARTESIAN_POINT ( 'NONE', ( -2.849829047465823884, 190.2190360668230653, 106.6490825001534404 ) ) ; -#31655 = CARTESIAN_POINT ( 'NONE', ( 12.63720056867337682, 130.2028334981800981, 92.58456458875848227 ) ) ; -#31656 = DIRECTION ( 'NONE', ( 0.0005884949961256158652, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#31657 = CARTESIAN_POINT ( 'NONE', ( 32.37049208056998140, 174.4092940747139551, 99.89893022217735563 ) ) ; -#31658 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#31659 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #23053, #19565, #20162, #39180 ), - ( #16883, #11183, #10587, #35684 ), - ( #32062, #32255, #14255, #10388 ), - ( #1567, #20366, #29193, #32648 ), - ( #4022, #32843, #16489, #32454 ), - ( #1777, #19953, #4627, #7487 ), - ( #23656, #7288, #29389, #36103 ), - ( #13639, #26526, #28981, #16692 ), - ( #4824, #26130, #38762, #14049 ), - ( #958, #1161, #13447, #38376 ), - ( #17087, #22855, #17289, #4425 ), - ( #38568, #1357, #35477, #13838 ), - ( #10782, #29587, #23246, #38979 ), - ( #10985, #15261, #8113, #21198 ), - ( #20992, #39376, #33848, #33651 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.01205588739532000020, 0.000000000000000000, 0.01570492664887999934, 0.03132662402703000060, 0.06257001878335000100, 0.1250568082959999938, 0.1875435978084999955, 0.2500303873211999761, 0.3750039663465000173, 0.4999775453717000273, 0.7499247034221999675, 1.000000000000000000, 1.559246406558000064 ), - ( -0.2722091963193000175, 1.270754018114000017 ), - .UNSPECIFIED. ) ; -#31660 = DIRECTION ( 'NONE', ( 0.7692168386926722112, 0.6301897592057729147, -0.1056708212508138262 ) ) ; -#31661 = CARTESIAN_POINT ( 'NONE', ( -25.53897216374099699, 190.4810016023160131, 106.2066927615159955 ) ) ; -#31662 = ORIENTED_EDGE ( 'NONE', *, *, #6808, .T. ) ; -#31663 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#31664 = EDGE_CURVE ( 'NONE', #30923, #27237, #31497, .T. ) ; -#31665 = ADVANCED_FACE ( 'NONE', ( #19641 ), #9966, .F. ) ; -#31666 = EDGE_CURVE ( 'NONE', #16952, #1321, #28859, .T. ) ; -#31667 = CONICAL_SURFACE ( 'NONE', #32327, 2.503079361083045296, 0.7853981633955212649 ) ; -#31668 = CARTESIAN_POINT ( 'NONE', ( 20.48673967653602901, 211.0896571907997554, 75.54495990469186495 ) ) ; -#31669 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17321, #17529, #5471, #1601 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31670 = CARTESIAN_POINT ( 'NONE', ( 14.24259403095196319, 124.1280741090887574, 175.6403682132716426 ) ) ; -#31671 = CARTESIAN_POINT ( 'NONE', ( 31.79177788329871746, 115.2378434783073544, 176.5461507620590567 ) ) ; -#31672 = AXIS2_PLACEMENT_3D ( 'NONE', #16244, #712, #28146 ) ; -#31673 = CIRCLE ( 'NONE', #36204, 51.90509898893394336 ) ; -#31674 = ORIENTED_EDGE ( 'NONE', *, *, #27808, .F. ) ; -#31675 = FACE_OUTER_BOUND ( 'NONE', #14857, .T. ) ; -#31676 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490303348942, 156.2427122711440575, 96.23754757945233962 ) ) ; -#31677 = EDGE_CURVE ( 'NONE', #29541, #11287, #1035, .T. ) ; -#31678 = CARTESIAN_POINT ( 'NONE', ( 28.18621395003418328, 187.0539859719742140, 103.3338670887423376 ) ) ; -#31679 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178570903572E-05, -0.0002331579774915885982 ) ) ; -#31680 = AXIS2_PLACEMENT_3D ( 'NONE', #32417, #20328, #29547 ) ; -#31681 = CARTESIAN_POINT ( 'NONE', ( 3.600895702622226136, 143.5595025811426524, 95.80631016907535979 ) ) ; -#31682 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971544308 ) ) ; -#31683 = ORIENTED_EDGE ( 'NONE', *, *, #38832, .T. ) ; -#31684 = EDGE_LOOP ( 'NONE', ( #12976, #339 ) ) ; -#31685 = EDGE_CURVE ( 'NONE', #3241, #16069, #9656, .T. ) ; -#31686 = DIRECTION ( 'NONE', ( -0.2342984846413009858, -0.04020344573792828530, 0.9713330546447944691 ) ) ; -#31687 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6352, #37834, #27657, #28055 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31688 = FACE_OUTER_BOUND ( 'NONE', #34365, .T. ) ; -#31689 = CARTESIAN_POINT ( 'NONE', ( -38.20586753382468004, 218.5902260770999987, 73.08157946901140178 ) ) ; -#31690 = CARTESIAN_POINT ( 'NONE', ( 41.37348633212936022, 109.4896380203848025, 169.0614224528716818 ) ) ; -#31691 = VERTEX_POINT ( 'NONE', #31531 ) ; -#31692 = CARTESIAN_POINT ( 'NONE', ( -16.85990575305292083, 127.4181457678018035, 171.9189068126523807 ) ) ; -#31693 = ORIENTED_EDGE ( 'NONE', *, *, #3475, .F. ) ; -#31694 = CARTESIAN_POINT ( 'NONE', ( -25.99734782917291298, 118.8155664120999973, 94.28348731542803307 ) ) ; -#31695 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34670, #13029, #6670, #25513 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31696 = CYLINDRICAL_SURFACE ( 'NONE', #14457, 6.000000000000008882 ) ; -#31697 = EDGE_LOOP ( 'NONE', ( #4446, #22174, #16300, #32549 ) ) ; -#31698 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -1.674357682623054533E-18, 0.0006039748319388627039 ) ) ; -#31699 = DIRECTION ( 'NONE', ( 0.0006039748319387941823, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#31700 = FACE_OUTER_BOUND ( 'NONE', #16857, .T. ) ; -#31701 = CARTESIAN_POINT ( 'NONE', ( 75.33557036604483415, 196.2212959549355560, 191.1727427149328093 ) ) ; -#31702 = CIRCLE ( 'NONE', #10160, 7.499999999987333688 ) ; -#31703 = ORIENTED_EDGE ( 'NONE', *, *, #10031, .F. ) ; -#31704 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -0.000000000000000000, 0.0006039748319387907129 ) ) ; -#31705 = CARTESIAN_POINT ( 'NONE', ( 42.83485424785748563, 120.8183422764421948, 92.52881085981866249 ) ) ; -#31706 = AXIS2_PLACEMENT_3D ( 'NONE', #20246, #35559, #32733 ) ; -#31707 = CIRCLE ( 'NONE', #23193, 2.749999999872844381 ) ; -#31708 = PLANE ( 'NONE', #14285 ) ; -#31709 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#31710 = CIRCLE ( 'NONE', #12119, 6.000000000000007994 ) ; -#31711 = VERTEX_POINT ( 'NONE', #3490 ) ; -#31712 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#31713 = VERTEX_POINT ( 'NONE', #13524 ) ; -#31714 = CARTESIAN_POINT ( 'NONE', ( 12.68911377202444690, 149.1576569327452830, 181.5431584767406719 ) ) ; -#31715 = DIRECTION ( 'NONE', ( -0.0005884949961257719903, 0.2249510543439054711, -0.9743698870671265722 ) ) ; -#31716 = ADVANCED_FACE ( 'NONE', ( #19828 ), #11185, .F. ) ; -#31717 = ADVANCED_FACE ( 'NONE', ( #437 ), #38055, .F. ) ; -#31718 = CARTESIAN_POINT ( 'NONE', ( -12.63071249806800722, 177.0758676880871292, 103.5673281599171816 ) ) ; -#31719 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#31720 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384538513 ) ) ; -#31721 = CARTESIAN_POINT ( 'NONE', ( 38.14137417362000093, 118.9128982934000049, 90.39730654139999899 ) ) ; -#31722 = ORIENTED_EDGE ( 'NONE', *, *, #36736, .F. ) ; -#31723 = CARTESIAN_POINT ( 'NONE', ( 30.05533549523401149, 104.1131156702010969, 90.24963216969922541 ) ) ; -#31724 = CARTESIAN_POINT ( 'NONE', ( 35.04494061520995274, 225.9002260770261330, 73.03733781633900435 ) ) ; -#31725 = DIRECTION ( 'NONE', ( 0.0005884962718225328912, -0.2249510543436811782, 0.9743698870664077027 ) ) ; -#31726 = ORIENTED_EDGE ( 'NONE', *, *, #8299, .T. ) ; -#31727 = CIRCLE ( 'NONE', #14654, 22.50000000000000000 ) ; -#31728 = AXIS2_PLACEMENT_3D ( 'NONE', #27999, #40434, #18744 ) ; -#31729 = VERTEX_POINT ( 'NONE', #31743 ) ; -#31730 = FACE_OUTER_BOUND ( 'NONE', #5257, .T. ) ; -#31731 = CARTESIAN_POINT ( 'NONE', ( 28.46511207851075653, 181.6173849797036439, 104.1311689223658448 ) ) ; -#31732 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989907490, 0.1373964268091706076 ) ) ; -#31733 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384538513 ) ) ; -#31734 = VECTOR ( 'NONE', #21792, 1000.000000000000000 ) ; -#31735 = ORIENTED_EDGE ( 'NONE', *, *, #31525, .T. ) ; -#31736 = ORIENTED_EDGE ( 'NONE', *, *, #11651, .T. ) ; -#31737 = PLANE ( 'NONE', #25061 ) ; -#31738 = ADVANCED_FACE ( 'NONE', ( #16178 ), #3700, .F. ) ; -#31739 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22651, #32245, #19357, #18947 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.004218741086469320230, 0.004610302917384741239 ), - .UNSPECIFIED. ) ; -#31740 = CARTESIAN_POINT ( 'NONE', ( -38.60375092211999970, 119.0085671394000002, 90.10761541063000379 ) ) ; -#31741 = CARTESIAN_POINT ( 'NONE', ( -38.04037173331000332, 119.2271231706999970, 87.30284227318999513 ) ) ; -#31742 = CARTESIAN_POINT ( 'NONE', ( -23.36190354062885888, 137.3525714946963774, 91.37421276297489214 ) ) ; -#31743 = CARTESIAN_POINT ( 'NONE', ( 16.57242805487306470, 121.7393926975746155, 178.0454114939713861 ) ) ; -#31744 = ORIENTED_EDGE ( 'NONE', *, *, #37515, .T. ) ; -#31745 = CARTESIAN_POINT ( 'NONE', ( -19.40399956016737804, 125.0084816723671395, 177.4278432361402054 ) ) ; -#31746 = ORIENTED_EDGE ( 'NONE', *, *, #3356, .F. ) ; -#31747 = CARTESIAN_POINT ( 'NONE', ( -20.01736593119981222, 207.8686407175673594, 77.28911966098117148 ) ) ; -#31748 = CARTESIAN_POINT ( 'NONE', ( -0.0008827424941783000058, 156.0177612168000394, 97.21191746652000631 ) ) ; -#31749 = ORIENTED_EDGE ( 'NONE', *, *, #6316, .T. ) ; -#31750 = VERTEX_POINT ( 'NONE', #10057 ) ; -#31751 = FACE_OUTER_BOUND ( 'NONE', #6784, .T. ) ; -#31752 = CARTESIAN_POINT ( 'NONE', ( 0.8901324790414124610, 188.6335715761424865, 103.2018773863535728 ) ) ; -#31753 = LINE ( 'NONE', #38659, #26028 ) ; -#31754 = EDGE_CURVE ( 'NONE', #9013, #15229, #15746, .T. ) ; -#31755 = ORIENTED_EDGE ( 'NONE', *, *, #11696, .T. ) ; -#31756 = CARTESIAN_POINT ( 'NONE', ( 20.32319569345560595, 118.1108005801726506, 87.57833703372055822 ) ) ; -#31757 = CARTESIAN_POINT ( 'NONE', ( -42.83388826220544132, 121.9349074780233195, 87.82968285981074530 ) ) ; -#31758 = ORIENTED_EDGE ( 'NONE', *, *, #38166, .T. ) ; -#31759 = VECTOR ( 'NONE', #20788, 1000.000000000000000 ) ; -#31760 = EDGE_CURVE ( 'NONE', #4754, #7856, #11063, .T. ) ; -#31761 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319411731388 ) ) ; -#31762 = CARTESIAN_POINT ( 'NONE', ( -25.82554725903140636, 193.9703421726525789, 102.7836296653337484 ) ) ; -#31763 = CARTESIAN_POINT ( 'NONE', ( -26.05208678994999971, 122.4317902912000022, 90.62476585039999577 ) ) ; -#31764 = CIRCLE ( 'NONE', #21955, 5.499999999957825736 ) ; -#31765 = ORIENTED_EDGE ( 'NONE', *, *, #9416, .T. ) ; -#31766 = EDGE_CURVE ( 'NONE', #10320, #29452, #35247, .T. ) ; -#31767 = CARTESIAN_POINT ( 'NONE', ( -16.54564866400918532, 121.8302699986925148, 177.5519171002900407 ) ) ; -#31768 = EDGE_CURVE ( 'NONE', #24320, #13773, #26026, .T. ) ; -#31769 = CARTESIAN_POINT ( 'NONE', ( 22.15443392043009752, 115.2196822810860510, 152.7520160474520026 ) ) ; -#31770 = CARTESIAN_POINT ( 'NONE', ( 39.72476718210158708, 169.1831314395676031, 164.4948153179034307 ) ) ; -#31771 = EDGE_LOOP ( 'NONE', ( #34811, #22401, #23761, #3318 ) ) ; -#31772 = CARTESIAN_POINT ( 'NONE', ( -15.49839344145972397, 153.4668451609490205, 95.09289564923821558 ) ) ; -#31773 = LINE ( 'NONE', #33708, #4784 ) ; -#31774 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26802, #4903, #14529, #33320, #17356, #27011, #21072, #1848, #33515, #14327, #5310, #30680, #11251, #2059, #17767, #2673, #39449 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000001060818, 0.1875000000001437184, 0.2187500000001966760, 0.2343750000002728651, 0.2500000000003490541, 0.3750000000003807510, 0.4375000000003967382, 0.4687500000004181100, 0.5000000000004395373, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31776 = CARTESIAN_POINT ( 'NONE', ( -13.49899752757120019, 187.7917310252263974, 103.4871798716026916 ) ) ; -#31775 = DIRECTION ( 'NONE', ( -1.387778780819091104E-15, 0.9743700557921587402, 0.2249510932971557908 ) ) ; -#31777 = ORIENTED_EDGE ( 'NONE', *, *, #23760, .T. ) ; -#31778 = DIRECTION ( 'NONE', ( 0.0005884949961233809992, -0.2249510543439078580, 0.9743698870671259060 ) ) ; -#31779 = ORIENTED_EDGE ( 'NONE', *, *, #27414, .T. ) ; -#31780 = FACE_OUTER_BOUND ( 'NONE', #14253, .T. ) ; -#31781 = VECTOR ( 'NONE', #28318, 1000.000000000000227 ) ; -#31782 = CARTESIAN_POINT ( 'NONE', ( 21.72804141255551968, 135.8412665901933281, 91.00123227078390187 ) ) ; -#31783 = ORIENTED_EDGE ( 'NONE', *, *, #121, .F. ) ; -#31784 = CIRCLE ( 'NONE', #33713, 5.499999999909167769 ) ; -#31785 = AXIS2_PLACEMENT_3D ( 'NONE', #26337, #19571, #14265 ) ; -#31786 = ORIENTED_EDGE ( 'NONE', *, *, #18216, .F. ) ; -#31787 = CARTESIAN_POINT ( 'NONE', ( 45.19898052048043979, 188.2352433429451537, 105.6199565309152746 ) ) ; -#31788 = CARTESIAN_POINT ( 'NONE', ( 21.44693687352840783, 182.5616219828937687, 101.7876413893260974 ) ) ; -#31789 = CARTESIAN_POINT ( 'NONE', ( 29.78094669178764065, 126.4966683339110460, 91.40475166325242640 ) ) ; -#31790 = CARTESIAN_POINT ( 'NONE', ( 35.83803577802999740, 191.9457902004000118, 104.0590614479000067 ) ) ; -#31791 = AXIS2_PLACEMENT_3D ( 'NONE', #19392, #22280, #35105 ) ; -#31792 = VERTEX_POINT ( 'NONE', #29466 ) ; -#31793 = ORIENTED_EDGE ( 'NONE', *, *, #21396, .T. ) ; -#31794 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319696310, 136.7477301991403920, 291.5295797804309359 ) ) ; -#31795 = CARTESIAN_POINT ( 'NONE', ( -23.36591346911345468, 134.3034081359250251, 93.69901219035510564 ) ) ; -#31796 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971570953 ) ) ; -#31797 = VERTEX_POINT ( 'NONE', #4911 ) ; -#31798 = CARTESIAN_POINT ( 'NONE', ( 39.05618840431949934, 127.6228066749279577, 91.65913928136414768 ) ) ; -#31799 = ORIENTED_EDGE ( 'NONE', *, *, #18682, .F. ) ; -#31800 = EDGE_CURVE ( 'NONE', #16377, #1321, #19844, .T. ) ; -#31801 = DIRECTION ( 'NONE', ( -0.5987319960703951782, -0.8009494346596170988, 0.000000000000000000 ) ) ; -#31802 = DIRECTION ( 'NONE', ( 7.677760455957277161E-18, -1.000000000000000000, 1.271205131337255403E-14 ) ) ; -#31803 = ADVANCED_FACE ( 'NONE', ( #23132 ), #10786, .F. ) ; -#31804 = CARTESIAN_POINT ( 'NONE', ( -48.18910981145552341, 141.1918910709570980, 290.9667924317506049 ) ) ; -#31805 = CARTESIAN_POINT ( 'NONE', ( -75.43109585695218300, 195.4393986266478578, 195.0604493770005945 ) ) ; -#31806 = CONICAL_SURFACE ( 'NONE', #17413, 2.499999999939590101, 0.7853981634430725611 ) ; -#31807 = ORIENTED_EDGE ( 'NONE', *, *, #34133, .F. ) ; -#31808 = CARTESIAN_POINT ( 'NONE', ( -40.95638651214006387, 217.7719116656250264, 73.58324080466826445 ) ) ; -#31809 = ORIENTED_EDGE ( 'NONE', *, *, #38211, .F. ) ; -#31811 = ADVANCED_FACE ( 'NONE', ( #6325 ), #24964, .F. ) ; -#31810 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971551802 ) ) ; -#31812 = AXIS2_PLACEMENT_3D ( 'NONE', #25758, #13669, #13865 ) ; -#31813 = EDGE_CURVE ( 'NONE', #15187, #14638, #20116, .T. ) ; -#31814 = CARTESIAN_POINT ( 'NONE', ( 22.99138912207082441, 214.0899462551063266, 73.04463992848049259 ) ) ; -#31815 = CIRCLE ( 'NONE', #3709, 6.499999999944858331 ) ; -#31816 = DIRECTION ( 'NONE', ( -0.7066795774897113303, 3.556110865384900083E-18, 0.7075337269409588403 ) ) ; -#31817 = ADVANCED_FACE ( 'NONE', ( #36610 ), #8614, .T. ) ; -#31818 = EDGE_CURVE ( 'NONE', #34948, #28895, #9012, .T. ) ; -#31819 = CARTESIAN_POINT ( 'NONE', ( 5.958856854324413810, 148.4719693777741725, 97.00569074539359349 ) ) ; -#31820 = VERTEX_POINT ( 'NONE', #14942 ) ; -#31821 = VECTOR ( 'NONE', #21117, 1000.000000000000227 ) ; -#31822 = CARTESIAN_POINT ( 'NONE', ( 20.59009467808899529, 212.9326083685893138, 76.04786435846743586 ) ) ; -#31823 = CARTESIAN_POINT ( 'NONE', ( 33.37602094669033193, 84.06324503389978986, 284.1448219155665242 ) ) ; -#31824 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#31825 = ORIENTED_EDGE ( 'NONE', *, *, #40086, .F. ) ; -#31826 = ORIENTED_EDGE ( 'NONE', *, *, #35576, .F. ) ; -#31827 = CARTESIAN_POINT ( 'NONE', ( 39.80107749601363309, 119.4152471894954601, 89.76382462946382645 ) ) ; -#31828 = CARTESIAN_POINT ( 'NONE', ( -27.33572494190097757, 124.2741252816392858, 88.36037343900612484 ) ) ; -#31829 = CARTESIAN_POINT ( 'NONE', ( 35.04524256069796451, 220.4002260770999726, 73.53733772521300693 ) ) ; -#31830 = CARTESIAN_POINT ( 'NONE', ( 23.36282490288553859, 177.5222052319614363, 100.8559891474603916 ) ) ; -#31831 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971538202 ) ) ; -#31832 = EDGE_LOOP ( 'NONE', ( #3246, #21646, #5772 ) ) ; -#31833 = ORIENTED_EDGE ( 'NONE', *, *, #1246, .T. ) ; -#31834 = CARTESIAN_POINT ( 'NONE', ( 2.107992061087183622, 189.7122439190391958, 105.9414811856116927 ) ) ; -#31835 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26292, #32812, #14417, #38731, #35653, #36070, #8286, #14629, #23219, #11557, #20536, #36487 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 4 ), - ( 1.387778780781445521E-17, 0.0001130297836568479959, 0.0002260595673136821140, 0.0004521191346273053017, 0.0009042382692545467438, 0.001808476538509029737 ), - .UNSPECIFIED. ) ; -#31836 = LINE ( 'NONE', #3994, #37277 ) ; -#31837 = CIRCLE ( 'NONE', #28563, 2.499999999999997335 ) ; -#31838 = VERTEX_POINT ( 'NONE', #17982 ) ; -#31839 = CARTESIAN_POINT ( 'NONE', ( -45.98416322616978391, 186.8584405881918542, 105.3861271832789583 ) ) ; -#31840 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26340, #11388, #38772, #1999 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31841 = CARTESIAN_POINT ( 'NONE', ( 21.98581530479853541, 129.8239281020156568, 89.95395906820830589 ) ) ; -#31842 = CARTESIAN_POINT ( 'NONE', ( 36.02656720897999776, 191.4402619432999870, 103.6984301366999972 ) ) ; -#31843 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #31819, #39482 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31844 = ORIENTED_EDGE ( 'NONE', *, *, #29078, .F. ) ; -#31845 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825945353352502, 0.0005734119018001440160 ) ) ; -#31846 = CARTESIAN_POINT ( 'NONE', ( -37.27925446228768891, 172.2690084905978267, 165.2355064606533688 ) ) ; -#31847 = LINE ( 'NONE', #3802, #28046 ) ; -#31848 = ORIENTED_EDGE ( 'NONE', *, *, #24736, .T. ) ; -#31849 = CARTESIAN_POINT ( 'NONE', ( -39.32442775238350663, 119.6599143282171411, 90.38126434724790670 ) ) ; -#31850 = EDGE_CURVE ( 'NONE', #529, #7159, #24072, .T. ) ; -#31851 = LINE ( 'NONE', #3806, #10097 ) ; -#31852 = CARTESIAN_POINT ( 'NONE', ( -75.99035305782904004, 156.3451282303881555, 95.79393540400387508 ) ) ; -#31853 = CARTESIAN_POINT ( 'NONE', ( -35.93925692340999944, 191.9759150222000130, 101.9431537509999970 ) ) ; -#31854 = CARTESIAN_POINT ( 'NONE', ( 43.53560975226982777, 121.3918131887250524, 90.46069063649885322 ) ) ; -#31855 = ORIENTED_EDGE ( 'NONE', *, *, #15093, .F. ) ; -#31856 = CARTESIAN_POINT ( 'NONE', ( -13.73975480748715938, 125.4641165511624621, 174.2036076504717244 ) ) ; -#31857 = EDGE_CURVE ( 'NONE', #21705, #6809, #18384, .T. ) ; -#31858 = CARTESIAN_POINT ( 'NONE', ( 0.5667676650968811458, 188.9999965746388000, 103.6932924457196918 ) ) ; -#31859 = FACE_OUTER_BOUND ( 'NONE', #26224, .T. ) ; -#31860 = ADVANCED_FACE ( 'NONE', ( #11671 ), #33732, .T. ) ; -#31861 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35548, #4495, #1433, #32916 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31862 = CARTESIAN_POINT ( 'NONE', ( -17.26187419364011078, 152.0564478534674038, 184.5517043374173340 ) ) ; -#31863 = PLANE ( 'NONE', #24503 ) ; -#31864 = DIRECTION ( 'NONE', ( -0.0005884949961204437871, 0.2249510543439066645, -0.9743698870671262391 ) ) ; -#31865 = CARTESIAN_POINT ( 'NONE', ( 75.31247730783820771, 195.3485392357280261, 195.0764703131155500 ) ) ; -#31866 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#31867 = ADVANCED_FACE ( 'NONE', ( #27444 ), #26225, .F. ) ; -#31868 = CARTESIAN_POINT ( 'NONE', ( -26.28844936523910292, 188.3519279905150086, 105.7138994502329723 ) ) ; -#31869 = ORIENTED_EDGE ( 'NONE', *, *, #18297, .F. ) ; -#31870 = CARTESIAN_POINT ( 'NONE', ( 23.68470175345883888, 128.4763013119720085, 89.81285948505966132 ) ) ; -#31871 = DIRECTION ( 'NONE', ( -0.0005884949961211176188, 0.2249510543439072752, -0.9743698870671261281 ) ) ; -#31872 = ORIENTED_EDGE ( 'NONE', *, *, #35402, .F. ) ; -#31873 = CARTESIAN_POINT ( 'NONE', ( -35.93631444865729918, 190.8511581158954300, 106.8150028089617081 ) ) ; -#31874 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825944461171208, 0.0005734119018205528209 ) ) ; -#31875 = PLANE ( 'NONE', #34565 ) ; -#31876 = CARTESIAN_POINT ( 'NONE', ( 36.06383752871749948, 192.3744905196089974, 104.3246838901409888 ) ) ; -#31877 = DIRECTION ( 'NONE', ( 0.0005884949961658158049, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#31878 = CARTESIAN_POINT ( 'NONE', ( 0.5984374305236895841, 211.0000000000000000, 162.9824824848976448 ) ) ; -#31879 = CARTESIAN_POINT ( 'NONE', ( 21.21575625058384063, 175.4487304674486552, 102.7114009836462003 ) ) ; -#31880 = VERTEX_POINT ( 'NONE', #14749 ) ; -#31881 = ORIENTED_EDGE ( 'NONE', *, *, #1878, .T. ) ; -#31882 = CARTESIAN_POINT ( 'NONE', ( -2.531805045932999931, 209.6150325076999934, 75.72670028419000232 ) ) ; -#31883 = CARTESIAN_POINT ( 'NONE', ( 36.70167842581782480, 117.3142576294874573, 87.24561739792864046 ) ) ; -#31884 = PLANE ( 'NONE', #39587 ) ; -#31885 = VERTEX_POINT ( 'NONE', #37019 ) ; -#31886 = CARTESIAN_POINT ( 'NONE', ( 6.037490238918274521, 177.7058967128525921, 100.7497073300592234 ) ) ; -#31887 = ORIENTED_EDGE ( 'NONE', *, *, #23244, .T. ) ; -#31888 = CARTESIAN_POINT ( 'NONE', ( 20.50147089296921266, 119.8278772667796090, 89.87074392140300461 ) ) ; -#31889 = LINE ( 'NONE', #13275, #8595 ) ; -#31890 = EDGE_CURVE ( 'NONE', #10482, #35056, #34328, .T. ) ; -#31891 = LINE ( 'NONE', #590, #17989 ) ; -#31892 = EDGE_CURVE ( 'NONE', #36032, #20264, #25019, .T. ) ; -#31893 = AXIS2_PLACEMENT_3D ( 'NONE', #40322, #3504, #37669 ) ; -#31895 = EDGE_CURVE ( 'NONE', #2995, #1454, #31441, .T. ) ; -#31894 = DIRECTION ( 'NONE', ( -0.0005884949961246006183, 0.2249510543439056653, -0.9743698870671265722 ) ) ; -#31896 = CARTESIAN_POINT ( 'NONE', ( -44.69076577494958258, 186.0129530593780487, 106.6282315781383119 ) ) ; -#31897 = ADVANCED_FACE ( 'NONE', ( #11880, #40465, #15340 ), #39661, .F. ) ; -#31898 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178582662422E-05, 0.0002331579774919529443 ) ) ; -#31899 = CARTESIAN_POINT ( 'NONE', ( 21.97072628506042591, 177.4133455279457223, 100.5987514716936175 ) ) ; -#31900 = CONICAL_SURFACE ( 'NONE', #18148, 8.000001494568962812, 0.7853981633972983989 ) ; -#31901 = DIRECTION ( 'NONE', ( 0.7942818278044005975, 0.5920830005357868853, 0.1362134299408100657 ) ) ; -#31902 = ORIENTED_EDGE ( 'NONE', *, *, #32714, .T. ) ; -#31903 = ORIENTED_EDGE ( 'NONE', *, *, #26017, .T. ) ; -#31904 = CARTESIAN_POINT ( 'NONE', ( 15.95614559854525361, 121.8890334969419769, 174.5201005345669216 ) ) ; -#31905 = CARTESIAN_POINT ( 'NONE', ( 30.07122368478816199, 177.6509743871843909, 100.7722334953168826 ) ) ; -#31906 = CARTESIAN_POINT ( 'NONE', ( -14.74892900667990503, 122.6387602747236514, 152.1279856558663823 ) ) ; -#31907 = CARTESIAN_POINT ( 'NONE', ( -29.20104124293470349, 162.9607637445586192, 100.3719287999282130 ) ) ; -#31908 = ORIENTED_EDGE ( 'NONE', *, *, #34586, .T. ) ; -#31909 = DIRECTION ( 'NONE', ( 0.7072759766253134961, 0.1592272936566852259, -0.6887723585071316990 ) ) ; -#31910 = EDGE_LOOP ( 'NONE', ( #12943, #8447, #31606, #32545 ) ) ; -#31911 = EDGE_CURVE ( 'NONE', #33584, #35348, #4990, .T. ) ; -#31912 = CARTESIAN_POINT ( 'NONE', ( -20.33319487501234235, 138.1136697287241475, 91.89341636764112309 ) ) ; -#31913 = DIRECTION ( 'NONE', ( -0.0002331579778304450367, 0.000000000000000000, 0.9999999728186783621 ) ) ; -#31914 = LINE ( 'NONE', #28246, #4546 ) ; -#31915 = DIRECTION ( 'NONE', ( 0.0005559617641698784158, -0.3907311284608755431, 0.9205046855710228293 ) ) ; -#31916 = ADVANCED_FACE ( 'NONE', ( #30686 ), #31087, .T. ) ; -#31917 = VECTOR ( 'NONE', #20868, 1000.000000000000114 ) ; -#31918 = DIRECTION ( 'NONE', ( -0.0005884949961214528541, 0.2249510543439078303, -0.9743698870671260170 ) ) ; -#31919 = CARTESIAN_POINT ( 'NONE', ( -2.943769803757999792, 209.8858866696000121, 72.92663106025999298 ) ) ; -#31920 = CARTESIAN_POINT ( 'NONE', ( 38.67304637376000187, 118.3857514081000062, 89.51272550298999420 ) ) ; -#31921 = VERTEX_POINT ( 'NONE', #19595 ) ; -#31922 = DIRECTION ( 'NONE', ( 0.7075337269008550312, 8.718783055999616425E-15, 0.7066795775298634341 ) ) ; -#31923 = VECTOR ( 'NONE', #37229, 1000.000000000000114 ) ; -#31924 = CARTESIAN_POINT ( 'NONE', ( -20.01834611325332247, 210.1689860900705753, 76.07064898925692376 ) ) ; -#31925 = DIRECTION ( 'NONE', ( 0.7933533411653078682, 0.5931840316265221125, 0.1368326740407710407 ) ) ; -#31926 = AXIS2_PLACEMENT_3D ( 'NONE', #26478, #38926, #32798 ) ; -#31927 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #706, #32206, #13393, #9932 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 8.431138928378200018E-07, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31928 = CARTESIAN_POINT ( 'NONE', ( 16.99952089899044694, 136.5640433068810182, 181.4726123975704297 ) ) ; -#31929 = ORIENTED_EDGE ( 'NONE', *, *, #28339, .F. ) ; -#31930 = ORIENTED_EDGE ( 'NONE', *, *, #35081, .F. ) ; -#31931 = EDGE_LOOP ( 'NONE', ( #13423, #19522 ) ) ; -#31932 = DIRECTION ( 'NONE', ( 8.625810036883390059E-16, 0.9743700557916298299, 0.2249510932994460699 ) ) ; -#31933 = CARTESIAN_POINT ( 'NONE', ( -26.01494426630450008, 211.0902259182902014, 73.07465174665132679 ) ) ; -#31934 = ORIENTED_EDGE ( 'NONE', *, *, #36599, .T. ) ; -#31935 = CARTESIAN_POINT ( 'NONE', ( 20.23141915213000175, 210.3997737976999929, 75.79629159974001595 ) ) ; -#31936 = CARTESIAN_POINT ( 'NONE', ( -34.37617727112554178, 159.7078911223883608, 187.3767538074542358 ) ) ; -#31937 = CARTESIAN_POINT ( 'NONE', ( -38.86369648667000121, 118.8228811146000083, 89.72077586238000890 ) ) ; -#31938 = CARTESIAN_POINT ( 'NONE', ( -38.36013681963000010, 118.8201344991000070, 87.71886890835001793 ) ) ; -#31939 = DIRECTION ( 'NONE', ( 0.0005884949961257158286, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#31940 = CARTESIAN_POINT ( 'NONE', ( -14.39900080767387358, 134.4949918206585551, 152.5558619512717371 ) ) ; -#31941 = VERTEX_POINT ( 'NONE', #589 ) ; -#31942 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927769559465, -0.0005734119022075471854 ) ) ; -#31943 = ORIENTED_EDGE ( 'NONE', *, *, #33371, .T. ) ; -#31944 = EDGE_CURVE ( 'NONE', #37610, #7652, #26969, .T. ) ; -#31945 = LINE ( 'NONE', #19646, #39665 ) ; -#31946 = DIRECTION ( 'NONE', ( 0.0005884949961246697904, -0.2249510543439056376, 0.9743698870671265722 ) ) ; -#31947 = CARTESIAN_POINT ( 'NONE', ( -12.63676213157982531, 181.6119438013536183, 104.1547372293333495 ) ) ; -#31948 = EDGE_LOOP ( 'NONE', ( #11281, #12489, #19158, #15648 ) ) ; -#31949 = ORIENTED_EDGE ( 'NONE', *, *, #37832, .T. ) ; -#31950 = AXIS2_PLACEMENT_3D ( 'NONE', #1392, #26560, #26759 ) ; -#31951 = CARTESIAN_POINT ( 'NONE', ( -2.937322396554999937, 191.1124756257999877, 103.7764890163000047 ) ) ; -#31952 = FACE_OUTER_BOUND ( 'NONE', #23009, .T. ) ; -#31953 = CARTESIAN_POINT ( 'NONE', ( 2.685751687114999786, 190.9521868795999922, 106.4257393099999973 ) ) ; -#31954 = VECTOR ( 'NONE', #20726, 1000.000000000000000 ) ; -#31955 = AXIS2_PLACEMENT_3D ( 'NONE', #18609, #30720, #12911 ) ; -#31956 = ORIENTED_EDGE ( 'NONE', *, *, #15362, .F. ) ; -#31957 = CARTESIAN_POINT ( 'NONE', ( -20.02016821360482268, 211.0854730039747267, 73.07052224373646254 ) ) ; -#31958 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#31959 = ORIENTED_EDGE ( 'NONE', *, *, #38334, .F. ) ; -#31960 = CARTESIAN_POINT ( 'NONE', ( 114.5937281169188253, 50.54601443099469549, 171.8750556891886276 ) ) ; -#31961 = DIRECTION ( 'NONE', ( -0.0005884949961262653023, 0.2249510543439053600, -0.9743698870671265722 ) ) ; -#31962 = CARTESIAN_POINT ( 'NONE', ( -25.99977390623968532, 118.5811435109333303, 90.28348805114744380 ) ) ; -#31963 = ORIENTED_EDGE ( 'NONE', *, *, #13151, .T. ) ; -#31964 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10338, #7239, #20106, #1307 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#31965 = CARTESIAN_POINT ( 'NONE', ( -19.99829785685910011, 119.7153791177249502, 90.38236254249699186 ) ) ; -#31966 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; -#31967 = EDGE_CURVE ( 'NONE', #6135, #22589, #31889, .T. ) ; -#31968 = VERTEX_POINT ( 'NONE', #7326 ) ; -#31969 = CARTESIAN_POINT ( 'NONE', ( 25.66733978393000015, 120.1839125632999981, 90.12708786838000208 ) ) ; -#31970 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971593713 ) ) ; -#31971 = CARTESIAN_POINT ( 'NONE', ( -14.75545039936645253, 171.9013578063558043, 152.1279856333616465 ) ) ; -#31973 = CARTESIAN_POINT ( 'NONE', ( -11.82471700305710627, 154.1761034371582468, 95.25442204585927186 ) ) ; -#31972 = CARTESIAN_POINT ( 'NONE', ( -20.49970524097187763, 120.2776284062741325, 87.94673202274765345 ) ) ; -#31974 = ORIENTED_EDGE ( 'NONE', *, *, #25723, .T. ) ; -#31975 = CARTESIAN_POINT ( 'NONE', ( -19.99984748064912665, 127.7403057018771904, 89.15611954941233819 ) ) ; -#31976 = AXIS2_PLACEMENT_3D ( 'NONE', #39318, #1107, #13590 ) ; -#31977 = AXIS2_PLACEMENT_3D ( 'NONE', #28209, #19165, #15907 ) ; -#31978 = CARTESIAN_POINT ( 'NONE', ( 39.71644276554569331, 128.0354526761064164, 94.31825870285607039 ) ) ; -#31979 = EDGE_LOOP ( 'NONE', ( #184, #9259, #20904, #37658 ) ) ; -#31980 = ORIENTED_EDGE ( 'NONE', *, *, #18405, .T. ) ; -#31981 = CARTESIAN_POINT ( 'NONE', ( 15.50147167064367437, 126.2420947773427997, 91.35460322390918009 ) ) ; -#31982 = CARTESIAN_POINT ( 'NONE', ( -45.01686328689083894, 124.5428679525740989, 91.48657569876101547 ) ) ; -#31983 = CARTESIAN_POINT ( 'NONE', ( -2.300492201474999998, 191.0297072097000068, 106.1836901105999971 ) ) ; -#31984 = CARTESIAN_POINT ( 'NONE', ( 35.57400175955999799, 192.0876667541000131, 103.8903688872000117 ) ) ; -#31985 = ORIENTED_EDGE ( 'NONE', *, *, #9741, .F. ) ; -#31986 = ORIENTED_EDGE ( 'NONE', *, *, #22674, .F. ) ; -#31987 = CARTESIAN_POINT ( 'NONE', ( -42.85824143706140177, 121.9102241652851575, 87.85339546770353536 ) ) ; -#31989 = ADVANCED_FACE ( 'NONE', ( #790 ), #18987, .F. ) ; -#31988 = CARTESIAN_POINT ( 'NONE', ( -12.63707034089905612, 177.5566571168823486, 100.8521260122499683 ) ) ; -#31990 = CARTESIAN_POINT ( 'NONE', ( -23.36303326529986890, 134.3845102228084158, 93.64833256334264888 ) ) ; -#31991 = EDGE_CURVE ( 'NONE', #33925, #13672, #39242, .T. ) ; -#31992 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971536259 ) ) ; -#31993 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #370, #562, #6296 ), - ( #15517, #38193, #16302 ), - ( #9386, #37987, #3826 ), - ( #18755, #9990, #12640 ) ), - .UNSPECIFIED., .F., .F., .T. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), - ( 3, 3 ), - ( 0.4680274479876873617, 0.4680515558888064809 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.7506739324345677034, 1.000000000000000000), - ( 1.000000000000000000, 0.7506633861694811394, 1.000000000000000000), - ( 1.000000000000000000, 0.7506528395853189206, 1.000000000000000000), - ( 1.000000000000000000, 0.7506422926820343067, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#31994 = ORIENTED_EDGE ( 'NONE', *, *, #9270, .T. ) ; -#31995 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #8508, #29969, #26508, #14644 ), - ( #27332, #36299, #18082, #17474 ), - ( #1755, #8298, #27128, #14848 ), - ( #20761, #17877, #8719, #20346 ), - ( #39564, #23636, #38957, #20974 ), - ( #17679, #17265, #33427, #36087 ), - ( #26710, #30175, #35873, #2173 ), - ( #21176, #11574, #30586, #30373 ), - ( #2575, #39156, #36504, #2374 ), - ( #33634, #23430, #7882, #4803 ), - ( #20548, #11165, #39760, #33021 ), - ( #11779, #24263, #5012, #1966 ), - ( #26920, #3154, #22190, #6619 ), - ( #21395, #24866, #33835, #37317 ), - ( #9509, #3355, #28321, #6420 ), - ( #8921, #15043, #9310, #21992 ), - ( #31184, #30986, #37117, #12368 ), - ( #18284, #21788, #34226, #5836 ), - ( #34424, #2951, #30787, #34618 ), - ( #287, #15827, #15445, #18883 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 3, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.009978065169328498643, 2.171379472327000104E-05, 0.001571209923265000103, 0.003133759667688999859, 0.006258859156535999738, 0.01250905813423000036, 0.01875925711191999898, 0.02500945608961999828, 0.05001025200038999863, 0.1000118438218999956, 0.1500134356435000038, 0.2000150274648999915, 0.4000110835753000194, 0.6000071396855000128, 0.8000031957958999573, 0.9999996101999000242 ), - ( 0.1755988089626999982, 0.8244287575951999569 ), - .UNSPECIFIED. ) ; -#31996 = DIRECTION ( 'NONE', ( -0.7069397806464156053, 0.6508950906897285060, 0.2767159689204939932 ) ) ; -#31997 = ORIENTED_EDGE ( 'NONE', *, *, #10939, .T. ) ; -#31998 = CARTESIAN_POINT ( 'NONE', ( 35.93343626571697769, 108.4364864373064137, 169.8429943716569994 ) ) ; -#31999 = ORIENTED_EDGE ( 'NONE', *, *, #38522, .T. ) ; -#32000 = FACE_OUTER_BOUND ( 'NONE', #6409, .T. ) ; -#32001 = AXIS2_PLACEMENT_3D ( 'NONE', #21234, #3011, #24924 ) ; -#32002 = VECTOR ( 'NONE', #40354, 1000.000000000000114 ) ; -#32003 = CARTESIAN_POINT ( 'NONE', ( -0.3488545754133000054, 188.2235992194000289, 106.3567909089000096 ) ) ; -#32004 = DIRECTION ( 'NONE', ( 0.7069375452530322068, -0.1593035203500595132, 0.6891020936811141917 ) ) ; -#32005 = ORIENTED_EDGE ( 'NONE', *, *, #12694, .F. ) ; -#32006 = PLANE ( 'NONE', #30859 ) ; -#32007 = ORIENTED_EDGE ( 'NONE', *, *, #4660, .F. ) ; -#32008 = CONICAL_SURFACE ( 'NONE', #14374, 3.003158621626311309, 0.7854054549419372533 ) ; -#32009 = DIRECTION ( 'NONE', ( 0.0005884965073590145944, -0.2249510525036911290, 0.9743698874910607932 ) ) ; -#32010 = CARTESIAN_POINT ( 'NONE', ( -38.49874843363917165, 163.0800447631557688, 197.8568742794042805 ) ) ; -#32011 = CARTESIAN_POINT ( 'NONE', ( 13.50015683897842678, 123.9577177740650598, 91.11541229130565966 ) ) ; -#32012 = CARTESIAN_POINT ( 'NONE', ( -29.94810845983804271, 109.6131156702000027, 87.28587219900418859 ) ) ; -#32013 = ORIENTED_EDGE ( 'NONE', *, *, #4873, .F. ) ; -#32014 = CARTESIAN_POINT ( 'NONE', ( 20.89286828480348035, 176.3842452922319524, 100.3618186666556369 ) ) ; -#32015 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178582662422E-05, 0.0002331579774919529443 ) ) ; -#32016 = CARTESIAN_POINT ( 'NONE', ( -36.79164517774999865, 117.4412903973999960, 90.44275846995999757 ) ) ; -#32017 = ORIENTED_EDGE ( 'NONE', *, *, #32753, .T. ) ; -#32018 = DIRECTION ( 'NONE', ( 0.0001358595490717324182, 0.9743700647852328034, 0.2249510133175757765 ) ) ; -#32019 = CARTESIAN_POINT ( 'NONE', ( 38.56885418974432866, 118.4610218664272452, 89.66265752007532797 ) ) ; -#32020 = EDGE_LOOP ( 'NONE', ( #18127, #39145, #32933, #33520, #8889, #11888, #14811, #33146, #1507, #54, #12018 ) ) ; -#32021 = CARTESIAN_POINT ( 'NONE', ( 0.5456353394255060163, 210.9999999999900240, 75.55817498829998158 ) ) ; -#32022 = EDGE_CURVE ( 'NONE', #11123, #9057, #22494, .T. ) ; -#32023 = CARTESIAN_POINT ( 'NONE', ( -27.18894999058629480, 124.1015279925761661, 88.32043755942639507 ) ) ; -#32024 = CARTESIAN_POINT ( 'NONE', ( -29.96982177062705333, 161.3773976535714780, 187.2046641938986511 ) ) ; -#32025 = CARTESIAN_POINT ( 'NONE', ( -20.49970533570471787, 160.6243682191729363, 97.26151316895288801 ) ) ; -#32026 = ORIENTED_EDGE ( 'NONE', *, *, #5294, .T. ) ; -#32027 = VERTEX_POINT ( 'NONE', #32096 ) ; -#32028 = CARTESIAN_POINT ( 'NONE', ( 42.60888955940591671, 68.11159795993565069, 322.0780808329887464 ) ) ; -#32029 = ORIENTED_EDGE ( 'NONE', *, *, #38124, .F. ) ; -#32030 = ORIENTED_EDGE ( 'NONE', *, *, #32073, .F. ) ; -#32031 = ORIENTED_EDGE ( 'NONE', *, *, #1415, .F. ) ; -#32032 = CARTESIAN_POINT ( 'NONE', ( 20.50039165879256942, 118.8156470718432729, 87.75541749211321019 ) ) ; -#32034 = CIRCLE ( 'NONE', #22894, 2.499999161650496848 ) ; -#32033 = FACE_OUTER_BOUND ( 'NONE', #13305, .T. ) ; -#32035 = ADVANCED_FACE ( 'NONE', ( #19784 ), #26960, .F. ) ; -#32036 = AXIS2_PLACEMENT_3D ( 'NONE', #37358, #37163, #40415 ) ; -#32037 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#32038 = AXIS2_PLACEMENT_3D ( 'NONE', #19820, #29257, #23517 ) ; -#32039 = ORIENTED_EDGE ( 'NONE', *, *, #22520, .F. ) ; -#32040 = DIRECTION ( 'NONE', ( -0.7942820423213359238, -0.5918950211223032998, -0.1370267171630252523 ) ) ; -#32041 = VECTOR ( 'NONE', #37724, 1000.000000000000114 ) ; -#32043 = ADVANCED_FACE ( 'NONE', ( #13081 ), #31696, .F. ) ; -#32042 = CARTESIAN_POINT ( 'NONE', ( 23.36366720388904383, 174.6836436729091133, 103.0466216106880495 ) ) ; -#32044 = CARTESIAN_POINT ( 'NONE', ( 36.18873234541000272, 116.0516713650000185, 87.35401155214999847 ) ) ; -#32045 = CARTESIAN_POINT ( 'NONE', ( -38.68891799773000884, 119.1263286439999973, 90.16723566163000214 ) ) ; -#32046 = ADVANCED_FACE ( 'NONE', ( #9611 ), #19182, .T. ) ; -#32047 = CARTESIAN_POINT ( 'NONE', ( 19.99974539165517839, 193.0912053986162391, 103.5857589997535797 ) ) ; -#32048 = EDGE_CURVE ( 'NONE', #25706, #11904, #13765, .T. ) ; -#32049 = EDGE_CURVE ( 'NONE', #23147, #17425, #38410, .T. ) ; -#32050 = CARTESIAN_POINT ( 'NONE', ( 30.07038801303579234, 136.6840993378064866, 94.26968325502151913 ) ) ; -#32051 = VERTEX_POINT ( 'NONE', #10420 ) ; -#32052 = CARTESIAN_POINT ( 'NONE', ( 21.15680152563498950, 128.4898158065484779, 92.04116564476515805 ) ) ; -#32053 = CARTESIAN_POINT ( 'NONE', ( -20.51784484524898389, 207.7575274251524604, 76.50869542728868566 ) ) ; -#32054 = CARTESIAN_POINT ( 'NONE', ( -10.30841286990177430, 131.0201488766975046, 89.90757730957309946 ) ) ; -#32055 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999900169, 132.9679238121742912, 90.36185680194377312 ) ) ; -#32056 = CARTESIAN_POINT ( 'NONE', ( 3.850504590650025261, 136.1268787497847370, 91.07796198998222792 ) ) ; -#32057 = ORIENTED_EDGE ( 'NONE', *, *, #37844, .F. ) ; -#32058 = DIRECTION ( 'NONE', ( -0.6068733047655824331, -0.7745082036644093115, -0.1784428043363773808 ) ) ; -#32059 = CARTESIAN_POINT ( 'NONE', ( 0.6355662970509753373, 189.0012791104650205, 103.6864957496327264 ) ) ; -#32060 = CARTESIAN_POINT ( 'NONE', ( 20.50028285398298777, 191.4126458000098978, 104.3447517631808097 ) ) ; -#32061 = CARTESIAN_POINT ( 'NONE', ( 13.50130427969020275, 124.2930898829833524, 90.90584795771297877 ) ) ; -#32062 = CARTESIAN_POINT ( 'NONE', ( -26.12734889465999899, 191.8689129175999994, 103.7983224447000055 ) ) ; -#32063 = CARTESIAN_POINT ( 'NONE', ( -26.00138850119475364, 118.1173731751006102, 87.28355378449504087 ) ) ; -#32064 = CARTESIAN_POINT ( 'NONE', ( -3.168077445297452055, 127.9087829914206651, 92.26382811782556814 ) ) ; -#32065 = PLANE ( 'NONE', #3979 ) ; -#32066 = CARTESIAN_POINT ( 'NONE', ( -42.83272783108322557, 107.4558756614410697, 150.2543767220365680 ) ) ; -#32067 = ORIENTED_EDGE ( 'NONE', *, *, #23720, .T. ) ; -#32068 = AXIS2_PLACEMENT_3D ( 'NONE', #31428, #24911, #22235 ) ; -#32069 = FACE_OUTER_BOUND ( 'NONE', #7410, .T. ) ; -#32070 = ORIENTED_EDGE ( 'NONE', *, *, #5992, .T. ) ; -#32071 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#32072 = CARTESIAN_POINT ( 'NONE', ( -25.99161325705826897, 191.8394051827992826, 103.9324257214252754 ) ) ; -#32073 = EDGE_CURVE ( 'NONE', #10983, #26453, #32313, .T. ) ; -#32074 = DIRECTION ( 'NONE', ( 0.0004161288024568778944, 0.5299192578645700591, 0.8480479980408438534 ) ) ; -#32075 = FACE_OUTER_BOUND ( 'NONE', #18701, .T. ) ; -#32076 = CARTESIAN_POINT ( 'NONE', ( -12.64523939051215073, 134.9174765714697344, 90.80875027841997849 ) ) ; -#32077 = CARTESIAN_POINT ( 'NONE', ( 41.10429549663972892, 182.7543144023022137, 104.8991682080530126 ) ) ; -#32078 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4313, #3714, #10679, #27458 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32079 = CARTESIAN_POINT ( 'NONE', ( 35.69170447249999967, 192.9058989856999915, 106.6881889106000045 ) ) ; -#32080 = ORIENTED_EDGE ( 'NONE', *, *, #15955, .T. ) ; -#32081 = CARTESIAN_POINT ( 'NONE', ( -2.780775877414999986, 209.2815418106999914, 75.92975070871000298 ) ) ; -#32082 = ADVANCED_FACE ( 'NONE', ( #19397 ), #22693, .T. ) ; -#32083 = CARTESIAN_POINT ( 'NONE', ( 35.93828886713654924, 107.3103096182504146, 174.7145176258908350 ) ) ; -#32084 = EDGE_CURVE ( 'NONE', #21381, #7388, #4457, .T. ) ; -#32085 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10085, #9893, #19667, #31354, #465, #38086, #16203, #25836, #10293, #13348 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999963918, 0.4999999999999927836, 0.7499999999999963363, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32086 = DIRECTION ( 'NONE', ( 8.326672684845666840E-15, 0.9743700557921587402, 0.2249510932971545696 ) ) ; -#32087 = ORIENTED_EDGE ( 'NONE', *, *, #3613, .T. ) ; -#32088 = CARTESIAN_POINT ( 'NONE', ( 14.27573290317919330, 135.8449083118874228, 91.00656752237129865 ) ) ; -#32089 = ADVANCED_FACE ( 'NONE', ( #13675 ), #26762, .F. ) ; -#32090 = ORIENTED_EDGE ( 'NONE', *, *, #28165, .F. ) ; -#32091 = EDGE_CURVE ( 'NONE', #4584, #25855, #34020, .T. ) ; -#32092 = VECTOR ( 'NONE', #32202, 1000.000000000000227 ) ; -#32093 = VECTOR ( 'NONE', #1019, 1000.000000000000000 ) ; -#32094 = CARTESIAN_POINT ( 'NONE', ( 39.53379105069361543, 120.3902222971681368, 87.42331650858173475 ) ) ; -#32095 = CARTESIAN_POINT ( 'NONE', ( 25.92237104596770081, 117.3323686320814119, 87.25212782947929213 ) ) ; -#32096 = CARTESIAN_POINT ( 'NONE', ( -12.63675505126982657, 134.8421811116586753, 93.35708474409203461 ) ) ; -#32097 = CARTESIAN_POINT ( 'NONE', ( -39.33474900027509591, 175.4267096001368316, 136.0977776169101787 ) ) ; -#32098 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#32099 = LINE ( 'NONE', #31701, #2749 ) ; -#32100 = VERTEX_POINT ( 'NONE', #17527 ) ; -#32101 = CARTESIAN_POINT ( 'NONE', ( 15.94060000479266925, 152.3716036959190205, 183.5932755018154694 ) ) ; -#32102 = CARTESIAN_POINT ( 'NONE', ( 30.06998772288336141, 177.5055085816675842, 100.8631312348358193 ) ) ; -#32103 = CARTESIAN_POINT ( 'NONE', ( -15.10713178427481651, 176.3794795624077096, 100.3824614381103828 ) ) ; -#32104 = CARTESIAN_POINT ( 'NONE', ( -37.13682434169999880, 191.1674602843000059, 103.9294490895999985 ) ) ; -#32105 = ORIENTED_EDGE ( 'NONE', *, *, #32127, .T. ) ; -#32106 = FACE_OUTER_BOUND ( 'NONE', #21768, .T. ) ; -#32107 = EDGE_LOOP ( 'NONE', ( #39548, #28408, #5319, #23854 ) ) ; -#32108 = CARTESIAN_POINT ( 'NONE', ( 35.04645051037203984, 217.7719116314000303, 75.53733736051519543 ) ) ; -#32109 = PLANE ( 'NONE', #39322 ) ; -#32110 = DIRECTION ( 'NONE', ( -0.0005884949961225237206, 0.2249510543439054433, -0.9743698870671265722 ) ) ; -#32111 = CIRCLE ( 'NONE', #4015, 2.250000000000011102 ) ; -#32112 = FACE_OUTER_BOUND ( 'NONE', #7281, .T. ) ; -#32113 = VECTOR ( 'NONE', #5490, 999.9999999999998863 ) ; -#32114 = DIRECTION ( 'NONE', ( 0.0006039748319384539597, 1.295170900108887039E-14, 0.9999998176071845934 ) ) ; -#32115 = CARTESIAN_POINT ( 'NONE', ( -37.70271471075000136, 190.8147333642999968, 106.4196837288999973 ) ) ; -#32116 = ORIENTED_EDGE ( 'NONE', *, *, #22399, .F. ) ; -#32117 = EDGE_CURVE ( 'NONE', #37405, #16629, #37304, .T. ) ; -#32118 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971568733 ) ) ; -#32119 = ADVANCED_FACE ( 'NONE', ( #32288 ), #23281, .F. ) ; -#32120 = CARTESIAN_POINT ( 'NONE', ( 18.59950176164737812, 148.9135478570107409, 180.2224150185023177 ) ) ; -#32121 = LINE ( 'NONE', #38037, #26873 ) ; -#32122 = EDGE_CURVE ( 'NONE', #12519, #33382, #32174, .T. ) ; -#32123 = FACE_OUTER_BOUND ( 'NONE', #37843, .T. ) ; -#32124 = VERTEX_POINT ( 'NONE', #19989 ) ; -#32125 = ORIENTED_EDGE ( 'NONE', *, *, #14306, .F. ) ; -#32126 = CARTESIAN_POINT ( 'NONE', ( 25.83231656248760189, 118.8155665305523740, 87.41885382068512911 ) ) ; -#32127 = EDGE_CURVE ( 'NONE', #11480, #40319, #17119, .T. ) ; -#32128 = CARTESIAN_POINT ( 'NONE', ( 16.00173003433196328, 160.0551282760237086, 99.67379390875994716 ) ) ; -#32129 = VERTEX_POINT ( 'NONE', #10621 ) ; -#32130 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#32131 = EDGE_CURVE ( 'NONE', #19810, #328, #20651, .T. ) ; -#32132 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#32133 = CARTESIAN_POINT ( 'NONE', ( -20.30860343291056225, 211.0893031747332316, 75.78085498041677681 ) ) ; -#32134 = CARTESIAN_POINT ( 'NONE', ( -38.01249147463000355, 119.1964217757000029, 87.30166645433000383 ) ) ; -#32135 = CARTESIAN_POINT ( 'NONE', ( 14.30273991137152123, 209.7096250667529205, 76.04986613324078348 ) ) ; -#32136 = ORIENTED_EDGE ( 'NONE', *, *, #11121, .F. ) ; -#32137 = CARTESIAN_POINT ( 'NONE', ( 19.32231137207130800, 148.3832603922512021, 183.4602508322493009 ) ) ; -#32138 = ORIENTED_EDGE ( 'NONE', *, *, #34223, .T. ) ; -#32139 = CARTESIAN_POINT ( 'NONE', ( -26.00760980910003184, 207.8686442860052921, 77.29275028082734877 ) ) ; -#32140 = AXIS2_PLACEMENT_3D ( 'NONE', #19599, #13678, #22892 ) ; -#32141 = CARTESIAN_POINT ( 'NONE', ( 20.22266559583958667, 184.3432592364629272, 105.0517724516481906 ) ) ; -#32142 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319380481428 ) ) ; -#32143 = CARTESIAN_POINT ( 'NONE', ( -20.00017858637951207, 184.9560350789418237, 102.3655360699851400 ) ) ; -#32144 = CARTESIAN_POINT ( 'NONE', ( 40.92144267131097024, 126.9198679979903233, 91.49572650408431684 ) ) ; -#32145 = VERTEX_POINT ( 'NONE', #39007 ) ; -#32146 = VECTOR ( 'NONE', #31134, 1000.000000000000227 ) ; -#32147 = ADVANCED_FACE ( 'NONE', ( #11017 ), #719, .F. ) ; -#32148 = ORIENTED_EDGE ( 'NONE', *, *, #17500, .F. ) ; -#32149 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971526822 ) ) ; -#32150 = CIRCLE ( 'NONE', #29540, 1.999999999914603865 ) ; -#32151 = CARTESIAN_POINT ( 'NONE', ( 25.49223589608078555, 207.9233622696484360, 76.22750517669706483 ) ) ; -#32152 = CARTESIAN_POINT ( 'NONE', ( -39.76913700811847718, 110.4455167082730753, 170.2888389991151143 ) ) ; -#32153 = CARTESIAN_POINT ( 'NONE', ( 2.685592881625999961, 190.9411674561000041, 106.4227546106999966 ) ) ; -#32154 = EDGE_LOOP ( 'NONE', ( #36761, #15165, #36148, #2423 ) ) ; -#32155 = ORIENTED_EDGE ( 'NONE', *, *, #27852, .F. ) ; -#32156 = CARTESIAN_POINT ( 'NONE', ( 19.99941580399983110, 118.1025156334579265, 87.25545403306659864 ) ) ; -#32157 = CARTESIAN_POINT ( 'NONE', ( 22.50034184233011914, 153.8097659799650501, 95.66226703669086362 ) ) ; -#32158 = EDGE_LOOP ( 'NONE', ( #29072, #29140, #36465, #5110 ) ) ; -#32159 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26166, #25360, #3650, #25967 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32160 = DIRECTION ( 'NONE', ( 0.0004161288024809969475, 0.5299192578176238344, 0.8480479980701790543 ) ) ; -#32161 = VERTEX_POINT ( 'NONE', #12420 ) ; -#32162 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411731388 ) ) ; -#32163 = CARTESIAN_POINT ( 'NONE', ( 28.46433317244940753, 130.4256741595737310, 90.26002097211915043 ) ) ; -#32164 = CYLINDRICAL_SURFACE ( 'NONE', #26087, 2.000000000000011546 ) ; -#32165 = ORIENTED_EDGE ( 'NONE', *, *, #5947, .T. ) ; -#32166 = CARTESIAN_POINT ( 'NONE', ( 26.00088934340000080, 120.1020457456000088, 90.44395696404001228 ) ) ; -#32167 = EDGE_CURVE ( 'NONE', #3248, #32435, #13142, .T. ) ; -#32168 = DIRECTION ( 'NONE', ( 0.9999998268370356991, 0.0001323828866989250124, -0.0005734114318351182446 ) ) ; -#32169 = EDGE_CURVE ( 'NONE', #29827, #5998, #30437, .T. ) ; -#32170 = EDGE_CURVE ( 'NONE', #34570, #27269, #16389, .T. ) ; -#32172 = CARTESIAN_POINT ( 'NONE', ( -11.42861031051659637, 154.0584472107514671, 95.22701972222303368 ) ) ; -#32171 = CARTESIAN_POINT ( 'NONE', ( 76.10601358362096391, 156.3575724116909669, 95.70494597592171715 ) ) ; -#32173 = VERTEX_POINT ( 'NONE', #18532 ) ; -#32174 = CIRCLE ( 'NONE', #3342, 1.749999999999998446 ) ; -#32175 = AXIS2_PLACEMENT_3D ( 'NONE', #6789, #16200, #31156 ) ; -#32176 = DIRECTION ( 'NONE', ( -0.7933532970003738249, -0.5930762008556724751, -0.1372995488602876402 ) ) ; -#32177 = ORIENTED_EDGE ( 'NONE', *, *, #2076, .F. ) ; -#32178 = PLANE ( 'NONE', #20590 ) ; -#32179 = EDGE_CURVE ( 'NONE', #38692, #24100, #29481, .T. ) ; -#32180 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#32181 = EDGE_LOOP ( 'NONE', ( #33346, #30363, #8675, #7963 ) ) ; -#32182 = ORIENTED_EDGE ( 'NONE', *, *, #6085, .F. ) ; -#32183 = CARTESIAN_POINT ( 'NONE', ( -25.74991476775000265, 118.4643410412000009, 90.03333709688999420 ) ) ; -#32184 = EDGE_CURVE ( 'NONE', #26074, #34987, #23546, .T. ) ; -#32185 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921596284, 0.2249510932971517940 ) ) ; -#32186 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319356122658 ) ) ; -#32187 = ORIENTED_EDGE ( 'NONE', *, *, #1074, .F. ) ; -#32188 = ORIENTED_EDGE ( 'NONE', *, *, #3259, .F. ) ; -#32189 = ORIENTED_EDGE ( 'NONE', *, *, #21973, .F. ) ; -#32190 = CARTESIAN_POINT ( 'NONE', ( -6.035103513883293580, 176.8182870450115161, 103.1499335225169887 ) ) ; -#32191 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; -#32192 = DIRECTION ( 'NONE', ( -0.0005884949961226190220, 0.2249510543439057486, -0.9743698870671265722 ) ) ; -#32193 = ADVANCED_FACE ( 'NONE', ( #33679 ), #30637, .F. ) ; -#32194 = ORIENTED_EDGE ( 'NONE', *, *, #5767, .T. ) ; -#32195 = CARTESIAN_POINT ( 'NONE', ( -3.668404236352207359, 128.0226348367964988, 91.77725148510558029 ) ) ; -#32196 = ORIENTED_EDGE ( 'NONE', *, *, #23439, .T. ) ; -#32197 = AXIS2_PLACEMENT_3D ( 'NONE', #25801, #31732, #24999 ) ; -#32198 = CARTESIAN_POINT ( 'NONE', ( -12.63072017624268106, 177.7897717398484474, 100.7065154983451407 ) ) ; -#32199 = CARTESIAN_POINT ( 'NONE', ( 22.99888613823950578, 118.1131156702000169, 87.25083745503069110 ) ) ; -#32200 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29719, #4957, #33164, #23993 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32201 = ORIENTED_EDGE ( 'NONE', *, *, #38829, .F. ) ; -#32202 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825929682393506, -0.0005734119019024616929 ) ) ; -#32203 = VECTOR ( 'NONE', #17384, 1000.000000000000114 ) ; -#32204 = CARTESIAN_POINT ( 'NONE', ( -26.00142186005520983, 120.7678123865047297, 87.55007858260474052 ) ) ; -#32205 = CARTESIAN_POINT ( 'NONE', ( 20.61396327107688364, 153.5808548369363962, 95.09740590315053055 ) ) ; -#32206 = CARTESIAN_POINT ( 'NONE', ( 21.85653426457336579, 135.3094414512686967, 93.78622837506166832 ) ) ; -#32207 = ORIENTED_EDGE ( 'NONE', *, *, #8420, .T. ) ; -#32208 = CARTESIAN_POINT ( 'NONE', ( -23.00127433124000476, 115.6131156702010401, 87.78148031792994743 ) ) ; -#32209 = CARTESIAN_POINT ( 'NONE', ( 22.13129314184573460, 118.4600442149447161, 173.2772851743895899 ) ) ; -#32210 = CARTESIAN_POINT ( 'NONE', ( 19.52627756605939169, 125.2598979802000656, 175.1265769270767976 ) ) ; -#32211 = CARTESIAN_POINT ( 'NONE', ( 45.25458193946054308, 131.0018592820668175, 90.04080149089566021 ) ) ; -#32212 = ORIENTED_EDGE ( 'NONE', *, *, #14390, .T. ) ; -#32213 = CARTESIAN_POINT ( 'NONE', ( 21.14632598203208147, 213.4889694835328271, 76.04699967246882863 ) ) ; -#32214 = CARTESIAN_POINT ( 'NONE', ( 33.58239838537006250, 82.39900825877703028, 287.2850754345870428 ) ) ; -#32215 = ADVANCED_FACE ( 'NONE', ( #5470 ), #30836, .F. ) ; -#32216 = EDGE_CURVE ( 'NONE', #20739, #8063, #30876, .T. ) ; -#32217 = CARTESIAN_POINT ( 'NONE', ( -38.47073163710999921, 118.2823429409999960, 89.55163764424000306 ) ) ; -#32218 = ORIENTED_EDGE ( 'NONE', *, *, #7043, .T. ) ; -#32219 = AXIS2_PLACEMENT_3D ( 'NONE', #1476, #29298, #13754 ) ; -#32220 = ORIENTED_EDGE ( 'NONE', *, *, #3615, .F. ) ; -#32221 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6968, #22536, #32133, #23130 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.8698163993620108281 ), - .UNSPECIFIED. ) ; -#32222 = CARTESIAN_POINT ( 'NONE', ( 35.11870792466202573, 88.60542317626236297, 280.9309724330075255 ) ) ; -#32223 = DIRECTION ( 'NONE', ( 0.6087904839324246309, -0.7729173423006461263, -0.1788097554503957631 ) ) ; -#32224 = ORIENTED_EDGE ( 'NONE', *, *, #19320, .F. ) ; -#32225 = ORIENTED_EDGE ( 'NONE', *, *, #29404, .T. ) ; -#32226 = LINE ( 'NONE', #32028, #17389 ) ; -#32227 = EDGE_LOOP ( 'NONE', ( #699, #27121, #2159, #28989 ) ) ; -#32228 = ORIENTED_EDGE ( 'NONE', *, *, #23399, .T. ) ; -#32229 = CARTESIAN_POINT ( 'NONE', ( -6.036392767846526120, 177.5104564733402697, 100.8777564939393159 ) ) ; -#32230 = CIRCLE ( 'NONE', #5450, 4.500000113611068997 ) ; -#32231 = LINE ( 'NONE', #13420, #22927 ) ; -#32232 = CARTESIAN_POINT ( 'NONE', ( 19.71701219870257304, 124.6133069866743455, 177.2811646003819135 ) ) ; -#32233 = EDGE_LOOP ( 'NONE', ( #22595, #2311, #29710, #24804 ) ) ; -#32234 = CARTESIAN_POINT ( 'NONE', ( -75.43109585698152841, 195.4393986266174750, 195.0604493769935459 ) ) ; -#32235 = CARTESIAN_POINT ( 'NONE', ( 36.19634185401000082, 113.3779856859000006, 87.88489253477000318 ) ) ; -#32236 = CARTESIAN_POINT ( 'NONE', ( 36.09356709709999933, 191.3986140952000028, 103.6885138668000081 ) ) ; -#32237 = CARTESIAN_POINT ( 'NONE', ( -45.39606049366843621, 123.6566771517818637, 91.23024032489176705 ) ) ; -#32238 = EDGE_CURVE ( 'NONE', #24392, #8481, #27390, .T. ) ; -#32239 = DIRECTION ( 'NONE', ( -0.0002267487151011638629, -0.6230052038431761474, -0.7822176580526309930 ) ) ; -#32240 = ORIENTED_EDGE ( 'NONE', *, *, #7733, .T. ) ; -#32241 = CARTESIAN_POINT ( 'NONE', ( 25.66582274369000061, 120.7019146121999995, 87.84584558110999808 ) ) ; -#32242 = DIRECTION ( 'NONE', ( -0.0004229286328628529840, 0.2247401617665200635, -0.9744186373528217482 ) ) ; -#32243 = LINE ( 'NONE', #28576, #38411 ) ; -#32244 = CARTESIAN_POINT ( 'NONE', ( 3.767825934166819213, 175.3046377764247268, 100.3625370439014830 ) ) ; -#32245 = CARTESIAN_POINT ( 'NONE', ( -18.84220113800309448, 125.7468176466592382, 175.1817517265227195 ) ) ; -#32246 = ORIENTED_EDGE ( 'NONE', *, *, #11918, .F. ) ; -#32247 = CARTESIAN_POINT ( 'NONE', ( 44.90853464007773965, 181.5172347420035237, 101.5323552624301016 ) ) ; -#32248 = CARTESIAN_POINT ( 'NONE', ( 0.8683326238474313730, 189.0234992568099983, 103.6916932741592063 ) ) ; -#32249 = AXIS2_PLACEMENT_3D ( 'NONE', #1769, #14248, #27140 ) ; -#32250 = AXIS2_PLACEMENT_3D ( 'NONE', #21862, #15129, #15319 ) ; -#32251 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709482895, 82.27946979429644614, 322.5205145037751890 ) ) ; -#32252 = ADVANCED_FACE ( 'NONE', ( #39815 ), #36756, .F. ) ; -#32253 = CARTESIAN_POINT ( 'NONE', ( 3.667815741540035646, 183.5629855103865964, 104.5953232250576406 ) ) ; -#32254 = CIRCLE ( 'NONE', #17857, 3.000000000000000888 ) ; -#32255 = CARTESIAN_POINT ( 'NONE', ( -25.87019154357000161, 191.8551652017999913, 104.0556614200000212 ) ) ; -#32256 = DIRECTION ( 'NONE', ( -1.868163743397223657E-15, 0.9743700557921585181, 0.2249510932971567623 ) ) ; -#32257 = CARTESIAN_POINT ( 'NONE', ( -3.625412116750075686, 168.4715326382302294, 98.63986567913343606 ) ) ; -#32258 = CARTESIAN_POINT ( 'NONE', ( 36.54215494650633644, 137.9975274739460644, 288.6199674919093923 ) ) ; -#32259 = CARTESIAN_POINT ( 'NONE', ( -20.24838124913999948, 167.0064264920000028, 101.0439605547000070 ) ) ; -#32260 = ORIENTED_EDGE ( 'NONE', *, *, #32486, .F. ) ; -#32261 = CARTESIAN_POINT ( 'NONE', ( -1.987599235653746188, 161.6130078871375417, 102.0969471392255770 ) ) ; -#32262 = EDGE_CURVE ( 'NONE', #12930, #12044, #17147, .T. ) ; -#32263 = EDGE_CURVE ( 'NONE', #27919, #35056, #25956, .T. ) ; -#32264 = ADVANCED_FACE ( 'NONE', ( #6275 ), #540, .T. ) ; -#32265 = FACE_OUTER_BOUND ( 'NONE', #5132, .T. ) ; -#32266 = ORIENTED_EDGE ( 'NONE', *, *, #24342, .T. ) ; -#32267 = FACE_OUTER_BOUND ( 'NONE', #9429, .T. ) ; -#32268 = CARTESIAN_POINT ( 'NONE', ( -25.99613447915552555, 191.6796580302363964, 103.9154390762144260 ) ) ; -#32269 = EDGE_CURVE ( 'NONE', #10234, #11951, #38097, .T. ) ; -#32270 = CARTESIAN_POINT ( 'NONE', ( 36.77959379203999646, 191.5319398393999961, 106.2265964018000091 ) ) ; -#32271 = CARTESIAN_POINT ( 'NONE', ( -41.34363534162371678, 121.0516446937131718, 87.79591618170475442 ) ) ; -#32272 = CARTESIAN_POINT ( 'NONE', ( 40.49581267819608854, 84.18892247206676416, 282.5307213418886931 ) ) ; -#32273 = DIRECTION ( 'NONE', ( 0.0005884949961262337520, -0.2249510543439053878, 0.9743698870671265722 ) ) ; -#32274 = VERTEX_POINT ( 'NONE', #3406 ) ; -#32275 = CARTESIAN_POINT ( 'NONE', ( -2.713411677741000450, 209.5989927075000026, 75.89345322724000198 ) ) ; -#32276 = CIRCLE ( 'NONE', #29683, 22.50000000000899902 ) ; -#32277 = CARTESIAN_POINT ( 'NONE', ( -16.28146077159970062, 122.7838420707920051, 174.3381434293534937 ) ) ; -#32278 = AXIS2_PLACEMENT_3D ( 'NONE', #9364, #37170, #39817 ) ; -#32279 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29473, #4922, #36196, #17377, #35772, #20253, #39670, #30493, #30693, #21294, #33531, #33935, #24161, #14948, #27642, #2868, #39874, #36816, #9222, #24570 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000489053, 0.1875000000000614786, 0.2187500000000586475, 0.2343750000000572042, 0.2500000000000557332, 0.5000000000000536238, 0.6250000000000585088, 0.6875000000000549560, 0.7187500000000485167, 0.7343750000000416334, 0.7500000000000347500, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32280 = CARTESIAN_POINT ( 'NONE', ( -45.68157572959258772, 116.8137947612332681, 122.5502833297559135 ) ) ; -#32281 = ORIENTED_EDGE ( 'NONE', *, *, #19430, .F. ) ; -#32282 = DIRECTION ( 'NONE', ( -0.9999998186616234630, 7.423303222494310403E-07, 0.0006022260116136528329 ) ) ; -#32283 = AXIS2_PLACEMENT_3D ( 'NONE', #6301, #34112, #27618 ) ; -#32284 = ORIENTED_EDGE ( 'NONE', *, *, #36948, .F. ) ; -#32285 = CARTESIAN_POINT ( 'NONE', ( -4.726290685248240919, 130.8407438226161048, 89.86274152813891192 ) ) ; -#32286 = CARTESIAN_POINT ( 'NONE', ( -16.15354643035712812, 122.9157560190214156, 174.2038265287079071 ) ) ; -#32287 = ORIENTED_EDGE ( 'NONE', *, *, #34642, .T. ) ; -#32288 = FACE_OUTER_BOUND ( 'NONE', #12183, .T. ) ; -#32289 = CARTESIAN_POINT ( 'NONE', ( 23.77777407637487883, 214.0117437154297590, 76.04410721373406545 ) ) ; -#32290 = CARTESIAN_POINT ( 'NONE', ( -36.45592555318621919, 191.2086150054764175, 103.8189291966230741 ) ) ; -#32291 = DIRECTION ( 'NONE', ( -0.5976534202554355524, 0.8017545692149061765, 0.000000000000000000 ) ) ; -#32292 = ORIENTED_EDGE ( 'NONE', *, *, #2893, .F. ) ; -#32293 = ORIENTED_EDGE ( 'NONE', *, *, #25588, .T. ) ; -#32294 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; -#32295 = CARTESIAN_POINT ( 'NONE', ( -5.662686464640452222, 188.3429660633563287, 103.1387990589197869 ) ) ; -#32296 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971594823 ) ) ; -#32297 = EDGE_CURVE ( 'NONE', #38998, #14154, #746, .T. ) ; -#32298 = CARTESIAN_POINT ( 'NONE', ( -22.78292978085340081, 157.6260587155269661, 99.13643849004034792 ) ) ; -#32299 = ORIENTED_EDGE ( 'NONE', *, *, #14552, .F. ) ; -#32300 = CARTESIAN_POINT ( 'NONE', ( -23.36013622322100858, 127.9076955631267509, 92.27576111913165846 ) ) ; -#32301 = CONICAL_SURFACE ( 'NONE', #27093, 2.500000000042679638, 0.7853981634197695350 ) ; -#32302 = EDGE_CURVE ( 'NONE', #17683, #10631, #13173, .T. ) ; -#32303 = AXIS2_PLACEMENT_3D ( 'NONE', #12045, #8983, #21461 ) ; -#32304 = AXIS2_PLACEMENT_3D ( 'NONE', #5020, #23849, #19943 ) ; -#32305 = CARTESIAN_POINT ( 'NONE', ( -20.39369818271929802, 136.8328687898372777, 91.25559555417643764 ) ) ; -#32306 = VECTOR ( 'NONE', #36735, 1000.000000000000000 ) ; -#32307 = ADVANCED_FACE ( 'NONE', ( #22646 ), #10120, .F. ) ; -#32308 = ADVANCED_FACE ( 'NONE', ( #20496 ), #14481, .T. ) ; -#32309 = CARTESIAN_POINT ( 'NONE', ( -38.95668886436796896, 209.7096538830999748, 73.08203294633123903 ) ) ; -#32310 = EDGE_CURVE ( 'NONE', #20231, #14032, #18091, .T. ) ; -#32311 = FACE_OUTER_BOUND ( 'NONE', #32696, .T. ) ; -#32312 = EDGE_CURVE ( 'NONE', #2464, #3137, #9262, .T. ) ; -#32313 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9814, #194, #16132, #10222, #38006, #22287, #22086, #16516, #12666, #6516, #10011, #29012 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999890088, 0.3749999999999897304, 0.4374999999999955036, 0.5000000000000013323, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32314 = CARTESIAN_POINT ( 'NONE', ( -2.713752470710999898, 209.7550057423999874, 73.18224161559000152 ) ) ; -#32315 = CARTESIAN_POINT ( 'NONE', ( -37.67176343985000386, 190.1981568370999867, 106.8040751365000034 ) ) ; -#32316 = ORIENTED_EDGE ( 'NONE', *, *, #527, .F. ) ; -#32317 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#32318 = CARTESIAN_POINT ( 'NONE', ( -36.17397473344645675, 191.8429952646565937, 106.4342576988118623 ) ) ; -#32319 = CARTESIAN_POINT ( 'NONE', ( 2.561557522426482159, 191.9759150222000130, 101.9199002238076162 ) ) ; -#32320 = CARTESIAN_POINT ( 'NONE', ( -28.16705410445850433, 186.9743050576410326, 105.9152681543748997 ) ) ; -#32321 = ORIENTED_EDGE ( 'NONE', *, *, #6623, .T. ) ; -#32322 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #7465, #9607, #7675, #10965 ), - ( #3249, #35662, #4608, #16864 ), - ( #20137, #13817, #29563, #28224 ), - ( #29368, #1540, #190, #10563 ), - ( #19935, #38359, #1338, #35458 ), - ( #13427, #32044, #14024, #26506 ), - ( #16468, #25913, #12663, #25153 ), - ( #22082, #10366, #35266, #32235 ), - ( #4195, #30063, #14731, #33310 ), - ( #23512, #23933, #24133, #30468 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.004176192228627999790, 0.000000000000000000, 7.579363622111999969E-07, 0.2500138562320999847, 0.5000092427718999533, 0.7500046293118000085, 1.000000000000000000, 1.016692674581000100 ), - ( 1.377093476695000024E-06, 1.000019867702000020 ), - .UNSPECIFIED. ) ; -#32323 = ORIENTED_EDGE ( 'NONE', *, *, #19120, .T. ) ; -#32324 = DIRECTION ( 'NONE', ( -0.6087611427424988175, -0.7731004630501198127, -0.1781166615410728349 ) ) ; -#32325 = DIRECTION ( 'NONE', ( 0.5987319967475925875, 0.8009494341533932582, 0.000000000000000000 ) ) ; -#32326 = EDGE_LOOP ( 'NONE', ( #17997, #11168, #32029, #15429 ) ) ; -#32327 = AXIS2_PLACEMENT_3D ( 'NONE', #24070, #17088, #36526 ) ; -#32328 = CARTESIAN_POINT ( 'NONE', ( 13.50147201671766695, 185.3473651114627501, 105.0013405082515163 ) ) ; -#32329 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052565999616 ) ) ; -#32330 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; -#32331 = CARTESIAN_POINT ( 'NONE', ( -38.35450013695000138, 119.2981560018999971, 87.45630205388999912 ) ) ; -#32332 = VECTOR ( 'NONE', #16836, 999.9999999999998863 ) ; -#32333 = CONICAL_SURFACE ( 'NONE', #24505, 2.500000000096461505, 0.7853981634068133433 ) ; -#32334 = FACE_OUTER_BOUND ( 'NONE', #2369, .T. ) ; -#32335 = ORIENTED_EDGE ( 'NONE', *, *, #22520, .T. ) ; -#32336 = CARTESIAN_POINT ( 'NONE', ( 0.04412548967593893368, 271.9029643396000324, 73.05847743173070796 ) ) ; -#32337 = EDGE_LOOP ( 'NONE', ( #18660, #1920, #4327, #31414 ) ) ; -#32338 = CARTESIAN_POINT ( 'NONE', ( -3.169906973560626895, 184.1222312815566795, 102.1628149875517408 ) ) ; -#32339 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23259, #20379, #23875, #35695 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32340 = CONICAL_SURFACE ( 'NONE', #31059, 2.503171115049211082, 0.7853981633607578505 ) ; -#32341 = DIRECTION ( 'NONE', ( -0.0005884949961204158147, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#32342 = LINE ( 'NONE', #32536, #34035 ) ; -#32343 = CARTESIAN_POINT ( 'NONE', ( 46.04942073387295665, 125.5491642319759791, 88.61041671179513912 ) ) ; -#32344 = VERTEX_POINT ( 'NONE', #7276 ) ; -#32345 = CARTESIAN_POINT ( 'NONE', ( -2.179982539881000214, 189.9716861103999861, 103.9665167251000071 ) ) ; -#32346 = CARTESIAN_POINT ( 'NONE', ( 25.49246811489144804, 207.5987292058227354, 76.61788227749146074 ) ) ; -#32347 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319386436951 ) ) ; -#32348 = EDGE_CURVE ( 'NONE', #37942, #23839, #16679, .T. ) ; -#32349 = ORIENTED_EDGE ( 'NONE', *, *, #25031, .T. ) ; -#32350 = CARTESIAN_POINT ( 'NONE', ( -20.33223045282921149, 118.1161730931157763, 89.94609189684267392 ) ) ; -#32351 = CARTESIAN_POINT ( 'NONE', ( -38.93661188355890346, 190.9636362828419749, 106.3296291375942388 ) ) ; -#32352 = ORIENTED_EDGE ( 'NONE', *, *, #33118, .T. ) ; -#32353 = EDGE_CURVE ( 'NONE', #11480, #6338, #28273, .T. ) ; -#32354 = EDGE_CURVE ( 'NONE', #30934, #7762, #24821, .T. ) ; -#32355 = EDGE_LOOP ( 'NONE', ( #36485, #1635, #30079, #7949 ) ) ; -#32356 = EDGE_LOOP ( 'NONE', ( #5106, #39001, #17790, #28369 ) ) ; -#32357 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971579003 ) ) ; -#32358 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -1.027544597027591327E-15, 0.0006039748319388571745 ) ) ; -#32359 = CARTESIAN_POINT ( 'NONE', ( 16.71302903106570881, 121.9752588367690436, 177.8431961985013459 ) ) ; -#32360 = EDGE_CURVE ( 'NONE', #6578, #4754, #24068, .T. ) ; -#32361 = VECTOR ( 'NONE', #32557, 1000.000000000000227 ) ; -#32362 = AXIS2_PLACEMENT_3D ( 'NONE', #15789, #37877, #10079 ) ; -#32363 = ORIENTED_EDGE ( 'NONE', *, *, #1536, .T. ) ; -#32364 = CARTESIAN_POINT ( 'NONE', ( 25.84393118718000082, 120.4857180374000052, 90.36132433278000065 ) ) ; -#32365 = FACE_OUTER_BOUND ( 'NONE', #10958, .T. ) ; -#32366 = AXIS2_PLACEMENT_3D ( 'NONE', #23845, #28815, #23432 ) ; -#32368 = LINE ( 'NONE', #16408, #37716 ) ; -#32367 = DIRECTION ( 'NONE', ( 0.0005884949961245237483, -0.2249510543439061649, 0.9743698870671263501 ) ) ; -#32369 = ORIENTED_EDGE ( 'NONE', *, *, #4118, .F. ) ; -#32370 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 67.27946979429633245, 315.0857197240632672 ) ) ; -#32371 = PLANE ( 'NONE', #2797 ) ; -#32372 = CARTESIAN_POINT ( 'NONE', ( -35.94780537797892350, 109.6131156792400105, 87.78949595639598158 ) ) ; -#32373 = VERTEX_POINT ( 'NONE', #6569 ) ; -#32374 = ORIENTED_EDGE ( 'NONE', *, *, #37517, .T. ) ; -#32375 = LINE ( 'NONE', #39504, #28320 ) ; -#32376 = CARTESIAN_POINT ( 'NONE', ( 5.669411459768906703, 187.4950212787814223, 105.7757252900559592 ) ) ; -#32377 = CARTESIAN_POINT ( 'NONE', ( -35.93807696458344481, 196.5784392977275843, 103.8968090176416297 ) ) ; -#32378 = ORIENTED_EDGE ( 'NONE', *, *, #17729, .T. ) ; -#32379 = ORIENTED_EDGE ( 'NONE', *, *, #24852, .T. ) ; -#32380 = VECTOR ( 'NONE', #33016, 1000.000000000000000 ) ; -#32381 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921579630, -0.2249510932971586774 ) ) ; -#32382 = VECTOR ( 'NONE', #30522, 1000.000000000000114 ) ; -#32383 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#32384 = AXIS2_PLACEMENT_3D ( 'NONE', #29198, #35291, #1165 ) ; -#32385 = EDGE_LOOP ( 'NONE', ( #22985, #12444, #15619, #10453 ) ) ; -#32386 = ORIENTED_EDGE ( 'NONE', *, *, #35833, .T. ) ; -#32387 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#32388 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34051, #24683, #8524, #36934 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32389 = ADVANCED_FACE ( 'NONE', ( #9663 ), #15393, .F. ) ; -#32390 = AXIS2_PLACEMENT_3D ( 'NONE', #22585, #35006, #12973 ) ; -#32391 = ADVANCED_FACE ( 'NONE', ( #5785 ), #8628, .T. ) ; -#32392 = EDGE_CURVE ( 'NONE', #13325, #39904, #27496, .T. ) ; -#32393 = AXIS2_PLACEMENT_3D ( 'NONE', #12325, #21744, #27688 ) ; -#32394 = DIRECTION ( 'NONE', ( -0.0002393071182776102175, -0.2252352986010028590, 0.9743043687658493601 ) ) ; -#32395 = EDGE_CURVE ( 'NONE', #650, #26354, #18830, .T. ) ; -#32396 = CARTESIAN_POINT ( 'NONE', ( 2.897570750862338507, 190.9033107830884148, 106.6325337691695836 ) ) ; -#32397 = ORIENTED_EDGE ( 'NONE', *, *, #36075, .T. ) ; -#32398 = CARTESIAN_POINT ( 'NONE', ( -30.07328833497793497, 135.0802858635263135, 91.08308969254834153 ) ) ; -#32399 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971575394 ) ) ; -#32400 = CARTESIAN_POINT ( 'NONE', ( 21.26219377714503622, 154.1161458975605001, 95.22059608960054788 ) ) ; -#32401 = CARTESIAN_POINT ( 'NONE', ( 44.30339254327586218, 188.9591885891941558, 103.2508314896253552 ) ) ; -#32402 = EDGE_CURVE ( 'NONE', #26493, #17270, #18598, .T. ) ; -#32403 = ORIENTED_EDGE ( 'NONE', *, *, #9836, .F. ) ; -#32404 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319385907860 ) ) ; -#32405 = CARTESIAN_POINT ( 'NONE', ( -28.94659870514799849, 110.6131156702000027, 89.78526776826356581 ) ) ; -#32406 = DIRECTION ( 'NONE', ( 0.0005884949961259294164, -0.2255194585872565272, 0.9742384859325513569 ) ) ; -#32407 = EDGE_CURVE ( 'NONE', #5335, #37130, #33400, .T. ) ; -#32408 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118781, 163.7809401697382725, 187.7700750526365425 ) ) ; -#32409 = VERTEX_POINT ( 'NONE', #31143 ) ; -#32410 = CARTESIAN_POINT ( 'NONE', ( 15.01573401434461807, 123.4937399423546509, 178.4505912408948802 ) ) ; -#32411 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35032, #3774, #35240, #32010, #37934, #19314, #9940 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 4 ), - ( 6.938893903907228378E-18, 0.001964037002783663999, 0.003942463309350621725 ), - .UNSPECIFIED. ) ; -#32412 = VECTOR ( 'NONE', #17914, 1000.000000000000114 ) ; -#32413 = AXIS2_PLACEMENT_3D ( 'NONE', #12104, #24788, #37042 ) ; -#32414 = CARTESIAN_POINT ( 'NONE', ( -35.82052824944000236, 112.9963127814999950, 89.90514415641000312 ) ) ; -#32415 = ORIENTED_EDGE ( 'NONE', *, *, #13177, .F. ) ; -#32416 = ORIENTED_EDGE ( 'NONE', *, *, #13812, .T. ) ; -#32417 = CARTESIAN_POINT ( 'NONE', ( -34.43835868710999648, 176.6247318011000402, 103.5296681725999974 ) ) ; -#32418 = DIRECTION ( 'NONE', ( 0.5988681445390194868, -0.8008476418498040594, 0.000000000000000000 ) ) ; -#32419 = CARTESIAN_POINT ( 'NONE', ( 23.69388335781209776, 131.0246890999723632, 89.88804818403849595 ) ) ; -#32420 = AXIS2_PLACEMENT_3D ( 'NONE', #34919, #11028, #13680 ) ; -#32421 = LINE ( 'NONE', #1324, #5079 ) ; -#32422 = VERTEX_POINT ( 'NONE', #15198 ) ; -#32423 = EDGE_LOOP ( 'NONE', ( #29968, #11771, #30300, #19853 ) ) ; -#32424 = FACE_BOUND ( 'NONE', #22721, .T. ) ; -#32425 = VERTEX_POINT ( 'NONE', #36865 ) ; -#32426 = VERTEX_POINT ( 'NONE', #28085 ) ; -#32427 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091564245 ) ) ; -#32428 = FACE_OUTER_BOUND ( 'NONE', #21460, .T. ) ; -#32429 = ORIENTED_EDGE ( 'NONE', *, *, #13297, .F. ) ; -#32430 = ORIENTED_EDGE ( 'NONE', *, *, #7413, .F. ) ; -#32431 = CARTESIAN_POINT ( 'NONE', ( -38.93814858684476121, 191.0388300950886560, 103.7812318162937686 ) ) ; -#32432 = CARTESIAN_POINT ( 'NONE', ( -35.68392459317214360, 192.7466937109657863, 106.6325799381910286 ) ) ; -#32433 = CARTESIAN_POINT ( 'NONE', ( -38.73646192734999971, 118.8634567458999953, 89.85986150100001169 ) ) ; -#32434 = CARTESIAN_POINT ( 'NONE', ( -19.29085203336684984, 116.9605294434551439, 189.5008840201654721 ) ) ; -#32435 = VERTEX_POINT ( 'NONE', #8870 ) ; -#32436 = FACE_BOUND ( 'NONE', #7032, .T. ) ; -#32437 = VERTEX_POINT ( 'NONE', #240 ) ; -#32438 = AXIS2_PLACEMENT_3D ( 'NONE', #25336, #32601, #14002 ) ; -#32439 = CARTESIAN_POINT ( 'NONE', ( -6.037316053083784162, 134.5233555713580813, 93.55307079258861336 ) ) ; -#32440 = CYLINDRICAL_SURFACE ( 'NONE', #31237, 1.749999999999998446 ) ; -#32441 = ADVANCED_FACE ( 'NONE', ( #21340 ), #5333, .F. ) ; -#32442 = EDGE_CURVE ( 'NONE', #30934, #1537, #2910, .T. ) ; -#32443 = VECTOR ( 'NONE', #27228, 1000.000000000000227 ) ; -#32444 = CARTESIAN_POINT ( 'NONE', ( -25.71821783760721303, 116.8420470932888406, 90.28331799833721050 ) ) ; -#32445 = CARTESIAN_POINT ( 'NONE', ( -21.57293377124131339, 182.0229620896140261, 104.5971269518084341 ) ) ; -#32446 = CIRCLE ( 'NONE', #4986, 2.000000000000000000 ) ; -#32447 = ORIENTED_EDGE ( 'NONE', *, *, #27, .F. ) ; -#32448 = DIRECTION ( 'NONE', ( 0.7871416011357068587, -0.6167723240884888103, 0.000000000000000000 ) ) ; -#32449 = CARTESIAN_POINT ( 'NONE', ( 0.6060660036824134789, 189.0004550687757501, 103.6810276021836756 ) ) ; -#32450 = CARTESIAN_POINT ( 'NONE', ( -40.80749064254892744, 126.9113585741438754, 91.54312417642556454 ) ) ; -#32451 = VECTOR ( 'NONE', #17112, 1000.000000000000114 ) ; -#32452 = CARTESIAN_POINT ( 'NONE', ( 20.48021663872660625, 209.7101073659619601, 73.54617496015868028 ) ) ; -#32453 = ORIENTED_EDGE ( 'NONE', *, *, #7178, .T. ) ; -#32454 = CARTESIAN_POINT ( 'NONE', ( -25.35579335349000019, 191.8103324465000128, 104.5670375079999985 ) ) ; -#32455 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971545696 ) ) ; -#32456 = DIRECTION ( 'NONE', ( 0.7933532970003738249, 0.5930762008556724751, 0.1372995488602876402 ) ) ; -#32457 = CARTESIAN_POINT ( 'NONE', ( -45.04728614389591002, 188.6755623356005174, 103.7177943918455156 ) ) ; -#32458 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825975761958095, 0.0005734119010998334383 ) ) ; -#32459 = ORIENTED_EDGE ( 'NONE', *, *, #32747, .T. ) ; -#32460 = DIRECTION ( 'NONE', ( -0.0004161288024550937855, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#32461 = ADVANCED_FACE ( 'NONE', ( #9063 ), #53, .F. ) ; -#32462 = ORIENTED_EDGE ( 'NONE', *, *, #32392, .F. ) ; -#32463 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#32464 = CARTESIAN_POINT ( 'NONE', ( -26.00800983458967508, 191.5260122442129216, 103.8858970416150385 ) ) ; -#32465 = VECTOR ( 'NONE', #29273, 999.9999999999998863 ) ; -#32466 = CARTESIAN_POINT ( 'NONE', ( 36.90835879720000179, 191.4328249133999975, 106.2128322142000059 ) ) ; -#32467 = FACE_OUTER_BOUND ( 'NONE', #8504, .T. ) ; -#32468 = CARTESIAN_POINT ( 'NONE', ( -40.95578253733000196, 219.5549399801000163, 74.58324062236999907 ) ) ; -#32469 = DIRECTION ( 'NONE', ( -1.725162000157249213E-15, -0.9743700557915021543, -0.2249510932999991553 ) ) ; -#32470 = VECTOR ( 'NONE', #6850, 1000.000000000000114 ) ; -#32471 = ORIENTED_EDGE ( 'NONE', *, *, #25623, .F. ) ; -#32472 = CARTESIAN_POINT ( 'NONE', ( -2.531195081725338358, 209.6169330143079321, 75.72670068308755731 ) ) ; -#32473 = CARTESIAN_POINT ( 'NONE', ( 36.22847411652472260, 116.3454942628183773, 87.24590320147396483 ) ) ; -#32474 = DIRECTION ( 'NONE', ( -0.9999998268368289756, -0.0001323825434281097023, 0.0005734118713717894101 ) ) ; -#32475 = FACE_OUTER_BOUND ( 'NONE', #17491, .T. ) ; -#32476 = ORIENTED_EDGE ( 'NONE', *, *, #19681, .T. ) ; -#32477 = CARTESIAN_POINT ( 'NONE', ( 6.035547152934244153, 177.3162026418089567, 100.9932161903808066 ) ) ; -#32478 = CARTESIAN_POINT ( 'NONE', ( -5.958856852865682896, 148.4703916786008904, 97.01252450521799631 ) ) ; -#32479 = VERTEX_POINT ( 'NONE', #21941 ) ; -#32480 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802245 ) ) ; -#32481 = CARTESIAN_POINT ( 'NONE', ( 5.659153654835778369, 124.3673852322629187, 88.36203164978959990 ) ) ; -#32482 = CARTESIAN_POINT ( 'NONE', ( 22.99909745638999681, 115.1133511170128969, 87.25389341346352978 ) ) ; -#32483 = ORIENTED_EDGE ( 'NONE', *, *, #17207, .T. ) ; -#32484 = CARTESIAN_POINT ( 'NONE', ( 36.10829853855725702, 192.3105547256718069, 106.3856345698964816 ) ) ; -#32485 = PLANE ( 'NONE', #25999 ) ; -#32486 = EDGE_CURVE ( 'NONE', #21267, #10098, #2083, .T. ) ; -#32488 = EDGE_CURVE ( 'NONE', #30360, #25128, #34383, .T. ) ; -#32487 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15001, #27506, #3123, #11941, #24424, #8879 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 4 ), - ( 6.938893903907228378E-18, 0.0005393080574366226855, 0.001078647824828534536, 0.001617990336877349073 ), - .UNSPECIFIED. ) ; -#32489 = CARTESIAN_POINT ( 'NONE', ( -12.63672208255219331, 130.6949650040740778, 90.11191724478814535 ) ) ; -#32490 = LINE ( 'NONE', #1398, #36021 ) ; -#32491 = VERTEX_POINT ( 'NONE', #6377 ) ; -#32492 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560684 ) ) ; -#32493 = CARTESIAN_POINT ( 'NONE', ( 12.31576967456374838, 135.2953866561074676, 91.39403622019926843 ) ) ; -#32494 = CARTESIAN_POINT ( 'NONE', ( -41.43719618776999880, 191.1885863319999999, 105.3567702172999958 ) ) ; -#32495 = EDGE_CURVE ( 'NONE', #17976, #36762, #9358, .T. ) ; -#32496 = AXIS2_PLACEMENT_3D ( 'NONE', #1658, #7986, #2070 ) ; -#32497 = CARTESIAN_POINT ( 'NONE', ( -76.10925030609611497, 156.2249461908330375, 96.27941314736982292 ) ) ; -#32498 = VERTEX_POINT ( 'NONE', #5982 ) ; -#32499 = CARTESIAN_POINT ( 'NONE', ( 19.99999382154498662, 120.3902235794415816, 87.43511282661482653 ) ) ; -#32500 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37819, #35330, #4465, #32103 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32501 = CARTESIAN_POINT ( 'NONE', ( 5.335329622941979544, 131.0223101498888241, 89.89858245878815524 ) ) ; -#32502 = PLANE ( 'NONE', #28022 ) ; -#32503 = CARTESIAN_POINT ( 'NONE', ( -28.53030869656295110, 124.6043131503039803, 91.51623810099293621 ) ) ; -#32504 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971559574 ) ) ; -#32505 = CARTESIAN_POINT ( 'NONE', ( 39.06510290334847468, 190.7637496868926235, 106.4074214906108438 ) ) ; -#32506 = CARTESIAN_POINT ( 'NONE', ( 38.65260204170999714, 118.3717869362999977, 89.51298073911000586 ) ) ; -#32507 = ORIENTED_EDGE ( 'NONE', *, *, #26633, .F. ) ; -#32508 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2252353050503803633, -0.9743043966640312359 ) ) ; -#32509 = FACE_OUTER_BOUND ( 'NONE', #23187, .T. ) ; -#32510 = CARTESIAN_POINT ( 'NONE', ( 16.14434960479789538, 123.6872145150956754, 173.7816462225611929 ) ) ; -#32511 = CARTESIAN_POINT ( 'NONE', ( 24.86462005268904463, 181.6234868533104816, 104.6479044067819899 ) ) ; -#32512 = ORIENTED_EDGE ( 'NONE', *, *, #36361, .T. ) ; -#32513 = ORIENTED_EDGE ( 'NONE', *, *, #15059, .T. ) ; -#32514 = ORIENTED_EDGE ( 'NONE', *, *, #30225, .T. ) ; -#32515 = CARTESIAN_POINT ( 'NONE', ( -30.04055490880000079, 163.2729245447999915, 152.4718672074000381 ) ) ; -#32516 = EDGE_CURVE ( 'NONE', #2348, #18841, #23991, .T. ) ; -#32517 = VECTOR ( 'NONE', #12467, 1000.000000000000227 ) ; -#32518 = CARTESIAN_POINT ( 'NONE', ( -41.57645147788533535, 119.6918065143027405, 90.38997552799222035 ) ) ; -#32519 = DIRECTION ( 'NONE', ( 0.7856007465113979960, 0.6187337610642675845, 0.000000000000000000 ) ) ; -#32520 = VECTOR ( 'NONE', #26955, 1000.000000000000000 ) ; -#32521 = ORIENTED_EDGE ( 'NONE', *, *, #40140, .F. ) ; -#32522 = CARTESIAN_POINT ( 'NONE', ( -13.50000077688951450, 188.3420892684051751, 103.1432776901117307 ) ) ; -#32523 = ADVANCED_FACE ( 'NONE', ( #843 ), #19649, .T. ) ; -#32524 = CARTESIAN_POINT ( 'NONE', ( 16.00176583137093189, 118.9451395335793649, 90.18281804087267517 ) ) ; -#32525 = CARTESIAN_POINT ( 'NONE', ( -38.05128246918000912, 119.2386161678000036, 87.30352700896000329 ) ) ; -#32526 = CARTESIAN_POINT ( 'NONE', ( -26.01125412628304190, 210.1698902315000055, 73.07311846223655039 ) ) ; -#32527 = EDGE_LOOP ( 'NONE', ( #18395, #683 ) ) ; -#32528 = CARTESIAN_POINT ( 'NONE', ( 19.37875314990832720, 147.8161002492973353, 183.5612100039927839 ) ) ; -#32529 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1821, #4470, #7338, #10836 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32530 = ORIENTED_EDGE ( 'NONE', *, *, #29188, .F. ) ; -#32531 = PLANE ( 'NONE', #35061 ) ; -#32532 = EDGE_CURVE ( 'NONE', #11953, #15935, #4100, .T. ) ; -#32533 = EDGE_CURVE ( 'NONE', #38661, #15772, #15775, .T. ) ; -#32534 = CARTESIAN_POINT ( 'NONE', ( 5.674687014606257129, 130.3475820607916660, 92.82156578849662765 ) ) ; -#32535 = DIRECTION ( 'NONE', ( 0.0005884949961215158462, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#32536 = CARTESIAN_POINT ( 'NONE', ( 44.72966403672143798, 107.3098357594950301, 174.7165674052034774 ) ) ; -#32537 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#32538 = ADVANCED_FACE ( 'NONE', ( #13729 ), #32742, .T. ) ; -#32539 = ORIENTED_EDGE ( 'NONE', *, *, #4707, .F. ) ; -#32540 = CARTESIAN_POINT ( 'NONE', ( -0.6437799103817298807, 188.6069639608899990, 103.1926838550779877 ) ) ; -#32541 = EDGE_CURVE ( 'NONE', #34570, #13870, #9907, .T. ) ; -#32542 = DIRECTION ( 'NONE', ( -0.7716293354502457014, 0.6291556465476403348, -0.09354860282138378891 ) ) ; -#32543 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#32544 = CARTESIAN_POINT ( 'NONE', ( 2.942818760358000052, 190.8925541295000130, 106.6760814302000000 ) ) ; -#32545 = ORIENTED_EDGE ( 'NONE', *, *, #3964, .T. ) ; -#32546 = ORIENTED_EDGE ( 'NONE', *, *, #21680, .T. ) ; -#32547 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971553745 ) ) ; -#32548 = CARTESIAN_POINT ( 'NONE', ( 19.98635445618997863, 211.0854288155255460, 76.04696776081749476 ) ) ; -#32549 = ORIENTED_EDGE ( 'NONE', *, *, #16278, .F. ) ; -#32550 = AXIS2_PLACEMENT_3D ( 'NONE', #31647, #38175, #3408 ) ; -#32551 = VERTEX_POINT ( 'NONE', #38455 ) ; -#32552 = ORIENTED_EDGE ( 'NONE', *, *, #18993, .T. ) ; -#32553 = CARTESIAN_POINT ( 'NONE', ( -28.43520508893000098, 186.6528701677999891, 105.6701704825000121 ) ) ; -#32554 = FACE_OUTER_BOUND ( 'NONE', #21679, .T. ) ; -#32555 = DIRECTION ( 'NONE', ( -0.9999998176071905887, 9.946155655599188003E-12, 0.0006039748219953627959 ) ) ; -#32556 = EDGE_CURVE ( 'NONE', #32614, #19409, #1511, .T. ) ; -#32557 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557922372330, 0.2249510932968150356 ) ) ; -#32558 = EDGE_LOOP ( 'NONE', ( #21216, #36847, #5431, #271 ) ) ; -#32559 = CARTESIAN_POINT ( 'NONE', ( 25.50197546413999916, 120.3616906317000002, 89.99026255478999303 ) ) ; -#32560 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -5.029098237799274788E-18, 0.0006039748319384018096 ) ) ; -#32562 = CARTESIAN_POINT ( 'NONE', ( 20.53675418873675795, 124.4626139095243786, 152.4730720674764939 ) ) ; -#32561 = CARTESIAN_POINT ( 'NONE', ( -39.03036842918214688, 175.8132598318450448, 136.1868359453157780 ) ) ; -#32563 = VERTEX_POINT ( 'NONE', #4309 ) ; -#32564 = EDGE_CURVE ( 'NONE', #30774, #27000, #11209, .T. ) ; -#32565 = CARTESIAN_POINT ( 'NONE', ( -9.144678143162121131, 6.413363568748468246, 291.5640670916855015 ) ) ; -#32566 = CARTESIAN_POINT ( 'NONE', ( 30.06443600138266703, 134.9229365128052507, 90.78414315763292564 ) ) ; -#32567 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #39649, #14323, #14924, #4898 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 2.960051731740213743, 3.141592653589768691 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9972554596699719776, 0.9972554596699719776, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#32568 = VERTEX_POINT ( 'NONE', #20048 ) ; -#32569 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799577453, 175.3514230958872133, 100.1541516780437320 ) ) ; -#32570 = AXIS2_PLACEMENT_3D ( 'NONE', #39402, #36354, #24098 ) ; -#32571 = EDGE_CURVE ( 'NONE', #23382, #25978, #21676, .T. ) ; -#32572 = CARTESIAN_POINT ( 'NONE', ( -46.29179777306748633, 126.3974345674219677, 91.94093998034792037 ) ) ; -#32573 = CARTESIAN_POINT ( 'NONE', ( 29.38693461565323872, 112.1844516200949755, 175.8396907018270383 ) ) ; -#32574 = VERTEX_POINT ( 'NONE', #10278 ) ; -#32575 = ADVANCED_FACE ( 'NONE', ( #29277 ), #449, .T. ) ; -#32576 = ORIENTED_EDGE ( 'NONE', *, *, #36315, .T. ) ; -#32577 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17339, #19799, #11039, #23102 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32578 = CIRCLE ( 'NONE', #24103, 2.500000000000003997 ) ; -#32579 = ORIENTED_EDGE ( 'NONE', *, *, #21824, .T. ) ; -#32580 = VECTOR ( 'NONE', #470, 1000.000000000000114 ) ; -#32581 = CARTESIAN_POINT ( 'NONE', ( -23.36112322160831312, 134.5243777609601921, 93.56093267912147837 ) ) ; -#32582 = AXIS2_PLACEMENT_3D ( 'NONE', #24836, #8476, #15214 ) ; -#32583 = EDGE_CURVE ( 'NONE', #29610, #19329, #27421, .T. ) ; -#32584 = ORIENTED_EDGE ( 'NONE', *, *, #37778, .T. ) ; -#32585 = CARTESIAN_POINT ( 'NONE', ( 39.04644978079199547, 209.7096538831000032, 75.53492146109870475 ) ) ; -#32586 = ORIENTED_EDGE ( 'NONE', *, *, #126, .T. ) ; -#32587 = CARTESIAN_POINT ( 'NONE', ( -22.49783753475205472, 153.7286132221404955, 98.23646823715600362 ) ) ; -#32588 = CARTESIAN_POINT ( 'NONE', ( -30.07324787560831325, 135.0898699095424718, 91.09842734486377935 ) ) ; -#32589 = CARTESIAN_POINT ( 'NONE', ( 20.00148625195223318, 152.2913976755475858, 94.80008112724152625 ) ) ; -#32590 = CARTESIAN_POINT ( 'NONE', ( -35.96311564216326673, 218.5902260770998282, 61.08022271436995965 ) ) ; -#32591 = ORIENTED_EDGE ( 'NONE', *, *, #2541, .F. ) ; -#32592 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 3.469446951982499751E-14 ) ) ; -#32593 = FACE_OUTER_BOUND ( 'NONE', #20497, .T. ) ; -#32594 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825984634766995, 0.0005734119008966697805 ) ) ; -#32595 = CIRCLE ( 'NONE', #32570, 6.500000000035469405 ) ; -#32596 = EDGE_LOOP ( 'NONE', ( #10273, #17396, #24357, #33869 ) ) ; -#32597 = VECTOR ( 'NONE', #7896, 999.9999999999998863 ) ; -#32598 = DIRECTION ( 'NONE', ( -0.0005884949961249498398, 0.2249510543439061649, -0.9743698870671263501 ) ) ; -#32599 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13804, #20332, #7255, #35441, #32610, #14220, #1127, #4788, #3984, #35252 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999281686, 0.3749999999998922529, 0.4374999999998897549, 0.4999999999998873124, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32600 = CIRCLE ( 'NONE', #8460, 5.000000000000022204 ) ; -#32602 = CARTESIAN_POINT ( 'NONE', ( -37.14029669136999701, 117.9240011325999973, 90.44462167566000232 ) ) ; -#32601 = DIRECTION ( 'NONE', ( 0.0005884949961243941862, -0.2249510543439062205, 0.9743698870671264611 ) ) ; -#32603 = ORIENTED_EDGE ( 'NONE', *, *, #36871, .T. ) ; -#32604 = ORIENTED_EDGE ( 'NONE', *, *, #31297, .F. ) ; -#32605 = ADVANCED_FACE ( 'NONE', ( #38652 ), #22746, .F. ) ; -#32606 = DIRECTION ( 'NONE', ( 0.0006039748319392010834, 1.387181216573299978E-14, 0.9999998176071847045 ) ) ; -#32607 = EDGE_CURVE ( 'NONE', #1188, #26218, #39097, .T. ) ; -#32608 = CARTESIAN_POINT ( 'NONE', ( -12.60636661545733084, 165.2216646692707229, 152.9217693202412818 ) ) ; -#32609 = ADVANCED_FACE ( 'NONE', ( #648 ), #36678, .F. ) ; -#32610 = CARTESIAN_POINT ( 'NONE', ( -13.49992725747581979, 124.0400051682925380, 91.07724209068317123 ) ) ; -#32611 = ORIENTED_EDGE ( 'NONE', *, *, #13984, .T. ) ; -#32612 = EDGE_CURVE ( 'NONE', #30359, #10990, #33230, .T. ) ; -#32613 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #14028, #16470 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32614 = VERTEX_POINT ( 'NONE', #26820 ) ; -#32615 = CARTESIAN_POINT ( 'NONE', ( -14.29616513773771125, 176.1108002494009384, 103.0567508915260362 ) ) ; -#32616 = ORIENTED_EDGE ( 'NONE', *, *, #39344, .F. ) ; -#32617 = VERTEX_POINT ( 'NONE', #8620 ) ; -#32618 = CARTESIAN_POINT ( 'NONE', ( -15.99819964153972585, 151.3054952985143302, 97.67310904513065850 ) ) ; -#32619 = CARTESIAN_POINT ( 'NONE', ( 2.711010865941999803, 209.0456857263999950, 73.43539125376000243 ) ) ; -#32620 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6496, #12256, #37197, #18971, #9193, #4228, #4439 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 4 ), - ( 0.000000000000000000, 0.2500002580796455431, 0.5000005535300821036, 0.7500008489806186951, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32621 = EDGE_CURVE ( 'NONE', #33415, #19817, #16154, .T. ) ; -#32622 = EDGE_LOOP ( 'NONE', ( #34203, #18678, #37109, #36626 ) ) ; -#32623 = LINE ( 'NONE', #17873, #32380 ) ; -#32624 = DIRECTION ( 'NONE', ( -0.9999998268367878973, -0.0001323826274100926099, 0.0005734119238466204227 ) ) ; -#32625 = CARTESIAN_POINT ( 'NONE', ( 36.89400472785000318, 191.0540516233000119, 103.5962395498000035 ) ) ; -#32626 = CARTESIAN_POINT ( 'NONE', ( 20.00005890743648607, 191.9885872211059734, 103.9228223727556752 ) ) ; -#32627 = EDGE_CURVE ( 'NONE', #25669, #11269, #2550, .T. ) ; -#32628 = AXIS2_PLACEMENT_3D ( 'NONE', #19648, #16780, #12778 ) ; -#32629 = ORIENTED_EDGE ( 'NONE', *, *, #33352, .F. ) ; -#32630 = FACE_OUTER_BOUND ( 'NONE', #15883, .T. ) ; -#32631 = CARTESIAN_POINT ( 'NONE', ( -23.35930774392331344, 176.9677908774963271, 103.4027938875997563 ) ) ; -#32632 = AXIS2_PLACEMENT_3D ( 'NONE', #19534, #32037, #7460 ) ; -#32633 = ORIENTED_EDGE ( 'NONE', *, *, #3454, .T. ) ; -#32634 = AXIS2_PLACEMENT_3D ( 'NONE', #39633, #14106, #26580 ) ; -#32635 = CARTESIAN_POINT ( 'NONE', ( 45.51092638067240870, 130.6862150259999282, 92.36248445504377003 ) ) ; -#32636 = CIRCLE ( 'NONE', #37861, 5.499999999738644618 ) ; -#32637 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#32638 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#32639 = CIRCLE ( 'NONE', #15651, 3.499999999950280216 ) ; -#32640 = CARTESIAN_POINT ( 'NONE', ( -27.80047107912594484, 149.4166296170034514, 291.5753347231419639 ) ) ; -#32641 = ORIENTED_EDGE ( 'NONE', *, *, #8916, .T. ) ; -#32642 = FACE_OUTER_BOUND ( 'NONE', #35349, .T. ) ; -#32643 = DIRECTION ( 'NONE', ( 0.1943643238945236551, -0.07321898756438741107, 0.9781929714821462341 ) ) ; -#32644 = CARTESIAN_POINT ( 'NONE', ( 32.06958471603104499, 135.8635028755992948, 91.00011324994767392 ) ) ; -#32645 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#32646 = EDGE_LOOP ( 'NONE', ( #36512, #16531, #8297, #25718 ) ) ; -#32647 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #3902, #15578, #28076 ), - ( #9658, #22135, #25011 ), - ( #31330, #16378, #3302 ), - ( #12932, #25410, #28665 ) ), - .UNSPECIFIED., .F., .F., .T. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), - ( 3, 3 ), - ( 0.5327326735548589820, 0.5327532648617869793 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.7516706677407538617, 1.000000000000000000), - ( 1.000000000000000000, 0.7516796584409587423, 1.000000000000000000), - ( 1.000000000000000000, 0.7516886489076254341, 1.000000000000000000), - ( 1.000000000000000000, 0.7516976391407651503, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#32648 = CARTESIAN_POINT ( 'NONE', ( -25.35572225526000167, 191.8208763773999976, 104.5667680184999995 ) ) ; -#32649 = CARTESIAN_POINT ( 'NONE', ( -35.95517947438523976, 209.7096537232000344, 75.58022056590567672 ) ) ; -#32650 = CARTESIAN_POINT ( 'NONE', ( 16.56169987041441161, 121.8384666780658563, 177.5555275195565059 ) ) ; -#32651 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #23831, #23628, #1749, #39341 ), - ( #11345, #20132, #32619, #7874 ), - ( #27120, #8081, #20339, #4600 ), - ( #2365, #17059, #8290, #39555 ), - ( #14227, #4799, #39151, #11153 ), - ( #20750, #30167, #2161, #37108 ), - ( #34218, #12361, #279, #2568 ), - ( #3148, #9501, #30580, #18877 ), - ( #31374, #8911, #11972, #28121 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 3, 4 ), - ( 4, 4 ), - ( 1.441988195786000121E-07, 0.3333318610857000097, 0.6666636764651000524, 0.9999981099119999994, 1.009998089569131841 ), - ( 0.1756413813676999947, 0.8243586172615999796 ), - .UNSPECIFIED. ) ; -#32652 = CARTESIAN_POINT ( 'NONE', ( -45.55635243984895055, 188.0246239919785012, 103.5677856498340788 ) ) ; -#32653 = CARTESIAN_POINT ( 'NONE', ( -15.49852918602411300, 173.9514291674110780, 102.3878961845165776 ) ) ; -#32654 = ORIENTED_EDGE ( 'NONE', *, *, #14491, .T. ) ; -#32655 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 1.540743955509789367E-33, -0.0006039748319385908944 ) ) ; -#32656 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#32657 = VECTOR ( 'NONE', #38217, 1000.000000000000114 ) ; -#32658 = AXIS2_PLACEMENT_3D ( 'NONE', #40211, #535, #3002 ) ; -#32659 = CARTESIAN_POINT ( 'NONE', ( -1.267128270904386511, 153.7461414230707533, 99.91119810786710786 ) ) ; -#32660 = CARTESIAN_POINT ( 'NONE', ( -15.94429972368852866, 121.8869921648800698, 174.4792395813007886 ) ) ; -#32661 = AXIS2_PLACEMENT_3D ( 'NONE', #4387, #16849, #3579 ) ; -#32662 = EDGE_CURVE ( 'NONE', #10007, #24020, #38620, .T. ) ; -#32663 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1340, #38167, #26109, #26305, #3799, #29175, #25915, #25715, #28964, #13624, #4610, #7271, #16277 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 0.000000000000000000, 0.3333373294491250860, 0.6666757894374520932, 0.7500296442072931224, 0.8333834989771342627, 0.8750604263620048728, 0.9167373537469253320, 0.9584142811318459021, 0.9792527448243011357, 0.9896719766705238674, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32664 = DIRECTION ( 'NONE', ( 0.1305263947813386505, -0.9660168765824634907, -0.2231014442428547184 ) ) ; -#32665 = CARTESIAN_POINT ( 'NONE', ( -29.94780647573000110, 103.6131156702000027, 87.78587210775999949 ) ) ; -#32666 = VECTOR ( 'NONE', #39023, 1000.000000000000114 ) ; -#32667 = EDGE_CURVE ( 'NONE', #21316, #37119, #25866, .T. ) ; -#32668 = FACE_OUTER_BOUND ( 'NONE', #39619, .T. ) ; -#32669 = EDGE_CURVE ( 'NONE', #24826, #40142, #19066, .T. ) ; -#32670 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#32671 = CARTESIAN_POINT ( 'NONE', ( -38.36188292311027936, 118.8221229462069886, 87.72102071481469920 ) ) ; -#32672 = ORIENTED_EDGE ( 'NONE', *, *, #37793, .T. ) ; -#32673 = CARTESIAN_POINT ( 'NONE', ( -15.66646767741427126, 185.8311504091911388, 102.9069918773323735 ) ) ; -#32674 = CARTESIAN_POINT ( 'NONE', ( 18.98506067126258046, 148.2070439170772431, 184.7168109706149721 ) ) ; -#32675 = EDGE_CURVE ( 'NONE', #9595, #24926, #29533, .T. ) ; -#32676 = LINE ( 'NONE', #4654, #32451 ) ; -#32677 = ORIENTED_EDGE ( 'NONE', *, *, #3401, .T. ) ; -#32678 = CARTESIAN_POINT ( 'NONE', ( 15.59122080578150005, 126.7491934480292599, 179.2057717501043612 ) ) ; -#32679 = ORIENTED_EDGE ( 'NONE', *, *, #25126, .F. ) ; -#32680 = ADVANCED_FACE ( 'NONE', ( #20254 ), #4718, .F. ) ; -#32681 = CARTESIAN_POINT ( 'NONE', ( 25.49063000826092562, 211.0902260967494897, 73.54299573436949800 ) ) ; -#32682 = ORIENTED_EDGE ( 'NONE', *, *, #17380, .T. ) ; -#32683 = CARTESIAN_POINT ( 'NONE', ( 36.74499328828947142, 191.3591568088928909, 106.3388620510278457 ) ) ; -#32684 = PLANE ( 'NONE', #5496 ) ; -#32685 = CARTESIAN_POINT ( 'NONE', ( 116.6745667766377892, 205.5703614864765427, 191.2914269756732040 ) ) ; -#32686 = CARTESIAN_POINT ( 'NONE', ( 3.534343284623258974, 175.3621990150981276, 100.1363906404241675 ) ) ; -#32687 = CARTESIAN_POINT ( 'NONE', ( 6.036905256830820576, 177.7921244214965668, 100.6958231142670712 ) ) ; -#32688 = ORIENTED_EDGE ( 'NONE', *, *, #33196, .T. ) ; -#32689 = ORIENTED_EDGE ( 'NONE', *, *, #23038, .F. ) ; -#32690 = AXIS2_PLACEMENT_3D ( 'NONE', #33437, #20561, #20151 ) ; -#32691 = CARTESIAN_POINT ( 'NONE', ( 17.25792980860752124, 152.7424877160250389, 181.6016748130998906 ) ) ; -#32692 = CARTESIAN_POINT ( 'NONE', ( 12.63778118622178859, 182.0343951221179850, 102.1422187760583284 ) ) ; -#32693 = LINE ( 'NONE', #36368, #39741 ) ; -#32694 = CONICAL_SURFACE ( 'NONE', #5932, 5.003058809538631024, 0.7854316141403709928 ) ; -#32695 = CARTESIAN_POINT ( 'NONE', ( -20.49960732757744353, 118.8154816606033393, 87.78015075453545535 ) ) ; -#32696 = EDGE_LOOP ( 'NONE', ( #29157, #19789, #28851 ) ) ; -#32697 = ORIENTED_EDGE ( 'NONE', *, *, #29117, .T. ) ; -#32698 = ORIENTED_EDGE ( 'NONE', *, *, #24037, .T. ) ; -#32699 = DIRECTION ( 'NONE', ( 3.989863994746633598E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#32700 = CARTESIAN_POINT ( 'NONE', ( 36.90266447701996810, 191.1365804696341968, 103.7579919604353478 ) ) ; -#32701 = LINE ( 'NONE', #20628, #1935 ) ; -#32702 = CARTESIAN_POINT ( 'NONE', ( 37.03777023944995506, 116.4244683402141618, 89.69148395127533036 ) ) ; -#32703 = CARTESIAN_POINT ( 'NONE', ( -35.93878493987465816, 193.8169247290935004, 102.7246158654722734 ) ) ; -#32704 = DIRECTION ( 'NONE', ( 0.0005884949961235723609, -0.2249510543439049992, 0.9743698870671266832 ) ) ; -#32705 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#32706 = LINE ( 'NONE', #1215, #40249 ) ; -#32707 = PLANE ( 'NONE', #10094 ) ; -#32708 = LINE ( 'NONE', #4692, #17386 ) ; -#32709 = ORIENTED_EDGE ( 'NONE', *, *, #25160, .T. ) ; -#32710 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#32711 = CARTESIAN_POINT ( 'NONE', ( -42.56963625464027245, 120.8513313564750575, 90.65827283841386475 ) ) ; -#32712 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 1.238758140229869926E-30, -0.0006039748319385906776 ) ) ; -#32713 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#32714 = EDGE_CURVE ( 'NONE', #16908, #38246, #28240, .T. ) ; -#32715 = EDGE_CURVE ( 'NONE', #30537, #2172, #11304, .T. ) ; -#32716 = CARTESIAN_POINT ( 'NONE', ( 31.50927902874334308, 191.9221069586437807, 104.4557568079087133 ) ) ; -#32717 = ORIENTED_EDGE ( 'NONE', *, *, #17823, .F. ) ; -#32718 = VERTEX_POINT ( 'NONE', #14341 ) ; -#32719 = AXIS2_PLACEMENT_3D ( 'NONE', #16346, #37628, #38024 ) ; -#32720 = EDGE_LOOP ( 'NONE', ( #36602, #24031, #38962, #20991 ) ) ; -#32721 = FACE_OUTER_BOUND ( 'NONE', #28752, .T. ) ; -#32722 = LINE ( 'NONE', #16764, #1025 ) ; -#32723 = ORIENTED_EDGE ( 'NONE', *, *, #5428, .F. ) ; -#32724 = CIRCLE ( 'NONE', #30785, 2.499999999936769690 ) ; -#32725 = CARTESIAN_POINT ( 'NONE', ( -25.99272582769830819, 191.9759150222000130, 101.9371462954573673 ) ) ; -#32726 = ADVANCED_FACE ( 'NONE', ( #23956 ), #39266, .T. ) ; -#32727 = VERTEX_POINT ( 'NONE', #33130 ) ; -#32728 = ORIENTED_EDGE ( 'NONE', *, *, #28530, .T. ) ; -#32729 = CARTESIAN_POINT ( 'NONE', ( 37.96521291183479008, 190.3639829187772250, 106.6578906949923464 ) ) ; -#32730 = CARTESIAN_POINT ( 'NONE', ( 13.36057577586396938, 130.9455636308544229, 89.87601707795123218 ) ) ; -#32731 = CARTESIAN_POINT ( 'NONE', ( -37.84794342418000213, 119.0111939293000063, 87.26395353379000142 ) ) ; -#32732 = ORIENTED_EDGE ( 'NONE', *, *, #11733, .F. ) ; -#32733 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7151642779479941980, 0.6989564046112777262 ) ) ; -#32734 = CARTESIAN_POINT ( 'NONE', ( 17.27337838772892553, 121.3064376902564589, 177.4324028043064345 ) ) ; -#32735 = CARTESIAN_POINT ( 'NONE', ( -19.61865725212798139, 149.0880427795878518, 183.0335604834078254 ) ) ; -#32736 = ORIENTED_EDGE ( 'NONE', *, *, #8106, .F. ) ; -#32737 = EDGE_CURVE ( 'NONE', #20264, #349, #38589, .T. ) ; -#32738 = CARTESIAN_POINT ( 'NONE', ( -19.99998307616975524, 191.6734502099888005, 103.9162975344601136 ) ) ; -#32739 = DIRECTION ( 'NONE', ( 0.1695469893270774853, -1.252670582138759799E-14, -0.9855221044756549142 ) ) ; -#32740 = CARTESIAN_POINT ( 'NONE', ( 26.00233459572431371, 120.1578067510816510, 90.45674428593952143 ) ) ; -#32741 = EDGE_LOOP ( 'NONE', ( #16345, #12159, #18461, #1776, #4321 ) ) ; -#32742 = CONICAL_SURFACE ( 'NONE', #6634, 5.999999999944576778, 0.7853981633665771955 ) ; -#32743 = CARTESIAN_POINT ( 'NONE', ( 19.98324763982542862, 210.6264698755651921, 76.04472544804136191 ) ) ; -#32744 = ORIENTED_EDGE ( 'NONE', *, *, #7150, .F. ) ; -#32745 = ORIENTED_EDGE ( 'NONE', *, *, #35470, .T. ) ; -#32746 = AXIS2_PLACEMENT_3D ( 'NONE', #27085, #21136, #18442 ) ; -#32747 = EDGE_CURVE ( 'NONE', #19220, #10604, #31300, .T. ) ; -#32748 = EDGE_LOOP ( 'NONE', ( #34420, #25700, #38870, #10518 ) ) ; -#32749 = ORIENTED_EDGE ( 'NONE', *, *, #14742, .T. ) ; -#32750 = CARTESIAN_POINT ( 'NONE', ( -28.06646533513999842, 186.8817599097000084, 105.7227911433000003 ) ) ; -#32751 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927745150551, 0.0005734119022082871534 ) ) ; -#32752 = CARTESIAN_POINT ( 'NONE', ( 46.97661709579189449, 139.7843841080672007, 297.5301723299980381 ) ) ; -#32753 = EDGE_CURVE ( 'NONE', #8044, #16264, #143, .T. ) ; -#32754 = ORIENTED_EDGE ( 'NONE', *, *, #2531, .F. ) ; -#32755 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12268, #34123, #24757, #6320 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32756 = CARTESIAN_POINT ( 'NONE', ( 25.99874167938696345, 118.1131156663084738, 87.25205387058410622 ) ) ; -#32757 = EDGE_LOOP ( 'NONE', ( #4498, #29375, #14750, #24403 ) ) ; -#32758 = CARTESIAN_POINT ( 'NONE', ( 26.52219644700000245, 123.5473871732999953, 90.72568424453001512 ) ) ; -#32759 = CARTESIAN_POINT ( 'NONE', ( -24.27786784973672241, 213.2748330173207592, 75.57328985925654763 ) ) ; -#32760 = ADVANCED_FACE ( 'NONE', ( #200 ), #12284, .T. ) ; -#32761 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39892, #9031, #23976, #11700 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#32762 = EDGE_CURVE ( 'NONE', #23829, #37534, #27452, .T. ) ; -#32764 = LINE ( 'NONE', #30305, #26619 ) ; -#32763 = CARTESIAN_POINT ( 'NONE', ( 20.48145322531597756, 209.2067958958842269, 75.59590488910892248 ) ) ; -#32765 = EDGE_CURVE ( 'NONE', #10706, #1289, #19706, .T. ) ; -#32766 = ORIENTED_EDGE ( 'NONE', *, *, #17359, .T. ) ; -#32767 = VERTEX_POINT ( 'NONE', #6331 ) ; -#32768 = CARTESIAN_POINT ( 'NONE', ( 20.49882255141355714, 191.9760415900621808, 101.9090510850346192 ) ) ; -#32769 = AXIS2_PLACEMENT_3D ( 'NONE', #3857, #6523, #10424 ) ; -#32770 = ORIENTED_EDGE ( 'NONE', *, *, #31523, .F. ) ; -#32772 = AXIS2_PLACEMENT_3D ( 'NONE', #23449, #7898, #33041 ) ; -#32771 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#32773 = AXIS2_PLACEMENT_3D ( 'NONE', #613, #19209, #33957 ) ; -#32774 = DIRECTION ( 'NONE', ( 0.4303597330247870278, 0.7060138277436147636, -0.5624366410767025481 ) ) ; -#32775 = LINE ( 'NONE', #27275, #5688 ) ; -#32776 = DIRECTION ( 'NONE', ( -0.0004270746993301995954, 0.7071067811865993091, -0.7071066522152992251 ) ) ; -#32777 = EDGE_LOOP ( 'NONE', ( #36548, #10484, #9252, #15004, #1481 ) ) ; -#32778 = ORIENTED_EDGE ( 'NONE', *, *, #6849, .T. ) ; -#32779 = ORIENTED_EDGE ( 'NONE', *, *, #13886, .F. ) ; -#32780 = CARTESIAN_POINT ( 'NONE', ( -12.63696992648818451, 177.4628036669718369, 100.9107721134794105 ) ) ; -#32781 = CYLINDRICAL_SURFACE ( 'NONE', #2450, 1.999999999999996891 ) ; -#32782 = ORIENTED_EDGE ( 'NONE', *, *, #35422, .F. ) ; -#32783 = CARTESIAN_POINT ( 'NONE', ( -35.43627711642999856, 192.7868341534999956, 106.8766536760000037 ) ) ; -#32784 = CARTESIAN_POINT ( 'NONE', ( 3.064393835126558496, 190.8773406645956072, 106.7989981663780981 ) ) ; -#32785 = ORIENTED_EDGE ( 'NONE', *, *, #36972, .F. ) ; -#32786 = CARTESIAN_POINT ( 'NONE', ( 39.80107749601363309, 119.4152471894954601, 89.76382462946382645 ) ) ; -#32787 = CARTESIAN_POINT ( 'NONE', ( -20.49852834815464320, 160.1744661120611681, 99.21025293621499941 ) ) ; -#32788 = LINE ( 'NONE', #7236, #19550 ) ; -#32789 = CARTESIAN_POINT ( 'NONE', ( 20.89466079040630575, 182.4265417833274796, 104.8357029080749783 ) ) ; -#32790 = EDGE_CURVE ( 'NONE', #8044, #5645, #29339, .T. ) ; -#32791 = VERTEX_POINT ( 'NONE', #28233 ) ; -#32792 = CIRCLE ( 'NONE', #23673, 2.500000000088257401 ) ; -#32793 = CARTESIAN_POINT ( 'NONE', ( 3.882702609227124846, 148.9606115484772602, 129.9617790688552077 ) ) ; -#32794 = CARTESIAN_POINT ( 'NONE', ( -18.79252570011861678, 125.8499160133713133, 175.1155745579973484 ) ) ; -#32795 = AXIS2_PLACEMENT_3D ( 'NONE', #29061, #28662, #838 ) ; -#32796 = VECTOR ( 'NONE', #19117, 1000.000000000000114 ) ; -#32797 = ORIENTED_EDGE ( 'NONE', *, *, #37650, .T. ) ; -#32798 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557941447071, -0.2249510932885531445 ) ) ; -#32799 = EDGE_CURVE ( 'NONE', #629, #31589, #27842, .T. ) ; -#32800 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #19337, #22428, #28360, #34855 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 2.960011224583242839, 3.141237505301649247 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9972649584264866585, 0.9972649584264866585, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#32802 = CARTESIAN_POINT ( 'NONE', ( -37.90028209746999721, 118.4258653137000010, 90.15013806132000695 ) ) ; -#32801 = CARTESIAN_POINT ( 'NONE', ( -35.94659742893283294, 111.0397749124999933, 89.78949559157379667 ) ) ; -#32803 = ADVANCED_FACE ( 'NONE', ( #24369 ), #34732, .F. ) ; -#32804 = ORIENTED_EDGE ( 'NONE', *, *, #27546, .T. ) ; -#32805 = ADVANCED_FACE ( 'NONE', ( #40271 ), #9617, .F. ) ; -#32806 = ORIENTED_EDGE ( 'NONE', *, *, #10530, .F. ) ; -#32807 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319377456504 ) ) ; -#32808 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7071067167009886800, -0.7071068456721004702 ) ) ; -#32809 = LINE ( 'NONE', #35650, #2507 ) ; -#32810 = ORIENTED_EDGE ( 'NONE', *, *, #5745, .F. ) ; -#32811 = VERTEX_POINT ( 'NONE', #21694 ) ; -#32812 = CARTESIAN_POINT ( 'NONE', ( -42.56961273145186908, 120.8423396639923055, 90.69722013036826525 ) ) ; -#32813 = EDGE_LOOP ( 'NONE', ( #21397, #17016, #18232, #39613 ) ) ; -#32814 = EDGE_LOOP ( 'NONE', ( #22136, #12556, #17455, #6614 ) ) ; -#32815 = EDGE_LOOP ( 'NONE', ( #1745, #1926, #23986, #6392 ) ) ; -#32816 = CARTESIAN_POINT ( 'NONE', ( 8.710107595624538845, 190.8512735252159018, 106.7880641322737034 ) ) ; -#32817 = CARTESIAN_POINT ( 'NONE', ( 25.16034815843458361, 152.9446670041224081, 185.2614157039075167 ) ) ; -#32818 = AXIS2_PLACEMENT_3D ( 'NONE', #10118, #1097, #22594 ) ; -#32819 = EDGE_LOOP ( 'NONE', ( #9822, #35851, #4999, #1478 ) ) ; -#32820 = CYLINDRICAL_SURFACE ( 'NONE', #19321, 51.40509898897001761 ) ; -#32821 = CARTESIAN_POINT ( 'NONE', ( -36.21997592040000313, 192.0428499488999989, 104.5653900318999945 ) ) ; -#32823 = CIRCLE ( 'NONE', #12565, 2.500000000051482818 ) ; -#32822 = CARTESIAN_POINT ( 'NONE', ( 30.11497173888000134, 126.4642963853000168, 91.65365240219000498 ) ) ; -#32824 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971541810 ) ) ; -#32825 = EDGE_LOOP ( 'NONE', ( #13212, #28567, #27189, #40338 ) ) ; -#32826 = CARTESIAN_POINT ( 'NONE', ( 22.78070441975003391, 158.6816533748419147, 96.78686173997256503 ) ) ; -#32827 = CARTESIAN_POINT ( 'NONE', ( -30.07038618952948639, 174.6758729064384283, 103.0802804918280771 ) ) ; -#32828 = EDGE_LOOP ( 'NONE', ( #37051, #23266, #26444, #4529 ) ) ; -#32829 = CARTESIAN_POINT ( 'NONE', ( -20.51845187336659748, 208.8853181553784850, 75.71044176397822412 ) ) ; -#32830 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#32831 = CARTESIAN_POINT ( 'NONE', ( 20.50009675764631467, 195.3341997283218348, 104.9064908536454226 ) ) ; -#32832 = DIRECTION ( 'NONE', ( 0.9914447795421099663, -0.1270909273343945323, -0.02975139169821508847 ) ) ; -#32833 = ORIENTED_EDGE ( 'NONE', *, *, #14814, .F. ) ; -#32834 = DIRECTION ( 'NONE', ( 5.782411586589349356E-15, 0.9743700557921587402, 0.2249510932971554578 ) ) ; -#32835 = PLANE ( 'NONE', #18591 ) ; -#32836 = DIRECTION ( 'NONE', ( 0.1305263947825949788, 0.9659212016154236080, 0.2235153071601011787 ) ) ; -#32837 = EDGE_CURVE ( 'NONE', #7061, #20336, #12754, .T. ) ; -#32838 = ADVANCED_FACE ( 'NONE', ( #3060 ), #2110, .F. ) ; -#32839 = VERTEX_POINT ( 'NONE', #33532 ) ; -#32840 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566235 ) ) ; -#32841 = ORIENTED_EDGE ( 'NONE', *, *, #18390, .F. ) ; -#32842 = ADVANCED_FACE ( 'NONE', ( #39875 ), #3397, .T. ) ; -#32843 = CARTESIAN_POINT ( 'NONE', ( -25.87037428029999830, 191.8434814924999898, 104.0540975785000057 ) ) ; -#32844 = DIRECTION ( 'NONE', ( 0.7066795775021695869, -1.083657843182747848E-14, -0.7075337269285155717 ) ) ; -#32845 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825852062932896, 0.0005734119039538788888 ) ) ; -#32846 = ADVANCED_FACE ( 'NONE', ( #11886 ), #26275, .F. ) ; -#32847 = CARTESIAN_POINT ( 'NONE', ( 22.78191781013921968, 158.2317512751428126, 98.73560149028561739 ) ) ; -#32848 = ORIENTED_EDGE ( 'NONE', *, *, #4043, .T. ) ; -#32849 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#32850 = ADVANCED_FACE ( 'NONE', ( #40074 ), #15163, .F. ) ; -#32851 = CIRCLE ( 'NONE', #11296, 2.500000000039660275 ) ; -#32852 = CARTESIAN_POINT ( 'NONE', ( -35.94409206926000167, 192.9208245654000109, 106.5386867681999945 ) ) ; -#32853 = CARTESIAN_POINT ( 'NONE', ( -17.17998261867176524, 121.8556495602137488, 175.2825063656824511 ) ) ; -#32854 = CARTESIAN_POINT ( 'NONE', ( 37.05652324767000039, 190.9934127923000062, 106.4015284892000039 ) ) ; -#32855 = CARTESIAN_POINT ( 'NONE', ( 31.26527125512335559, 177.5014052372173410, 100.6134679889321575 ) ) ; -#32856 = DIRECTION ( 'NONE', ( -0.0005884928212895037744, 0.2249510522791092204, -0.9743698875451359820 ) ) ; -#32857 = LINE ( 'NONE', #1793, #14513 ) ; -#32858 = CARTESIAN_POINT ( 'NONE', ( -38.46834805455461037, 118.9254695117024028, 87.72566723886511397 ) ) ; -#32859 = ORIENTED_EDGE ( 'NONE', *, *, #18914, .T. ) ; -#32860 = ADVANCED_FACE ( 'NONE', ( #26168 ), #38218, .F. ) ; -#32861 = CARTESIAN_POINT ( 'NONE', ( -15.49970618539471268, 185.7934281236995844, 103.0692296848312282 ) ) ; -#32862 = CARTESIAN_POINT ( 'NONE', ( 16.00178153260169722, 185.2344458670014831, 105.4869183982072371 ) ) ; -#32863 = EDGE_LOOP ( 'NONE', ( #5270, #36276, #17334, #12788, #27321, #8525, #3494 ) ) ; -#32864 = CARTESIAN_POINT ( 'NONE', ( 5.665213903590472277, 181.8726204490157272, 101.8888004455338745 ) ) ; -#32865 = DIRECTION ( 'NONE', ( -0.0005884949961240561319, 0.2249510543439064147, -0.9743698870671262391 ) ) ; -#32866 = ORIENTED_EDGE ( 'NONE', *, *, #22986, .T. ) ; -#32867 = CYLINDRICAL_SURFACE ( 'NONE', #18200, 54.50273826251000742 ) ; -#32868 = VERTEX_POINT ( 'NONE', #12889 ) ; -#32869 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971545418 ) ) ; -#32870 = CIRCLE ( 'NONE', #18503, 2.000000000000000000 ) ; -#32871 = DIRECTION ( 'NONE', ( 0.0005884949961224158425, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#32872 = CARTESIAN_POINT ( 'NONE', ( -35.94780537797892350, 109.6131156792400105, 87.78949595639598158 ) ) ; -#32873 = AXIS2_PLACEMENT_3D ( 'NONE', #38255, #25605, #4089 ) ; -#32874 = DIRECTION ( 'NONE', ( -0.9999998176073598977, 1.232348283187829930E-10, 0.0006039745416129974672 ) ) ; -#32875 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#32876 = VERTEX_POINT ( 'NONE', #16334 ) ; -#32877 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; -#32878 = VECTOR ( 'NONE', #6130, 1000.000000000000114 ) ; -#32879 = CARTESIAN_POINT ( 'NONE', ( 13.50029502673440795, 184.8538583973032701, 102.8347976078998443 ) ) ; -#32880 = CARTESIAN_POINT ( 'NONE', ( 3.534343284623258974, 175.3621990150981276, 100.1363906404241675 ) ) ; -#32881 = EDGE_CURVE ( 'NONE', #6175, #36179, #35117, .T. ) ; -#32883 = ORIENTED_EDGE ( 'NONE', *, *, #15371, .F. ) ; -#32882 = EDGE_CURVE ( 'NONE', #24370, #6504, #7296, .T. ) ; -#32884 = CARTESIAN_POINT ( 'NONE', ( -5.668553076710673544, 181.6128662711424795, 104.1507415732276769 ) ) ; -#32885 = ORIENTED_EDGE ( 'NONE', *, *, #31396, .T. ) ; -#32886 = ORIENTED_EDGE ( 'NONE', *, *, #34629, .T. ) ; -#32887 = ADVANCED_FACE ( 'NONE', ( #19401 ), #13085, .T. ) ; -#32888 = ORIENTED_EDGE ( 'NONE', *, *, #25816, .F. ) ; -#32889 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971557076 ) ) ; -#32890 = ADVANCED_FACE ( 'NONE', ( #38607 ), #18998, .F. ) ; -#32891 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 179.4050256829000034, 102.6004212787000114 ) ) ; -#32892 = CARTESIAN_POINT ( 'NONE', ( 6.034581674326127576, 134.5951993983805437, 93.50225422090859695 ) ) ; -#32893 = CARTESIAN_POINT ( 'NONE', ( -30.07215349727681541, 177.7873460224360542, 100.7165300549321643 ) ) ; -#32894 = CARTESIAN_POINT ( 'NONE', ( 3.484078850188212506, 129.8174280154724158, 89.62153155823813222 ) ) ; -#32895 = CARTESIAN_POINT ( 'NONE', ( -21.69612205307337760, 152.4962460410746417, 197.7980205213018507 ) ) ; -#32896 = ADVANCED_FACE ( 'NONE', ( #10227 ), #22092, .F. ) ; -#32897 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971576505 ) ) ; -#32898 = CARTESIAN_POINT ( 'NONE', ( -42.32952069418180230, 102.4430063022160056, 173.5700923359364651 ) ) ; -#32899 = CARTESIAN_POINT ( 'NONE', ( 20.16831244149273417, 119.7528658665681576, 90.19575101107872683 ) ) ; -#32900 = EDGE_CURVE ( 'NONE', #19924, #27116, #4053, .T. ) ; -#32901 = DIRECTION ( 'NONE', ( -0.0005884949961247530571, 0.2249510543439059984, -0.9743698870671264611 ) ) ; -#32902 = CARTESIAN_POINT ( 'NONE', ( 3.251734184265008931, 183.4850195645019824, 102.0118139314580930 ) ) ; -#32903 = CIRCLE ( 'NONE', #244, 2.000000000223218333 ) ; -#32904 = VECTOR ( 'NONE', #154, 1000.000000000000114 ) ; -#32905 = ORIENTED_EDGE ( 'NONE', *, *, #20468, .T. ) ; -#32906 = CARTESIAN_POINT ( 'NONE', ( -0.4361371084449976454, 189.0000000011299619, 105.7376017226662128 ) ) ; -#32907 = CARTESIAN_POINT ( 'NONE', ( -44.23619079995874870, 188.4918799454829355, 106.1042852104303336 ) ) ; -#32908 = CARTESIAN_POINT ( 'NONE', ( -35.94945294205002995, 192.4527268789682921, 106.4191431240564469 ) ) ; -#32909 = DIRECTION ( 'NONE', ( 0.1632030864945563375, -0.3417424273710317206, 0.9255143790850607344 ) ) ; -#32910 = CIRCLE ( 'NONE', #2227, 4.499999997027624765 ) ; -#32911 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921578520, 0.2249510932971587607 ) ) ; -#32912 = VERTEX_POINT ( 'NONE', #16141 ) ; -#32913 = ORIENTED_EDGE ( 'NONE', *, *, #19773, .T. ) ; -#32914 = ORIENTED_EDGE ( 'NONE', *, *, #9742, .T. ) ; -#32915 = DIRECTION ( 'NONE', ( 0.6087614115774877543, -0.7730004600455410158, -0.1785492440296698458 ) ) ; -#32916 = CARTESIAN_POINT ( 'NONE', ( -2.853038766185818087, 209.7096500570610544, 73.06022702708840200 ) ) ; -#32917 = LINE ( 'NONE', #26804, #38328 ) ; -#32918 = EDGE_LOOP ( 'NONE', ( #17344, #21120, #4087, #33154, #8425, #14790, #32988 ) ) ; -#32919 = DIRECTION ( 'NONE', ( 0.0006039748319386652707, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#32920 = DIRECTION ( 'NONE', ( 0.0006039748319392047697, -6.984862132708257173E-19, 0.9999998176071845934 ) ) ; -#32921 = CARTESIAN_POINT ( 'NONE', ( -26.01077944034773282, 209.7097224531575534, 73.07398733611859143 ) ) ; -#32922 = ORIENTED_EDGE ( 'NONE', *, *, #17488, .T. ) ; -#32923 = FACE_OUTER_BOUND ( 'NONE', #24138, .T. ) ; -#32924 = ORIENTED_EDGE ( 'NONE', *, *, #15626, .T. ) ; -#32925 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#32926 = CARTESIAN_POINT ( 'NONE', ( -19.70055405364098533, 149.1723619494412389, 182.9474843209757751 ) ) ; -#32927 = ORIENTED_EDGE ( 'NONE', *, *, #17130, .T. ) ; -#32928 = CARTESIAN_POINT ( 'NONE', ( -2.879056355731880235, 190.4460883268289990, 103.6209980420309904 ) ) ; -#32929 = CARTESIAN_POINT ( 'NONE', ( 0.6371854363678430833, 189.0060406513339615, 103.6969466364630108 ) ) ; -#32930 = AXIS2_PLACEMENT_3D ( 'NONE', #22905, #35942, #5077 ) ; -#32931 = VECTOR ( 'NONE', #7186, 1000.000000000000000 ) ; -#32932 = DIRECTION ( 'NONE', ( -0.7933530821293339752, -0.5932640870757631690, -0.1364866662427065558 ) ) ; -#32933 = ORIENTED_EDGE ( 'NONE', *, *, #21653, .F. ) ; -#32934 = EDGE_CURVE ( 'NONE', #11929, #28306, #32099, .T. ) ; -#32935 = AXIS2_PLACEMENT_3D ( 'NONE', #31463, #30668, #8996 ) ; -#32936 = ORIENTED_EDGE ( 'NONE', *, *, #23351, .T. ) ; -#32937 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#32938 = ORIENTED_EDGE ( 'NONE', *, *, #39033, .F. ) ; -#32939 = VERTEX_POINT ( 'NONE', #22697 ) ; -#32940 = VERTEX_POINT ( 'NONE', #31486 ) ; -#32941 = CARTESIAN_POINT ( 'NONE', ( -14.78542622577100119, 175.8938623147257374, 100.7833030093998303 ) ) ; -#32942 = ORIENTED_EDGE ( 'NONE', *, *, #3256, .F. ) ; -#32943 = CARTESIAN_POINT ( 'NONE', ( 21.45428261829664862, 213.0890995499228211, 73.54560849209069318 ) ) ; -#32944 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927782063840, -0.0005734119022076108281 ) ) ; -#32945 = CARTESIAN_POINT ( 'NONE', ( 23.68596773153978319, 129.9751393256367464, 92.21150139214144303 ) ) ; -#32946 = VERTEX_POINT ( 'NONE', #25567 ) ; -#32947 = CARTESIAN_POINT ( 'NONE', ( 44.86724994974370162, 186.7825132065745777, 105.8343309753838213 ) ) ; -#32948 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988409597765, 156.3551877982712028, 95.75036263596727792 ) ) ; -#32949 = ORIENTED_EDGE ( 'NONE', *, *, #9203, .T. ) ; -#32950 = CARTESIAN_POINT ( 'NONE', ( 26.02608998670000062, 120.6389521098000159, 90.56795384212999522 ) ) ; -#32951 = CARTESIAN_POINT ( 'NONE', ( 43.11176529853025130, 93.58819903903858517, 291.5325055092823163 ) ) ; -#32953 = CARTESIAN_POINT ( 'NONE', ( -27.82759976036524918, 177.7876074752642808, 100.7152660398233479 ) ) ; -#32952 = DIRECTION ( 'NONE', ( 0.7855991485562935361, -0.6187357899682438545, 0.000000000000000000 ) ) ; -#32954 = VECTOR ( 'NONE', #20729, 999.9999999999998863 ) ; -#32955 = ORIENTED_EDGE ( 'NONE', *, *, #23802, .F. ) ; -#32956 = EDGE_CURVE ( 'NONE', #31008, #1984, #13282, .T. ) ; -#32957 = AXIS2_PLACEMENT_3D ( 'NONE', #40037, #14907, #12244 ) ; -#32958 = ORIENTED_EDGE ( 'NONE', *, *, #3613, .F. ) ; -#32959 = CIRCLE ( 'NONE', #36889, 2.000000000735676409 ) ; -#32960 = ORIENTED_EDGE ( 'NONE', *, *, #21617, .F. ) ; -#32961 = DIRECTION ( 'NONE', ( -0.0005884949961259294164, 0.2255194585872565272, -0.9742384859325513569 ) ) ; -#32962 = CARTESIAN_POINT ( 'NONE', ( -20.51880467302672173, 211.0905570380611493, 75.57084890002228406 ) ) ; -#32963 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901141, 132.2978364233219963, 93.26432363102219369 ) ) ; -#32964 = CARTESIAN_POINT ( 'NONE', ( 44.69319620505716273, 133.1441970321177166, 337.0970861341226623 ) ) ; -#32965 = ORIENTED_EDGE ( 'NONE', *, *, #20100, .T. ) ; -#32966 = ORIENTED_EDGE ( 'NONE', *, *, #13900, .T. ) ; -#32967 = EDGE_LOOP ( 'NONE', ( #16428, #38580, #10005, #35279 ) ) ; -#32968 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 82.27946979429628982, 310.0857197240630967 ) ) ; -#32969 = CARTESIAN_POINT ( 'NONE', ( 16.00004425883027537, 186.0638578529228369, 102.5994861110636265 ) ) ; -#32970 = ADVANCED_FACE ( 'NONE', ( #16733 ), #28621, .T. ) ; -#32971 = VERTEX_POINT ( 'NONE', #22499 ) ; -#32972 = CARTESIAN_POINT ( 'NONE', ( -35.64317240526990815, 191.6880555651530074, 106.9491066055539790 ) ) ; -#32973 = EDGE_CURVE ( 'NONE', #30934, #1598, #22295, .T. ) ; -#32974 = CARTESIAN_POINT ( 'NONE', ( 3.079959205947283785, 190.7372649033252969, 106.7807747737359705 ) ) ; -#32975 = EDGE_CURVE ( 'NONE', #22792, #37113, #22468, .T. ) ; -#32976 = ORIENTED_EDGE ( 'NONE', *, *, #10016, .F. ) ; -#32977 = CARTESIAN_POINT ( 'NONE', ( -30.07831637853678686, 134.9151858147922667, 90.81876078434068233 ) ) ; -#32978 = CONICAL_SURFACE ( 'NONE', #360, 7.002999999845556545, 0.7853981633426221354 ) ; -#32979 = CARTESIAN_POINT ( 'NONE', ( 23.36232515670958065, 177.1947614343970372, 101.0605990059838462 ) ) ; -#32980 = AXIS2_PLACEMENT_3D ( 'NONE', #30890, #39663, #24365 ) ; -#32981 = VECTOR ( 'NONE', #18443, 1000.000000000000114 ) ; -#32982 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927801571618, -0.0005734119022069843761 ) ) ; -#32983 = CARTESIAN_POINT ( 'NONE', ( 44.53027206012822603, 189.1225043543478250, 103.6304983192370770 ) ) ; -#32984 = AXIS2_PLACEMENT_3D ( 'NONE', #20551, #27335, #26922 ) ; -#32985 = ORIENTED_EDGE ( 'NONE', *, *, #29590, .T. ) ; -#32986 = DIRECTION ( 'NONE', ( 0.0006039748319385908944, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#32987 = CARTESIAN_POINT ( 'NONE', ( -20.00111603559079398, 118.1131148921541438, 87.27965578728156970 ) ) ; -#32988 = ORIENTED_EDGE ( 'NONE', *, *, #24852, .F. ) ; -#32989 = CARTESIAN_POINT ( 'NONE', ( 32.17532506523997426, 77.89466421350269343, 291.2180765908466356 ) ) ; -#32991 = CARTESIAN_POINT ( 'NONE', ( -44.23776012402447577, 189.0917505549361692, 103.5059606069654592 ) ) ; -#32990 = DIRECTION ( 'NONE', ( 0.0005884949961246456127, -0.2249510543439063592, 0.9743698870671262391 ) ) ; -#32992 = ORIENTED_EDGE ( 'NONE', *, *, #25896, .F. ) ; -#32993 = EDGE_CURVE ( 'NONE', #21765, #29199, #38414, .T. ) ; -#32994 = VERTEX_POINT ( 'NONE', #37814 ) ; -#32995 = CARTESIAN_POINT ( 'NONE', ( 3.072975579511000532, 209.7481171635999999, 76.19203123645000630 ) ) ; -#32996 = VECTOR ( 'NONE', #37600, 1000.000000000000227 ) ; -#32997 = DIRECTION ( 'NONE', ( -0.7933532411131104523, -0.5932638852154226150, -0.1364866195435462393 ) ) ; -#32998 = LINE ( 'NONE', #23213, #16340 ) ; -#32999 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; -#33000 = FACE_OUTER_BOUND ( 'NONE', #25298, .T. ) ; -#33001 = VERTEX_POINT ( 'NONE', #25969 ) ; -#33002 = CONICAL_SURFACE ( 'NONE', #12805, 4.502999914355317657, 0.7853981633639942617 ) ; -#33003 = ORIENTED_EDGE ( 'NONE', *, *, #12992, .T. ) ; -#33004 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971561239 ) ) ; -#33005 = ORIENTED_EDGE ( 'NONE', *, *, #30842, .T. ) ; -#33006 = CONICAL_SURFACE ( 'NONE', #15403, 5.000000000026098235, 0.7853981633778843729 ) ; -#33007 = ORIENTED_EDGE ( 'NONE', *, *, #18255, .F. ) ; -#33008 = CARTESIAN_POINT ( 'NONE', ( -25.99225322733902033, 193.8169247290898625, 102.7186084094957010 ) ) ; -#33009 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560961 ) ) ; -#33010 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4464, #23096, #798, #38417, #1401, #7333, #23292, #35725, #13883, #25571 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000314193, 0.3750000000000814349, 0.4375000000000909828, 0.5000000000001004752, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33011 = CARTESIAN_POINT ( 'NONE', ( 39.80107749601363309, 119.4152471894954601, 89.76382462946382645 ) ) ; -#33012 = AXIS2_PLACEMENT_3D ( 'NONE', #10588, #19956, #32455 ) ; -#33013 = AXIS2_PLACEMENT_3D ( 'NONE', #20295, #32774, #17422 ) ; -#33014 = EDGE_CURVE ( 'NONE', #5410, #39888, #6727, .T. ) ; -#33015 = ORIENTED_EDGE ( 'NONE', *, *, #16184, .T. ) ; -#33016 = DIRECTION ( 'NONE', ( -0.0005884949961181158967, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#33017 = VECTOR ( 'NONE', #2376, 1000.000000000000114 ) ; -#33018 = CARTESIAN_POINT ( 'NONE', ( -36.09109704704999899, 192.2866562552000005, 104.5690802119000011 ) ) ; -#33019 = CARTESIAN_POINT ( 'NONE', ( 36.12644007640999888, 191.3780648084000404, 103.6831328241000136 ) ) ; -#33020 = ORIENTED_EDGE ( 'NONE', *, *, #18060, .F. ) ; -#33021 = CARTESIAN_POINT ( 'NONE', ( -26.00373979082000275, 120.9358918448999987, 87.58883631886999410 ) ) ; -#33022 = ADVANCED_FACE ( 'NONE', ( #34916 ), #36146, .F. ) ; -#33023 = VERTEX_POINT ( 'NONE', #1812 ) ; -#33024 = CARTESIAN_POINT ( 'NONE', ( -6.037737380061058090, 175.3552788058639464, 100.1374507664885414 ) ) ; -#33025 = PLANE ( 'NONE', #31298 ) ; -#33026 = ORIENTED_EDGE ( 'NONE', *, *, #32486, .T. ) ; -#33027 = CARTESIAN_POINT ( 'NONE', ( 0.6522971013523114481, 188.6126488384289530, 103.1971906374716497 ) ) ; -#33028 = LINE ( 'NONE', #1977, #2505 ) ; -#33029 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #4419, #753 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33030 = EDGE_CURVE ( 'NONE', #39550, #39205, #11416, .T. ) ; -#33031 = FACE_OUTER_BOUND ( 'NONE', #31931, .T. ) ; -#33032 = EDGE_CURVE ( 'NONE', #13011, #36039, #7735, .T. ) ; -#33033 = CARTESIAN_POINT ( 'NONE', ( 45.28002203899477962, 186.1588271223781987, 106.1973972072094341 ) ) ; -#33034 = VERTEX_POINT ( 'NONE', #10822 ) ; -#33035 = CARTESIAN_POINT ( 'NONE', ( -2.453444162457494304, 207.4083922256737651, 77.08315769752742597 ) ) ; -#33036 = EDGE_CURVE ( 'NONE', #14526, #6177, #15801, .T. ) ; -#33037 = CARTESIAN_POINT ( 'NONE', ( 2.243609847812261471, 189.9161030272695712, 103.9477651519655552 ) ) ; -#33038 = CARTESIAN_POINT ( 'NONE', ( 32.25078568539211687, 136.1275797149361892, 91.06097076243848676 ) ) ; -#33039 = AXIS2_PLACEMENT_3D ( 'NONE', #26706, #36295, #11772 ) ; -#33040 = ORIENTED_EDGE ( 'NONE', *, *, #22616, .F. ) ; -#33041 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971570121 ) ) ; -#33042 = FACE_OUTER_BOUND ( 'NONE', #11744, .T. ) ; -#33043 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714601725811, -0.5299193037554699170 ) ) ; -#33044 = CARTESIAN_POINT ( 'NONE', ( 25.94088316678000083, 191.2889162021000118, 103.9146051783999951 ) ) ; -#33045 = LINE ( 'NONE', #14668, #39928 ) ; -#33046 = CARTESIAN_POINT ( 'NONE', ( -20.83442437065999542, 212.3494483913675595, 75.57101870502553709 ) ) ; -#33047 = CARTESIAN_POINT ( 'NONE', ( 6.026693642215255053, 134.9199437178238838, 90.79804054718465522 ) ) ; -#33048 = ORIENTED_EDGE ( 'NONE', *, *, #37291, .T. ) ; -#33049 = VECTOR ( 'NONE', #3917, 1000.000000000000000 ) ; -#33050 = AXIS2_PLACEMENT_3D ( 'NONE', #16031, #25873, #9721 ) ; -#33051 = CARTESIAN_POINT ( 'NONE', ( 2.729325451305233852, 196.2716069310007470, 103.7432050589404042 ) ) ; -#33052 = CARTESIAN_POINT ( 'NONE', ( -15.66510137924916712, 184.3629618927121498, 104.9627433997273869 ) ) ; -#33053 = CARTESIAN_POINT ( 'NONE', ( 25.50924745143719718, 191.9344736266071436, 104.4056993596765039 ) ) ; -#33054 = DIRECTION ( 'NONE', ( 0.0006039748319393677253, 3.488873499045632102E-19, 0.9999998176071845934 ) ) ; -#33055 = PLANE ( 'NONE', #22870 ) ; -#33056 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319383136639 ) ) ; -#33057 = LINE ( 'NONE', #26957, #37360 ) ; -#33058 = CARTESIAN_POINT ( 'NONE', ( 20.73661144324140437, 116.1345660314903938, 90.25526044551206439 ) ) ; -#33059 = ORIENTED_EDGE ( 'NONE', *, *, #38401, .T. ) ; -#33060 = CARTESIAN_POINT ( 'NONE', ( -15.99998595512920652, 185.9065961375156348, 102.5825112407314634 ) ) ; -#33061 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421903059, 127.0698778186146995, 92.06007195132379195 ) ) ; -#33062 = EDGE_CURVE ( 'NONE', #29701, #19402, #32490, .T. ) ; -#33063 = AXIS2_PLACEMENT_3D ( 'NONE', #18159, #2842, #39841 ) ; -#33064 = ORIENTED_EDGE ( 'NONE', *, *, #18752, .T. ) ; -#33065 = DIRECTION ( 'NONE', ( 0.7933532411131101192, 0.5932638852154232811, 0.1364866195435442964 ) ) ; -#33066 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498903273, 176.3880814479794878, 103.4433606027979948 ) ) ; -#33067 = CONICAL_SURFACE ( 'NONE', #8938, 2.750000000007442491, 0.7853981633308424470 ) ; -#33068 = ORIENTED_EDGE ( 'NONE', *, *, #14387, .T. ) ; -#33069 = AXIS2_PLACEMENT_3D ( 'NONE', #31870, #31252, #34302 ) ; -#33070 = EDGE_CURVE ( 'NONE', #27116, #13945, #7318, .T. ) ; -#33071 = CARTESIAN_POINT ( 'NONE', ( 20.00007076059032940, 143.0057557026720190, 92.65639515983836816 ) ) ; -#33072 = EDGE_LOOP ( 'NONE', ( #21589, #32374, #22323, #34482 ) ) ; -#33073 = CARTESIAN_POINT ( 'NONE', ( 36.27379766703212738, 191.8934879371578290, 106.3925458811340690 ) ) ; -#33074 = AXIS2_PLACEMENT_3D ( 'NONE', #458, #31958, #19659 ) ; -#33075 = EDGE_CURVE ( 'NONE', #37725, #12815, #16442, .T. ) ; -#33076 = CARTESIAN_POINT ( 'NONE', ( -14.78422084203157461, 175.4439834284964945, 102.7320481277236013 ) ) ; -#33077 = DIRECTION ( 'NONE', ( -0.6068735732728635091, -0.7743428331745977333, -0.1791581501750992289 ) ) ; -#33078 = FACE_OUTER_BOUND ( 'NONE', #1960, .T. ) ; -#33079 = CARTESIAN_POINT ( 'NONE', ( 39.79702541312468611, 141.5973318770025173, 284.1405295046018864 ) ) ; -#33080 = EDGE_CURVE ( 'NONE', #12120, #14434, #1008, .T. ) ; -#33081 = VERTEX_POINT ( 'NONE', #23288 ) ; -#33082 = FACE_OUTER_BOUND ( 'NONE', #35271, .T. ) ; -#33083 = DIRECTION ( 'NONE', ( 0.6087611427445810408, 0.7731004622513006908, 0.1781166650011639374 ) ) ; -#33084 = PLANE ( 'NONE', #26690 ) ; -#33085 = ORIENTED_EDGE ( 'NONE', *, *, #9160, .F. ) ; -#33086 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13908, #23322, #35749, #7757 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33087 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#33088 = VERTEX_POINT ( 'NONE', #26767 ) ; -#33089 = EDGE_LOOP ( 'NONE', ( #38314, #2118, #29936 ) ) ; -#33090 = CARTESIAN_POINT ( 'NONE', ( 14.16683332331358613, 129.7278030047937705, 90.10754002185558420 ) ) ; -#33091 = CARTESIAN_POINT ( 'NONE', ( 22.67317654999515852, 115.6131156702006990, 89.75429555850769248 ) ) ; -#33092 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569011 ) ) ; -#33093 = CARTESIAN_POINT ( 'NONE', ( -30.07215349727681541, 177.7873460224360542, 100.7165300549321643 ) ) ; -#33094 = CARTESIAN_POINT ( 'NONE', ( 14.84630245323845621, 136.2557976693637158, 93.83789554009061362 ) ) ; -#33095 = AXIS2_PLACEMENT_3D ( 'NONE', #6820, #32191, #16821 ) ; -#33096 = VECTOR ( 'NONE', #4243, 1000.000000000000114 ) ; -#33097 = CARTESIAN_POINT ( 'NONE', ( -26.01077944034773282, 209.7097224531575534, 73.07398733611859143 ) ) ; -#33098 = CIRCLE ( 'NONE', #15489, 1.750000000000001998 ) ; -#33099 = CARTESIAN_POINT ( 'NONE', ( 26.15694028684000472, 190.9579671749999932, 106.9451011959999960 ) ) ; -#33100 = CARTESIAN_POINT ( 'NONE', ( 4.017367618393966389, 182.2867097658143507, 101.7346998419586868 ) ) ; -#33101 = VERTEX_POINT ( 'NONE', #23695 ) ; -#33102 = CARTESIAN_POINT ( 'NONE', ( 14.75941300677970602, 124.6753782222769615, 88.42758558798597335 ) ) ; -#33103 = PLANE ( 'NONE', #31582 ) ; -#33104 = FACE_OUTER_BOUND ( 'NONE', #12323, .T. ) ; -#33105 = CARTESIAN_POINT ( 'NONE', ( -16.50035848821718076, 136.6784666199758931, 180.9776494209432656 ) ) ; -#33106 = CARTESIAN_POINT ( 'NONE', ( -20.02047174850214617, 117.7199421200607077, 87.27987615529596610 ) ) ; -#33108 = EDGE_LOOP ( 'NONE', ( #5736, #33852 ) ) ; -#33107 = CARTESIAN_POINT ( 'NONE', ( 13.47343164508975377, 158.6809479346725595, 96.79232023565108989 ) ) ; -#33109 = VERTEX_POINT ( 'NONE', #35930 ) ; -#33110 = ORIENTED_EDGE ( 'NONE', *, *, #28623, .T. ) ; -#33111 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#33112 = ORIENTED_EDGE ( 'NONE', *, *, #9203, .F. ) ; -#33113 = DIRECTION ( 'NONE', ( -6.938893903965234306E-16, 0.9743700557921580740, 0.2249510932971585664 ) ) ; -#33114 = EDGE_CURVE ( 'NONE', #12555, #35055, #26885, .T. ) ; -#33115 = EDGE_CURVE ( 'NONE', #1132, #2098, #10308, .T. ) ; -#33116 = DIRECTION ( 'NONE', ( -0.6773442687123379935, -0.7356661890032381024, 0.000000000000000000 ) ) ; -#33117 = CARTESIAN_POINT ( 'NONE', ( -20.49852834491502307, 151.4051363116404900, 97.18569326181511769 ) ) ; -#33118 = EDGE_CURVE ( 'NONE', #27521, #38809, #8345, .T. ) ; -#33119 = ORIENTED_EDGE ( 'NONE', *, *, #35820, .F. ) ; -#33120 = ORIENTED_EDGE ( 'NONE', *, *, #23817, .F. ) ; -#33121 = FACE_BOUND ( 'NONE', #18010, .T. ) ; -#33122 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921572969, -0.2249510932971618138 ) ) ; -#33123 = VERTEX_POINT ( 'NONE', #35720 ) ; -#33124 = EDGE_CURVE ( 'NONE', #6589, #23150, #29781, .T. ) ; -#33125 = CIRCLE ( 'NONE', #1787, 2.000000000223404850 ) ; -#33126 = ORIENTED_EDGE ( 'NONE', *, *, #30260, .T. ) ; -#33127 = CARTESIAN_POINT ( 'NONE', ( 3.230169986108356373, 186.5436302562499122, 102.7179630022487657 ) ) ; -#33128 = CARTESIAN_POINT ( 'NONE', ( 28.46953594426098277, 131.0252485042709338, 89.88531577736306133 ) ) ; -#33129 = VECTOR ( 'NONE', #4233, 1000.000000000000000 ) ; -#33130 = CARTESIAN_POINT ( 'NONE', ( 39.17918664236205473, 77.03152903297159071, 290.9156096052041676 ) ) ; -#33131 = ADVANCED_FACE ( 'NONE', ( #30028 ), #2025, .T. ) ; -#33132 = ORIENTED_EDGE ( 'NONE', *, *, #18292, .F. ) ; -#33133 = CARTESIAN_POINT ( 'NONE', ( -1.512059224926999956, 189.1271795652999970, 103.5915707072000203 ) ) ; -#33134 = CARTESIAN_POINT ( 'NONE', ( 0.5945664429271031448, 189.0157257392609722, 103.6937134704449903 ) ) ; -#33135 = CARTESIAN_POINT ( 'NONE', ( -36.02915914471689973, 191.1279744515711627, 106.8708103113893770 ) ) ; -#33136 = ORIENTED_EDGE ( 'NONE', *, *, #40303, .F. ) ; -#33137 = ORIENTED_EDGE ( 'NONE', *, *, #9211, .F. ) ; -#33138 = CYLINDRICAL_SURFACE ( 'NONE', #24442, 59.40509898897001051 ) ; -#33139 = EDGE_LOOP ( 'NONE', ( #23352, #14479, #17053, #17983 ) ) ; -#33140 = EDGE_CURVE ( 'NONE', #36682, #2366, #17123, .T. ) ; -#33141 = ORIENTED_EDGE ( 'NONE', *, *, #4188, .T. ) ; -#33142 = ORIENTED_EDGE ( 'NONE', *, *, #27813, .F. ) ; -#33143 = CARTESIAN_POINT ( 'NONE', ( 20.49113379396988677, 211.4170907343362558, 73.54650032140015981 ) ) ; -#33144 = CARTESIAN_POINT ( 'NONE', ( -20.01944572060296323, 207.3562132816129520, 73.63222224179746433 ) ) ; -#33145 = CARTESIAN_POINT ( 'NONE', ( 45.38216566575481892, 131.0689882075479886, 90.22727308576753558 ) ) ; -#33146 = ORIENTED_EDGE ( 'NONE', *, *, #12307, .F. ) ; -#33147 = FACE_OUTER_BOUND ( 'NONE', #22231, .T. ) ; -#33148 = EDGE_LOOP ( 'NONE', ( #35077, #17083, #22881, #9469 ) ) ; -#33149 = CARTESIAN_POINT ( 'NONE', ( 28.53280061317499872, 124.6087127242800108, 91.48628689533521197 ) ) ; -#33150 = DIRECTION ( 'NONE', ( 0.7933310414247656261, 0.5931044597393390072, 0.1373060761554398823 ) ) ; -#33151 = CIRCLE ( 'NONE', #15542, 2.000000000354214436 ) ; -#33153 = DIRECTION ( 'NONE', ( -0.0005884949961224158425, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#33152 = DIRECTION ( 'NONE', ( 0.0005884949961230158400, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33154 = ORIENTED_EDGE ( 'NONE', *, *, #30365, .F. ) ; -#33155 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6476, #38369, #25120, #37565, #16089, #545, #25726, #3810, #12837, #37972 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33156 = ORIENTED_EDGE ( 'NONE', *, *, #39856, .F. ) ; -#33157 = CARTESIAN_POINT ( 'NONE', ( 21.57626859835584909, 176.1824540492217750, 103.2226781424499649 ) ) ; -#33158 = EDGE_CURVE ( 'NONE', #12909, #8503, #13852, .T. ) ; -#33159 = EDGE_CURVE ( 'NONE', #13769, #28042, #5357, .T. ) ; -#33160 = ORIENTED_EDGE ( 'NONE', *, *, #4934, .F. ) ; -#33161 = CARTESIAN_POINT ( 'NONE', ( 39.02975055476000676, 119.0105336778999998, 89.82596006120000709 ) ) ; -#33162 = DIRECTION ( 'NONE', ( 0.7933532970003738249, 0.5930762008556724751, 0.1372995488602876402 ) ) ; -#33163 = DIRECTION ( 'NONE', ( -0.5988682214889313737, 0.8008475843072039302, -6.938893903907200768E-15 ) ) ; -#33164 = CARTESIAN_POINT ( 'NONE', ( 20.16666278967802484, 160.7088898722922465, 96.91425943719899294 ) ) ; -#33165 = CARTESIAN_POINT ( 'NONE', ( 36.22776625462999789, 191.6123771812999905, 104.0140211655999991 ) ) ; -#33166 = ORIENTED_EDGE ( 'NONE', *, *, #30939, .F. ) ; -#33167 = VERTEX_POINT ( 'NONE', #9367 ) ; -#33168 = CARTESIAN_POINT ( 'NONE', ( -19.99827944177191341, 118.8155627782461181, 90.27982142893266371 ) ) ; -#33169 = CARTESIAN_POINT ( 'NONE', ( 14.69746453343251957, 188.0513169112800824, 103.0591139980062252 ) ) ; -#33170 = ORIENTED_EDGE ( 'NONE', *, *, #28089, .T. ) ; -#33171 = CARTESIAN_POINT ( 'NONE', ( 30.06788597519531336, 135.1232275265250280, 91.10458376635099853 ) ) ; -#33172 = AXIS2_PLACEMENT_3D ( 'NONE', #9877, #24621, #25021 ) ; -#33173 = CARTESIAN_POINT ( 'NONE', ( -22.49806768458547168, 153.6037118230980241, 98.03658197602312896 ) ) ; -#33174 = CARTESIAN_POINT ( 'NONE', ( 5.674778016381245571, 131.0223034755605909, 89.89838139801142347 ) ) ; -#33175 = AXIS2_PLACEMENT_3D ( 'NONE', #18666, #22376, #682 ) ; -#33176 = EDGE_CURVE ( 'NONE', #36248, #26024, #30444, .T. ) ; -#33177 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; -#33178 = CARTESIAN_POINT ( 'NONE', ( 31.79391164649184631, 220.4002260770999726, 73.03930135617515873 ) ) ; -#33179 = CARTESIAN_POINT ( 'NONE', ( 21.00169408020338224, 182.5884499274252164, 104.7019667032076455 ) ) ; -#33180 = ORIENTED_EDGE ( 'NONE', *, *, #7141, .F. ) ; -#33181 = DIRECTION ( 'NONE', ( 0.6771712326825870543, -0.7358254695422995484, 0.000000000000000000 ) ) ; -#33182 = CARTESIAN_POINT ( 'NONE', ( 20.89285664109717189, 183.1014278315721810, 101.9125999898524242 ) ) ; -#33183 = ORIENTED_EDGE ( 'NONE', *, *, #37696, .T. ) ; -#33184 = CARTESIAN_POINT ( 'NONE', ( 36.06588537441000142, 194.9391275604999976, 107.7152975676000040 ) ) ; -#33186 = CARTESIAN_POINT ( 'NONE', ( 15.99849543194476986, 160.4080026200020086, 96.67636507677717361 ) ) ; -#33185 = CARTESIAN_POINT ( 'NONE', ( 36.05533436145224613, 118.8155677978006111, 90.24600832072150070 ) ) ; -#33187 = ORIENTED_EDGE ( 'NONE', *, *, #19411, .T. ) ; -#33188 = VECTOR ( 'NONE', #18624, 1000.000000000000227 ) ; -#33189 = VERTEX_POINT ( 'NONE', #3212 ) ; -#33190 = ORIENTED_EDGE ( 'NONE', *, *, #16309, .F. ) ; -#33191 = CARTESIAN_POINT ( 'NONE', ( 20.00000522920557700, 138.5176112521621690, 91.62015419223651236 ) ) ; -#33192 = VECTOR ( 'NONE', #6138, 999.9999999999998863 ) ; -#33193 = CARTESIAN_POINT ( 'NONE', ( 36.74499328828947142, 191.3591568088928909, 106.3388620510278457 ) ) ; -#33194 = CONICAL_SURFACE ( 'NONE', #20822, 5.000000000042579273, 0.7853981634430861059 ) ; -#33195 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#33196 = EDGE_CURVE ( 'NONE', #13844, #16326, #36740, .T. ) ; -#33197 = ORIENTED_EDGE ( 'NONE', *, *, #30521, .T. ) ; -#33198 = EDGE_CURVE ( 'NONE', #1613, #1746, #9989, .T. ) ; -#33199 = VERTEX_POINT ( 'NONE', #24319 ) ; -#33200 = DIRECTION ( 'NONE', ( 0.0002393071182782299474, 0.2252352986010034697, -0.9743043687658493601 ) ) ; -#33201 = AXIS2_PLACEMENT_3D ( 'NONE', #5177, #26884, #35430 ) ; -#33202 = ORIENTED_EDGE ( 'NONE', *, *, #1800, .F. ) ; -#33203 = ORIENTED_EDGE ( 'NONE', *, *, #4982, .F. ) ; -#33204 = CARTESIAN_POINT ( 'NONE', ( -36.46592998411147590, 191.1051656101541596, 106.5992029824818701 ) ) ; -#33205 = DIRECTION ( 'NONE', ( -0.0005884949961159196283, 0.2249510543439052768, -0.9743698870671265722 ) ) ; -#33206 = CARTESIAN_POINT ( 'NONE', ( 39.51684480652362907, 114.5628099923930847, 151.3186418573310732 ) ) ; -#33207 = DIRECTION ( 'NONE', ( -0.6982900371914136928, 0.000000000000000000, -0.7158149369489394953 ) ) ; -#33208 = ORIENTED_EDGE ( 'NONE', *, *, #18747, .T. ) ; -#33209 = ORIENTED_EDGE ( 'NONE', *, *, #29131, .T. ) ; -#33210 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1187, #4045, #16322, #37598 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33211 = ORIENTED_EDGE ( 'NONE', *, *, #28159, .F. ) ; -#33212 = CARTESIAN_POINT ( 'NONE', ( -20.45366101552173532, 211.0901972962080322, 75.63591788811629613 ) ) ; -#33213 = EDGE_CURVE ( 'NONE', #1201, #1952, #25645, .T. ) ; -#33214 = CARTESIAN_POINT ( 'NONE', ( -35.31822109755999861, 192.0397647290000407, 103.8027042277000049 ) ) ; -#33215 = CARTESIAN_POINT ( 'NONE', ( 36.47870239224999978, 191.4233604986999921, 103.9343244230000067 ) ) ; -#33216 = EDGE_LOOP ( 'NONE', ( #28182, #8485, #23514, #25803 ) ) ; -#33217 = CARTESIAN_POINT ( 'NONE', ( 20.48555995111231809, 211.0898943587194481, 73.54694346759191603 ) ) ; -#33218 = ORIENTED_EDGE ( 'NONE', *, *, #32348, .F. ) ; -#33219 = EDGE_LOOP ( 'NONE', ( #8226, #25290, #24907, #24822 ) ) ; -#33220 = DIRECTION ( 'NONE', ( -0.0005865300001401835836, 0.2249510543434335152, -0.9743698882520622773 ) ) ; -#33221 = CARTESIAN_POINT ( 'NONE', ( -40.45487666593005827, 220.4002261020000049, 76.08293836150286893 ) ) ; -#33222 = ORIENTED_EDGE ( 'NONE', *, *, #11115, .F. ) ; -#33223 = CARTESIAN_POINT ( 'NONE', ( -16.89229910586540129, 151.8805145963252698, 184.0522065937344962 ) ) ; -#33224 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#33225 = DIRECTION ( 'NONE', ( -0.0005884949961239352434, 0.2249510543439079413, -0.9743698870671259060 ) ) ; -#33226 = FACE_OUTER_BOUND ( 'NONE', #20077, .T. ) ; -#33227 = ORIENTED_EDGE ( 'NONE', *, *, #8158, .F. ) ; -#33228 = CIRCLE ( 'NONE', #29338, 4.999999999999990230 ) ; -#33229 = EDGE_CURVE ( 'NONE', #282, #275, #31232, .T. ) ; -#33230 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31947, #4510, #20877, #26414, #29884, #30277, #8418, #27032, #5325, #17782, #1448, #11679, #36618, #14756 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000249800, 0.3750000000000530687, 0.5000000000000811573, 0.6250000000001093570, 0.6875000000001233458, 0.7500000000001373346, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33231 = DIRECTION ( 'NONE', ( -0.0005884949961244357111, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#33232 = CARTESIAN_POINT ( 'NONE', ( 22.11776643986201663, 129.2357545819063773, 92.04174809736024088 ) ) ; -#33233 = VECTOR ( 'NONE', #14450, 1000.000000000000114 ) ; -#33234 = ORIENTED_EDGE ( 'NONE', *, *, #27211, .T. ) ; -#33235 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33236 = EDGE_LOOP ( 'NONE', ( #11088, #10633, #21207, #25506, #18129 ) ) ; -#33237 = AXIS2_PLACEMENT_3D ( 'NONE', #12065, #14521, #24543 ) ; -#33238 = CARTESIAN_POINT ( 'NONE', ( -8.050307605157906110, 151.4365984322141117, 94.61967771673485572 ) ) ; -#33239 = LINE ( 'NONE', #8114, #4944 ) ; -#33240 = VECTOR ( 'NONE', #20891, 1000.000000000000000 ) ; -#33241 = CARTESIAN_POINT ( 'NONE', ( -23.02004673814065683, 213.5902071504527839, 73.57250091739375364 ) ) ; -#33242 = CARTESIAN_POINT ( 'NONE', ( 6.033439958583901586, 135.0872164925444281, 91.06582754317723527 ) ) ; -#33243 = ORIENTED_EDGE ( 'NONE', *, *, #15653, .F. ) ; -#33244 = EDGE_CURVE ( 'NONE', #5686, #23549, #24317, .T. ) ; -#33245 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971560684 ) ) ; -#33246 = ADVANCED_FACE ( 'NONE', ( #40425 ), #40005, .F. ) ; -#33247 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -0.000000000000000000, 0.0006039748319387908213 ) ) ; -#33248 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21379, #15762, #25200, #39957 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33249 = CARTESIAN_POINT ( 'NONE', ( -24.51675559260586468, 115.4936548059245069, 87.28259179807037071 ) ) ; -#33250 = CARTESIAN_POINT ( 'NONE', ( -2.955836285853710610, 208.9211498072354800, 73.12285454242802984 ) ) ; -#33251 = CARTESIAN_POINT ( 'NONE', ( -20.49853057565002601, 184.3993303303604705, 104.8029991440840973 ) ) ; -#33252 = LINE ( 'NONE', #32665, #30726 ) ; -#33253 = DIRECTION ( 'NONE', ( -0.0005884949961255136249, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#33254 = ADVANCED_FACE ( 'NONE', ( #36975 ), #25000, .F. ) ; -#33255 = CARTESIAN_POINT ( 'NONE', ( -17.26236276037843353, 152.4432311036538579, 182.8745738163920862 ) ) ; -#33256 = ADVANCED_FACE ( 'NONE', ( #34089 ), #19736, .F. ) ; -#33257 = CARTESIAN_POINT ( 'NONE', ( 20.54337478632077918, 116.3706092612608529, 90.25537715561074492 ) ) ; -#33258 = ORIENTED_EDGE ( 'NONE', *, *, #27298, .T. ) ; -#33259 = ADVANCED_FACE ( 'NONE', ( #33481 ), #7987, .F. ) ; -#33260 = CARTESIAN_POINT ( 'NONE', ( 14.42708641008473869, 182.0277504606679884, 104.5764898171669302 ) ) ; -#33262 = CONICAL_SURFACE ( 'NONE', #18895, 2.250000000020516921, 0.7853981633778843729 ) ; -#33261 = CARTESIAN_POINT ( 'NONE', ( 3.868711044008855460, 144.1404883528797995, 93.27114193733976322 ) ) ; -#33263 = DIRECTION ( 'NONE', ( 5.204170427930391307E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#33264 = AXIS2_PLACEMENT_3D ( 'NONE', #5500, #27214, #2051 ) ; -#33265 = ORIENTED_EDGE ( 'NONE', *, *, #22399, .T. ) ; -#33266 = DIRECTION ( 'NONE', ( -0.0005884949961258157921, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#33267 = CYLINDRICAL_SURFACE ( 'NONE', #26338, 2.500000000000000888 ) ; -#33268 = AXIS2_PLACEMENT_3D ( 'NONE', #7343, #38820, #26586 ) ; -#33269 = ORIENTED_EDGE ( 'NONE', *, *, #5508, .F. ) ; -#33270 = CARTESIAN_POINT ( 'NONE', ( -38.66421384966999852, 119.1055377026000031, 87.73960695917999431 ) ) ; -#33271 = DIRECTION ( 'NONE', ( -0.0005884949961231158034, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#33272 = ORIENTED_EDGE ( 'NONE', *, *, #331, .T. ) ; -#33273 = CARTESIAN_POINT ( 'NONE', ( 36.22531506482754793, 191.0466354042188755, 106.8125635786149701 ) ) ; -#33274 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28198, #3024, #34486, #24330, #2445, #12246, #37382, #167, #18549, #2835, #24529, #24734, #15511, #6098, #9580, #8985, #33698, #21464, #6291, #15311 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999998834821, 0.1874999999998343270, 0.2187499999998188949, 0.2343749999998115674, 0.2499999999998042122, 0.4999999999998561151, 0.6249999999998827604, 0.6874999999998961941, 0.7187499999999076294, 0.7343749999999144018, 0.7499999999999211742, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33275 = DIRECTION ( 'NONE', ( 1.734723475976797036E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#33276 = CARTESIAN_POINT ( 'NONE', ( -15.99823432472775941, 127.0706064849903782, 92.07805732825173095 ) ) ; -#33277 = CARTESIAN_POINT ( 'NONE', ( 3.534269831815406882, 173.0753051157153664, 99.60843731991197103 ) ) ; -#33278 = CARTESIAN_POINT ( 'NONE', ( 29.88752274199697823, 186.0181866662012737, 102.7516051117415401 ) ) ; -#33279 = ORIENTED_EDGE ( 'NONE', *, *, #7444, .F. ) ; -#33280 = CARTESIAN_POINT ( 'NONE', ( 38.31118519780999776, 119.2261486170999945, 87.35962453867999500 ) ) ; -#33281 = EDGE_CURVE ( 'NONE', #26352, #20529, #2824, .T. ) ; -#33282 = PLANE ( 'NONE', #8826 ) ; -#33283 = DIRECTION ( 'NONE', ( 0.6075493383219849886, -0.7739051213223927528, -0.1787586772592888451 ) ) ; -#33284 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971558186 ) ) ; -#33285 = EDGE_LOOP ( 'NONE', ( #1677, #31181 ) ) ; -#33286 = ORIENTED_EDGE ( 'NONE', *, *, #21000, .T. ) ; -#33287 = CARTESIAN_POINT ( 'NONE', ( -32.82620923289504589, 141.9145509277669532, 282.5750060058261965 ) ) ; -#33288 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33289 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 67.27946979429630403, 312.5857197240632104 ) ) ; -#33290 = CARTESIAN_POINT ( 'NONE', ( -30.06677054097168522, 177.7873425219656838, 100.7165248410704379 ) ) ; -#33291 = CARTESIAN_POINT ( 'NONE', ( -20.02005459657448583, 210.1682184491333203, 73.07059569371034513 ) ) ; -#33292 = VECTOR ( 'NONE', #30692, 1000.000000000000114 ) ; -#33293 = AXIS2_PLACEMENT_3D ( 'NONE', #21330, #12313, #8662 ) ; -#33294 = CARTESIAN_POINT ( 'NONE', ( -20.00005230623649410, 189.3360834415266538, 103.3767362770949205 ) ) ; -#33295 = EDGE_CURVE ( 'NONE', #22051, #27937, #13192, .T. ) ; -#33296 = VECTOR ( 'NONE', #8127, 1000.000000000000000 ) ; -#33297 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33298 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25653, #22576, #7009, #21970, #19482, #34411, #8238, #20078, #1695, #20702, #14373, #1482, #26855, #10508, #38683, #19873, #4340, #13758, #26445, #38895, #23377, #35807, #17210, #23566, #14184, #39092, #9251, #37055 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 1, 1, 2, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000002658984, 0.1875000000003988476, 0.2187500000004621303, 0.2343750000005202783, 0.2421875000005241918, 0.2500000000005281331, 0.3750000000000497935, 0.4374999999998557820, 0.4687499999997587485, 0.4999999999996617706, 0.6249999999996865840, 0.6874999999997115641, 0.7499999999997366551, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33299 = VECTOR ( 'NONE', #13048, 1000.000000000000114 ) ; -#33300 = CARTESIAN_POINT ( 'NONE', ( -12.63810005728112529, 128.5846432257639549, 89.34357918520186104 ) ) ; -#33301 = CARTESIAN_POINT ( 'NONE', ( 6.037333824820820816, 176.9751110601698940, 103.3914243744087713 ) ) ; -#33302 = ADVANCED_FACE ( 'NONE', ( #38177 ), #34876, .T. ) ; -#33303 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#33304 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -1.540743955509788340E-33, -0.0006039748319384538513 ) ) ; -#33305 = ORIENTED_EDGE ( 'NONE', *, *, #31405, .T. ) ; -#33306 = ADVANCED_FACE ( 'NONE', ( #28188 ), #19746, .F. ) ; -#33307 = DIRECTION ( 'NONE', ( 0.0005884949961230292841, -0.2249510543439062205, 0.9743698870671264611 ) ) ; -#33308 = LINE ( 'NONE', #30251, #274 ) ; -#33309 = CARTESIAN_POINT ( 'NONE', ( 25.49226348177107582, 205.5673819639667954, 76.28481786455526503 ) ) ; -#33310 = CARTESIAN_POINT ( 'NONE', ( 36.20140471363000501, 112.8637457762999929, 87.89413822324999614 ) ) ; -#33311 = EDGE_CURVE ( 'NONE', #35054, #16205, #31739, .T. ) ; -#33313 = ORIENTED_EDGE ( 'NONE', *, *, #23305, .T. ) ; -#33312 = CARTESIAN_POINT ( 'NONE', ( 13.47101530616665954, 158.5560635654926216, 96.59244381856061068 ) ) ; -#33314 = EDGE_LOOP ( 'NONE', ( #29422, #14222, #31364, #26281 ) ) ; -#33315 = VERTEX_POINT ( 'NONE', #10376 ) ; -#33316 = EDGE_CURVE ( 'NONE', #5373, #12599, #13438, .T. ) ; -#33317 = CARTESIAN_POINT ( 'NONE', ( -1.671695307840509237, 188.9373267610033906, 103.2735520890073815 ) ) ; -#33318 = EDGE_CURVE ( 'NONE', #6430, #31651, #6369, .T. ) ; -#33319 = EDGE_LOOP ( 'NONE', ( #9934, #34957, #30235, #9547 ) ) ; -#33320 = CARTESIAN_POINT ( 'NONE', ( -23.35774878981629854, 177.6820881319245871, 100.7790085384882559 ) ) ; -#33321 = FACE_OUTER_BOUND ( 'NONE', #10908, .T. ) ; -#33322 = ORIENTED_EDGE ( 'NONE', *, *, #35981, .F. ) ; -#33323 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251387457, 132.4055461763558128, 92.79778151956838883 ) ) ; -#33324 = VECTOR ( 'NONE', #38506, 1000.000000000000227 ) ; -#33325 = VECTOR ( 'NONE', #19639, 1000.000000000000227 ) ; -#33326 = CARTESIAN_POINT ( 'NONE', ( -2.435581690730916016, 190.9709058671855360, 106.3075837308457352 ) ) ; -#33327 = CARTESIAN_POINT ( 'NONE', ( -35.56677799604999990, 112.8225408933000011, 87.40728143148000129 ) ) ; -#33328 = EDGE_LOOP ( 'NONE', ( #463, #34231, #26842, #40281, #35327 ) ) ; -#33329 = CARTESIAN_POINT ( 'NONE', ( -16.53785153513707584, 123.0772470471530085, 172.1883206570706477 ) ) ; -#33330 = AXIS2_PLACEMENT_3D ( 'NONE', #8701, #33614, #2555 ) ; -#33331 = CIRCLE ( 'NONE', #9187, 5.500000704070026281 ) ; -#33332 = CARTESIAN_POINT ( 'NONE', ( -31.13366096836537622, 145.3289308342401114, 291.5773478863123387 ) ) ; -#33333 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971576227 ) ) ; -#33334 = DIRECTION ( 'NONE', ( 0.0004161288024366806716, 0.5299192579072459219, 0.8480479980141769625 ) ) ; -#33335 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825841446765121, 0.0005734119041989553089 ) ) ; -#33336 = ORIENTED_EDGE ( 'NONE', *, *, #18529, .F. ) ; -#33337 = CARTESIAN_POINT ( 'NONE', ( -28.38063916929000285, 186.9956065833000025, 103.2298156084000027 ) ) ; -#33338 = CARTESIAN_POINT ( 'NONE', ( 0.7116569482820880310, 189.0174315982739870, 103.6976887742920184 ) ) ; -#33339 = CARTESIAN_POINT ( 'NONE', ( -35.58150936734264036, 191.9112545771486111, 106.9427098373480192 ) ) ; -#33340 = ORIENTED_EDGE ( 'NONE', *, *, #36645, .T. ) ; -#33341 = PLANE ( 'NONE', #19808 ) ; -#33342 = VERTEX_POINT ( 'NONE', #16482 ) ; -#33343 = EDGE_CURVE ( 'NONE', #28170, #17879, #33155, .T. ) ; -#33344 = ORIENTED_EDGE ( 'NONE', *, *, #38022, .T. ) ; -#33345 = ADVANCED_FACE ( 'NONE', ( #9772 ), #11266, .F. ) ; -#33346 = ORIENTED_EDGE ( 'NONE', *, *, #19147, .F. ) ; -#33347 = CARTESIAN_POINT ( 'NONE', ( -35.93274180817000030, 192.3161995874999945, 104.1918708424999949 ) ) ; -#33348 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21046, #14300, #14505, #20416 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33349 = CARTESIAN_POINT ( 'NONE', ( -30.14946743423720221, 157.4708583386490659, 204.7746580714026834 ) ) ; -#33350 = VECTOR ( 'NONE', #15452, 1000.000000000000227 ) ; -#33351 = CARTESIAN_POINT ( 'NONE', ( 39.06896504242525481, 77.46065173580983299, 289.9734668182510404 ) ) ; -#33352 = EDGE_CURVE ( 'NONE', #367, #38321, #13688, .T. ) ; -#33353 = CONICAL_SURFACE ( 'NONE', #13775, 2.503000015120896204, 0.7853981633802915585 ) ; -#33354 = ORIENTED_EDGE ( 'NONE', *, *, #8916, .F. ) ; -#33355 = FACE_OUTER_BOUND ( 'NONE', #27261, .T. ) ; -#33356 = LINE ( 'NONE', #8440, #21283 ) ; -#33357 = ORIENTED_EDGE ( 'NONE', *, *, #18205, .F. ) ; -#33358 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38992, #20381, #19766, #22871 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999913805631791552 ), - .UNSPECIFIED. ) ; -#33359 = AXIS2_PLACEMENT_3D ( 'NONE', #25104, #18719, #34664 ) ; -#33360 = CARTESIAN_POINT ( 'NONE', ( 26.03705070847000158, 122.6857235223999965, 90.52704919891000657 ) ) ; -#33361 = AXIS2_PLACEMENT_3D ( 'NONE', #24820, #33984, #18434 ) ; -#33362 = CARTESIAN_POINT ( 'NONE', ( -26.00898928064792059, 209.7096528057114710, 76.07444037909847623 ) ) ; -#33364 = CARTESIAN_POINT ( 'NONE', ( 40.34565112152872501, 84.30714302849141006, 281.9928763557079492 ) ) ; -#33363 = DIRECTION ( 'NONE', ( 2.710505431213760483E-20, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#33365 = ORIENTED_EDGE ( 'NONE', *, *, #34200, .F. ) ; -#33366 = EDGE_CURVE ( 'NONE', #12177, #6270, #32823, .T. ) ; -#33367 = EDGE_LOOP ( 'NONE', ( #30675, #13206, #2209, #34438, #236, #39336, #28015, #28093, #13123, #34703, #29555, #27063 ) ) ; -#33368 = VERTEX_POINT ( 'NONE', #28772 ) ; -#33369 = CARTESIAN_POINT ( 'NONE', ( 38.65290384512000088, 119.3054438774999966, 90.42302427312999669 ) ) ; -#33370 = DIRECTION ( 'NONE', ( -0.0006039748319393752063, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#33371 = EDGE_CURVE ( 'NONE', #23183, #9539, #21016, .T. ) ; -#33372 = DIRECTION ( 'NONE', ( -7.677760455957277161E-18, 1.000000000000000000, -1.271205131337255403E-14 ) ) ; -#33373 = CARTESIAN_POINT ( 'NONE', ( -25.57959927007320644, 190.0284346369258230, 106.1056550784269348 ) ) ; -#33374 = EDGE_LOOP ( 'NONE', ( #8473, #19023, #11158, #31746 ) ) ; -#33375 = ORIENTED_EDGE ( 'NONE', *, *, #30051, .T. ) ; -#33376 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12128, #4961, #30324, #2321, #39921, #8667, #23789, #36244, #11720 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 1, 4 ), - ( 0.000000000000000000, 0.1666665328685613123, 0.3333330550499289946, 0.4999995772315967146, 0.6666660994132644902, 0.8333326215947320925, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33377 = FACE_OUTER_BOUND ( 'NONE', #304, .T. ) ; -#33378 = AXIS2_PLACEMENT_3D ( 'NONE', #9215, #21285, #24154 ) ; -#33379 = CARTESIAN_POINT ( 'NONE', ( 20.94827535171210897, 136.6018947531004244, 91.17730147031002730 ) ) ; -#33380 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971564847 ) ) ; -#33381 = CIRCLE ( 'NONE', #3345, 2.000000000000011546 ) ; -#33382 = VERTEX_POINT ( 'NONE', #26747 ) ; -#33383 = CARTESIAN_POINT ( 'NONE', ( -36.31434820589119283, 190.8494679263099840, 106.8166726591159943 ) ) ; -#33384 = CARTESIAN_POINT ( 'NONE', ( 1.193074764343845962, 188.4261495725348539, 106.2465465345643452 ) ) ; -#33385 = VERTEX_POINT ( 'NONE', #20390 ) ; -#33386 = CARTESIAN_POINT ( 'NONE', ( 5.667817003649492591, 130.7086471584207175, 90.09438582789336181 ) ) ; -#33387 = CARTESIAN_POINT ( 'NONE', ( 39.86705590273664512, 163.8835619643772645, 187.7938324431582089 ) ) ; -#33388 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7431, #38915, #20311, #16829, #4975, #1502, #17435, #23395, #29329, #32786 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 4 ), - ( 0.000000000000000000, 0.04166555891684221857, 0.08333241167583366193, 0.1666661171939165242, 0.2499998227117794236, 0.3333335282297422708, 0.6666667690975455196, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33389 = LINE ( 'NONE', #24425, #20213 ) ; -#33390 = DIRECTION ( 'NONE', ( -0.7933532970003733809, -0.5930762008556731413, -0.1372995488602877234 ) ) ; -#33391 = VERTEX_POINT ( 'NONE', #14884 ) ; -#33392 = ADVANCED_FACE ( 'NONE', ( #24087 ), #28261, .T. ) ; -#33393 = EDGE_CURVE ( 'NONE', #8895, #529, #21081, .T. ) ; -#33394 = CARTESIAN_POINT ( 'NONE', ( -21.44693694427656538, 176.9185168219783009, 100.5107344958116897 ) ) ; -#33395 = CARTESIAN_POINT ( 'NONE', ( 15.83996889908606853, 123.3007470976622812, 173.6922296629854259 ) ) ; -#33396 = ORIENTED_EDGE ( 'NONE', *, *, #185, .F. ) ; -#33397 = EDGE_CURVE ( 'NONE', #24029, #18457, #20179, .T. ) ; -#33398 = DIRECTION ( 'NONE', ( 0.1305262051639064502, -0.9658997602660150950, -0.2236080563923503461 ) ) ; -#33399 = VERTEX_POINT ( 'NONE', #35703 ) ; -#33400 = CIRCLE ( 'NONE', #24307, 2.999999999692155583 ) ; -#33402 = CARTESIAN_POINT ( 'NONE', ( -25.73988229027240848, 191.3495811618992661, 106.6455200333169557 ) ) ; -#33401 = FACE_OUTER_BOUND ( 'NONE', #5101, .T. ) ; -#33403 = ORIENTED_EDGE ( 'NONE', *, *, #29174, .F. ) ; -#33404 = AXIS2_PLACEMENT_3D ( 'NONE', #9778, #28585, #10385 ) ; -#33405 = EDGE_CURVE ( 'NONE', #75, #17792, #11743, .T. ) ; -#33406 = ORIENTED_EDGE ( 'NONE', *, *, #2396, .T. ) ; -#33407 = VECTOR ( 'NONE', #15363, 1000.000000000000114 ) ; -#33408 = ORIENTED_EDGE ( 'NONE', *, *, #849, .T. ) ; -#33409 = DIRECTION ( 'NONE', ( 0.0005884949961257158286, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33410 = CARTESIAN_POINT ( 'NONE', ( 36.81706287246154119, 191.3054326740181352, 106.3308896061233639 ) ) ; -#33411 = DIRECTION ( 'NONE', ( 0.0005884949961252012663, -0.2249510543439044163, 0.9743698870671267942 ) ) ; -#33412 = ORIENTED_EDGE ( 'NONE', *, *, #23404, .T. ) ; -#33413 = EDGE_LOOP ( 'NONE', ( #30317, #26910, #34613, #11442 ) ) ; -#33414 = CARTESIAN_POINT ( 'NONE', ( -14.42373141347307985, 176.1776882614505269, 103.2433209713472877 ) ) ; -#33415 = VERTEX_POINT ( 'NONE', #8133 ) ; -#33416 = ORIENTED_EDGE ( 'NONE', *, *, #13474, .F. ) ; -#33417 = EDGE_LOOP ( 'NONE', ( #29271, #18571, #38333, #23542 ) ) ; -#33418 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971554578 ) ) ; -#33419 = ADVANCED_FACE ( 'NONE', ( #11007 ), #4652, .T. ) ; -#33420 = CARTESIAN_POINT ( 'NONE', ( -19.99999816303952471, 191.5261162992163690, 103.8822987450886046 ) ) ; -#33421 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 1.271205595054999941E-14 ) ) ; -#33422 = ORIENTED_EDGE ( 'NONE', *, *, #12537, .T. ) ; -#33423 = ORIENTED_EDGE ( 'NONE', *, *, #28235, .T. ) ; -#33424 = ORIENTED_EDGE ( 'NONE', *, *, #13343, .F. ) ; -#33425 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319368671214 ) ) ; -#33426 = CARTESIAN_POINT ( 'NONE', ( -35.83347173055000212, 192.2043590798000139, 104.3136215505000024 ) ) ; -#33427 = CARTESIAN_POINT ( 'NONE', ( -25.83463620619999901, 120.7390220298999992, 87.71382168438999827 ) ) ; -#33428 = ORIENTED_EDGE ( 'NONE', *, *, #17363, .F. ) ; -#33429 = CARTESIAN_POINT ( 'NONE', ( -24.13060896835314395, 149.4040876299065417, 197.0825913028203900 ) ) ; -#33430 = ORIENTED_EDGE ( 'NONE', *, *, #38990, .F. ) ; -#33431 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#33432 = CARTESIAN_POINT ( 'NONE', ( 29.05533563819800236, 110.6131156702000027, 90.25023614458406485 ) ) ; -#33433 = EDGE_LOOP ( 'NONE', ( #23394, #32116, #28786, #21170 ) ) ; -#33434 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22415, #10145, #6848, #19322 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.0003352960797964262582 ), - .UNSPECIFIED. ) ; -#33435 = CARTESIAN_POINT ( 'NONE', ( 1.007187599721282245, 188.6511345722273347, 103.2058614258702107 ) ) ; -#33436 = VECTOR ( 'NONE', #26976, 1000.000000000000227 ) ; -#33437 = CARTESIAN_POINT ( 'NONE', ( -28.94810864222802849, 110.6131156702000027, 87.28526822420690223 ) ) ; -#33438 = CARTESIAN_POINT ( 'NONE', ( -3.994524027314616088, 167.9238973488463103, 101.0321959041968967 ) ) ; -#33439 = VERTEX_POINT ( 'NONE', #23467 ) ; -#33440 = AXIS2_PLACEMENT_3D ( 'NONE', #35162, #13321, #25408 ) ; -#33441 = LINE ( 'NONE', #33035, #28341 ) ; -#33442 = CARTESIAN_POINT ( 'NONE', ( 45.36643772523598983, 116.4348365831125705, 122.4283839521299768 ) ) ; -#33443 = CARTESIAN_POINT ( 'NONE', ( -14.08011580147661235, 129.1601492223334446, 176.8499123979196099 ) ) ; -#33444 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2654, #12437, #31457, #15895 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0001076180654492282703, 0.0007700079201253817729 ), - .UNSPECIFIED. ) ; -#33445 = ORIENTED_EDGE ( 'NONE', *, *, #35044, .F. ) ; -#33446 = CARTESIAN_POINT ( 'NONE', ( 22.11776643986201663, 129.2357545819063773, 92.04174809736024088 ) ) ; -#33447 = ORIENTED_EDGE ( 'NONE', *, *, #32179, .F. ) ; -#33448 = EDGE_CURVE ( 'NONE', #27242, #4779, #33668, .T. ) ; -#33449 = LINE ( 'NONE', #23861, #17271 ) ; -#33450 = FACE_OUTER_BOUND ( 'NONE', #438, .T. ) ; -#33451 = CARTESIAN_POINT ( 'NONE', ( 38.35945018049999788, 118.7771177168999941, 90.10301542510001127 ) ) ; -#33452 = CARTESIAN_POINT ( 'NONE', ( -45.78692920758950180, 187.6730625466252604, 103.4985544161652626 ) ) ; -#33453 = CARTESIAN_POINT ( 'NONE', ( -25.49980755039416280, 121.1804654486459896, 90.21079787901257419 ) ) ; -#33454 = ORIENTED_EDGE ( 'NONE', *, *, #17625, .F. ) ; -#33455 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#33456 = AXIS2_PLACEMENT_3D ( 'NONE', #39544, #20953, #15026 ) ; -#33457 = CARTESIAN_POINT ( 'NONE', ( -15.99825118274618063, 184.2885608609500423, 105.2878711035513817 ) ) ; -#33458 = DIRECTION ( 'NONE', ( -1.262878690511118089E-13, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#33459 = CARTESIAN_POINT ( 'NONE', ( 19.46094739937527152, 125.6704563215593993, 178.4613359473326568 ) ) ; -#33460 = LINE ( 'NONE', #24082, #33296 ) ; -#33461 = CARTESIAN_POINT ( 'NONE', ( 20.00176513865794448, 118.9456690639568990, 90.18052439326535819 ) ) ; -#33462 = AXIS2_PLACEMENT_3D ( 'NONE', #9976, #22448, #31650 ) ; -#33463 = CARTESIAN_POINT ( 'NONE', ( 20.22318834111896635, 116.9804196145639423, 90.25557054020046621 ) ) ; -#33464 = EDGE_LOOP ( 'NONE', ( #26489, #32782, #32403, #23471 ) ) ; -#33465 = CARTESIAN_POINT ( 'NONE', ( -15.83322916944478820, 185.8688726946225813, 102.7447540698997130 ) ) ; -#33466 = EDGE_CURVE ( 'NONE', #23376, #33023, #17108, .T. ) ; -#33467 = AXIS2_PLACEMENT_3D ( 'NONE', #30048, #32704, #8583 ) ; -#33468 = CARTESIAN_POINT ( 'NONE', ( -31.52379782310919865, 135.3548788018836433, 90.92109691820547823 ) ) ; -#33469 = ORIENTED_EDGE ( 'NONE', *, *, #38131, .T. ) ; -#33470 = DIRECTION ( 'NONE', ( 0.0005884949961176092490, -0.2249510543439112442, 0.9743698870671252399 ) ) ; -#33471 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384972194 ) ) ; -#33472 = ORIENTED_EDGE ( 'NONE', *, *, #35152, .T. ) ; -#33473 = CARTESIAN_POINT ( 'NONE', ( -38.41441041566999814, 118.8735418521000042, 87.72269134817000236 ) ) ; -#33474 = CARTESIAN_POINT ( 'NONE', ( -3.706756796165672441, 143.5747363548986755, 95.70573741494366971 ) ) ; -#33475 = EDGE_LOOP ( 'NONE', ( #22826, #12574, #5821, #34040 ) ) ; -#33476 = CARTESIAN_POINT ( 'NONE', ( 36.38135911213310436, 190.8957024088025491, 106.7816086242061289 ) ) ; -#33477 = EDGE_CURVE ( 'NONE', #2293, #31797, #37085, .T. ) ; -#33478 = FACE_OUTER_BOUND ( 'NONE', #25597, .T. ) ; -#33479 = LINE ( 'NONE', #2822, #13583 ) ; -#33480 = CARTESIAN_POINT ( 'NONE', ( -1.762796036306197633, 151.6652447677196847, 130.5904578367407396 ) ) ; -#33481 = FACE_OUTER_BOUND ( 'NONE', #196, .T. ) ; -#33482 = ORIENTED_EDGE ( 'NONE', *, *, #22210, .F. ) ; -#33483 = ORIENTED_EDGE ( 'NONE', *, *, #9045, .T. ) ; -#33484 = EDGE_CURVE ( 'NONE', #21410, #18813, #13890, .T. ) ; -#33485 = CARTESIAN_POINT ( 'NONE', ( -40.05024589846355099, 182.7376013918133140, 105.6081377280634257 ) ) ; -#33486 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; -#33487 = VECTOR ( 'NONE', #12215, 1000.000000000000114 ) ; -#33488 = FACE_OUTER_BOUND ( 'NONE', #33417, .T. ) ; -#33489 = CARTESIAN_POINT ( 'NONE', ( 38.11757776978107159, 119.1971814748143146, 87.25517274288121428 ) ) ; -#33490 = EDGE_CURVE ( 'NONE', #37955, #12152, #18519, .T. ) ; -#33491 = VERTEX_POINT ( 'NONE', #30212 ) ; -#33492 = AXIS2_PLACEMENT_3D ( 'NONE', #33621, #5619, #27929 ) ; -#33493 = CYLINDRICAL_SURFACE ( 'NONE', #35501, 4.999999999999990230 ) ; -#33494 = EDGE_CURVE ( 'NONE', #39629, #12644, #2210, .T. ) ; -#33495 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#33496 = CARTESIAN_POINT ( 'NONE', ( 6.028443089694566659, 134.2450043241766195, 93.72108952724657627 ) ) ; -#33497 = CARTESIAN_POINT ( 'NONE', ( -20.02010896950462637, 210.6268457253666782, 73.07059572655020929 ) ) ; -#33498 = AXIS2_PLACEMENT_3D ( 'NONE', #14075, #36349, #16719 ) ; -#33499 = CARTESIAN_POINT ( 'NONE', ( 19.99999382154498662, 120.3902235794415816, 87.43511282661482653 ) ) ; -#33500 = EDGE_CURVE ( 'NONE', #26219, #3788, #32792, .T. ) ; -#33501 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13036, #16087, #34873, #22648 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33502 = CARTESIAN_POINT ( 'NONE', ( -26.00666714465146612, 209.7097296363926660, 73.07769990689128292 ) ) ; -#33503 = FACE_OUTER_BOUND ( 'NONE', #7355, .T. ) ; -#33504 = CALENDAR_DATE ( 2025, 24, 6 ) ; -#33505 = CARTESIAN_POINT ( 'NONE', ( 20.79492132475692401, 105.5805168949505486, 90.25522522787177593 ) ) ; -#33506 = VERTEX_POINT ( 'NONE', #24501 ) ; -#33507 = CARTESIAN_POINT ( 'NONE', ( 44.36208288160555213, 114.2238992016985577, 129.8113731785908271 ) ) ; -#33508 = CARTESIAN_POINT ( 'NONE', ( 35.09291703229374093, 226.4002260771000010, 152.4718672074037329 ) ) ; -#33509 = CARTESIAN_POINT ( 'NONE', ( 17.97063383950254334, 126.0060190202803341, 174.3181455802166795 ) ) ; -#33510 = LINE ( 'NONE', #39846, #23500 ) ; -#33511 = CARTESIAN_POINT ( 'NONE', ( -38.23160862004999672, 118.6973730046999975, 90.09692188751000685 ) ) ; -#33512 = ORIENTED_EDGE ( 'NONE', *, *, #35815, .T. ) ; -#33513 = LINE ( 'NONE', #14928, #25176 ) ; -#33514 = ORIENTED_EDGE ( 'NONE', *, *, #7917, .T. ) ; -#33515 = CARTESIAN_POINT ( 'NONE', ( -23.35994101754937091, 177.6215018238531513, 100.8168681451780202 ) ) ; -#33516 = AXIS2_PLACEMENT_3D ( 'NONE', #265, #6006, #30960 ) ; -#33517 = CARTESIAN_POINT ( 'NONE', ( 36.06505478217123795, 192.7057421143160525, 106.3400883098223915 ) ) ; -#33518 = DIRECTION ( 'NONE', ( 0.6087613503693988237, 0.7731003926570265694, 0.1781162574555661682 ) ) ; -#33519 = AXIS2_PLACEMENT_3D ( 'NONE', #33973, #10265, #15767 ) ; -#33520 = ORIENTED_EDGE ( 'NONE', *, *, #129, .F. ) ; -#33521 = DIRECTION ( 'NONE', ( 0.7072759766253136071, 0.1592272936566845043, -0.6887723585071315879 ) ) ; -#33522 = CIRCLE ( 'NONE', #21791, 6.000000000000007994 ) ; -#33523 = CARTESIAN_POINT ( 'NONE', ( 14.03037017219619109, 130.6394716187099903, 89.80494561686856514 ) ) ; -#33524 = CARTESIAN_POINT ( 'NONE', ( -20.49970533410106910, 151.8550384231813553, 95.23695349207935124 ) ) ; -#33525 = EDGE_LOOP ( 'NONE', ( #35454, #20888, #39600, #33960 ) ) ; -#33526 = FACE_OUTER_BOUND ( 'NONE', #16982, .T. ) ; -#33527 = EDGE_CURVE ( 'NONE', #10675, #7714, #29565, .T. ) ; -#33528 = CARTESIAN_POINT ( 'NONE', ( 23.36666681450611449, 177.0338548618016432, 103.4718259550949142 ) ) ; -#33529 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250100424, 132.8554482850266538, 90.84904174538199584 ) ) ; -#33530 = DIRECTION ( 'NONE', ( -0.0005884965908176638741, 0.2249510543436329113, -0.9743698870662261813 ) ) ; -#33531 = CARTESIAN_POINT ( 'NONE', ( -4.020572368890905857, 187.7456919456083142, 102.9998601274035934 ) ) ; -#33532 = CARTESIAN_POINT ( 'NONE', ( 39.01961099979754266, 175.8196705488005023, 136.1591049921323986 ) ) ; -#33533 = ORIENTED_EDGE ( 'NONE', *, *, #33036, .F. ) ; -#33534 = EDGE_CURVE ( 'NONE', #20168, #14135, #30822, .T. ) ; -#33535 = DIRECTION ( 'NONE', ( -0.7075337269008554753, -2.191878737649064204E-15, -0.7066795775298629900 ) ) ; -#33536 = CARTESIAN_POINT ( 'NONE', ( 0.9454324690280999643, 189.0434255943999915, 103.7039833884000046 ) ) ; -#33537 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319411731388 ) ) ; -#33538 = EDGE_CURVE ( 'NONE', #20341, #901, #27580, .T. ) ; -#33539 = ORIENTED_EDGE ( 'NONE', *, *, #36289, .F. ) ; -#33540 = CARTESIAN_POINT ( 'NONE', ( -3.996912173002292068, 136.7828067576370472, 93.84025925768952447 ) ) ; -#33541 = ORIENTED_EDGE ( 'NONE', *, *, #4350, .F. ) ; -#33542 = EDGE_CURVE ( 'NONE', #37891, #34375, #18419, .T. ) ; -#33543 = EDGE_CURVE ( 'NONE', #34749, #40179, #21632, .T. ) ; -#33544 = ADVANCED_FACE ( 'NONE', ( #40012 ), #12019, .F. ) ; -#33545 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422003068, 157.6312130328778096, 99.11571341752234332 ) ) ; -#33546 = AXIS2_PLACEMENT_3D ( 'NONE', #23148, #11479, #32547 ) ; -#33547 = AXIS2_PLACEMENT_3D ( 'NONE', #3829, #32463, #3631 ) ; -#33548 = VERTEX_POINT ( 'NONE', #34073 ) ; -#33549 = ORIENTED_EDGE ( 'NONE', *, *, #5315, .T. ) ; -#33550 = VECTOR ( 'NONE', #21687, 1000.000000000000114 ) ; -#33551 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33552 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#33553 = LINE ( 'NONE', #24390, #19984 ) ; -#33554 = AXIS2_PLACEMENT_3D ( 'NONE', #22492, #34907, #16514 ) ; -#33555 = ORIENTED_EDGE ( 'NONE', *, *, #21617, .T. ) ; -#33556 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921591843, 0.2249510932971530430 ) ) ; -#33557 = CARTESIAN_POINT ( 'NONE', ( -25.50129508846853099, 118.1132512059233335, 87.78307593003776788 ) ) ; -#33558 = VERTEX_POINT ( 'NONE', #18124 ) ; -#33559 = CARTESIAN_POINT ( 'NONE', ( 26.23959569209999998, 121.6931803613000085, 90.81114231919001156 ) ) ; -#33560 = LINE ( 'NONE', #2890, #28675 ) ; -#33562 = CARTESIAN_POINT ( 'NONE', ( 38.81159562487034265, 113.5937817496002396, 151.4290813728213152 ) ) ; -#33561 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023854076 ) ) ; -#33563 = ORIENTED_EDGE ( 'NONE', *, *, #19261, .T. ) ; -#33564 = CARTESIAN_POINT ( 'NONE', ( 39.31906229016909293, 183.3064585026729674, 101.9668787784548698 ) ) ; -#33565 = EDGE_CURVE ( 'NONE', #14526, #29201, #28300, .T. ) ; -#33566 = ORIENTED_EDGE ( 'NONE', *, *, #7319, .F. ) ; -#33567 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927790412197, 0.0005734119022076163575 ) ) ; -#33569 = ORIENTED_EDGE ( 'NONE', *, *, #2178, .F. ) ; -#33568 = AXIS2_PLACEMENT_3D ( 'NONE', #23740, #14540, #17776 ) ; -#33570 = CARTESIAN_POINT ( 'NONE', ( 38.78510361949000185, 119.3955236502000048, 90.43317343257000118 ) ) ; -#33571 = CARTESIAN_POINT ( 'NONE', ( -25.99964915362324192, 120.0929955239077032, 90.47318932755659660 ) ) ; -#33572 = CARTESIAN_POINT ( 'NONE', ( -15.99999440082457447, 126.8010213445309660, 88.93691041956509480 ) ) ; -#33573 = PLANE ( 'NONE', #30045 ) ; -#33574 = CONICAL_SURFACE ( 'NONE', #25755, 4.999999999883085522, 0.7853981633291653441 ) ; -#33575 = CARTESIAN_POINT ( 'NONE', ( -12.64523939051215073, 134.9174765714697344, 90.80875027841997849 ) ) ; -#33576 = ORIENTED_EDGE ( 'NONE', *, *, #26655, .T. ) ; -#33577 = EDGE_CURVE ( 'NONE', #9446, #11054, #30244, .T. ) ; -#33578 = ORIENTED_EDGE ( 'NONE', *, *, #33477, .T. ) ; -#33579 = FACE_OUTER_BOUND ( 'NONE', #35902, .T. ) ; -#33580 = AXIS2_PLACEMENT_3D ( 'NONE', #27426, #21863, #28208 ) ; -#33581 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35561, #29881, #30272, #8415, #26617, #23741, #14753, #33127, #11676, #36615 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.002384341708615501237, 0.2517882562814616199, 0.5011921708543077836, 0.7505960854271538363, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33582 = CARTESIAN_POINT ( 'NONE', ( 15.83316883261202612, 186.7852030470082525, 102.7661225901500330 ) ) ; -#33583 = ORIENTED_EDGE ( 'NONE', *, *, #4820, .T. ) ; -#33584 = VERTEX_POINT ( 'NONE', #37547 ) ; -#33585 = ADVANCED_FACE ( 'NONE', ( #28361 ), #34460, .T. ) ; -#33586 = CARTESIAN_POINT ( 'NONE', ( -25.49718356649553641, 191.5268115629067154, 104.3989865086577140 ) ) ; -#33587 = ADVANCED_FACE ( 'NONE', ( #11818 ), #21727, .T. ) ; -#33588 = CARTESIAN_POINT ( 'NONE', ( 2.549279137596999867, 190.7083476029000053, 106.2283635592000053 ) ) ; -#33589 = DIRECTION ( 'NONE', ( 0.6087906217132987852, -0.7729786229956010501, -0.1785441886642060716 ) ) ; -#33590 = ADVANCED_FACE ( 'NONE', ( #2806 ), #27974, .F. ) ; -#33591 = CARTESIAN_POINT ( 'NONE', ( 13.49969781725042139, 124.7119230207161991, 88.90738776642010066 ) ) ; -#33592 = CARTESIAN_POINT ( 'NONE', ( 45.36643772518247886, 116.4348365834111121, 122.4283839521990984 ) ) ; -#33593 = CARTESIAN_POINT ( 'NONE', ( 36.04737028556108669, 207.4083918097865649, 77.05990514452427931 ) ) ; -#33594 = ORIENTED_EDGE ( 'NONE', *, *, #30611, .F. ) ; -#33595 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418000665, 218.5902260770999987, 73.08022052565414128 ) ) ; -#33596 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5082, #33291, #33497, #14506 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33597 = CARTESIAN_POINT ( 'NONE', ( 15.99867818869383385, 138.1324741098936215, 91.53365305490791570 ) ) ; -#33598 = CARTESIAN_POINT ( 'NONE', ( -17.00047812746342402, 136.5658759208817230, 181.4646850263357010 ) ) ; -#33599 = LOCAL_TIME ( 14, 25, 27.00000000000000000, #21058 ) ; -#33600 = VECTOR ( 'NONE', #6635, 1000.000000000000000 ) ; -#33601 = AXIS2_PLACEMENT_3D ( 'NONE', #26943, #11592, #14665 ) ; -#33602 = VECTOR ( 'NONE', #6982, 999.9999999999998863 ) ; -#33603 = EDGE_LOOP ( 'NONE', ( #27127, #38515, #31703, #23081 ) ) ; -#33604 = CARTESIAN_POINT ( 'NONE', ( -5.667984704580542932, 187.9405149811499030, 103.3903667269636202 ) ) ; -#33605 = EDGE_LOOP ( 'NONE', ( #4700, #8244, #18122, #18370 ) ) ; -#33606 = VECTOR ( 'NONE', #38341, 1000.000000000000000 ) ; -#33608 = CARTESIAN_POINT ( 'NONE', ( -44.34948217328133069, 189.1747481438389684, 103.6962404974556335 ) ) ; -#33607 = CARTESIAN_POINT ( 'NONE', ( -13.55720661489401913, 148.0719226728492970, 93.84312808491080204 ) ) ; -#33609 = ORIENTED_EDGE ( 'NONE', *, *, #39756, .F. ) ; -#33610 = ORIENTED_EDGE ( 'NONE', *, *, #17648, .F. ) ; -#33611 = VERTEX_POINT ( 'NONE', #15286 ) ; -#33612 = FACE_OUTER_BOUND ( 'NONE', #30323, .T. ) ; -#33613 = DIRECTION ( 'NONE', ( 0.0005884949961242131244, -0.2249510543439063315, 0.9743698870671262391 ) ) ; -#33614 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#33615 = CARTESIAN_POINT ( 'NONE', ( 12.63852066807981345, 177.1933417902586427, 101.0667481637636627 ) ) ; -#33616 = ORIENTED_EDGE ( 'NONE', *, *, #37246, .T. ) ; -#33617 = ORIENTED_EDGE ( 'NONE', *, *, #26599, .T. ) ; -#33618 = CARTESIAN_POINT ( 'NONE', ( -15.30926470586320853, 122.3926578048745029, 284.1741477470645236 ) ) ; -#33619 = ORIENTED_EDGE ( 'NONE', *, *, #4586, .T. ) ; -#33620 = ORIENTED_EDGE ( 'NONE', *, *, #1317, .F. ) ; -#33621 = CARTESIAN_POINT ( 'NONE', ( -2.952854088846381231, 209.7096538831000032, 78.06028844423788371 ) ) ; -#33622 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#33623 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#33624 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#33625 = ADVANCED_FACE ( 'NONE', ( #31427 ), #24302, .T. ) ; -#33626 = ORIENTED_EDGE ( 'NONE', *, *, #33642, .T. ) ; -#33627 = EDGE_CURVE ( 'NONE', #9915, #34668, #40018, .T. ) ; -#33628 = EDGE_LOOP ( 'NONE', ( #17391, #4756, #28887, #34033 ) ) ; -#33629 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640286824, -0.2252353050503915488 ) ) ; -#33630 = ADVANCED_FACE ( 'NONE', ( #32033 ), #9753, .F. ) ; -#33631 = CARTESIAN_POINT ( 'NONE', ( -36.34349144616999894, 191.9206088457000021, 104.5561665447000195 ) ) ; -#33632 = ADVANCED_FACE ( 'NONE', ( #35258, #37956, #34856, #4187 ), #31632, .T. ) ; -#33633 = ORIENTED_EDGE ( 'NONE', *, *, #15409, .F. ) ; -#33634 = CARTESIAN_POINT ( 'NONE', ( -25.50186340329999979, 120.7653135713000125, 88.06248121368000170 ) ) ; -#33635 = AXIS2_PLACEMENT_3D ( 'NONE', #4330, #17602, #4525 ) ; -#33636 = ORIENTED_EDGE ( 'NONE', *, *, #39028, .T. ) ; -#33637 = CARTESIAN_POINT ( 'NONE', ( 42.78873758771006663, 120.8665316288775102, 92.29373204621693105 ) ) ; -#33638 = CARTESIAN_POINT ( 'NONE', ( 41.00931486137713478, 189.3830257637429781, 107.0363912322027886 ) ) ; -#33639 = ORIENTED_EDGE ( 'NONE', *, *, #1828, .T. ) ; -#33640 = CIRCLE ( 'NONE', #6198, 4.000000000000000000 ) ; -#33641 = VECTOR ( 'NONE', #6478, 1000.000000000000114 ) ; -#33642 = EDGE_CURVE ( 'NONE', #15381, #6338, #13222, .T. ) ; -#33643 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#33644 = CARTESIAN_POINT ( 'NONE', ( -14.50493307988418579, 124.5700211486796434, 88.42093691827915336 ) ) ; -#33646 = EDGE_CURVE ( 'NONE', #32344, #37440, #22429, .T. ) ; -#33645 = CARTESIAN_POINT ( 'NONE', ( 15.01700441902629990, 123.4944333684167361, 178.4524337621022880 ) ) ; -#33647 = FACE_OUTER_BOUND ( 'NONE', #772, .T. ) ; -#33648 = CARTESIAN_POINT ( 'NONE', ( 26.37129435717525183, 189.9627969739057107, 103.4933647081285670 ) ) ; -#33649 = EDGE_LOOP ( 'NONE', ( #27007, #13174, #12459, #25017 ) ) ; -#33650 = FACE_OUTER_BOUND ( 'NONE', #20542, .T. ) ; -#33651 = CARTESIAN_POINT ( 'NONE', ( -25.40050087938999823, 191.0670114341999977, 104.4191319587000066 ) ) ; -#33652 = DIRECTION ( 'NONE', ( -0.0002393071182782278061, -0.2252352986010052738, 0.9743043687658489160 ) ) ; -#33653 = CARTESIAN_POINT ( 'NONE', ( 35.42042856514999727, 112.3953715357999954, 90.38152322809999362 ) ) ; -#33654 = DIRECTION ( 'NONE', ( -0.0005884949961221202890, 0.2249510543439054433, -0.9743698870671265722 ) ) ; -#33655 = VERTEX_POINT ( 'NONE', #38353 ) ; -#33656 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15574, #31529, #24607, #28072 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33657 = VECTOR ( 'NONE', #9442, 1000.000000000000114 ) ; -#33658 = LINE ( 'NONE', #12008, #35701 ) ; -#33659 = CIRCLE ( 'NONE', #34296, 2.500000000000002220 ) ; -#33660 = EDGE_LOOP ( 'NONE', ( #16625, #1472, #15232, #35875 ) ) ; -#33661 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927694284121, 0.0005734119022093313485 ) ) ; -#33662 = CYLINDRICAL_SURFACE ( 'NONE', #38488, 5.999999999999998224 ) ; -#33663 = CARTESIAN_POINT ( 'NONE', ( 26.00894374567046441, 191.9425530329557716, 103.9054621679136261 ) ) ; -#33664 = FACE_OUTER_BOUND ( 'NONE', #32748, .T. ) ; -#33665 = DIRECTION ( 'NONE', ( -0.5988682214945756366, 0.8008475843029833063, 0.000000000000000000 ) ) ; -#33666 = ORIENTED_EDGE ( 'NONE', *, *, #10807, .T. ) ; -#33667 = CARTESIAN_POINT ( 'NONE', ( -22.50040042369792559, 158.4258594287385336, 96.41306356714065373 ) ) ; -#33668 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21015, #35916, #23680, #8344 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33669 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33670 = VERTEX_POINT ( 'NONE', #38543 ) ; -#33671 = CARTESIAN_POINT ( 'NONE', ( -20.16657097893908102, 174.4711545278903770, 100.1159964656488626 ) ) ; -#33672 = EDGE_CURVE ( 'NONE', #5169, #12942, #38048, .T. ) ; -#33673 = CARTESIAN_POINT ( 'NONE', ( -20.07611744496675144, 117.3322318276110821, 90.27991031107923448 ) ) ; -#33674 = EDGE_CURVE ( 'NONE', #13786, #1942, #6842, .T. ) ; -#33675 = ORIENTED_EDGE ( 'NONE', *, *, #16818, .F. ) ; -#33676 = CARTESIAN_POINT ( 'NONE', ( -38.67639030779000109, 119.8305709359000133, 87.36412529714000641 ) ) ; -#33677 = CARTESIAN_POINT ( 'NONE', ( -5.668152766071871795, 130.6151334557387145, 90.15838212948281694 ) ) ; -#33678 = ORIENTED_EDGE ( 'NONE', *, *, #22853, .T. ) ; -#33679 = FACE_OUTER_BOUND ( 'NONE', #20658, .T. ) ; -#33680 = PRODUCT_RELATED_PRODUCT_CATEGORY ( 'detail', '', ( #16623 ) ) ; -#33681 = LINE ( 'NONE', #36757, #2878 ) ; -#33682 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#33683 = VECTOR ( 'NONE', #18323, 1000.000000000000000 ) ; -#33684 = CARTESIAN_POINT ( 'NONE', ( -24.07944809770393846, 115.3139759671915527, 90.28232822247846912 ) ) ; -#33685 = DIRECTION ( 'NONE', ( -0.0001408422045155705395, 0.2255194951287508853, -0.9742386450353663907 ) ) ; -#33686 = ORIENTED_EDGE ( 'NONE', *, *, #23620, .T. ) ; -#33687 = CARTESIAN_POINT ( 'NONE', ( 15.50147167040156049, 184.4041534622001279, 104.7823749527994011 ) ) ; -#33688 = CARTESIAN_POINT ( 'NONE', ( 21.05032377942072230, 129.1782700951465017, 89.63443569402672040 ) ) ; -#33689 = CARTESIAN_POINT ( 'NONE', ( 36.93642613006880282, 191.5645808114473709, 104.3410322388217963 ) ) ; -#33690 = CIRCLE ( 'NONE', #29130, 1.999999999999996891 ) ; -#33691 = CARTESIAN_POINT ( 'NONE', ( 21.44870230457277316, 181.8867687911781559, 104.7107509713525388 ) ) ; -#33692 = ORIENTED_EDGE ( 'NONE', *, *, #25691, .T. ) ; -#33693 = AXIS2_PLACEMENT_3D ( 'NONE', #11312, #30127, #29728 ) ; -#33694 = ORIENTED_EDGE ( 'NONE', *, *, #6389, .T. ) ; -#33695 = CARTESIAN_POINT ( 'NONE', ( -20.51767729163077547, 205.5669979433283743, 76.31342074382325791 ) ) ; -#33696 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14058, #20376, #19760, #22864 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33697 = CARTESIAN_POINT ( 'NONE', ( -43.12194749330705434, 120.9924285383533800, 90.69118127765682402 ) ) ; -#33698 = CARTESIAN_POINT ( 'NONE', ( 24.11730455176802934, 213.8702922232344292, 73.04393783477425472 ) ) ; -#33699 = ADVANCED_FACE ( 'NONE', ( #12817 ), #21758, .T. ) ; -#33700 = CARTESIAN_POINT ( 'NONE', ( -26.01494426630450008, 211.0902259182902014, 73.07465174665132679 ) ) ; -#33701 = FACE_OUTER_BOUND ( 'NONE', #2928, .T. ) ; -#33702 = CARTESIAN_POINT ( 'NONE', ( 5.674778016381245571, 131.0223034755605909, 89.89838139801142347 ) ) ; -#33703 = CARTESIAN_POINT ( 'NONE', ( 29.40353763218626426, 109.9356066219137205, 185.6772796757410333 ) ) ; -#33704 = CARTESIAN_POINT ( 'NONE', ( -48.19679236399461786, 85.21962457735440921, 278.2468068767242357 ) ) ; -#33705 = CARTESIAN_POINT ( 'NONE', ( 38.13142613197000230, 119.0401570749999962, 87.34858926297999915 ) ) ; -#33706 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; -#33707 = CARTESIAN_POINT ( 'NONE', ( 20.25161797161999999, 144.6238388024999892, 95.85207109489999766 ) ) ; -#33708 = CARTESIAN_POINT ( 'NONE', ( 2.805728947812045071, 191.0546403038702294, 104.0235302350474882 ) ) ; -#33709 = PLANE ( 'NONE', #32283 ) ; -#33710 = AXIS2_PLACEMENT_3D ( 'NONE', #6615, #885, #13375 ) ; -#33711 = CYLINDRICAL_SURFACE ( 'NONE', #7793, 8.999999999999994671 ) ; -#33712 = FACE_OUTER_BOUND ( 'NONE', #31832, .T. ) ; -#33713 = AXIS2_PLACEMENT_3D ( 'NONE', #36694, #2561, #30573 ) ; -#33714 = LINE ( 'NONE', #1630, #4965 ) ; -#33715 = VERTEX_POINT ( 'NONE', #37746 ) ; -#33716 = ORIENTED_EDGE ( 'NONE', *, *, #26632, .F. ) ; -#33717 = ORIENTED_EDGE ( 'NONE', *, *, #25583, .F. ) ; -#33718 = CARTESIAN_POINT ( 'NONE', ( 6.035970131896343460, 174.6813497870895446, 103.0565575201574262 ) ) ; -#33719 = VERTEX_POINT ( 'NONE', #6656 ) ; -#33720 = CARTESIAN_POINT ( 'NONE', ( 20.22968469989555729, 126.8125685881874603, 91.76255132582693363 ) ) ; -#33721 = AXIS2_PLACEMENT_3D ( 'NONE', #25828, #13340, #19052 ) ; -#33722 = FACE_BOUND ( 'NONE', #31148, .T. ) ; -#33723 = LINE ( 'NONE', #5510, #32443 ) ; -#33724 = AXIS2_PLACEMENT_3D ( 'NONE', #23487, #26770, #1400 ) ; -#33725 = EDGE_CURVE ( 'NONE', #20347, #33088, #17220, .T. ) ; -#33726 = EDGE_CURVE ( 'NONE', #14638, #1910, #34592, .T. ) ; -#33727 = EDGE_LOOP ( 'NONE', ( #4831, #27318, #24065, #3843 ) ) ; -#33728 = CARTESIAN_POINT ( 'NONE', ( -39.54761222249000241, 119.6738064118000011, 90.25994719927001597 ) ) ; -#33729 = LINE ( 'NONE', #2268, #30296 ) ; -#33730 = FACE_OUTER_BOUND ( 'NONE', #26830, .T. ) ; -#33731 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319364164186 ) ) ; -#33732 = PLANE ( 'NONE', #17699 ) ; -#33733 = ORIENTED_EDGE ( 'NONE', *, *, #12148, .T. ) ; -#33734 = EDGE_CURVE ( 'NONE', #13097, #6212, #6725, .T. ) ; -#33735 = FACE_OUTER_BOUND ( 'NONE', #22003, .T. ) ; -#33736 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32548, #32743, #4519, #16793 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33737 = LINE ( 'NONE', #27027, #6100 ) ; -#33738 = CARTESIAN_POINT ( 'NONE', ( 23.36703012845244487, 177.0397020477106480, 103.4811831259390118 ) ) ; -#33739 = FACE_OUTER_BOUND ( 'NONE', #12465, .T. ) ; -#33740 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; -#33741 = DIRECTION ( 'NONE', ( -0.0006039748319377573598, -1.390293078070570268E-14, -0.9999998176071845934 ) ) ; -#33742 = ORIENTED_EDGE ( 'NONE', *, *, #33371, .F. ) ; -#33743 = CARTESIAN_POINT ( 'NONE', ( -27.42685105812000046, 188.0600985815999877, 103.2113217096000000 ) ) ; -#33744 = CARTESIAN_POINT ( 'NONE', ( 1.043337447816000019, 188.6569751936000046, 103.2066641554000057 ) ) ; -#33745 = CARTESIAN_POINT ( 'NONE', ( 35.80518341334000354, 111.0397749124999933, 89.99615936003000627 ) ) ; -#33746 = VECTOR ( 'NONE', #37915, 1000.000000000000227 ) ; -#33747 = ORIENTED_EDGE ( 'NONE', *, *, #36419, .T. ) ; -#33748 = ORIENTED_EDGE ( 'NONE', *, *, #36113, .F. ) ; -#33749 = CARTESIAN_POINT ( 'NONE', ( -3.654516724589964127, 136.7043362491127709, 94.17313141517827546 ) ) ; -#33750 = AXIS2_PLACEMENT_3D ( 'NONE', #21438, #37160, #21635 ) ; -#33751 = ORIENTED_EDGE ( 'NONE', *, *, #7123, .T. ) ; -#33752 = AXIS2_PLACEMENT_3D ( 'NONE', #34350, #34933, #815 ) ; -#33753 = AXIS2_PLACEMENT_3D ( 'NONE', #34217, #278, #9104 ) ; -#33754 = LINE ( 'NONE', #30709, #30213 ) ; -#33755 = ORIENTED_EDGE ( 'NONE', *, *, #17130, .F. ) ; -#33756 = CARTESIAN_POINT ( 'NONE', ( -35.95796026000000012, 192.1755911781000066, 104.2095329361000040 ) ) ; -#33757 = CARTESIAN_POINT ( 'NONE', ( 15.10888617544567047, 175.7086446263182609, 103.2882499569403336 ) ) ; -#33758 = PLANE ( 'NONE', #17352 ) ; -#33759 = EDGE_LOOP ( 'NONE', ( #32415, #26912, #23979, #34289 ) ) ; -#33760 = CARTESIAN_POINT ( 'NONE', ( 44.90791382799785225, 186.3646954527586388, 107.7818492509791639 ) ) ; -#33761 = FACE_OUTER_BOUND ( 'NONE', #34638, .T. ) ; -#33762 = CARTESIAN_POINT ( 'NONE', ( -45.98255491755426050, 185.1241532521533770, 105.4988869918989707 ) ) ; -#33763 = ORIENTED_EDGE ( 'NONE', *, *, #23575, .T. ) ; -#33764 = EDGE_CURVE ( 'NONE', #25255, #8977, #27118, .T. ) ; -#33765 = CARTESIAN_POINT ( 'NONE', ( -15.74838202838000178, 126.6534244744000119, 91.72501638641000454 ) ) ; -#33766 = CARTESIAN_POINT ( 'NONE', ( -35.98817295377529746, 191.5260130662397273, 103.8919236801626340 ) ) ; -#33768 = CARTESIAN_POINT ( 'NONE', ( -16.00000031268763934, 184.9628657724767606, 102.3646292465979855 ) ) ; -#33767 = LINE ( 'NONE', #1895, #12772 ) ; -#33769 = ORIENTED_EDGE ( 'NONE', *, *, #26017, .F. ) ; -#33770 = ADVANCED_FACE ( 'NONE', ( #39150 ), #11344, .T. ) ; -#33771 = CARTESIAN_POINT ( 'NONE', ( 3.793707726449507600, 143.5984041309152417, 95.61717448282179532 ) ) ; -#33772 = ORIENTED_EDGE ( 'NONE', *, *, #11255, .T. ) ; -#33773 = CIRCLE ( 'NONE', #7644, 6.000000000079828588 ) ; -#33774 = ADVANCED_FACE ( 'NONE', ( #26702 ), #18450, .F. ) ; -#33775 = EDGE_CURVE ( 'NONE', #11249, #39849, #20413, .T. ) ; -#33776 = ORIENTED_EDGE ( 'NONE', *, *, #16411, .F. ) ; -#33777 = ADVANCED_FACE ( 'NONE', ( #23830 ), #38949, .T. ) ; -#33778 = DIRECTION ( 'NONE', ( 0.1942034849621051273, -0.07301477786151058802, 0.9782401794254863558 ) ) ; -#33779 = ADVANCED_FACE ( 'NONE', ( #8289 ), #14574, .F. ) ; -#33780 = CARTESIAN_POINT ( 'NONE', ( -28.46561152641098857, 127.9070196869205063, 92.27868865996876480 ) ) ; -#33781 = CARTESIAN_POINT ( 'NONE', ( 16.00176529486913424, 184.2900636920902002, 105.2688851223920778 ) ) ; -#33782 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989941907, 0.1373964268091562579 ) ) ; -#33783 = VERTEX_POINT ( 'NONE', #29962 ) ; -#33784 = ORIENTED_EDGE ( 'NONE', *, *, #14147, .F. ) ; -#33785 = CARTESIAN_POINT ( 'NONE', ( -10.03596762622328420, 143.5365797932718976, 95.87908835225771043 ) ) ; -#33786 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#33787 = CARTESIAN_POINT ( 'NONE', ( 18.90090771971125960, 120.9219860925226300, 173.6350968582803205 ) ) ; -#33788 = EDGE_LOOP ( 'NONE', ( #11915, #14349, #28087, #10922 ) ) ; -#33789 = CARTESIAN_POINT ( 'NONE', ( -36.32064378393000226, 191.6133591983000031, 106.4203980247000061 ) ) ; -#33790 = CARTESIAN_POINT ( 'NONE', ( -12.63809837006106918, 177.7897768145701036, 100.7065200156251166 ) ) ; -#33791 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35287, #10589, #32257, #7490, #9984, #19566, #3419, #9783, #22662, #10391, #4219 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999896194, 0.3749999999999844569, 0.4374999999999824030, 0.4687499999999729661, 0.4999999999999635847, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33792 = CARTESIAN_POINT ( 'NONE', ( 1.194460023360268908, 188.4195049100522965, 106.2519222112965167 ) ) ; -#33793 = CARTESIAN_POINT ( 'NONE', ( -13.73764163818622386, 127.1905248059583045, 179.0443690650147630 ) ) ; -#33794 = ADVANCED_FACE ( 'NONE', ( #5412 ), #13811, .F. ) ; -#33795 = CARTESIAN_POINT ( 'NONE', ( 12.63493752645000434, 130.4235786269885580, 90.26909773830440997 ) ) ; -#33796 = CARTESIAN_POINT ( 'NONE', ( 34.29502520496742335, 218.5902260770999987, 74.53779102012590840 ) ) ; -#33797 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7258, #13612, #34660, #23021 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 7.755276718584622330E-08, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33798 = AXIS2_PLACEMENT_3D ( 'NONE', #28032, #6329, #9219 ) ; -#33799 = VERTEX_POINT ( 'NONE', #11561 ) ; -#33800 = DIRECTION ( 'NONE', ( -0.0005884949961258157921, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#33801 = FACE_OUTER_BOUND ( 'NONE', #39020, .T. ) ; -#33802 = VECTOR ( 'NONE', #26852, 1000.000000000000000 ) ; -#33803 = CARTESIAN_POINT ( 'NONE', ( 5.666470275070142115, 124.7419549499387159, 88.96160009709909389 ) ) ; -#33804 = VERTEX_POINT ( 'NONE', #38734 ) ; -#33805 = EDGE_CURVE ( 'NONE', #8977, #31599, #30236, .T. ) ; -#33806 = CARTESIAN_POINT ( 'NONE', ( -5.668359501568912329, 187.8404812842893534, 103.4528749086814372 ) ) ; -#33807 = ORIENTED_EDGE ( 'NONE', *, *, #12901, .F. ) ; -#33809 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250099003, 132.8554482850215663, 90.84904174538408483 ) ) ; -#33808 = CARTESIAN_POINT ( 'NONE', ( 16.56127283256421734, 122.5154997165936521, 174.6307753585464582 ) ) ; -#33810 = ORIENTED_EDGE ( 'NONE', *, *, #1032, .F. ) ; -#33812 = VERTEX_POINT ( 'NONE', #23222 ) ; -#33811 = EDGE_CURVE ( 'NONE', #15505, #30695, #20338, .T. ) ; -#33813 = ORIENTED_EDGE ( 'NONE', *, *, #36893, .F. ) ; -#33814 = CARTESIAN_POINT ( 'NONE', ( 2.660888226647000199, 209.2248638908999965, 75.71736931623000544 ) ) ; -#33815 = ADVANCED_FACE ( 'NONE', ( #35656 ), #7670, .F. ) ; -#33816 = FACE_OUTER_BOUND ( 'NONE', #33947, .T. ) ; -#33817 = LINE ( 'NONE', #5193, #39080 ) ; -#33818 = ORIENTED_EDGE ( 'NONE', *, *, #10567, .F. ) ; -#33819 = ORIENTED_EDGE ( 'NONE', *, *, #2287, .F. ) ; -#33820 = EDGE_CURVE ( 'NONE', #12963, #24174, #26986, .T. ) ; -#33821 = ORIENTED_EDGE ( 'NONE', *, *, #31617, .T. ) ; -#33822 = ORIENTED_EDGE ( 'NONE', *, *, #26599, .F. ) ; -#33823 = EDGE_CURVE ( 'NONE', #16043, #8808, #10774, .T. ) ; -#33824 = PLANE ( 'NONE', #25033 ) ; -#33825 = LINE ( 'NONE', #16418, #40226 ) ; -#33826 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 67.27946979429630403, 312.5857197240632104 ) ) ; -#33827 = CARTESIAN_POINT ( 'NONE', ( 36.04502488578000197, 218.5902260770999987, 74.53673406417000535 ) ) ; -#33828 = CARTESIAN_POINT ( 'NONE', ( 35.72421708400000284, 192.2730493352999872, 104.0441781799000012 ) ) ; -#33829 = VERTEX_POINT ( 'NONE', #32618 ) ; -#33830 = AXIS2_PLACEMENT_3D ( 'NONE', #8307, #20771, #33224 ) ; -#33831 = EDGE_LOOP ( 'NONE', ( #29129, #1121, #7606, #26427 ) ) ; -#33832 = CARTESIAN_POINT ( 'NONE', ( 25.99023297330436932, 210.6304865614666539, 73.04280663293934595 ) ) ; -#33833 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#33834 = CARTESIAN_POINT ( 'NONE', ( 20.02131841667728551, 127.7987263759923167, 89.14548939899454183 ) ) ; -#33835 = CARTESIAN_POINT ( 'NONE', ( -25.89614368559000113, 121.5587206332999983, 87.90364931204000243 ) ) ; -#33836 = AXIS2_PLACEMENT_3D ( 'NONE', #29156, #26289, #1739 ) ; -#33837 = ORIENTED_EDGE ( 'NONE', *, *, #6662, .F. ) ; -#33838 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178570922545E-05, 0.0002331579774915894113 ) ) ; -#33839 = CARTESIAN_POINT ( 'NONE', ( -20.99846996374797570, 182.5827991098829841, 104.7260292976064449 ) ) ; -#33840 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#33841 = ORIENTED_EDGE ( 'NONE', *, *, #24333, .F. ) ; -#33842 = FACE_OUTER_BOUND ( 'NONE', #5618, .T. ) ; -#33843 = PLANE ( 'NONE', #8567 ) ; -#33844 = CYLINDRICAL_SURFACE ( 'NONE', #21899, 2.000000000000011546 ) ; -#33845 = CARTESIAN_POINT ( 'NONE', ( -4.036657055717371101, 136.9419995428667391, 93.15246900959645870 ) ) ; -#33846 = ORIENTED_EDGE ( 'NONE', *, *, #29765, .T. ) ; -#33847 = DIRECTION ( 'NONE', ( -0.7069397808326125521, 0.6508952215178184231, 0.2767156607089806264 ) ) ; -#33848 = CARTESIAN_POINT ( 'NONE', ( -25.65592658278999849, 191.1787881358000050, 104.1823754182999977 ) ) ; -#33849 = PLANE ( 'NONE', #14715 ) ; -#33850 = CARTESIAN_POINT ( 'NONE', ( 38.70841243942000176, 118.4099359663000115, 89.50418070357000033 ) ) ; -#33851 = VECTOR ( 'NONE', #15533, 1000.000000000000114 ) ; -#33852 = ORIENTED_EDGE ( 'NONE', *, *, #1654, .T. ) ; -#33853 = CARTESIAN_POINT ( 'NONE', ( 16.50047814177647965, 137.4650114514834911, 177.5752783435502238 ) ) ; -#33854 = ADVANCED_FACE ( 'NONE', ( #29764 ), #40036, .T. ) ; -#33855 = VERTEX_POINT ( 'NONE', #5003 ) ; -#33856 = EDGE_CURVE ( 'NONE', #18476, #31506, #1955, .T. ) ; -#33857 = CIRCLE ( 'NONE', #9738, 1.750000000000001998 ) ; -#33858 = VECTOR ( 'NONE', #4579, 1000.000000000000114 ) ; -#33859 = EDGE_CURVE ( 'NONE', #27102, #37645, #38061, .T. ) ; -#33860 = ADVANCED_FACE ( 'NONE', ( #2763 ), #8709, .F. ) ; -#33861 = DIRECTION ( 'NONE', ( 0.0005884949961230158400, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33862 = ORIENTED_EDGE ( 'NONE', *, *, #38647, .T. ) ; -#33863 = DIRECTION ( 'NONE', ( 0.0005884949961210958263, -0.2249510543439056931, 0.9743698870671265722 ) ) ; -#33864 = EDGE_CURVE ( 'NONE', #21782, #33315, #10015, .T. ) ; -#33865 = CARTESIAN_POINT ( 'NONE', ( -32.55313974955839740, 153.0051697192221241, 291.5776016089990321 ) ) ; -#33866 = CARTESIAN_POINT ( 'NONE', ( -36.50461923224486327, 165.0077707801626445, 193.7817447150420094 ) ) ; -#33867 = LINE ( 'NONE', #14680, #1146 ) ; -#33868 = DIRECTION ( 'NONE', ( 0.7933531821952876095, 0.5932639600228909460, 0.1364866368497979210 ) ) ; -#33869 = ORIENTED_EDGE ( 'NONE', *, *, #10229, .T. ) ; -#33870 = ORIENTED_EDGE ( 'NONE', *, *, #13324, .F. ) ; -#33871 = EDGE_CURVE ( 'NONE', #1494, #20919, #34416, .T. ) ; -#33872 = CARTESIAN_POINT ( 'NONE', ( -22.50072399476195528, 158.3009599602069954, 96.21317557253242114 ) ) ; -#33873 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33874 = VERTEX_POINT ( 'NONE', #18670 ) ; -#33875 = CARTESIAN_POINT ( 'NONE', ( -14.99815819359325175, 175.6178804679130963, 103.1144260744014929 ) ) ; -#33876 = ORIENTED_EDGE ( 'NONE', *, *, #34426, .T. ) ; -#33878 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #38548, #3999, #13228, #4192 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 1.570796326794897002, 2.218608660199707927 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9653329533393121276, 0.9653329533393121276, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#33877 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33879 = EDGE_CURVE ( 'NONE', #2188, #802, #37420, .T. ) ; -#33880 = VECTOR ( 'NONE', #7073, 1000.000000000000000 ) ; -#33881 = LINE ( 'NONE', #24716, #21287 ) ; -#33882 = CYLINDRICAL_SURFACE ( 'NONE', #26079, 6.000000000000008882 ) ; -#33883 = CARTESIAN_POINT ( 'NONE', ( 39.72476719869543160, 114.7060280101011784, 151.9010437499874513 ) ) ; -#33884 = VERTEX_POINT ( 'NONE', #9499 ) ; -#33885 = CARTESIAN_POINT ( 'NONE', ( 36.14783605804498734, 191.1371402971168152, 106.8287956632172211 ) ) ; -#33886 = VECTOR ( 'NONE', #15454, 1000.000000000000000 ) ; -#33887 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927775716107, -0.0005734119022078446905 ) ) ; -#33888 = CONICAL_SURFACE ( 'NONE', #20186, 7.002999999902385753, 0.7853981633639545157 ) ; -#33889 = CARTESIAN_POINT ( 'NONE', ( -25.36342966357999984, 191.0335386934000041, 106.2013971295999966 ) ) ; -#33890 = CARTESIAN_POINT ( 'NONE', ( 13.47382858277565632, 158.5309805054267827, 97.44190014375976716 ) ) ; -#33891 = CARTESIAN_POINT ( 'NONE', ( 3.293114068703774766, 126.0351413774823612, 88.74843706248260844 ) ) ; -#33892 = ORIENTED_EDGE ( 'NONE', *, *, #4320, .T. ) ; -#33893 = ORIENTED_EDGE ( 'NONE', *, *, #26967, .T. ) ; -#33894 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989908600, -0.1373964268091706076 ) ) ; -#33895 = CARTESIAN_POINT ( 'NONE', ( -1.212289009923043892, 140.3956132826605767, 157.8536590863297135 ) ) ; -#33896 = CARTESIAN_POINT ( 'NONE', ( 36.77250560128941714, 191.6244934190380889, 104.3438750475318244 ) ) ; -#33897 = CARTESIAN_POINT ( 'NONE', ( -16.56487446111976780, 151.7625539678538189, 183.4451438748824899 ) ) ; -#33898 = ORIENTED_EDGE ( 'NONE', *, *, #16763, .T. ) ; -#33899 = DIRECTION ( 'NONE', ( 0.0005884949961228156962, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#33900 = CARTESIAN_POINT ( 'NONE', ( -41.90907465551325828, 121.4486244169956422, 92.84837845933354572 ) ) ; -#33901 = FACE_OUTER_BOUND ( 'NONE', #498, .T. ) ; -#33902 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21241, #15307, #2645, #37376 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#33903 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#33904 = DIRECTION ( 'NONE', ( -0.7069397808237261049, 0.6508952152945399749, 0.2767156753701828231 ) ) ; -#33905 = EDGE_CURVE ( 'NONE', #11816, #35125, #34024, .T. ) ; -#33906 = ADVANCED_FACE ( 'NONE', ( #12172 ), #40351, .F. ) ; -#33907 = ADVANCED_FACE ( 'NONE', ( #15434 ), #13255, .F. ) ; -#33908 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319419764241 ) ) ; -#33909 = AXIS2_PLACEMENT_3D ( 'NONE', #38859, #29275, #28134 ) ; -#33910 = CARTESIAN_POINT ( 'NONE', ( 24.53318178951551332, 104.1131156702021201, 87.25296686497607368 ) ) ; -#33911 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7071067167009886800, -0.7071068456721004702 ) ) ; -#33912 = CARTESIAN_POINT ( 'NONE', ( -23.36763934512021734, 134.2409834847225625, 93.73796057560730333 ) ) ; -#33913 = ADVANCED_FACE ( 'NONE', ( #21382 ), #2170, .F. ) ; -#33914 = CIRCLE ( 'NONE', #26750, 2.000000000067106765 ) ; -#33915 = CARTESIAN_POINT ( 'NONE', ( -20.51920610917056820, 211.0905570355220391, 74.90421428432674134 ) ) ; -#33916 = CARTESIAN_POINT ( 'NONE', ( 36.67681181270000224, 191.6471298099000080, 104.3443906285999958 ) ) ; -#33917 = CONICAL_SURFACE ( 'NONE', #13692, 2.499999999937692063, 0.7853981634347277918 ) ; -#33918 = CARTESIAN_POINT ( 'NONE', ( 36.80425445088000203, 191.5142028368000240, 106.2233959256000020 ) ) ; -#33919 = ORIENTED_EDGE ( 'NONE', *, *, #30559, .T. ) ; -#33920 = ORIENTED_EDGE ( 'NONE', *, *, #38846, .T. ) ; -#33921 = ADVANCED_FACE ( 'NONE', ( #9301 ), #33824, .T. ) ; -#33922 = DIRECTION ( 'NONE', ( -0.0005884949961181158967, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#33923 = CARTESIAN_POINT ( 'NONE', ( 20.19664001585550039, 126.8052234450460531, 91.79480940071776729 ) ) ; -#33924 = CARTESIAN_POINT ( 'NONE', ( -32.25494784536992654, 176.5816106217703805, 100.4394812517788722 ) ) ; -#33925 = VERTEX_POINT ( 'NONE', #2362 ) ; -#33926 = CARTESIAN_POINT ( 'NONE', ( -40.70653755146000208, 219.0860688542000219, 73.33308985665999558 ) ) ; -#33927 = ADVANCED_FACE ( 'NONE', ( #27323 ), #10659, .T. ) ; -#33928 = CARTESIAN_POINT ( 'NONE', ( -20.00100377755662961, 193.8169056301028945, 102.7149817412491473 ) ) ; -#33929 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921591843, -0.2249510932971530985 ) ) ; -#33930 = CARTESIAN_POINT ( 'NONE', ( -14.31528021042088916, 130.4257148122239585, 89.77271602316196208 ) ) ; -#33931 = ORIENTED_EDGE ( 'NONE', *, *, #22058, .F. ) ; -#33932 = DIRECTION ( 'NONE', ( -5.204170427942586307E-15, -1.000000000000000000, 0.000000000000000000 ) ) ; -#33933 = FACE_OUTER_BOUND ( 'NONE', #8343, .T. ) ; -#33934 = CARTESIAN_POINT ( 'NONE', ( -26.00155756584835132, 118.8155666110999960, 87.28349583687662516 ) ) ; -#33935 = CARTESIAN_POINT ( 'NONE', ( -4.217312996133716574, 187.9026746933314200, 103.0362212834276505 ) ) ; -#33936 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319357747877 ) ) ; -#33937 = ORIENTED_EDGE ( 'NONE', *, *, #31331, .F. ) ; -#33938 = ORIENTED_EDGE ( 'NONE', *, *, #39113, .T. ) ; -#33939 = VECTOR ( 'NONE', #32098, 1000.000000000000114 ) ; -#33940 = CARTESIAN_POINT ( 'NONE', ( -28.24453843805000375, 186.7254228616999967, 103.4310317869999949 ) ) ; -#33941 = VECTOR ( 'NONE', #38691, 1000.000000000000114 ) ; -#33942 = CARTESIAN_POINT ( 'NONE', ( 30.07478355117409308, 177.7951688118731681, 100.6820556990014950 ) ) ; -#33943 = DIRECTION ( 'NONE', ( -0.1305260325596789561, -0.9660514818508212365, -0.2229517643753060330 ) ) ; -#33944 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #317, #25891, #22615, #35244 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.002384341708615501237 ), - .UNSPECIFIED. ) ; -#33945 = CIRCLE ( 'NONE', #17619, 2.499999999859688238 ) ; -#33946 = AXIS2_PLACEMENT_3D ( 'NONE', #33178, #11737, #30750 ) ; -#33947 = EDGE_LOOP ( 'NONE', ( #39944, #18675, #32688, #31930 ) ) ; -#33948 = DIRECTION ( 'NONE', ( -1.734723476026711224E-15, 0.9743700557921592953, 0.2249510932971530708 ) ) ; -#33949 = EDGE_LOOP ( 'NONE', ( #38134, #9025, #3592, #12916 ) ) ; -#33950 = CIRCLE ( 'NONE', #6501, 2.250000000000011102 ) ; -#33951 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25742, #22671, #967, #7103 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 8.293593285356573369E-05, 0.0002234385402793080384 ), - .UNSPECIFIED. ) ; -#33952 = EDGE_CURVE ( 'NONE', #18169, #18000, #18074, .T. ) ; -#33953 = EDGE_CURVE ( 'NONE', #30098, #31170, #21778, .T. ) ; -#33954 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#33955 = CARTESIAN_POINT ( 'NONE', ( -20.01803677399909986, 205.2975181657300823, 75.66848068974326225 ) ) ; -#33956 = CARTESIAN_POINT ( 'NONE', ( -13.49970653173593504, 151.8558615133134708, 95.23291569143458446 ) ) ; -#33957 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#33958 = CARTESIAN_POINT ( 'NONE', ( -12.63726403360912443, 134.5147472857125024, 93.56168837650750447 ) ) ; -#33959 = DIRECTION ( 'NONE', ( -0.7856007465113974408, -0.6187337610642683616, 0.000000000000000000 ) ) ; -#33960 = ORIENTED_EDGE ( 'NONE', *, *, #17669, .T. ) ; -#33961 = CYLINDRICAL_SURFACE ( 'NONE', #12661, 2.000000000000001332 ) ; -#33962 = CARTESIAN_POINT ( 'NONE', ( -21.82963564516986210, 182.7566075890955517, 102.3719474125277458 ) ) ; -#33963 = CARTESIAN_POINT ( 'NONE', ( 77.66065009075275327, 193.3992594998515244, 188.4681838635439419 ) ) ; -#33965 = FACE_OUTER_BOUND ( 'NONE', #34764, .T. ) ; -#33964 = CARTESIAN_POINT ( 'NONE', ( 12.63088349563799184, 181.6904995670203391, 101.5918601121804556 ) ) ; -#33966 = ORIENTED_EDGE ( 'NONE', *, *, #38563, .F. ) ; -#33967 = ORIENTED_EDGE ( 'NONE', *, *, #16683, .T. ) ; -#33968 = CIRCLE ( 'NONE', #14393, 4.499999999867380751 ) ; -#33969 = ORIENTED_EDGE ( 'NONE', *, *, #18349, .T. ) ; -#33970 = CARTESIAN_POINT ( 'NONE', ( 20.58859091300540101, 116.2799714523409307, 87.25534929902624981 ) ) ; -#33971 = CIRCLE ( 'NONE', #15672, 2.000000000000011546 ) ; -#33972 = ORIENTED_EDGE ( 'NONE', *, *, #39756, .T. ) ; -#33973 = CARTESIAN_POINT ( 'NONE', ( -23.36013624460098725, 136.6770260652199624, 94.30032095887112575 ) ) ; -#33974 = EDGE_CURVE ( 'NONE', #29634, #9657, #26335, .T. ) ; -#33975 = DIRECTION ( 'NONE', ( 0.0005884949961213889946, -0.2249510543439060262, 0.9743698870671263501 ) ) ; -#33976 = FACE_OUTER_BOUND ( 'NONE', #10473, .T. ) ; -#33977 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#33978 = CARTESIAN_POINT ( 'NONE', ( 12.63808109716345562, 130.8952551135587328, 89.97435998385378753 ) ) ; -#33979 = CYLINDRICAL_SURFACE ( 'NONE', #39298, 7.999999999999993783 ) ; -#33980 = ORIENTED_EDGE ( 'NONE', *, *, #8428, .F. ) ; -#33981 = VERTEX_POINT ( 'NONE', #11970 ) ; -#33982 = CARTESIAN_POINT ( 'NONE', ( -20.01829689993581596, 209.7096928646539880, 76.07061354826153377 ) ) ; -#33983 = DIRECTION ( 'NONE', ( -0.6087613508527969230, -0.7731002078751149087, -0.1781170578336949695 ) ) ; -#33984 = DIRECTION ( 'NONE', ( -0.0005884949961143349584, 0.2249510543439047494, -0.9743698870671267942 ) ) ; -#33985 = DIRECTION ( 'NONE', ( 0.0005885022774582036268, -0.2255194047039537075, 0.9742384984012096849 ) ) ; -#33986 = ORIENTED_EDGE ( 'NONE', *, *, #489, .T. ) ; -#33987 = ORIENTED_EDGE ( 'NONE', *, *, #12733, .F. ) ; -#33988 = CARTESIAN_POINT ( 'NONE', ( -36.09963665326999660, 191.9454656849000003, 106.4428026597999946 ) ) ; -#33989 = CARTESIAN_POINT ( 'NONE', ( 22.49999747537572503, 127.4352350531587916, 89.05702986626522488 ) ) ; -#33990 = EDGE_CURVE ( 'NONE', #4954, #22242, #18277, .T. ) ; -#33991 = CARTESIAN_POINT ( 'NONE', ( 39.76231351996260344, 182.5576203638986215, 106.5366729533402719 ) ) ; -#33992 = CARTESIAN_POINT ( 'NONE', ( -20.51975923822563885, 209.4935045172389323, 73.57087796969078397 ) ) ; -#33993 = AXIS2_PLACEMENT_3D ( 'NONE', #16166, #15374, #25387 ) ; -#33994 = FACE_OUTER_BOUND ( 'NONE', #15759, .T. ) ; -#33995 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421901105, 184.2914807614214681, 105.2707223255345070 ) ) ; -#33996 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971558741 ) ) ; -#33997 = CIRCLE ( 'NONE', #19630, 2.000000000000011546 ) ; -#33998 = ORIENTED_EDGE ( 'NONE', *, *, #32238, .T. ) ; -#33999 = CARTESIAN_POINT ( 'NONE', ( -8.575359839930298378, 209.7096282739807975, 73.06368338489360781 ) ) ; -#34000 = AXIS2_PLACEMENT_3D ( 'NONE', #19156, #31658, #3619 ) ; -#34002 = EDGE_CURVE ( 'NONE', #19078, #32161, #13917, .T. ) ; -#34001 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12039, #3016, #33688, #18141 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34003 = DIRECTION ( 'NONE', ( -0.7933533003967840891, -0.5930970592710931300, -0.1372093984882652717 ) ) ; -#34004 = CYLINDRICAL_SURFACE ( 'NONE', #18236, 3.000000000000001332 ) ; -#34005 = EDGE_CURVE ( 'NONE', #37794, #35545, #52, .T. ) ; -#34006 = ORIENTED_EDGE ( 'NONE', *, *, #39770, .T. ) ; -#34007 = DIRECTION ( 'NONE', ( 0.9914447795421099663, 0.1272537940605282525, 0.02904687618140097335 ) ) ; -#34008 = ORIENTED_EDGE ( 'NONE', *, *, #257, .T. ) ; -#34009 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10481, #29077, #13539, #38461 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 2.162974296351655106E-05 ), - .UNSPECIFIED. ) ; -#34011 = DIRECTION ( 'NONE', ( -0.9914448404770122014, 0.1272256268000152013, 0.02916793062345835602 ) ) ; -#34010 = CARTESIAN_POINT ( 'NONE', ( -13.55543936442095365, 147.3963946565080505, 96.76916085575265924 ) ) ; -#34012 = VERTEX_POINT ( 'NONE', #19282 ) ; -#34013 = VERTEX_POINT ( 'NONE', #38104 ) ; -#34014 = VERTEX_POINT ( 'NONE', #3745 ) ; -#34015 = DIRECTION ( 'NONE', ( -0.6087614810001749088, 0.7729390313185979799, 0.1788147452385885350 ) ) ; -#34016 = DIRECTION ( 'NONE', ( 0.7075227875441107983, -0.1589708073325023507, 0.6885780910847103531 ) ) ; -#34017 = DIRECTION ( 'NONE', ( 0.7933533175743878729, 0.5930761747309519771, 0.1372995428259456974 ) ) ; -#34018 = PLANE ( 'NONE', #5793 ) ; -#34019 = EDGE_LOOP ( 'NONE', ( #24772, #742, #2436, #31872 ) ) ; -#34020 = CIRCLE ( 'NONE', #30771, 5.999999999733434564 ) ; -#34021 = ORIENTED_EDGE ( 'NONE', *, *, #5575, .F. ) ; -#34022 = ORIENTED_EDGE ( 'NONE', *, *, #24386, .T. ) ; -#34023 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; -#34025 = AXIS2_PLACEMENT_3D ( 'NONE', #19609, #22902, #801 ) ; -#34024 = LINE ( 'NONE', #8908, #38702 ) ; -#34026 = VECTOR ( 'NONE', #35899, 1000.000000000000000 ) ; -#34027 = CARTESIAN_POINT ( 'NONE', ( -28.25689436368393714, 186.9042180597057836, 103.3333805992548093 ) ) ; -#34028 = FACE_OUTER_BOUND ( 'NONE', #27714, .T. ) ; -#34029 = LINE ( 'NONE', #21169, #27456 ) ; -#34030 = ORIENTED_EDGE ( 'NONE', *, *, #37072, .F. ) ; -#34031 = ORIENTED_EDGE ( 'NONE', *, *, #4820, .F. ) ; -#34032 = AXIS2_PLACEMENT_3D ( 'NONE', #1285, #37911, #9913 ) ; -#34033 = ORIENTED_EDGE ( 'NONE', *, *, #28037, .F. ) ; -#34034 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; -#34035 = VECTOR ( 'NONE', #5114, 1000.000000000000114 ) ; -#34036 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971552635 ) ) ; -#34037 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052566002458 ) ) ; -#34038 = VERTEX_POINT ( 'NONE', #6811 ) ; -#34039 = CARTESIAN_POINT ( 'NONE', ( 44.91030012776904812, 180.8423815822312974, 104.4554649243456339 ) ) ; -#34040 = ORIENTED_EDGE ( 'NONE', *, *, #12514, .T. ) ; -#34041 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921588512, -0.2249510932971550969 ) ) ; -#34042 = DIRECTION ( 'NONE', ( -0.7072735235281812916, -0.6508952706406510025, -0.2758613955842038612 ) ) ; -#34043 = EDGE_LOOP ( 'NONE', ( #39726, #4611, #28810, #33120 ) ) ; -#34044 = ADVANCED_FACE ( 'NONE', ( #26050 ), #9701, .T. ) ; -#34045 = CARTESIAN_POINT ( 'NONE', ( -28.43676750982233870, 187.2527449520754033, 103.0718515660780810 ) ) ; -#34046 = CARTESIAN_POINT ( 'NONE', ( -15.83960171297270669, 125.9416570919932639, 88.73841019156296284 ) ) ; -#34047 = EDGE_CURVE ( 'NONE', #6484, #22954, #10512, .T. ) ; -#34048 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#34049 = DIRECTION ( 'NONE', ( 0.0005121997063476214180, 0.5299192642332222203, 0.8480479414785353498 ) ) ; -#34050 = ORIENTED_EDGE ( 'NONE', *, *, #26091, .T. ) ; -#34051 = CARTESIAN_POINT ( 'NONE', ( -25.50870663471662780, 209.7066555246269104, 75.57407794464953099 ) ) ; -#34053 = EDGE_CURVE ( 'NONE', #24276, #25396, #34609, .T. ) ; -#34052 = CARTESIAN_POINT ( 'NONE', ( -23.36825939451128775, 181.8106237295894232, 101.8123839998682598 ) ) ; -#34054 = EDGE_CURVE ( 'NONE', #16610, #32971, #31261, .T. ) ; -#34055 = CARTESIAN_POINT ( 'NONE', ( -37.62979971966999670, 118.9928318095000037, 87.16482861535000382 ) ) ; -#34056 = CARTESIAN_POINT ( 'NONE', ( 35.79488954871000317, 114.2303209881000043, 90.11900988012999392 ) ) ; -#34057 = EDGE_CURVE ( 'NONE', #23210, #25244, #4375, .T. ) ; -#34058 = EDGE_CURVE ( 'NONE', #5169, #12815, #29308, .T. ) ; -#34059 = VECTOR ( 'NONE', #34351, 1000.000000000000000 ) ; -#34060 = ORIENTED_EDGE ( 'NONE', *, *, #34722, .T. ) ; -#34061 = LINE ( 'NONE', #31009, #5653 ) ; -#34062 = ORIENTED_EDGE ( 'NONE', *, *, #40010, .T. ) ; -#34063 = DIRECTION ( 'NONE', ( -0.7066795775423879711, -2.101331897360152536E-15, 0.7075337268883457043 ) ) ; -#34064 = ORIENTED_EDGE ( 'NONE', *, *, #16406, .F. ) ; -#34065 = DIRECTION ( 'NONE', ( 0.6075492010474008442, -0.7738441339353225867, -0.1790229724939112477 ) ) ; -#34066 = CARTESIAN_POINT ( 'NONE', ( 15.50147165924775372, 160.1795853765612492, 99.18969171619460212 ) ) ; -#34067 = CARTESIAN_POINT ( 'NONE', ( -34.25071196010493679, 164.1090595955299705, 189.9791968356034317 ) ) ; -#34068 = LINE ( 'NONE', #5456, #38386 ) ; -#34069 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#34070 = CARTESIAN_POINT ( 'NONE', ( -36.60903273347671671, 116.8843463709822856, 90.28989577763331908 ) ) ; -#34071 = ORIENTED_EDGE ( 'NONE', *, *, #16268, .T. ) ; -#34072 = ORIENTED_EDGE ( 'NONE', *, *, #27155, .T. ) ; -#34073 = CARTESIAN_POINT ( 'NONE', ( -19.73823131666757291, 124.3520775053762719, 178.1518425532499919 ) ) ; -#34074 = CARTESIAN_POINT ( 'NONE', ( 15.50029467073742140, 160.6294874787857623, 97.24095194441136414 ) ) ; -#34075 = ORIENTED_EDGE ( 'NONE', *, *, #37069, .F. ) ; -#34076 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490320223031, 156.2427122711505092, 96.23754757942438687 ) ) ; -#34077 = FACE_OUTER_BOUND ( 'NONE', #13242, .T. ) ; -#34078 = ORIENTED_EDGE ( 'NONE', *, *, #16538, .T. ) ; -#34079 = PLANE ( 'NONE', #18959 ) ; -#34080 = AXIS2_PLACEMENT_3D ( 'NONE', #17045, #1734, #5189 ) ; -#34081 = CARTESIAN_POINT ( 'NONE', ( -3.655627072371400832, 143.5621891693900523, 95.75525358861933967 ) ) ; -#34082 = CARTESIAN_POINT ( 'NONE', ( -37.27014767442771870, 125.7173236923148920, 91.77847513361253107 ) ) ; -#34083 = EDGE_LOOP ( 'NONE', ( #26016, #12077, #33243, #9557 ) ) ; -#34084 = CARTESIAN_POINT ( 'NONE', ( 35.96235740873753173, 191.3941559883908781, 106.8664037029334679 ) ) ; -#34085 = EDGE_CURVE ( 'NONE', #23911, #8209, #1484, .T. ) ; -#34086 = CARTESIAN_POINT ( 'NONE', ( 15.75014751337000263, 185.3820984328999941, 102.6988165233999979 ) ) ; -#34087 = CARTESIAN_POINT ( 'NONE', ( -25.35220960110000021, 191.3102199587999905, 106.2530543496999940 ) ) ; -#34088 = CARTESIAN_POINT ( 'NONE', ( -3.537743815313965978, 139.6338291191595147, 91.89207571717663825 ) ) ; -#34089 = FACE_OUTER_BOUND ( 'NONE', #33219, .T. ) ; -#34090 = EDGE_LOOP ( 'NONE', ( #7206, #926, #3600, #502 ) ) ; -#34091 = DIRECTION ( 'NONE', ( -0.5988683521957626210, 0.8008474865655332842, 0.000000000000000000 ) ) ; -#34092 = EDGE_CURVE ( 'NONE', #31116, #21943, #28511, .T. ) ; -#34093 = CARTESIAN_POINT ( 'NONE', ( -37.25193126930087573, 101.1987487022166192, 196.4587490517199910 ) ) ; -#34094 = CARTESIAN_POINT ( 'NONE', ( 37.03385106520757120, 191.5330081719584996, 104.3393119305905827 ) ) ; -#34095 = ADVANCED_FACE ( 'NONE', ( #22977 ), #12971, .T. ) ; -#34096 = CARTESIAN_POINT ( 'NONE', ( -16.56540403922939930, 152.2173637657497522, 181.4728899840186784 ) ) ; -#34097 = ORIENTED_EDGE ( 'NONE', *, *, #29998, .F. ) ; -#34098 = CARTESIAN_POINT ( 'NONE', ( 37.26954635975619823, 164.8944657675721999, 196.8584033196613916 ) ) ; -#34099 = CARTESIAN_POINT ( 'NONE', ( 19.70892818629356569, 149.4293184409359014, 181.7720440811204412 ) ) ; -#34100 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082099409, 80.75443884356324986, 297.5876476292040707 ) ) ; -#34101 = EDGE_CURVE ( 'NONE', #5530, #30592, #6095, .T. ) ; -#34102 = CARTESIAN_POINT ( 'NONE', ( -35.90337984466000165, 191.4407742571999904, 103.7425389865999961 ) ) ; -#34103 = CARTESIAN_POINT ( 'NONE', ( -27.14078297295159814, 187.2702107481940175, 105.4646800884559923 ) ) ; -#34104 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418800025, 218.5902260770999987, 73.08022052563953253 ) ) ; -#34105 = VECTOR ( 'NONE', #18581, 1000.000000000000114 ) ; -#34106 = CARTESIAN_POINT ( 'NONE', ( -12.64072194042923769, 181.7794263596476583, 101.7540337600396754 ) ) ; -#34107 = VECTOR ( 'NONE', #31406, 1000.000000000000227 ) ; -#34108 =( NAMED_UNIT ( * ) SI_UNIT ( $, .STERADIAN. ) SOLID_ANGLE_UNIT ( ) ); -#34109 = CARTESIAN_POINT ( 'NONE', ( 28.46561332783693743, 181.0140531701010218, 104.5081722671034044 ) ) ; -#34110 = CARTESIAN_POINT ( 'NONE', ( 15.99984756993140600, 126.4799761663122126, 88.84346073563017399 ) ) ; -#34111 = CARTESIAN_POINT ( 'NONE', ( 28.45310815370287472, 181.6925917411357148, 101.5827842051393617 ) ) ; -#34112 = DIRECTION ( 'NONE', ( 0.7933533411653341805, 0.5931840316264885837, 0.1368326740407639630 ) ) ; -#34113 = CARTESIAN_POINT ( 'NONE', ( 20.00523442206463187, 127.4381545316818034, 89.06762383505567016 ) ) ; -#34114 = CARTESIAN_POINT ( 'NONE', ( 37.68824946257000619, 191.1162786932000017, 105.6221892660999941 ) ) ; -#34116 = VERTEX_POINT ( 'NONE', #277 ) ; -#34115 = CARTESIAN_POINT ( 'NONE', ( 36.35466606127999967, 191.5373058733999869, 106.4897778570999947 ) ) ; -#34117 = ORIENTED_EDGE ( 'NONE', *, *, #17562, .F. ) ; -#34118 = VERTEX_POINT ( 'NONE', #9909 ) ; -#34119 = VERTEX_POINT ( 'NONE', #29110 ) ; -#34120 = PLANE ( 'NONE', #23197 ) ; -#34121 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1962, #23427, #26503, #36081, #8083, #14428 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34122 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7154541036601358428, 0.6986597351757661833 ) ) ; -#34123 = CARTESIAN_POINT ( 'NONE', ( 25.66718964653109936, 118.1138626092876933, 89.91897397334423658 ) ) ; -#34124 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #23881, #21010 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34125 = ORIENTED_EDGE ( 'NONE', *, *, #23571, .F. ) ; -#34126 = CARTESIAN_POINT ( 'NONE', ( 39.01510164518473545, 183.0220360124133379, 104.9622384439134919 ) ) ; -#34127 = CARTESIAN_POINT ( 'NONE', ( -15.99988230060963090, 169.9304744392778161, 98.89424861963034630 ) ) ; -#34128 = CARTESIAN_POINT ( 'NONE', ( -18.67137549021800069, 125.9747537310184669, 174.9884018054523551 ) ) ; -#34129 = AXIS2_PLACEMENT_3D ( 'NONE', #9494, #21971, #3939 ) ; -#34130 = EDGE_CURVE ( 'NONE', #7629, #29487, #21787, .T. ) ; -#34131 = VERTEX_POINT ( 'NONE', #22380 ) ; -#34132 = CARTESIAN_POINT ( 'NONE', ( -18.78463277247493224, 125.8407709676298794, 175.1119453963373473 ) ) ; -#34133 = EDGE_CURVE ( 'NONE', #1239, #38935, #12628, .T. ) ; -#34134 = EDGE_CURVE ( 'NONE', #4358, #1066, #26857, .T. ) ; -#34135 = CARTESIAN_POINT ( 'NONE', ( 23.36785027129286618, 177.0533458852208071, 103.5030171923318534 ) ) ; -#34136 = AXIS2_PLACEMENT_3D ( 'NONE', #19338, #19728, #32427 ) ; -#34137 = EDGE_CURVE ( 'NONE', #8441, #29325, #38898, .T. ) ; -#34138 = CARTESIAN_POINT ( 'NONE', ( 17.27144951970729991, 122.5453306081213043, 172.0736587966182469 ) ) ; -#34139 = CARTESIAN_POINT ( 'NONE', ( -24.42776677020912146, 104.1131156706543095, 87.28253805075753746 ) ) ; -#34140 = ORIENTED_EDGE ( 'NONE', *, *, #9085, .F. ) ; -#34141 = CARTESIAN_POINT ( 'NONE', ( -25.59434203952000075, 189.9641803873000185, 104.1771573359999934 ) ) ; -#34142 = CIRCLE ( 'NONE', #10663, 6.500000133288976301 ) ; -#34143 = CARTESIAN_POINT ( 'NONE', ( 2.300571176476160495, 189.9856582103720370, 103.9795987939660051 ) ) ; -#34144 = CARTESIAN_POINT ( 'NONE', ( 16.00176583134766517, 118.9451395335793649, 90.18281804087268938 ) ) ; -#34145 = EDGE_CURVE ( 'NONE', #18594, #25314, #26654, .T. ) ; -#34146 = VERTEX_POINT ( 'NONE', #35407 ) ; -#34147 = CARTESIAN_POINT ( 'NONE', ( -37.29428432633125112, 118.1868522465356364, 122.8630558711557796 ) ) ; -#34148 = ORIENTED_EDGE ( 'NONE', *, *, #8428, .T. ) ; -#34149 = EDGE_CURVE ( 'NONE', #3193, #26291, #32375, .T. ) ; -#34150 = CARTESIAN_POINT ( 'NONE', ( -16.56455474137609585, 122.0416192665172872, 176.5739763051747957 ) ) ; -#34151 = CARTESIAN_POINT ( 'NONE', ( -30.04041123780218570, 165.2216646703757590, 152.9217693104508555 ) ) ; -#34152 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#34153 = CARTESIAN_POINT ( 'NONE', ( 23.31905259271698583, 213.5902233259226932, 75.54461392219040761 ) ) ; -#34154 = CARTESIAN_POINT ( 'NONE', ( -37.98559843192000329, 191.1060541152999974, 105.7311499935999990 ) ) ; -#34155 = LINE ( 'NONE', #9631, #18906 ) ; -#34156 = CARTESIAN_POINT ( 'NONE', ( -28.94780665481193793, 110.6131156702000027, 87.78526813307001930 ) ) ; -#34157 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; -#34158 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971572064 ) ) ; -#34159 = CARTESIAN_POINT ( 'NONE', ( -2.077548941156783791, 189.8518222458260425, 105.9844770551106024 ) ) ; -#34160 = VECTOR ( 'NONE', #5553, 1000.000000000000000 ) ; -#34161 = ORIENTED_EDGE ( 'NONE', *, *, #9363, .T. ) ; -#34162 = FACE_OUTER_BOUND ( 'NONE', #19651, .T. ) ; -#34163 = CARTESIAN_POINT ( 'NONE', ( -35.97906088785056511, 191.5313222965560840, 103.8930300040437515 ) ) ; -#34164 = CARTESIAN_POINT ( 'NONE', ( 14.78600921306619576, 183.3613208809844366, 102.4894415693095340 ) ) ; -#34165 = AXIS2_PLACEMENT_3D ( 'NONE', #27881, #40310, #2313 ) ; -#34167 = CARTESIAN_POINT ( 'NONE', ( 37.22395090682895358, 117.3071371955010846, 87.68550344713307254 ) ) ; -#34166 = CARTESIAN_POINT ( 'NONE', ( 15.83342737871519113, 185.8720056236915923, 102.7263494051578334 ) ) ; -#34168 = EDGE_LOOP ( 'NONE', ( #4145, #26049, #39291, #35101 ) ) ; -#34169 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.271205363195980628E-14, -0.9999998176071845934 ) ) ; -#34170 = ORIENTED_EDGE ( 'NONE', *, *, #24688, .T. ) ; -#34171 = CARTESIAN_POINT ( 'NONE', ( 39.92597513567999812, 119.3672243733000045, 89.61382895184999597 ) ) ; -#34172 = CARTESIAN_POINT ( 'NONE', ( -41.48561289357779458, 135.1802067451934022, 25.19087159780533725 ) ) ; -#34173 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9334763082618803276, -0.3586390691402302489 ) ) ; -#34174 = DIRECTION ( 'NONE', ( 3.469446951914370331E-15, -1.000000000000000000, 1.387778780765748132E-14 ) ) ; -#34175 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#34176 = ORIENTED_EDGE ( 'NONE', *, *, #10304, .F. ) ; -#34177 = LINE ( 'NONE', #6972, #29059 ) ; -#34178 = EDGE_LOOP ( 'NONE', ( #18683, #23442, #6382, #4750, #29727, #23216, #2875 ) ) ; -#34179 = CARTESIAN_POINT ( 'NONE', ( 3.535839194698592980, 136.6870853775678825, 94.28644726325400427 ) ) ; -#34180 = DIRECTION ( 'NONE', ( 0.0004161288024508587834, -0.8480480898039491899, 0.5299191110128907978 ) ) ; -#34181 = ORIENTED_EDGE ( 'NONE', *, *, #31574, .T. ) ; -#34182 = ORIENTED_EDGE ( 'NONE', *, *, #17830, .F. ) ; -#34183 = CARTESIAN_POINT ( 'NONE', ( -25.51533646434189961, 211.0902259025884007, 73.57326538444725372 ) ) ; -#34184 = CARTESIAN_POINT ( 'NONE', ( 2.291809631987290263, 189.2956671362705663, 103.3538876406753104 ) ) ; -#34185 = VECTOR ( 'NONE', #35381, 1000.000000000000000 ) ; -#34186 = AXIS2_PLACEMENT_3D ( 'NONE', #37587, #9586, #22066 ) ; -#34187 = DIRECTION ( 'NONE', ( 0.0005884963607281444966, -0.2249510543436698262, 0.9743698870663567435 ) ) ; -#34188 = ORIENTED_EDGE ( 'NONE', *, *, #34709, .F. ) ; -#34189 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #15111, #34096, #30650 ), - ( #27604, #40034, #8981 ), - ( #21458, #33897, #18352 ), - ( #34882, #16488, #31862 ) ), - .UNSPECIFIED., .F., .F., .T. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), - ( 3, 3 ), - ( 0.5322958190830298086, 0.5323199333288397561 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.7510980103643672967, 1.000000000000000000), - ( 1.000000000000000000, 0.7511085508386285969, 1.000000000000000000), - ( 1.000000000000000000, 0.7511190909932190518, 1.000000000000000000), - ( 1.000000000000000000, 0.7511296308280239753, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#34190 = VECTOR ( 'NONE', #18607, 1000.000000000000000 ) ; -#34191 = VERTEX_POINT ( 'NONE', #7412 ) ; -#34192 = CARTESIAN_POINT ( 'NONE', ( 0.7692663204041000347, 188.3858291373000213, 106.2236757186000062 ) ) ; -#34193 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#34194 = CARTESIAN_POINT ( 'NONE', ( 36.13896817258297034, 191.5090930219296581, 103.8444545286726566 ) ) ; -#34195 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921594063, 0.2249510932971528487 ) ) ; -#34196 = ORIENTED_EDGE ( 'NONE', *, *, #20907, .T. ) ; -#34197 = CARTESIAN_POINT ( 'NONE', ( -13.49823352875945304, 151.2928090228515998, 97.67176352529210703 ) ) ; -#34198 = DIRECTION ( 'NONE', ( 0.1305262051636603415, -0.9658997602660466253, -0.2236080563923574516 ) ) ; -#34199 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#34200 = EDGE_CURVE ( 'NONE', #31885, #37835, #29311, .T. ) ; -#34201 = ORIENTED_EDGE ( 'NONE', *, *, #11723, .T. ) ; -#34202 = CARTESIAN_POINT ( 'NONE', ( 22.99918985293999540, 115.6131156702015801, 87.75369723384940812 ) ) ; -#34203 = ORIENTED_EDGE ( 'NONE', *, *, #3561, .F. ) ; -#34205 = CARTESIAN_POINT ( 'NONE', ( 35.57766939435025932, 192.1569325708144618, 103.8918082975675077 ) ) ; -#34204 = CARTESIAN_POINT ( 'NONE', ( -21.44693882331385026, 135.7861819143374760, 91.01458761472625270 ) ) ; -#34206 = VERTEX_POINT ( 'NONE', #14376 ) ; -#34207 = ORIENTED_EDGE ( 'NONE', *, *, #7806, .F. ) ; -#34208 = AXIS2_PLACEMENT_3D ( 'NONE', #34341, #28630, #38020 ) ; -#34209 = AXIS2_PLACEMENT_3D ( 'NONE', #7079, #38557, #13435 ) ; -#34210 = ORIENTED_EDGE ( 'NONE', *, *, #15021, .T. ) ; -#34211 = LINE ( 'NONE', #6015, #16608 ) ; -#34212 = FACE_OUTER_BOUND ( 'NONE', #15384, .T. ) ; -#34214 = ORIENTED_EDGE ( 'NONE', *, *, #19596, .F. ) ; -#34213 = VECTOR ( 'NONE', #20642, 1000.000000000000227 ) ; -#34215 = VERTEX_POINT ( 'NONE', #7821 ) ; -#34216 = CARTESIAN_POINT ( 'NONE', ( 22.50176470575405929, 151.2986482266788357, 97.64828959533576835 ) ) ; -#34217 = CARTESIAN_POINT ( 'NONE', ( -0.04020359587071823532, 99.17590004611790278, 343.2031739270701678 ) ) ; -#34218 = CARTESIAN_POINT ( 'NONE', ( 2.940600607905301089, 209.7122358168481355, 73.05672848799805763 ) ) ; -#34219 = ORIENTED_EDGE ( 'NONE', *, *, #16540, .F. ) ; -#34220 = ORIENTED_EDGE ( 'NONE', *, *, #19454, .T. ) ; -#34221 = CARTESIAN_POINT ( 'NONE', ( 25.99030105615392827, 209.7097546603872900, 73.04280869622928662 ) ) ; -#34223 = EDGE_CURVE ( 'NONE', #32718, #27269, #35443, .T. ) ; -#34222 = DIRECTION ( 'NONE', ( -0.7933535320750290110, 0.5931614265262136199, 0.1369295264925107503 ) ) ; -#34224 = CARTESIAN_POINT ( 'NONE', ( 20.94827535171210897, 136.6018947531004244, 91.17730147031002730 ) ) ; -#34225 = EDGE_CURVE ( 'NONE', #529, #844, #20293, .T. ) ; -#34226 = CARTESIAN_POINT ( 'NONE', ( -27.53589760592999980, 124.7259939882000026, 88.63586416396999823 ) ) ; -#34227 = VERTEX_POINT ( 'NONE', #11302 ) ; -#34228 = EDGE_LOOP ( 'NONE', ( #38226, #37809, #33876, #15793 ) ) ; -#34229 = CARTESIAN_POINT ( 'NONE', ( 35.83899097077466678, 166.8947553277887437, 183.3570906540052761 ) ) ; -#34230 = CARTESIAN_POINT ( 'NONE', ( 40.98057714432916754, 189.5249999328831336, 106.9586619333081217 ) ) ; -#34231 = ORIENTED_EDGE ( 'NONE', *, *, #25306, .F. ) ; -#34232 = ADVANCED_FACE ( 'NONE', ( #17624 ), #29505, .F. ) ; -#34233 = CARTESIAN_POINT ( 'NONE', ( 20.50098233080591470, 193.6977305113042007, 106.0730745358513474 ) ) ; -#34234 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319404519275 ) ) ; -#34235 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#34236 = VECTOR ( 'NONE', #22805, 1000.000000000000000 ) ; -#34237 = CONICAL_SURFACE ( 'NONE', #16604, 6.499999999988696153, 0.7853981634219892038 ) ; -#34238 = CARTESIAN_POINT ( 'NONE', ( 28.70699186922535873, 163.1576631238072821, 99.86925946332931403 ) ) ; -#34239 = VERTEX_POINT ( 'NONE', #1283 ) ; -#34240 = CARTESIAN_POINT ( 'NONE', ( -8.231320070466233929, 177.7901967163663528, 100.7040324006646017 ) ) ; -#34241 = ORIENTED_EDGE ( 'NONE', *, *, #25465, .T. ) ; -#34242 = VECTOR ( 'NONE', #10740, 1000.000000000000000 ) ; -#34243 = CARTESIAN_POINT ( 'NONE', ( 27.82602830715945785, 77.14301703112145958, 291.5417377113968769 ) ) ; -#34244 = DIRECTION ( 'NONE', ( 0.7933535320750287889, -0.5931614265262138419, -0.1369295264925107780 ) ) ; -#34245 = CARTESIAN_POINT ( 'NONE', ( 38.38453715826999968, 118.8006487722999935, 90.10292451339999786 ) ) ; -#34246 = EDGE_CURVE ( 'NONE', #6712, #38112, #40062, .T. ) ; -#34247 = ORIENTED_EDGE ( 'NONE', *, *, #2081, .F. ) ; -#34248 = DIRECTION ( 'NONE', ( -0.0005884949961230354640, 0.2249510543439063315, -0.9743698870671264611 ) ) ; -#34249 = VERTEX_POINT ( 'NONE', #38688 ) ; -#34250 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#34251 = CARTESIAN_POINT ( 'NONE', ( -38.19156396606999948, 118.7192053888999936, 90.14876594949001287 ) ) ; -#34252 = CARTESIAN_POINT ( 'NONE', ( 15.83500788452659869, 185.2721260511765138, 105.3246691832816566 ) ) ; -#34253 = VERTEX_POINT ( 'NONE', #10707 ) ; -#34254 = FACE_OUTER_BOUND ( 'NONE', #17860, .T. ) ; -#34255 = ADVANCED_FACE ( 'NONE', ( #39095 ), #11107, .T. ) ; -#34256 = FACE_OUTER_BOUND ( 'NONE', #21432, .T. ) ; -#34257 = DIRECTION ( 'NONE', ( -0.0005884949961216715377, 0.2249510543439054988, -0.9743698870671265722 ) ) ; -#34258 = LINE ( 'NONE', #324, #522 ) ; -#34259 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#34260 = CARTESIAN_POINT ( 'NONE', ( -37.03339179615628751, 117.5430036078971767, 90.29015207987367830 ) ) ; -#34261 = ORIENTED_EDGE ( 'NONE', *, *, #17925, .F. ) ; -#34262 = CARTESIAN_POINT ( 'NONE', ( 0.9871371177456488288, 189.0442807250963710, 105.7489971128403141 ) ) ; -#34263 = EDGE_CURVE ( 'NONE', #24174, #15694, #1700, .T. ) ; -#34264 = CIRCLE ( 'NONE', #28427, 4.999999999999990230 ) ; -#34265 = PLANE ( 'NONE', #24901 ) ; -#34266 = ORIENTED_EDGE ( 'NONE', *, *, #30926, .F. ) ; -#34267 = DIRECTION ( 'NONE', ( 0.0004161288024809103739, -0.8480480897620947811, 0.5299191110798721072 ) ) ; -#34268 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #31827, #19330 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34269 = CIRCLE ( 'NONE', #16641, 2.500000000008752998 ) ; -#34270 = EDGE_CURVE ( 'NONE', #38540, #17312, #4955, .T. ) ; -#34271 = ORIENTED_EDGE ( 'NONE', *, *, #21242, .T. ) ; -#34272 = CARTESIAN_POINT ( 'NONE', ( -16.27370299762399597, 147.0379182250262318, 180.4996822280638185 ) ) ; -#34273 = EDGE_CURVE ( 'NONE', #6720, #7841, #27810, .T. ) ; -#34274 = EDGE_CURVE ( 'NONE', #2805, #19017, #8452, .T. ) ; -#34275 = CARTESIAN_POINT ( 'NONE', ( 15.05621097240102912, 151.2968320376545819, 177.4259961740748963 ) ) ; -#34276 = CARTESIAN_POINT ( 'NONE', ( 37.69154582877660431, 190.3650434775613007, 106.6583049985661376 ) ) ; -#34277 = DIRECTION ( 'NONE', ( 0.1305260325596790116, 0.9660514818508153523, 0.2229517643753315681 ) ) ; -#34278 = ORIENTED_EDGE ( 'NONE', *, *, #22358, .F. ) ; -#34279 = CARTESIAN_POINT ( 'NONE', ( 28.25168715536999997, 125.5814672718000082, 89.14042886232999763 ) ) ; -#34280 = CARTESIAN_POINT ( 'NONE', ( 25.90751652792749482, 211.0919911608675363, 73.12569551730074124 ) ) ; -#34281 = LINE ( 'NONE', #16286, #37768 ) ; -#34282 = CARTESIAN_POINT ( 'NONE', ( 30.07150458489775957, 176.8779762188897848, 103.2171028121363463 ) ) ; -#34283 = CARTESIAN_POINT ( 'NONE', ( 36.04593084803796188, 218.5902260770999987, 76.03673379054495740 ) ) ; -#34284 = ORIENTED_EDGE ( 'NONE', *, *, #26154, .F. ) ; -#34285 = CARTESIAN_POINT ( 'NONE', ( 16.56127283256421734, 122.5154997165936521, 174.6307753585464582 ) ) ; -#34286 = CARTESIAN_POINT ( 'NONE', ( 26.00067918362605468, 118.8155664802563791, 90.25207353690788636 ) ) ; -#34287 = CARTESIAN_POINT ( 'NONE', ( -35.45366962862317450, 209.7096538831000032, 78.07991812243204777 ) ) ; -#34288 = DIRECTION ( 'NONE', ( -0.0005884949961255136249, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#34289 = ORIENTED_EDGE ( 'NONE', *, *, #32048, .T. ) ; -#34290 = ORIENTED_EDGE ( 'NONE', *, *, #38846, .F. ) ; -#34291 = CARTESIAN_POINT ( 'NONE', ( -40.70653755145999497, 217.7719116711000140, 73.33308985666000979 ) ) ; -#34292 = CARTESIAN_POINT ( 'NONE', ( -38.93778834861265636, 191.4135373867393355, 104.3808903904224508 ) ) ; -#34293 = AXIS2_PLACEMENT_3D ( 'NONE', #15602, #25035, #12337 ) ; -#34294 = FACE_BOUND ( 'NONE', #24093, .T. ) ; -#34295 = PLANE ( 'NONE', #13147 ) ; -#34296 = AXIS2_PLACEMENT_3D ( 'NONE', #5134, #17607, #2099 ) ; -#34297 = VECTOR ( 'NONE', #1922, 1000.000000000000000 ) ; -#34298 = CARTESIAN_POINT ( 'NONE', ( -36.36152854251999855, 191.9073049239999875, 104.5548041313000027 ) ) ; -#34299 = CARTESIAN_POINT ( 'NONE', ( -25.53732099362649421, 190.4811272833740077, 106.2050102730240013 ) ) ; -#34300 = AXIS2_PLACEMENT_3D ( 'NONE', #9142, #21625, #322 ) ; -#34301 = CIRCLE ( 'NONE', #10199, 6.500000000061821659 ) ; -#34302 = DIRECTION ( 'NONE', ( -1.214306433183758024E-14, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#34303 = CARTESIAN_POINT ( 'NONE', ( 39.53555642364394629, 119.7153706430301554, 90.34642614193101906 ) ) ; -#34304 = APPROVAL_DATE_TIME ( #2247, #17932 ) ; -#34305 = FACE_OUTER_BOUND ( 'NONE', #33603, .T. ) ; -#34306 = ORIENTED_EDGE ( 'NONE', *, *, #6611, .F. ) ; -#34307 = CARTESIAN_POINT ( 'NONE', ( 29.20104124293241910, 162.9684951647539322, 100.3384403448970659 ) ) ; -#34308 = CARTESIAN_POINT ( 'NONE', ( -19.99823943612422994, 184.2798415734382900, 105.2882683904008729 ) ) ; -#34309 = EDGE_CURVE ( 'NONE', #27723, #27687, #15572, .T. ) ; -#34310 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15447, #13531, #28132, #101 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34311 = DIRECTION ( 'NONE', ( 0.1305262051639064502, -0.9658997602660150950, -0.2236080563923503461 ) ) ; -#34312 = CARTESIAN_POINT ( 'NONE', ( 36.36572176811999668, 191.7985677483000018, 105.0395229366000081 ) ) ; -#34313 = CARTESIAN_POINT ( 'NONE', ( 35.62122414768001022, 191.7289062099000319, 107.0376823697000077 ) ) ; -#34314 = ORIENTED_EDGE ( 'NONE', *, *, #4080, .F. ) ; -#34315 = ORIENTED_EDGE ( 'NONE', *, *, #9255, .F. ) ; -#34316 = CARTESIAN_POINT ( 'NONE', ( -4.153479741491477917, 135.7446565152251026, 90.99455322396016754 ) ) ; -#34317 = EDGE_CURVE ( 'NONE', #267, #29667, #5777, .T. ) ; -#34318 = DIRECTION ( 'NONE', ( 0.5605692862037902069, 0.5785653851273900861, -0.5924729280712899282 ) ) ; -#34319 = EDGE_CURVE ( 'NONE', #3379, #12706, #21929, .T. ) ; -#34320 = CIRCLE ( 'NONE', #33039, 2.249999999967385644 ) ; -#34321 = CARTESIAN_POINT ( 'NONE', ( -30.04578366432821568, 126.2160355793363067, 91.71819783549720739 ) ) ; -#34322 = AXIS2_PLACEMENT_3D ( 'NONE', #11709, #11913, #29909 ) ; -#34323 = ORIENTED_EDGE ( 'NONE', *, *, #10807, .F. ) ; -#34324 = AXIS2_PLACEMENT_3D ( 'NONE', #23057, #26533, #32458 ) ; -#34325 = FACE_OUTER_BOUND ( 'NONE', #38347, .T. ) ; -#34326 = EDGE_CURVE ( 'NONE', #9860, #36789, #5447, .T. ) ; -#34327 = CARTESIAN_POINT ( 'NONE', ( -5.668553076710002081, 181.6128662685622999, 104.1507415738063571 ) ) ; -#34328 = LINE ( 'NONE', #9409, #14549 ) ; -#34329 = VERTEX_POINT ( 'NONE', #9254 ) ; -#34330 = AXIS2_PLACEMENT_3D ( 'NONE', #2512, #20909, #30309 ) ; -#34331 = CARTESIAN_POINT ( 'NONE', ( -18.77674127522291414, 125.8316197988405065, 175.1083285267641259 ) ) ; -#34332 = CARTESIAN_POINT ( 'NONE', ( -23.36052865741024931, 181.6105241600809563, 104.1608863649894374 ) ) ; -#34333 = CONICAL_SURFACE ( 'NONE', #32393, 2.502995680536484802, 0.7853981633384532479 ) ; -#34334 = CARTESIAN_POINT ( 'NONE', ( -43.94750435760008855, 112.8136638115850872, 88.29031078334202221 ) ) ; -#34335 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#34336 = VERTEX_POINT ( 'NONE', #30531 ) ; -#34337 = CARTESIAN_POINT ( 'NONE', ( -25.84214186235915278, 209.7086532927333451, 75.90780821924042243 ) ) ; -#34338 = CARTESIAN_POINT ( 'NONE', ( 1.719903430310000036, 189.0438803499000358, 103.4359278008000018 ) ) ; -#34339 = DIRECTION ( 'NONE', ( -0.0005884949961228156962, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#34340 = VERTEX_POINT ( 'NONE', #28068 ) ; -#34341 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; -#34342 = VERTEX_POINT ( 'NONE', #24404 ) ; -#34343 = DIRECTION ( 'NONE', ( -0.9999998268365722920, -0.0001323830666111439785, 0.0005734121982944762486 ) ) ; -#34344 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#34345 = CARTESIAN_POINT ( 'NONE', ( 25.49183423580130636, 211.0903769678246817, 75.54322026927223988 ) ) ; -#34346 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22960, #464, #6591, #12954 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34347 = CONICAL_SURFACE ( 'NONE', #19323, 2.503056644700593747, 0.7853981634374213039 ) ; -#34348 = FACE_OUTER_BOUND ( 'NONE', #23043, .T. ) ; -#34349 = AXIS2_PLACEMENT_3D ( 'NONE', #21811, #6246, #18702 ) ; -#34350 = CARTESIAN_POINT ( 'NONE', ( 26.00773540302725451, 191.9759150222000130, 101.9057393198873882 ) ) ; -#34351 = DIRECTION ( 'NONE', ( -0.0005884949961178157895, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#34352 = CARTESIAN_POINT ( 'NONE', ( -5.670596477536101077, 181.8451598895398149, 101.8537560070761714 ) ) ; -#34353 = CARTESIAN_POINT ( 'NONE', ( -1.850721682729105533, 189.5858787790424458, 105.9075550088280977 ) ) ; -#34354 = ORIENTED_EDGE ( 'NONE', *, *, #34246, .F. ) ; -#34355 = EDGE_CURVE ( 'NONE', #22883, #31048, #13078, .T. ) ; -#34356 = VECTOR ( 'NONE', #38075, 1000.000000000000000 ) ; -#34357 = FACE_OUTER_BOUND ( 'NONE', #21523, .T. ) ; -#34358 = ADVANCED_FACE ( 'NONE', ( #21729 ), #37444, .F. ) ; -#34359 = CARTESIAN_POINT ( 'NONE', ( -39.71549914202294218, 121.2606343799488826, 123.5760462896040934 ) ) ; -#34360 = DIRECTION ( 'NONE', ( 0.0005884949961204158147, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#34361 = EDGE_CURVE ( 'NONE', #32912, #40272, #9758, .T. ) ; -#34362 = ADVANCED_FACE ( 'NONE', ( #15188 ), #861, .T. ) ; -#34363 = CYLINDRICAL_SURFACE ( 'NONE', #31082, 4.999999999999990230 ) ; -#34364 = ORIENTED_EDGE ( 'NONE', *, *, #2240, .T. ) ; -#34365 = EDGE_LOOP ( 'NONE', ( #39735, #9866, #14380, #38944 ) ) ; -#34366 = EDGE_CURVE ( 'NONE', #22181, #906, #18422, .T. ) ; -#34367 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37442, #31924, #6357, #424 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34368 = CARTESIAN_POINT ( 'NONE', ( 21.80190282490775644, 115.3623219337571300, 87.25461648903451817 ) ) ; -#34369 = DIRECTION ( 'NONE', ( -0.0005884949961225150470, 0.2249510543439052768, -0.9743698870671265722 ) ) ; -#34370 = ORIENTED_EDGE ( 'NONE', *, *, #26400, .F. ) ; -#34371 = EDGE_CURVE ( 'NONE', #29701, #26876, #23882, .T. ) ; -#34372 = CARTESIAN_POINT ( 'NONE', ( 38.59702762342853077, 118.9500968533072580, 87.67928447194626074 ) ) ; -#34373 = CARTESIAN_POINT ( 'NONE', ( -25.49185251848652101, 194.0776887492533547, 103.3836342745381671 ) ) ; -#34374 = CARTESIAN_POINT ( 'NONE', ( -29.41585490894198784, 161.0327472628627561, 187.1177767716451399 ) ) ; -#34375 = VERTEX_POINT ( 'NONE', #18622 ) ; -#34376 = CARTESIAN_POINT ( 'NONE', ( 39.01707480719999666, 201.0803718256000252, 26.89884147244999824 ) ) ; -#34377 = ORIENTED_EDGE ( 'NONE', *, *, #8837, .T. ) ; -#34378 = AXIS2_PLACEMENT_3D ( 'NONE', #5495, #11044, #23928 ) ; -#34379 = CARTESIAN_POINT ( 'NONE', ( -20.01825848499977667, 209.3198982265599852, 76.07060713741022084 ) ) ; -#34380 = CARTESIAN_POINT ( 'NONE', ( -48.17001161002253440, 82.27946979429644614, 322.5876430693837733 ) ) ; -#34381 = CYLINDRICAL_SURFACE ( 'NONE', #21654, 2.000000000000011546 ) ; -#34382 = VECTOR ( 'NONE', #12906, 1000.000000000000000 ) ; -#34383 = LINE ( 'NONE', #3308, #16414 ) ; -#34384 = ADVANCED_FACE ( 'NONE', ( #8656 ), #13280, .F. ) ; -#34385 = EDGE_LOOP ( 'NONE', ( #5018, #13800, #30554, #22123 ) ) ; -#34386 = FACE_OUTER_BOUND ( 'NONE', #29898, .T. ) ; -#34387 = CARTESIAN_POINT ( 'NONE', ( 25.49959212878524539, 118.1133528988263919, 88.41900765034652920 ) ) ; -#34388 = VECTOR ( 'NONE', #8454, 1000.000000000000114 ) ; -#34389 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #23891, #32478 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34390 = EDGE_LOOP ( 'NONE', ( #1860, #30829, #31248, #31959, #35089 ) ) ; -#34391 = EDGE_LOOP ( 'NONE', ( #12683, #9635, #32965, #35932 ) ) ; -#34392 = CARTESIAN_POINT ( 'NONE', ( -19.46367937371129742, 126.2449231135791052, 175.9963188856066267 ) ) ; -#34393 = DIRECTION ( 'NONE', ( 0.5614015438086682463, 0.2604365532041851283, 0.7854941809869552261 ) ) ; -#34394 = CARTESIAN_POINT ( 'NONE', ( -39.61053789571219852, 75.07173372617528173, 323.7343870505221730 ) ) ; -#34395 = CARTESIAN_POINT ( 'NONE', ( -45.38555676493081137, 123.7228266434447903, 91.29725465774555460 ) ) ; -#34396 = CARTESIAN_POINT ( 'NONE', ( -25.87859003943000147, 120.0559740090000105, 90.33984099753000407 ) ) ; -#34397 = EDGE_LOOP ( 'NONE', ( #28572, #13815, #23753, #18888 ) ) ; -#34398 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#34399 = CARTESIAN_POINT ( 'NONE', ( 36.44552767798368365, 77.20147770176781421, 291.4604096236121222 ) ) ; -#34400 = ORIENTED_EDGE ( 'NONE', *, *, #8822, .T. ) ; -#34401 = FACE_OUTER_BOUND ( 'NONE', #8000, .T. ) ; -#34402 = CARTESIAN_POINT ( 'NONE', ( -43.94721011010098266, 112.7011882844193309, 88.77749572683383406 ) ) ; -#34403 = ADVANCED_FACE ( 'NONE', ( #40108 ), #10689, .F. ) ; -#34404 = EDGE_CURVE ( 'NONE', #35358, #14158, #1524, .T. ) ; -#34406 = CARTESIAN_POINT ( 'NONE', ( -15.56603823844334578, 127.7826210530077446, 174.7414047399612400 ) ) ; -#34405 = CARTESIAN_POINT ( 'NONE', ( 36.14392112904619836, 192.0943178556035775, 104.3839432946396784 ) ) ; -#34407 = ORIENTED_EDGE ( 'NONE', *, *, #23617, .T. ) ; -#34408 = EDGE_LOOP ( 'NONE', ( #33430, #6010, #36497, #33980 ) ) ; -#34409 = CARTESIAN_POINT ( 'NONE', ( -29.78271245060107830, 185.5388541528431290, 103.0190830191734648 ) ) ; -#34410 = EDGE_CURVE ( 'NONE', #37873, #9277, #25204, .T. ) ; -#34411 = CARTESIAN_POINT ( 'NONE', ( -35.98078365430546910, 192.1676821918738085, 104.4282768544623394 ) ) ; -#34412 = CARTESIAN_POINT ( 'NONE', ( 21.26009136220303120, 136.4215387128503494, 93.70123539943294588 ) ) ; -#34413 = DIRECTION ( 'NONE', ( -0.6087614883550945821, 0.7730004026499607273, 0.1785492307423600655 ) ) ; -#34414 = ORIENTED_EDGE ( 'NONE', *, *, #17510, .T. ) ; -#34415 = ORIENTED_EDGE ( 'NONE', *, *, #6118, .T. ) ; -#34416 = LINE ( 'NONE', #12552, #9345 ) ; -#34417 = ADVANCED_FACE ( 'NONE', ( #22332 ), #833, .T. ) ; -#34418 = CARTESIAN_POINT ( 'NONE', ( 21.72426698684031976, 130.1004708904147265, 89.67586055015539159 ) ) ; -#34419 = CARTESIAN_POINT ( 'NONE', ( -6.035968311314003465, 134.2396840962197189, 93.73032776046711945 ) ) ; -#34420 = ORIENTED_EDGE ( 'NONE', *, *, #32310, .F. ) ; -#34421 = EDGE_LOOP ( 'NONE', ( #39413, #20433, #30230, #4564, #2510, #37088, #1428, #9295, #21738, #19412, #805 ) ) ; -#34422 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#34423 = CARTESIAN_POINT ( 'NONE', ( 20.48136443024816344, 209.7093559074854454, 75.54613107284740181 ) ) ; -#34424 = CARTESIAN_POINT ( 'NONE', ( -27.92846131486000161, 125.3695171036000033, 89.12691434018999814 ) ) ; -#34425 = EDGE_LOOP ( 'NONE', ( #11680, #23466, #27787, #14181 ) ) ; -#34426 = EDGE_CURVE ( 'NONE', #31352, #24000, #9652, .T. ) ; -#34427 = ORIENTED_EDGE ( 'NONE', *, *, #848, .T. ) ; -#34428 = CARTESIAN_POINT ( 'NONE', ( -3.168077445297452055, 127.9087829914206651, 92.26382811782556814 ) ) ; -#34429 = LINE ( 'NONE', #16570, #7142 ) ; -#34430 = VERTEX_POINT ( 'NONE', #28659 ) ; -#34431 = CARTESIAN_POINT ( 'NONE', ( -37.67380420164612076, 117.5786341847554581, 89.72039306778212620 ) ) ; -#34432 = AXIS2_PLACEMENT_3D ( 'NONE', #5979, #12317, #36862 ) ; -#34433 = CYLINDRICAL_SURFACE ( 'NONE', #25529, 22.50000000000000000 ) ; -#34434 = CARTESIAN_POINT ( 'NONE', ( -15.99849772754149591, 160.0724928513803036, 99.69724197557108880 ) ) ; -#34435 = VECTOR ( 'NONE', #37152, 1000.000000000000000 ) ; -#34436 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921579630, -0.2249510932971593713 ) ) ; -#34437 = CARTESIAN_POINT ( 'NONE', ( 91.24491504682553966, 223.7088386879784423, 197.5310967501930577 ) ) ; -#34438 = ORIENTED_EDGE ( 'NONE', *, *, #36868, .T. ) ; -#34439 = DIRECTION ( 'NONE', ( 0.6771712326825307660, -0.7358254695423512848, 0.000000000000000000 ) ) ; -#34440 = ORIENTED_EDGE ( 'NONE', *, *, #11829, .T. ) ; -#34441 = CARTESIAN_POINT ( 'NONE', ( 38.45203725779199999, 79.83084358632200406, 285.1665681227444793 ) ) ; -#34442 = CARTESIAN_POINT ( 'NONE', ( -38.07016371915999997, 118.2980697155000058, 87.84172081773000684 ) ) ; -#34443 = LINE ( 'NONE', #38138, #21602 ) ; -#34444 = CARTESIAN_POINT ( 'NONE', ( 15.99998877809332143, 185.5947573397194219, 102.4911857378799880 ) ) ; -#34445 = ORIENTED_EDGE ( 'NONE', *, *, #27736, .F. ) ; -#34446 = CARTESIAN_POINT ( 'NONE', ( -37.83635444431042316, 190.3639788717852923, 106.7036751988638912 ) ) ; -#34447 = EDGE_LOOP ( 'NONE', ( #37318, #28317, #36628, #5940 ) ) ; -#34448 = DIRECTION ( 'NONE', ( 0.0005559617614583168633, -0.3907311284917806549, 0.9205046855579059883 ) ) ; -#34449 = EDGE_CURVE ( 'NONE', #14325, #21600, #23731, .T. ) ; -#34450 = EDGE_CURVE ( 'NONE', #9106, #36316, #17033, .T. ) ; -#34451 = ORIENTED_EDGE ( 'NONE', *, *, #33159, .F. ) ; -#34452 = CARTESIAN_POINT ( 'NONE', ( -28.46570037481023974, 129.9682353462455353, 92.24140578278095859 ) ) ; -#34453 = CYLINDRICAL_SURFACE ( 'NONE', #24841, 1.750000000000001998 ) ; -#34454 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#34455 = CARTESIAN_POINT ( 'NONE', ( -20.61404310602679502, 159.1294364323455568, 96.40329781580336999 ) ) ; -#34456 = CARTESIAN_POINT ( 'NONE', ( 45.12876369734329529, 130.2598771944438170, 92.77743955731769177 ) ) ; -#34457 = AXIS2_PLACEMENT_3D ( 'NONE', #20124, #26095, #14011 ) ; -#34458 = ORIENTED_EDGE ( 'NONE', *, *, #31297, .T. ) ; -#34459 = EDGE_LOOP ( 'NONE', ( #26428, #34284, #34755, #30120 ) ) ; -#34460 = PLANE ( 'NONE', #26956 ) ; -#34461 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971553190 ) ) ; -#34462 = VERTEX_POINT ( 'NONE', #19636 ) ; -#34463 = CARTESIAN_POINT ( 'NONE', ( -23.36361985736456148, 135.0109247816458833, 90.96681983546676520 ) ) ; -#34464 = CARTESIAN_POINT ( 'NONE', ( -28.55555411531191012, 225.5077044902969021, 75.57575137751560135 ) ) ; -#34465 = ORIENTED_EDGE ( 'NONE', *, *, #27015, .T. ) ; -#34466 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#34467 = EDGE_CURVE ( 'NONE', #14434, #21069, #14608, .T. ) ; -#34468 = CARTESIAN_POINT ( 'NONE', ( 17.18127995227040117, 121.6259304897876774, 177.7629839600756156 ) ) ; -#34469 = EDGE_LOOP ( 'NONE', ( #14886, #28489, #3742, #4469, #2260 ) ) ; -#34470 = CARTESIAN_POINT ( 'NONE', ( 28.48577721303999866, 125.2596771088999930, 88.55415022690999649 ) ) ; -#34471 = CARTESIAN_POINT ( 'NONE', ( 3.651536791988571728, 167.8514937833010379, 101.3625248932176959 ) ) ; -#34472 = CARTESIAN_POINT ( 'NONE', ( -12.63088703835403237, 131.0198726340251199, 89.90887950976862442 ) ) ; -#34473 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#34474 = CARTESIAN_POINT ( 'NONE', ( 44.00772395466434261, 121.9453774596282898, 90.79738088892072767 ) ) ; -#34475 = ORIENTED_EDGE ( 'NONE', *, *, #35357, .F. ) ; -#34476 = CARTESIAN_POINT ( 'NONE', ( 19.86084717194416172, 148.9562488000109965, 184.3380894802987484 ) ) ; -#34477 = CARTESIAN_POINT ( 'NONE', ( 25.74903847615999908, 118.4643410412000009, 87.50223256360000335 ) ) ; -#34478 = DIRECTION ( 'NONE', ( -0.0005884949954653354411, 0.2249049336873584770, -0.9743805337119194609 ) ) ; -#34479 = EDGE_CURVE ( 'NONE', #14957, #9728, #9861, .T. ) ; -#34480 = CONICAL_SURFACE ( 'NONE', #16848, 2.503022657348932700, 0.7853981633682908248 ) ; -#34481 = CARTESIAN_POINT ( 'NONE', ( -46.06386797141990996, 125.2795831766159438, 91.72091677834144718 ) ) ; -#34482 = ORIENTED_EDGE ( 'NONE', *, *, #25899, .F. ) ; -#34483 = CARTESIAN_POINT ( 'NONE', ( -26.71540925256000065, 134.5404870428999970, 93.55251239663999741 ) ) ; -#34484 = CARTESIAN_POINT ( 'NONE', ( -23.36043048140902911, 174.7899337806854589, 102.5862286567353436 ) ) ; -#34485 = VECTOR ( 'NONE', #18871, 1000.000000000000227 ) ; -#34486 = CARTESIAN_POINT ( 'NONE', ( 25.96376524127702368, 211.5623268173172278, 73.04282261878624638 ) ) ; -#34487 = EDGE_CURVE ( 'NONE', #13582, #30170, #27692, .T. ) ; -#34488 = EDGE_CURVE ( 'NONE', #4354, #4523, #12501, .T. ) ; -#34489 = EDGE_CURVE ( 'NONE', #19698, #37155, #24420, .T. ) ; -#34490 = EDGE_CURVE ( 'NONE', #36343, #31088, #15271, .T. ) ; -#34491 = CARTESIAN_POINT ( 'NONE', ( -12.64382648178746571, 181.7261798233791978, 101.6688239033984047 ) ) ; -#34492 = FACE_OUTER_BOUND ( 'NONE', #29840, .T. ) ; -#34493 = CARTESIAN_POINT ( 'NONE', ( -2.937261516931815919, 196.5784392894775010, 103.8768773714908775 ) ) ; -#34494 = CARTESIAN_POINT ( 'NONE', ( -20.25978691166676171, 184.3446264524550884, 105.0351082379391414 ) ) ; -#34495 = CARTESIAN_POINT ( 'NONE', ( -75.98947031532999574, 156.0077016488999959, 97.25549023460999365 ) ) ; -#34496 = CARTESIAN_POINT ( 'NONE', ( 37.68785012072999763, 191.2689211507999971, 104.9610270439000033 ) ) ; -#34498 = ORIENTED_EDGE ( 'NONE', *, *, #16639, .F. ) ; -#34497 = CARTESIAN_POINT ( 'NONE', ( 35.85700008397000005, 191.8443248289999872, 106.7786176113000067 ) ) ; -#34499 = ORIENTED_EDGE ( 'NONE', *, *, #26676, .F. ) ; -#34500 = ORIENTED_EDGE ( 'NONE', *, *, #31685, .T. ) ; -#34502 = AXIS2_PLACEMENT_3D ( 'NONE', #17773, #8409, #27234 ) ; -#34501 = CARTESIAN_POINT ( 'NONE', ( -3.598352747846551569, 136.7377413143313163, 91.22348967418774635 ) ) ; -#34503 = CARTESIAN_POINT ( 'NONE', ( -25.26021706816886692, 117.1739734221355889, 170.8214860574283591 ) ) ; -#34504 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27702, #6196, #31161, #37282, #20940, #24433, #27303, #9078, #2923, #15414, #24636 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000001509903, 0.3750000000001908473, 0.4375000000002049472, 0.4687500000001764144, 0.5000000000001478817, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34505 = DIRECTION ( 'NONE', ( 6.245004513562242117E-15, 0.9743700557921592953, 0.2249510932971531540 ) ) ; -#34506 = DIRECTION ( 'NONE', ( 0.0005734119072316638333, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#34507 = CONICAL_SURFACE ( 'NONE', #3181, 5.000000000151219481, 0.7853981634251813171 ) ; -#34508 = ORIENTED_EDGE ( 'NONE', *, *, #10155, .F. ) ; -#34509 = CARTESIAN_POINT ( 'NONE', ( -26.00138850119475364, 118.1173731751006102, 87.28355378449504087 ) ) ; -#34510 = CARTESIAN_POINT ( 'NONE', ( 3.667031087185668614, 126.5406573962001033, 90.06227382706777007 ) ) ; -#34511 = DIRECTION ( 'NONE', ( 0.7066903833891088338, 9.361005956520113971E-05, -0.7075229277292088836 ) ) ; -#34512 = ORIENTED_EDGE ( 'NONE', *, *, #27567, .F. ) ; -#34513 = LINE ( 'NONE', #34911, #37584 ) ; -#34514 = CARTESIAN_POINT ( 'NONE', ( -15.49823494792000034, 124.1767752774999991, 91.40966175313999997 ) ) ; -#34515 = CARTESIAN_POINT ( 'NONE', ( -25.99970180910948159, 119.7153706046974833, 90.38600776144090787 ) ) ; -#34516 = CARTESIAN_POINT ( 'NONE', ( -14.55306309020423505, 135.7870933973037211, 91.01063163966807679 ) ) ; -#34517 = DIRECTION ( 'NONE', ( 0.5988974202702760374, -0.8008257488327958917, 0.000000000000000000 ) ) ; -#34518 = VERTEX_POINT ( 'NONE', #6561 ) ; -#34519 = PLANE ( 'NONE', #37013 ) ; -#34520 = CARTESIAN_POINT ( 'NONE', ( 1.766901104769819986, 189.4078520347610208, 103.8106879554589881 ) ) ; -#34521 = DIRECTION ( 'NONE', ( -0.0005884949961205877692, 0.2249510543439036392, -0.9743698870671270162 ) ) ; -#34522 = ORIENTED_EDGE ( 'NONE', *, *, #20329, .F. ) ; -#34523 = ORIENTED_EDGE ( 'NONE', *, *, #3814, .F. ) ; -#34524 = PLANE ( 'NONE', #27744 ) ; -#34525 = ORIENTED_EDGE ( 'NONE', *, *, #5184, .T. ) ; -#34526 = CIRCLE ( 'NONE', #1904, 1.999999999847029697 ) ; -#34527 = EDGE_CURVE ( 'NONE', #802, #315, #18819, .T. ) ; -#34529 = EDGE_CURVE ( 'NONE', #35520, #37873, #30691, .T. ) ; -#34528 = CARTESIAN_POINT ( 'NONE', ( -13.55720484940903781, 164.6355387680886224, 97.67021978055177556 ) ) ; -#34530 = AXIS2_PLACEMENT_3D ( 'NONE', #34287, #39825, #40225 ) ; -#34531 = CIRCLE ( 'NONE', #14320, 4.999999999999990230 ) ; -#34532 = CARTESIAN_POINT ( 'NONE', ( 24.99091232081798708, 212.6266500085528151, 75.54358765244305118 ) ) ; -#34533 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14625, #5820, #18271, #27111, #11554, #30769, #24027, #18067, #36484, #8073, #21160, #40152, #12164, #14834, #14414, #8491, #33615 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999383271, 0.1874999999999074907, 0.2187499999999421296, 0.2343749999999594769, 0.2499999999999767963, 0.3750000000000690004, 0.4375000000001306732, 0.4687500000001615930, 0.5000000000001924017, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34534 = ADVANCED_FACE ( 'NONE', ( #19029 ), #31737, .T. ) ; -#34535 = VECTOR ( 'NONE', #12742, 1000.000000000000227 ) ; -#34536 = CARTESIAN_POINT ( 'NONE', ( -36.61650759155055113, 191.3591673295911733, 106.3831752203444267 ) ) ; -#34537 = EDGE_CURVE ( 'NONE', #28359, #4391, #7392, .T. ) ; -#34538 = CARTESIAN_POINT ( 'NONE', ( -25.50819987896827712, 205.5673820218000003, 76.31562095570974691 ) ) ; -#34539 = EDGE_CURVE ( 'NONE', #17036, #26229, #3895, .T. ) ; -#34540 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #14144, #11068, #26618, #29882, #35985, #20876, #24160, #17781, #36617, #8619, #5525, #2867, #3451, #9017, #24969, #15154, #37421, #18780, #15927 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 1, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000006939, 0.2500000000000013878, 0.3750000000000021094, 0.4375000000000024425, 0.5000000000000027756, 0.6249999999999968914, 0.6874999999999921174, 0.7187499999999890088, 0.7499999999999857891, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34541 = LINE ( 'NONE', #6543, #23223 ) ; -#34542 = PLANE ( 'NONE', #38925 ) ; -#34543 = ORIENTED_EDGE ( 'NONE', *, *, #38647, .F. ) ; -#34544 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971565402 ) ) ; -#34545 = CARTESIAN_POINT ( 'NONE', ( -51.85292886923593159, 86.58783266284258673, 291.5898618049438937 ) ) ; -#34546 = CARTESIAN_POINT ( 'NONE', ( 3.166350953592421025, 126.8041585549839709, 88.92605846951083493 ) ) ; -#34547 = DIRECTION ( 'NONE', ( 0.0005884949961208581692, -0.2249510543439069699, 0.9743698870671261281 ) ) ; -#34548 = ORIENTED_EDGE ( 'NONE', *, *, #20109, .T. ) ; -#34549 = ORIENTED_EDGE ( 'NONE', *, *, #10906, .T. ) ; -#34550 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #40422, #24722, #31230, #18534 ), - ( #27986, #18136, #12033, #36970 ), - ( #21448, #21643, #30640, #33889 ), - ( #40026, #18340, #30840, #34087 ), - ( #15298, #37172, #6083, #31040 ), - ( #12422, #37366, #9365, #21838 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 4 ), - ( 4, 4 ), - ( -0.4117284577470000095, 0.000000000000000000, 1.000000000000000000, 1.411728457748999910 ), - ( -3.970401296627000013E-07, 1.000000188336999996 ), - .UNSPECIFIED. ) ; -#34551 = VERTEX_POINT ( 'NONE', #16175 ) ; -#34552 = LINE ( 'NONE', #37647, #30752 ) ; -#34553 = CARTESIAN_POINT ( 'NONE', ( 15.99974815555098218, 138.5019114137554936, 91.61902897505088106 ) ) ; -#34554 = EDGE_LOOP ( 'NONE', ( #7601, #34628, #33180, #6182, #36620 ) ) ; -#34555 = ORIENTED_EDGE ( 'NONE', *, *, #29300, .T. ) ; -#34556 = CARTESIAN_POINT ( 'NONE', ( 15.99985850662387676, 165.3259634487874905, 97.81191083758460536 ) ) ; -#34557 = CIRCLE ( 'NONE', #16932, 6.000000000369111852 ) ; -#34558 = CYLINDRICAL_SURFACE ( 'NONE', #14634, 2.000000000000014655 ) ; -#34559 = CARTESIAN_POINT ( 'NONE', ( -20.51745969899640087, 207.4083551867479116, 77.09396086730279762 ) ) ; -#34560 = LINE ( 'NONE', #38257, #36606 ) ; -#34561 = CARTESIAN_POINT ( 'NONE', ( -62.16409435615067025, 244.6873810594820497, 206.4486349095241735 ) ) ; -#34562 = EDGE_LOOP ( 'NONE', ( #15222, #7419, #30518, #19883, #36894, #29696 ) ) ; -#34563 = CARTESIAN_POINT ( 'NONE', ( 30.06862252805091273, 137.3589525008079590, 91.34657359371807672 ) ) ; -#34564 = EDGE_LOOP ( 'NONE', ( #16674, #10962, #25468, #33807 ) ) ; -#34565 = AXIS2_PLACEMENT_3D ( 'NONE', #3236, #34311, #9997 ) ; -#34566 = CARTESIAN_POINT ( 'NONE', ( 31.91158941450065356, 174.0369345777030787, 102.3790021461855133 ) ) ; -#34567 = CONICAL_SURFACE ( 'NONE', #40450, 2.503072324631959944, 0.7853981633575404242 ) ; -#34568 = CARTESIAN_POINT ( 'NONE', ( 40.87660703992253275, 128.6351741493065219, 92.40491543180627332 ) ) ; -#34569 = ORIENTED_EDGE ( 'NONE', *, *, #21905, .T. ) ; -#34570 = VERTEX_POINT ( 'NONE', #13317 ) ; -#34571 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971577615 ) ) ; -#34572 = CARTESIAN_POINT ( 'NONE', ( 1.967363662627033216, 189.0444863294190156, 103.2960939288106488 ) ) ; -#34574 = ADVANCED_FACE ( 'NONE', ( #28856, #35158, #38640, #38845, #29664, #13919, #17367, #23523, #14332, #26004, #26610, #14136, #10865, #23331, #26806, #33121, #13714, #20036 ), #29871, .F. ) ; -#34573 = CARTESIAN_POINT ( 'NONE', ( -26.00892325947948436, 205.5538223707005727, 75.25157465572357296 ) ) ; -#34575 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#34576 = EDGE_CURVE ( 'NONE', #32435, #33874, #26345, .T. ) ; -#34577 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #4956, #17423 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 0.9999996464390269457 ), - .UNSPECIFIED. ) ; -#34578 = ORIENTED_EDGE ( 'NONE', *, *, #11909, .F. ) ; -#34579 = DIRECTION ( 'NONE', ( 0.7075337269147008445, -0.000000000000000000, 0.7066795775160008564 ) ) ; -#34580 = CARTESIAN_POINT ( 'NONE', ( 39.69446386203616584, 161.8153251821185563, 196.1471770628630793 ) ) ; -#34581 = ORIENTED_EDGE ( 'NONE', *, *, #8020, .T. ) ; -#34582 = EDGE_CURVE ( 'NONE', #26218, #3644, #32910, .T. ) ; -#34583 = DIRECTION ( 'NONE', ( -0.6087611434179116543, 0.7728348325624403437, 0.1792657018023851578 ) ) ; -#34584 = FACE_OUTER_BOUND ( 'NONE', #7530, .T. ) ; -#34585 = CARTESIAN_POINT ( 'NONE', ( -26.52798348243999982, 122.1192044545999948, 91.08024802501999773 ) ) ; -#34586 = EDGE_CURVE ( 'NONE', #23972, #34711, #15920, .T. ) ; -#34587 = ORIENTED_EDGE ( 'NONE', *, *, #6393, .F. ) ; -#34588 = DIRECTION ( 'NONE', ( 0.6087614115774881984, 0.7729348350621344510, 0.1788331191967955092 ) ) ; -#34589 = CARTESIAN_POINT ( 'NONE', ( -29.78153558668642376, 185.0889519685938183, 104.9678232557472199 ) ) ; -#34590 = EDGE_CURVE ( 'NONE', #12043, #75, #19937, .T. ) ; -#34591 = VECTOR ( 'NONE', #8361, 1000.000000000000227 ) ; -#34592 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3791, #16267, #30166, #2160 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34593 = EDGE_LOOP ( 'NONE', ( #11140, #21636, #18139, #11748 ) ) ; -#34594 = VECTOR ( 'NONE', #38344, 1000.000000000000227 ) ; -#34595 = VECTOR ( 'NONE', #37077, 1000.000000000000227 ) ; -#34596 = CARTESIAN_POINT ( 'NONE', ( 25.25244696082440754, 117.1946158480437248, 170.8386649222292704 ) ) ; -#34597 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989941907, 0.1373964268091566465 ) ) ; -#34599 = CARTESIAN_POINT ( 'NONE', ( -16.54773196322278750, 121.5501185848507220, 177.2466710267809447 ) ) ; -#34598 = CARTESIAN_POINT ( 'NONE', ( -36.27950425524976907, 191.8188495074159334, 104.4051415298545180 ) ) ; -#34600 = EDGE_LOOP ( 'NONE', ( #35610, #32603, #39342, #22427 ) ) ; -#34601 = EDGE_CURVE ( 'NONE', #5625, #19444, #38444, .T. ) ; -#34602 = CARTESIAN_POINT ( 'NONE', ( -42.43605116069559102, 176.1238575639636963, 166.1285832315935238 ) ) ; -#34603 = ORIENTED_EDGE ( 'NONE', *, *, #29917, .T. ) ; -#34604 = CARTESIAN_POINT ( 'NONE', ( 62.95950931629634795, 82.27946979429611929, 297.5205190635955432 ) ) ; -#34605 = CARTESIAN_POINT ( 'NONE', ( -4.036853220715999946, 174.6757490132999919, 101.5218917698000070 ) ) ; -#34606 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562904 ) ) ; -#34607 = VERTEX_POINT ( 'NONE', #10464 ) ; -#34608 = ORIENTED_EDGE ( 'NONE', *, *, #30879, .F. ) ; -#34609 = LINE ( 'NONE', #481, #22458 ) ; -#34610 = CARTESIAN_POINT ( 'NONE', ( 12.67270221306000089, 114.0103269029000188, 152.4718672074000381 ) ) ; -#34611 = CARTESIAN_POINT ( 'NONE', ( -39.77033354370986018, 109.3176668593371659, 175.1599740040520885 ) ) ; -#34612 = FACE_OUTER_BOUND ( 'NONE', #11338, .T. ) ; -#34613 = ORIENTED_EDGE ( 'NONE', *, *, #15596, .T. ) ; -#34614 = VERTEX_POINT ( 'NONE', #7769 ) ; -#34615 = CARTESIAN_POINT ( 'NONE', ( -63.17000887413028209, 82.27946979429644614, 322.5967026918628449 ) ) ; -#34616 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39878, #2694, #11889, #27645 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.018919284545057323E-05 ), - .UNSPECIFIED. ) ; -#34617 = CARTESIAN_POINT ( 'NONE', ( 20.00057261911097228, 127.6202858744403272, 89.10430568560569498 ) ) ; -#34618 = CARTESIAN_POINT ( 'NONE', ( -28.22659469502000107, 125.0890361073000179, 88.54897414206999429 ) ) ; -#34619 = ORIENTED_EDGE ( 'NONE', *, *, #26548, .F. ) ; -#34620 = VERTEX_POINT ( 'NONE', #1645 ) ; -#34621 = CARTESIAN_POINT ( 'NONE', ( -20.83567718070347397, 212.3494766734548591, 73.57110327059724852 ) ) ; -#34622 = AXIS2_PLACEMENT_3D ( 'NONE', #13231, #1543, #22641 ) ; -#34623 = EDGE_LOOP ( 'NONE', ( #11179, #13615, #37460, #13195 ) ) ; -#34624 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26356, #33071, #4455, #5059 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34625 = VECTOR ( 'NONE', #12074, 1000.000000000000227 ) ; -#34626 = EDGE_CURVE ( 'NONE', #31583, #26486, #19823, .T. ) ; -#34627 = VECTOR ( 'NONE', #31939, 1000.000000000000000 ) ; -#34628 = ORIENTED_EDGE ( 'NONE', *, *, #11909, .T. ) ; -#34629 = EDGE_CURVE ( 'NONE', #26621, #31941, #15123, .T. ) ; -#34630 = FACE_OUTER_BOUND ( 'NONE', #40454, .T. ) ; -#34631 = CARTESIAN_POINT ( 'NONE', ( -12.63676213157982531, 181.6119438013536183, 104.1547372293333495 ) ) ; -#34632 = CARTESIAN_POINT ( 'NONE', ( -2.726782783521000120, 189.4935947808999970, 106.6363833331000137 ) ) ; -#34633 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971542643 ) ) ; -#34634 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20473, #10294, #29091, #32945 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34635 = ADVANCED_FACE ( 'NONE', ( #7978 ), #20238, .T. ) ; -#34636 = ORIENTED_EDGE ( 'NONE', *, *, #20135, .T. ) ; -#34637 = CARTESIAN_POINT ( 'NONE', ( 2.804056179529000215, 199.6921533858000259, 89.49986858798999378 ) ) ; -#34638 = EDGE_LOOP ( 'NONE', ( #1038, #19887, #23421, #17735 ) ) ; -#34639 = CARTESIAN_POINT ( 'NONE', ( 32.48195952060035552, 83.06028001681806927, 291.5538007505838323 ) ) ; -#34640 = CARTESIAN_POINT ( 'NONE', ( -31.91276639771151125, 174.2534364592530949, 101.4412295696469926 ) ) ; -#34641 = DIRECTION ( 'NONE', ( -0.0004161288024623961039, -0.5299192578740949955, -0.8480479980348919478 ) ) ; -#34642 = EDGE_CURVE ( 'NONE', #40029, #21947, #34839, .T. ) ; -#34643 = VERTEX_POINT ( 'NONE', #1437 ) ; -#34644 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971575394 ) ) ; -#34645 = ORIENTED_EDGE ( 'NONE', *, *, #30662, .F. ) ; -#34646 = CARTESIAN_POINT ( 'NONE', ( 19.98880994172048275, 211.4784726885777957, 76.04928499183930057 ) ) ; -#34647 = CARTESIAN_POINT ( 'NONE', ( 22.78070441975003391, 158.6816533748419147, 96.78686173997256503 ) ) ; -#34648 = CYLINDRICAL_SURFACE ( 'NONE', #8966, 4.999999999999990230 ) ; -#34649 = ORIENTED_EDGE ( 'NONE', *, *, #27793, .F. ) ; -#34650 = CONICAL_SURFACE ( 'NONE', #9911, 2.499999999403085482, 0.7853981633778843729 ) ; -#34651 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319369828058 ) ) ; -#34652 = VERTEX_POINT ( 'NONE', #26402 ) ; -#34653 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#34654 = AXIS2_PLACEMENT_3D ( 'NONE', #19132, #1136, #23224 ) ; -#34655 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #1589, #27119 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34656 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250904288, 179.1753088542885735, 103.5954339978219281 ) ) ; -#34657 = DIRECTION ( 'NONE', ( -0.0006039748319417796414, 6.167438909946999677E-15, -0.9999998176071844824 ) ) ; -#34658 = AXIS2_PLACEMENT_3D ( 'NONE', #29070, #6977, #6771 ) ; -#34659 = CARTESIAN_POINT ( 'NONE', ( 23.36419446305882275, 177.6323096098335270, 100.7871876170524814 ) ) ; -#34660 = CARTESIAN_POINT ( 'NONE', ( -2.935406218811822399, 190.8780696450395737, 106.8012255142375864 ) ) ; -#34661 = EDGE_LOOP ( 'NONE', ( #4932, #17222, #26055, #7812 ) ) ; -#34662 = EDGE_LOOP ( 'NONE', ( #14700, #38315, #8894, #31010, #34176, #28189, #14588, #13566, #10454, #15221, #8729 ) ) ; -#34663 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178570903572E-05, -0.0002331579774915885982 ) ) ; -#34664 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564015 ) ) ; -#34665 = VERTEX_POINT ( 'NONE', #32729 ) ; -#34666 = CARTESIAN_POINT ( 'NONE', ( -15.99823277108970743, 185.2321969574450975, 105.5057198903149782 ) ) ; -#34667 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265227786, -0.1368326740407717901 ) ) ; -#34668 = VERTEX_POINT ( 'NONE', #27632 ) ; -#34669 = PLANE ( 'NONE', #22263 ) ; -#34670 = CARTESIAN_POINT ( 'NONE', ( -38.93814858684476121, 191.0388300950886560, 103.7812318162937686 ) ) ; -#34671 = ORIENTED_EDGE ( 'NONE', *, *, #27339, .F. ) ; -#34672 = CARTESIAN_POINT ( 'NONE', ( 28.34631006716999835, 125.4808168258000052, 88.95028025583000897 ) ) ; -#34673 = CARTESIAN_POINT ( 'NONE', ( 40.67213421850927801, 184.8215034846340075, 102.8109167764341407 ) ) ; -#34674 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799573900, 175.3514230958744520, 100.1541516780990406 ) ) ; -#34675 = ADVANCED_FACE ( 'NONE', ( #14745 ), #11876, .T. ) ; -#34676 = AXIS2_PLACEMENT_3D ( 'NONE', #2681, #21689, #28028 ) ; -#34677 = EDGE_CURVE ( 'NONE', #11521, #7245, #5314, .T. ) ; -#34678 = CARTESIAN_POINT ( 'NONE', ( -6.036405711824646581, 134.8430548843712131, 93.35330002513178727 ) ) ; -#34679 = CARTESIAN_POINT ( 'NONE', ( 3.613113740660051754, 136.7269897419313622, 91.21665193260847104 ) ) ; -#34680 = VERTEX_POINT ( 'NONE', #34126 ) ; -#34681 = CARTESIAN_POINT ( 'NONE', ( -13.35657892733726726, 177.7135493816460325, 100.6893958121277279 ) ) ; -#34682 = AXIS2_PLACEMENT_3D ( 'NONE', #13110, #25595, #31925 ) ; -#34683 = CARTESIAN_POINT ( 'NONE', ( 0.9866909474777101341, 189.0453558675688441, 103.6973837186184682 ) ) ; -#34684 = CARTESIAN_POINT ( 'NONE', ( 20.50029254611199292, 184.8549113859068029, 102.8308091169877798 ) ) ; -#34685 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -1.785014166949466476E-16, -0.0006039748319386109522 ) ) ; -#34686 = ORIENTED_EDGE ( 'NONE', *, *, #7123, .F. ) ; -#34687 = VERTEX_POINT ( 'NONE', #6124 ) ; -#34688 = EDGE_CURVE ( 'NONE', #38719, #28941, #2267, .T. ) ; -#34689 = CARTESIAN_POINT ( 'NONE', ( 38.22729489356998300, 118.8169745464294920, 90.24469516268244718 ) ) ; -#34690 = CARTESIAN_POINT ( 'NONE', ( -42.13796565469444744, 121.2774612726109922, 92.80900056227228845 ) ) ; -#34691 = FACE_OUTER_BOUND ( 'NONE', #38673, .T. ) ; -#34692 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#34693 = EDGE_LOOP ( 'NONE', ( #24410, #28464, #11917, #5849 ) ) ; -#34694 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15559, #5955, #20892, #33351, #2292, #27260, #21312, #24183, #18408, #8640 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.0007807016828180784107, 0.001561403365636156821, 0.003122806731272460661, 0.006245613462545087854 ), - .UNSPECIFIED. ) ; -#34695 = CARTESIAN_POINT ( 'NONE', ( -0.02805196447938418727, 127.1761617620222893, 297.5585619722723436 ) ) ; -#34696 = EDGE_CURVE ( 'NONE', #9444, #12044, #18506, .T. ) ; -#34697 = ORIENTED_EDGE ( 'NONE', *, *, #10487, .F. ) ; -#34698 = CARTESIAN_POINT ( 'NONE', ( -22.49857731217000278, 158.2257569204417393, 98.76156587226640227 ) ) ; -#34699 = CARTESIAN_POINT ( 'NONE', ( -26.00525532982161181, 191.5536840588030714, 103.8922918156798687 ) ) ; -#34700 = DIRECTION ( 'NONE', ( 0.0006039748319375912600, 1.387265140328410610E-14, 0.9999998176071847045 ) ) ; -#34701 = CARTESIAN_POINT ( 'NONE', ( 36.06507008640249268, 192.5935567513030264, 106.3654035318940032 ) ) ; -#34702 = CARTESIAN_POINT ( 'NONE', ( 13.50157275071688723, 188.0659121227523087, 103.3026035752030651 ) ) ; -#34703 = ORIENTED_EDGE ( 'NONE', *, *, #33725, .T. ) ; -#34704 = CONICAL_SURFACE ( 'NONE', #15166, 2.499999999971520115, 0.7853981633778842619 ) ; -#34705 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825837453473963, 0.0005734119042911652942 ) ) ; -#34706 = CONICAL_SURFACE ( 'NONE', #17078, 51.90509899241903469, 0.7853981633972695331 ) ; -#34707 = DIRECTION ( 'NONE', ( -0.7933533411653077572, -0.5931840316265212243, -0.1368326740407759534 ) ) ; -#34709 = EDGE_CURVE ( 'NONE', #26700, #14103, #27301, .T. ) ; -#34708 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27227, #5728, #20862, #5922, #2262, #14740, #36600, #24554, #30480, #27439 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.0004306238141922298450, 0.0008612476283844596901, 0.001291871442576689481, 0.001722495256768919380 ), - .UNSPECIFIED. ) ; -#34710 = CARTESIAN_POINT ( 'NONE', ( 22.74549108420935184, 156.0105960157455343, 185.9695902395600342 ) ) ; -#34711 = VERTEX_POINT ( 'NONE', #40064 ) ; -#34712 = ORIENTED_EDGE ( 'NONE', *, *, #6901, .F. ) ; -#34713 = EDGE_CURVE ( 'NONE', #34146, #36524, #2063, .T. ) ; -#34714 = CARTESIAN_POINT ( 'NONE', ( -22.64037623556000156, 153.5412426005999862, 97.93672204453001484 ) ) ; -#34715 = CARTESIAN_POINT ( 'NONE', ( -4.665344088811993473, 130.8156869893767578, 89.85691989110142686 ) ) ; -#34716 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#34717 = EDGE_LOOP ( 'NONE', ( #7219, #4482, #23431, #6464, #28393, #33986 ) ) ; -#34718 = CARTESIAN_POINT ( 'NONE', ( -21.82963563099358950, 129.7230376101904881, 90.12818080884812844 ) ) ; -#34719 = DIRECTION ( 'NONE', ( -0.7947985590179719173, 0.5913221741348985150, 0.1365039814779491212 ) ) ; -#34720 = CARTESIAN_POINT ( 'NONE', ( 0.05270753573806398473, 83.21792371834001756, 87.26775245801255210 ) ) ; -#34721 = EDGE_CURVE ( 'NONE', #29469, #39798, #8611, .T. ) ; -#34722 = EDGE_CURVE ( 'NONE', #24020, #5749, #8752, .T. ) ; -#34723 = DIRECTION ( 'NONE', ( 0.5987319967475925875, 0.8009494341533932582, 0.000000000000000000 ) ) ; -#34724 = CARTESIAN_POINT ( 'NONE', ( -30.06930555481828549, 176.9293638124302390, 103.3465668613376494 ) ) ; -#34725 = DIRECTION ( 'NONE', ( -0.9999998268368093246, -0.0001323825833059327241, 0.0005734118962871372982 ) ) ; -#34726 = ORIENTED_EDGE ( 'NONE', *, *, #6673, .T. ) ; -#34727 = CARTESIAN_POINT ( 'NONE', ( 20.94615154526903567, 129.3425601203839221, 89.50137061379278691 ) ) ; -#34728 = CARTESIAN_POINT ( 'NONE', ( 1.765871439063640080, 189.4088296708220014, 103.8123468599179802 ) ) ; -#34729 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971557908 ) ) ; -#34730 = CARTESIAN_POINT ( 'NONE', ( -36.31592225947999708, 191.9399448098000107, 104.5569264237000198 ) ) ; -#34731 = ORIENTED_EDGE ( 'NONE', *, *, #8399, .T. ) ; -#34732 = CONICAL_SURFACE ( 'NONE', #37993, 3.002819725383311322, 0.7853589219486486472 ) ; -#34733 = DIRECTION ( 'NONE', ( -0.0005884949961258157921, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#34734 = ORIENTED_EDGE ( 'NONE', *, *, #3890, .T. ) ; -#34735 = VECTOR ( 'NONE', #305, 1000.000000000000000 ) ; -#34736 = AXIS2_PLACEMENT_3D ( 'NONE', #10306, #3528, #8022 ) ; -#34737 = PLANE ( 'NONE', #22119 ) ; -#34738 = DIRECTION ( 'NONE', ( 0.7933535320750288999, 0.5930759023596231527, 0.1372994799130531351 ) ) ; -#34739 = CARTESIAN_POINT ( 'NONE', ( 25.99214295446221357, 205.1071317750680123, 76.08915132579089402 ) ) ; -#34740 = CARTESIAN_POINT ( 'NONE', ( -2.225641404526999878, 209.5844923308000034, 73.69572292342999731 ) ) ; -#34741 = CARTESIAN_POINT ( 'NONE', ( -37.23546393651999864, 190.2450898259000098, 106.8159057760000081 ) ) ; -#34742 = ORIENTED_EDGE ( 'NONE', *, *, #210, .T. ) ; -#34743 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971555410 ) ) ; -#34744 = CYLINDRICAL_SURFACE ( 'NONE', #7117, 2.499999999999997335 ) ; -#34745 = CARTESIAN_POINT ( 'NONE', ( 23.68617301127497043, 136.6832541776373660, 94.27334404510794741 ) ) ; -#34746 = CARTESIAN_POINT ( 'NONE', ( 13.49999901374599354, 184.9670087776437697, 102.3446895546948099 ) ) ; -#34747 = EDGE_LOOP ( 'NONE', ( #28872, #1312, #21871, #17486 ) ) ; -#34748 = ORIENTED_EDGE ( 'NONE', *, *, #36878, .F. ) ; -#34749 = VERTEX_POINT ( 'NONE', #36808 ) ; -#34750 = CARTESIAN_POINT ( 'NONE', ( 5.666344154467410910, 131.0223139869003148, 89.89838483048988849 ) ) ; -#34751 = AXIS2_PLACEMENT_3D ( 'NONE', #38940, #8072, #29954 ) ; -#34752 = EDGE_CURVE ( 'NONE', #19682, #32767, #10697, .T. ) ; -#34753 = CARTESIAN_POINT ( 'NONE', ( 28.45934412591282126, 181.0176348879864747, 104.5058915996823004 ) ) ; -#34754 = CARTESIAN_POINT ( 'NONE', ( 0.1760939904552156487, 3.781093664149108639E-12, 291.5584375788758393 ) ) ; -#34755 = ORIENTED_EDGE ( 'NONE', *, *, #32184, .F. ) ; -#34756 = CARTESIAN_POINT ( 'NONE', ( 43.76856227852993442, 122.2716156806393997, 88.00825085342030718 ) ) ; -#34757 = ADVANCED_FACE ( 'NONE', ( #2859 ), #30264, .T. ) ; -#34758 = CONICAL_SURFACE ( 'NONE', #13233, 5.999999999815448071, 0.7853981634347138030 ) ; -#34759 = DIRECTION ( 'NONE', ( 0.0006039748319379437342, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#34760 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -6.964038142101568045E-16, -0.0006039748319386693907 ) ) ; -#34761 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#34762 = VERTEX_POINT ( 'NONE', #14939 ) ; -#34763 = DIRECTION ( 'NONE', ( 0.6068735732728639531, 0.7743428331745974003, 0.1791581501750992012 ) ) ; -#34764 = EDGE_LOOP ( 'NONE', ( #17802, #934, #7011, #37954 ) ) ; -#34765 = LINE ( 'NONE', #13327, #40305 ) ; -#34766 = ADVANCED_FACE ( 'NONE', ( #39657 ), #28389, .F. ) ; -#34767 = ADVANCED_FACE ( 'NONE', ( #7071 ), #27047, .F. ) ; -#34768 = DIRECTION ( 'NONE', ( 4.270088556239930975E-15, 0.9743700557921584071, 0.2249510932971566790 ) ) ; -#34769 = ORIENTED_EDGE ( 'NONE', *, *, #29725, .F. ) ; -#34770 = ADVANCED_FACE ( 'NONE', ( #34325 ), #26108, .F. ) ; -#34771 = ORIENTED_EDGE ( 'NONE', *, *, #31890, .T. ) ; -#34772 = CARTESIAN_POINT ( 'NONE', ( -2.940303397145800357, 190.8908889203140120, 103.7236568775780086 ) ) ; -#34773 = EDGE_CURVE ( 'NONE', #36316, #12909, #25844, .T. ) ; -#34774 = CARTESIAN_POINT ( 'NONE', ( 0.9497808450137488201, 188.6415325040748598, 103.2036792856017939 ) ) ; -#34775 = CARTESIAN_POINT ( 'NONE', ( 2.428547639155000493, 191.0029869882000071, 106.1726329739999954 ) ) ; -#34776 = VERTEX_POINT ( 'NONE', #937 ) ; -#34777 = VERTEX_POINT ( 'NONE', #23230 ) ; -#34778 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971564015 ) ) ; -#34779 = FACE_OUTER_BOUND ( 'NONE', #3828, .T. ) ; -#34780 = ORIENTED_EDGE ( 'NONE', *, *, #2037, .T. ) ; -#34781 = CARTESIAN_POINT ( 'NONE', ( 36.04411892354000457, 218.5902260770999987, 73.03673433775999513 ) ) ; -#34782 = FACE_OUTER_BOUND ( 'NONE', #25854, .T. ) ; -#34783 = CARTESIAN_POINT ( 'NONE', ( -25.99976593112455348, 118.8155677978001705, 90.28348901843737906 ) ) ; -#34784 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21209, #5043, #30413, #18115, #8748, #33251 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34785 = ORIENTED_EDGE ( 'NONE', *, *, #12785, .T. ) ; -#34786 = VECTOR ( 'NONE', #18875, 1000.000000000000000 ) ; -#34787 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825838551259833, 0.0005734119042673001612 ) ) ; -#34788 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 7.822507694019387433E-18, 0.0006039748319385908944 ) ) ; -#34789 = AXIS2_PLACEMENT_3D ( 'NONE', #25713, #15674, #28566 ) ; -#34790 = ORIENTED_EDGE ( 'NONE', *, *, #8405, .F. ) ; -#34791 = CYLINDRICAL_SURFACE ( 'NONE', #8458, 2.500000000000000888 ) ; -#34792 = CARTESIAN_POINT ( 'NONE', ( -38.93661188417907937, 190.9636357529212773, 106.3296281109435171 ) ) ; -#34794 = CARTESIAN_POINT ( 'NONE', ( 21.83022404666562366, 176.4985800024501259, 100.9007981789296053 ) ) ; -#34793 = CARTESIAN_POINT ( 'NONE', ( 4.034499242067735025, 144.1016867008426061, 93.43213283160849869 ) ) ; -#34795 = CARTESIAN_POINT ( 'NONE', ( -39.67750709825072164, 110.6863703745082717, 169.3181700334782818 ) ) ; -#34796 = ORIENTED_EDGE ( 'NONE', *, *, #33820, .F. ) ; -#34797 = LINE ( 'NONE', #3740, #975 ) ; -#34798 = EDGE_CURVE ( 'NONE', #39862, #10712, #38761, .T. ) ; -#34799 = PLANE ( 'NONE', #14780 ) ; -#34800 = DIRECTION ( 'NONE', ( 0.0005884949961258157921, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#34801 = ORIENTED_EDGE ( 'NONE', *, *, #10626, .T. ) ; -#34802 = VERTEX_POINT ( 'NONE', #38742 ) ; -#34803 = CARTESIAN_POINT ( 'NONE', ( 15.66823304406520734, 126.2044585855555709, 91.51686078600738483 ) ) ; -#34804 = ADVANCED_FACE ( 'NONE', ( #10170 ), #19567, .F. ) ; -#34805 = CARTESIAN_POINT ( 'NONE', ( -0.001471237490399612217, 161.1145625500912217, 97.36230304590552009 ) ) ; -#34806 = CARTESIAN_POINT ( 'NONE', ( 8.188077164138951147, 151.3149838351109224, 94.75284390784567279 ) ) ; -#34807 = DIRECTION ( 'NONE', ( 0.0005884949961237125483, -0.2249508317808572577, 0.9743699384498373250 ) ) ; -#34808 = VECTOR ( 'NONE', #24746, 1000.000000000000000 ) ; -#34809 = ADVANCED_FACE ( 'NONE', ( #24043 ), #20972, .T. ) ; -#34810 = EDGE_LOOP ( 'NONE', ( #18272, #29460, #27175, #2284, #27510, #24637, #35173 ) ) ; -#34811 = ORIENTED_EDGE ( 'NONE', *, *, #7470, .F. ) ; -#34812 = CARTESIAN_POINT ( 'NONE', ( -6.035112224946922233, 176.9992328849287162, 103.4395074864133051 ) ) ; -#34813 = DIRECTION ( 'NONE', ( 0.0005884949961243157984, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#34814 = PLANE ( 'NONE', #33095 ) ; -#34815 = VECTOR ( 'NONE', #3695, 1000.000000000000000 ) ; -#34816 = LINE ( 'NONE', #10116, #3320 ) ; -#34817 = ADVANCED_FACE ( 'NONE', ( #11352 ), #22193, .F. ) ; -#34818 = EDGE_LOOP ( 'NONE', ( #27251, #20917, #36873, #18199 ) ) ; -#34819 = VECTOR ( 'NONE', #34719, 1000.000000000000114 ) ; -#34820 = DIRECTION ( 'NONE', ( -0.0005884949961190681514, 0.2249510543439036114, -0.9743698870671270162 ) ) ; -#34821 = ORIENTED_EDGE ( 'NONE', *, *, #31991, .T. ) ; -#34822 = CARTESIAN_POINT ( 'NONE', ( 5.666342389698421300, 131.0259113980956727, 89.89613783104117317 ) ) ; -#34823 = ORIENTED_EDGE ( 'NONE', *, *, #2730, .T. ) ; -#34824 = LINE ( 'NONE', #11124, #10546 ) ; -#34825 = CARTESIAN_POINT ( 'NONE', ( -3.075166755969000132, 190.6381430620999993, 106.8872809968000013 ) ) ; -#34826 = PLANE ( 'NONE', #8457 ) ; -#34827 = VERTEX_POINT ( 'NONE', #18011 ) ; -#34828 = DIRECTION ( 'NONE', ( 0.0006039748319390937474, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#34829 = ORIENTED_EDGE ( 'NONE', *, *, #17460, .F. ) ; -#34830 = CARTESIAN_POINT ( 'NONE', ( -23.36498252095550043, 181.9355249988448975, 102.0122652968446744 ) ) ; -#34831 = LINE ( 'NONE', #22610, #29053 ) ; -#34832 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; -#34833 = AXIS2_PLACEMENT_3D ( 'NONE', #24271, #30595, #39982 ) ; -#34834 = AXIS2_PLACEMENT_3D ( 'NONE', #5265, #17120, #11629 ) ; -#34835 = FACE_OUTER_BOUND ( 'NONE', #32741, .T. ) ; -#34836 = ORIENTED_EDGE ( 'NONE', *, *, #191, .T. ) ; -#34837 = CARTESIAN_POINT ( 'NONE', ( 21.47967604010160869, 213.7116322668614146, 76.04653396927230347 ) ) ; -#34838 = CARTESIAN_POINT ( 'NONE', ( -0.4558744193316150994, 208.9999999999999716, 73.05877908015641253 ) ) ; -#34839 = CIRCLE ( 'NONE', #8112, 4.500000000005264233 ) ; -#34840 = DIRECTION ( 'NONE', ( 0.7072735235946167043, 0.6508952239913153859, 0.2758615054830065305 ) ) ; -#34841 = VECTOR ( 'NONE', #6983, 999.9999999999998863 ) ; -#34842 = EDGE_LOOP ( 'NONE', ( #23174, #21574, #20673, #4310 ) ) ; -#34843 = ORIENTED_EDGE ( 'NONE', *, *, #13886, .T. ) ; -#34844 = ADVANCED_FACE ( 'NONE', ( #34162 ), #33961, .F. ) ; -#34845 = CARTESIAN_POINT ( 'NONE', ( -30.05378920129078679, 185.1945982732621303, 102.9397691308601566 ) ) ; -#34846 = EDGE_CURVE ( 'NONE', #29279, #20205, #1411, .T. ) ; -#34847 = DIRECTION ( 'NONE', ( 1.040834085584171900E-14, -1.000000000000000000, 1.387778780778895919E-14 ) ) ; -#34848 = ADVANCED_FACE ( 'NONE', ( #27661 ), #35476, .F. ) ; -#34849 = DIRECTION ( 'NONE', ( 0.7933533411653341805, -0.5930537057989598848, -0.1373964268091485141 ) ) ; -#34850 = EDGE_CURVE ( 'NONE', #9812, #40162, #11336, .T. ) ; -#34851 = ORIENTED_EDGE ( 'NONE', *, *, #32354, .T. ) ; -#34852 = FACE_BOUND ( 'NONE', #3743, .T. ) ; -#34853 = ORIENTED_EDGE ( 'NONE', *, *, #30970, .T. ) ; -#34854 = ORIENTED_EDGE ( 'NONE', *, *, #29348, .T. ) ; -#34855 = CARTESIAN_POINT ( 'NONE', ( 39.71644058364383056, 182.4824187750803333, 106.8892835983133693 ) ) ; -#34856 = FACE_OUTER_BOUND ( 'NONE', #10187, .T. ) ; -#34857 = LINE ( 'NONE', #22829, #16305 ) ; -#34858 = CARTESIAN_POINT ( 'NONE', ( -39.69261857620511336, 119.4152473592345842, 89.81183687744525912 ) ) ; -#34859 = EDGE_CURVE ( 'NONE', #30603, #12211, #15952, .T. ) ; -#34860 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21062, #27213, #2461, #2666 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0001635364534413593176, 0.004146948151462667188 ), - .UNSPECIFIED. ) ; -#34861 = EDGE_LOOP ( 'NONE', ( #30812, #23655, #22270, #22574 ) ) ; -#34862 = DIRECTION ( 'NONE', ( 0.5988682214945756366, -0.8008475843029833063, 0.000000000000000000 ) ) ; -#34863 = ORIENTED_EDGE ( 'NONE', *, *, #34130, .F. ) ; -#34864 = DIRECTION ( 'NONE', ( -0.0002393071182782278061, -0.2252352986010052738, 0.9743043687658489160 ) ) ; -#34865 = ADVANCED_FACE ( 'NONE', ( #34357 ), #39410, .T. ) ; -#34866 = CARTESIAN_POINT ( 'NONE', ( -20.00083028478659486, 118.1178238269678644, 87.27986429234402976 ) ) ; -#34867 = CARTESIAN_POINT ( 'NONE', ( 3.535984824131890747, 174.6891947503640949, 103.0598728709964576 ) ) ; -#34868 = ORIENTED_EDGE ( 'NONE', *, *, #31331, .T. ) ; -#34869 = CARTESIAN_POINT ( 'NONE', ( -39.39119571213127102, 125.1643528234327789, 106.5167466242582748 ) ) ; -#34870 = CIRCLE ( 'NONE', #17237, 2.499999999928080641 ) ; -#34871 = AXIS2_PLACEMENT_3D ( 'NONE', #26419, #846, #16787 ) ; -#34872 = CARTESIAN_POINT ( 'NONE', ( 39.82850832707630673, 129.5630499648841010, 336.2667217638223178 ) ) ; -#34873 = CARTESIAN_POINT ( 'NONE', ( -20.00014137437327477, 165.3209111610133561, 97.83248740047278602 ) ) ; -#34874 = VECTOR ( 'NONE', #18562, 1000.000000000000227 ) ; -#34875 = CARTESIAN_POINT ( 'NONE', ( -25.76950758596748514, 116.9601185120032341, 90.28334897606002585 ) ) ; -#34876 = PLANE ( 'NONE', #38678 ) ; -#34877 = EDGE_LOOP ( 'NONE', ( #29584, #11795, #24284, #29721 ) ) ; -#34878 = EDGE_CURVE ( 'NONE', #468, #24898, #6355, .T. ) ; -#34879 = CARTESIAN_POINT ( 'NONE', ( 36.04411892353206781, 218.5902260770999987, 73.03673433784747715 ) ) ; -#34880 = CARTESIAN_POINT ( 'NONE', ( 0.6578553307668130179, 189.0021778648430768, 103.6874789120222715 ) ) ; -#34881 = CARTESIAN_POINT ( 'NONE', ( -30.17966072969699454, 126.7544990129442795, 88.93473033871077860 ) ) ; -#34882 = CARTESIAN_POINT ( 'NONE', ( -15.94448539992367486, 152.1420578781454651, 184.5710641058456929 ) ) ; -#34883 = EDGE_LOOP ( 'NONE', ( #23515, #4151, #33313, #38049 ) ) ; -#34884 = CARTESIAN_POINT ( 'NONE', ( -75.39299575447557800, 195.0156528577979884, 194.9624990955367423 ) ) ; -#34885 = DIRECTION ( 'NONE', ( -0.7942820423213363679, -0.5918950211223027447, -0.1370267171630251690 ) ) ; -#34886 = CYLINDRICAL_SURFACE ( 'NONE', #34000, 2.500000000000002220 ) ; -#34887 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #15995, #35737, #3125, #28286 ), - ( #18645, #34396, #31551, #31152 ), - ( #15599, #661, #22156, #3513 ), - ( #12737, #28683, #12950, #9676 ), - ( #34585, #37879, #31763, #25229 ), - ( #22361, #37678, #19057, #6787 ), - ( #16197, #34975, #6991, #28097 ), - ( #35944, #36160, #30240, #11038 ), - ( #39425, #11646, #4881, #14717 ), - ( #23496, #36575, #7952, #23707 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.01755415582484000023, 0.000000000000000000, 0.2000000583409999866, 0.4000001253193000150, 0.6000001922975000124, 0.8000002592757999853, 1.000000000000000000, 1.017829353318999930 ), - ( -6.981046197284999828E-06, 0.9999879771333000100 ), - .UNSPECIFIED. ) ; -#34888 = CARTESIAN_POINT ( 'NONE', ( -26.58131687458000414, 188.4463779415999909, 106.0831147517999966 ) ) ; -#34889 = ORIENTED_EDGE ( 'NONE', *, *, #13646, .T. ) ; -#34890 = AXIS2_PLACEMENT_3D ( 'NONE', #7647, #36050, #8475 ) ; -#34891 = FACE_OUTER_BOUND ( 'NONE', #31013, .T. ) ; -#34892 = DIRECTION ( 'NONE', ( 0.0005884949961247159774, -0.2249510543439059707, 0.9743698870671263501 ) ) ; -#34893 = VECTOR ( 'NONE', #3820, 1000.000000000000227 ) ; -#34894 = CARTESIAN_POINT ( 'NONE', ( 20.49980344970378354, 118.1127835573565221, 87.75514417896067698 ) ) ; -#34895 = CARTESIAN_POINT ( 'NONE', ( -22.49852798327298586, 160.1744970386511113, 99.21146803022173799 ) ) ; -#34896 = CARTESIAN_POINT ( 'NONE', ( -2.935232621041004020, 190.8511156531020276, 106.7950609103722286 ) ) ; -#34897 = CARTESIAN_POINT ( 'NONE', ( 36.06384369686750802, 192.3127158670980066, 104.3348371342060119 ) ) ; -#34898 = ADVANCED_FACE ( 'NONE', ( #6154 ), #31119, .F. ) ; -#34899 = EDGE_CURVE ( 'NONE', #23158, #10328, #28057, .T. ) ; -#34900 = CARTESIAN_POINT ( 'NONE', ( 35.97497706240000070, 192.2961004130000333, 106.5149693472999957 ) ) ; -#34901 = ORIENTED_EDGE ( 'NONE', *, *, #2460, .T. ) ; -#34902 = CARTESIAN_POINT ( 'NONE', ( -2.448596876244000242, 209.1869211169000096, 75.60179039185000249 ) ) ; -#34903 = CARTESIAN_POINT ( 'NONE', ( 36.98450194789865719, 117.7737446942617652, 87.24544657960829852 ) ) ; -#34904 = ORIENTED_EDGE ( 'NONE', *, *, #39028, .F. ) ; -#34905 = DIRECTION ( 'NONE', ( 0.0006039748319381496242, 1.231904546584163304E-14, 0.9999998176071845934 ) ) ; -#34906 = EDGE_LOOP ( 'NONE', ( #11936, #11174, #24490, #19310 ) ) ; -#34907 = DIRECTION ( 'NONE', ( 0.0005884949961191896905, -0.2249510543439088017, 0.9743698870671257950 ) ) ; -#34908 = DIRECTION ( 'NONE', ( 0.0005884949961247097974, -0.2249510543025337594, 0.9743698870766778208 ) ) ; -#34909 = DIRECTION ( 'NONE', ( 0.9914448404770122014, 0.1271187482266248059, 0.02963025718429710201 ) ) ; -#34910 = DIRECTION ( 'NONE', ( 0.0001408405924830975634, -0.2249510899440180511, 0.9743700463873700146 ) ) ; -#34911 = CARTESIAN_POINT ( 'NONE', ( 0.1797178394468890161, 87.27946979429613350, 297.5584364845175287 ) ) ; -#34912 = DIRECTION ( 'NONE', ( 0.0005884949961230356809, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#34913 = CARTESIAN_POINT ( 'NONE', ( 24.83589897093233034, 213.4888011696037893, 76.04349619863447174 ) ) ; -#34914 = CARTESIAN_POINT ( 'NONE', ( -32.82620923289504589, 141.9145509277669532, 282.5750060058261965 ) ) ; -#34915 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319383846792 ) ) ; -#34916 = FACE_OUTER_BOUND ( 'NONE', #34385, .T. ) ; -#34917 = VERTEX_POINT ( 'NONE', #30916 ) ; -#34918 = ADVANCED_FACE ( 'NONE', ( #37441 ), #10715, .F. ) ; -#34919 = CARTESIAN_POINT ( 'NONE', ( 39.06275665112901407, 183.6185768681216928, 102.5341712574336839 ) ) ; -#34920 = CARTESIAN_POINT ( 'NONE', ( -3.537744320960331645, 175.3497732290038300, 100.1377481765469355 ) ) ; -#34921 = AXIS2_PLACEMENT_3D ( 'NONE', #26408, #2684, #33932 ) ; -#34922 = VECTOR ( 'NONE', #37381, 1000.000000000000227 ) ; -#34923 = CARTESIAN_POINT ( 'NONE', ( 23.68596773153978319, 129.9751393256367464, 92.21150139214144303 ) ) ; -#34924 = VECTOR ( 'NONE', #1814, 1000.000000000000000 ) ; -#34925 = CARTESIAN_POINT ( 'NONE', ( -37.92803197069999754, 191.1273742063999919, 103.9224423712000061 ) ) ; -#34926 = CIRCLE ( 'NONE', #8200, 2.500000000143204115 ) ; -#34927 = ORIENTED_EDGE ( 'NONE', *, *, #24581, .F. ) ; -#34928 = CARTESIAN_POINT ( 'NONE', ( 30.01965015980229978, 186.1545558735057853, 102.6119579121506433 ) ) ; -#34929 = EDGE_LOOP ( 'NONE', ( #17601, #40356, #24411, #21985 ) ) ; -#34930 = FACE_OUTER_BOUND ( 'NONE', #5001, .T. ) ; -#34931 = CARTESIAN_POINT ( 'NONE', ( 24.03005510465546024, 118.3147583197998500, 189.7187950137720804 ) ) ; -#34932 = CARTESIAN_POINT ( 'NONE', ( 15.95630665993094688, 122.0088281219967712, 174.0020537915881960 ) ) ; -#34933 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#34934 = CARTESIAN_POINT ( 'NONE', ( 20.48116099893153574, 206.8503807931785730, 74.54225624234382508 ) ) ; -#34935 = CARTESIAN_POINT ( 'NONE', ( -37.90071030898999993, 191.1265196322999884, 106.2274659473000042 ) ) ; -#34936 = VERTEX_POINT ( 'NONE', #5960 ) ; -#34937 = DIRECTION ( 'NONE', ( -0.0005884949961251572477, 0.2249510543439052768, -0.9743698870671265722 ) ) ; -#34938 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30338, #5799, #30754, #5175, #30140, #40134, #24634, #24011, #8474, #8052 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#34939 = CONICAL_SURFACE ( 'NONE', #17320, 9.999999999997443823, 0.7853981633972965115 ) ; -#34940 = CARTESIAN_POINT ( 'NONE', ( -36.46828157562536177, 191.4819344684914313, 106.4006585949724695 ) ) ; -#34941 = DIRECTION ( 'NONE', ( -0.7933533411653060918, 0.5930537057989944127, 0.1373964268091604213 ) ) ; -#34942 = EDGE_CURVE ( 'NONE', #11505, #10330, #37837, .T. ) ; -#34943 = ADVANCED_FACE ( 'NONE', ( #9439 ), #31312, .T. ) ; -#34944 = VECTOR ( 'NONE', #29252, 1000.000000000000000 ) ; -#34945 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#34946 = ORIENTED_EDGE ( 'NONE', *, *, #1356, .F. ) ; -#34947 = ORIENTED_EDGE ( 'NONE', *, *, #21700, .F. ) ; -#34948 = VERTEX_POINT ( 'NONE', #40297 ) ; -#34949 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825903766432776, 0.0005734119027608631505 ) ) ; -#34950 = AXIS2_PLACEMENT_3D ( 'NONE', #40072, #12281, #33333 ) ; -#34951 = CARTESIAN_POINT ( 'NONE', ( -43.55091174306983959, 114.1088787615071283, 121.9228278241799757 ) ) ; -#34952 = VECTOR ( 'NONE', #33220, 1000.000000000000114 ) ; -#34953 = ORIENTED_EDGE ( 'NONE', *, *, #19633, .T. ) ; -#34954 = CARTESIAN_POINT ( 'NONE', ( -29.94629653533174007, 109.6131156702000027, 90.28587165238377565 ) ) ; -#34955 = CARTESIAN_POINT ( 'NONE', ( 29.09341390908912572, 130.9670914280451655, 89.87148492245351861 ) ) ; -#34956 = LINE ( 'NONE', #34561, #146 ) ; -#34957 = ORIENTED_EDGE ( 'NONE', *, *, #14295, .F. ) ; -#34958 = DIRECTION ( 'NONE', ( -0.0006039748319380209294, -1.272479560138527092E-14, -0.9999998176071845934 ) ) ; -#34959 = ORIENTED_EDGE ( 'NONE', *, *, #34410, .T. ) ; -#34960 = CARTESIAN_POINT ( 'NONE', ( -15.99999263269153182, 160.7450692216915513, 96.77351201758563093 ) ) ; -#34961 = CARTESIAN_POINT ( 'NONE', ( -21.96933725929774894, 130.6372435488027861, 89.82617414751712204 ) ) ; -#34962 = ORIENTED_EDGE ( 'NONE', *, *, #24983, .F. ) ; -#34963 = EDGE_CURVE ( 'NONE', #30170, #37342, #32254, .T. ) ; -#34964 = CARTESIAN_POINT ( 'NONE', ( 35.04675250840001155, 225.9002260768477583, 76.03733726937247184 ) ) ; -#34965 = CARTESIAN_POINT ( 'NONE', ( -1.458415330486092287, 152.0517121852905973, 130.6798743963483673 ) ) ; -#34966 = CARTESIAN_POINT ( 'NONE', ( -26.00945644612357910, 206.1769029671598332, 74.50228096851449777 ) ) ; -#34967 = CARTESIAN_POINT ( 'NONE', ( 2.428684613870999875, 191.0118196296000121, 106.1753971897999946 ) ) ; -#34968 = ORIENTED_EDGE ( 'NONE', *, *, #17460, .T. ) ; -#34969 = CARTESIAN_POINT ( 'NONE', ( -28.42925635489000413, 114.0103269030000064, 152.4718672074000381 ) ) ; -#34970 = CYLINDRICAL_SURFACE ( 'NONE', #6953, 2.000000000000014655 ) ; -#34971 = VECTOR ( 'NONE', #11814, 1000.000000000000227 ) ; -#34972 = EDGE_LOOP ( 'NONE', ( #15865, #29349, #16076, #11870, #13986, #908, #10956, #24933, #22904, #16421, #13273, #22559 ) ) ; -#34973 = CARTESIAN_POINT ( 'NONE', ( 30.77752414631618194, 157.1438219166013823, 186.2335371180630830 ) ) ; -#34974 = CARTESIAN_POINT ( 'NONE', ( 22.50029346826586973, 127.3220923531718825, 89.54710465288404464 ) ) ; -#34975 = CARTESIAN_POINT ( 'NONE', ( -27.56633822591999916, 124.0845406765999996, 91.27092842416000451 ) ) ; -#34976 = CONICAL_SURFACE ( 'NONE', #13455, 6.000000391989175341, 0.7853981633985190891 ) ; -#34977 = ADVANCED_FACE ( 'NONE', ( #15178, #218, #25190 ), #37639, .F. ) ; -#34978 = ORIENTED_EDGE ( 'NONE', *, *, #1879, .F. ) ; -#34979 = CARTESIAN_POINT ( 'NONE', ( -37.28964217851552121, 124.9030048851708870, 93.64309515347758861 ) ) ; -#34980 = CIRCLE ( 'NONE', #17364, 2.000000000000011546 ) ; -#34981 = CARTESIAN_POINT ( 'NONE', ( -17.02496641354574791, 121.6075756348253236, 176.8826037927987329 ) ) ; -#34982 = DIRECTION ( 'NONE', ( 0.0006039748319391906751, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#34983 = DIRECTION ( 'NONE', ( -0.7933535320750288999, 0.5931614265262138419, 0.1369295264925107503 ) ) ; -#34984 = LINE ( 'NONE', #18101, #12621 ) ; -#34985 = EDGE_CURVE ( 'NONE', #3624, #22354, #24328, .T. ) ; -#34986 = ORIENTED_EDGE ( 'NONE', *, *, #4639, .F. ) ; -#34987 = VERTEX_POINT ( 'NONE', #19620 ) ; -#34988 = CARTESIAN_POINT ( 'NONE', ( 26.00236367227700285, 120.1369457580689897, 90.45093567563459658 ) ) ; -#34989 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971559851 ) ) ; -#34990 = CARTESIAN_POINT ( 'NONE', ( -43.18873574177670349, 77.14301703112145958, 291.5846288494013834 ) ) ; -#34991 = EDGE_CURVE ( 'NONE', #8120, #650, #20495, .T. ) ; -#34992 = EDGE_CURVE ( 'NONE', #10351, #16108, #31627, .T. ) ; -#34994 = FACE_OUTER_BOUND ( 'NONE', #38259, .T. ) ; -#34993 = CARTESIAN_POINT ( 'NONE', ( 29.77977117171763055, 126.9465717267340352, 89.45601389182257890 ) ) ; -#34995 = ADVANCED_FACE ( 'NONE', ( #1220 ), #13980, .F. ) ; -#34996 = EDGE_CURVE ( 'NONE', #8652, #2293, #10449, .T. ) ; -#34997 = EDGE_LOOP ( 'NONE', ( #11254, #21541, #34636, #9164 ) ) ; -#34998 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#34999 = VECTOR ( 'NONE', #2046, 1000.000000000000114 ) ; -#35000 = CARTESIAN_POINT ( 'NONE', ( 22.49983404245668339, 158.4318110641182216, 96.38725090939126972 ) ) ; -#35001 = EDGE_LOOP ( 'NONE', ( #15028, #40453, #36019, #29572, #11672, #33539, #27445, #33040, #13964, #23825, #4856, #14415, #15577, #23810 ) ) ; -#35002 = CIRCLE ( 'NONE', #4985, 10.00000000000000000 ) ; -#35003 = AXIS2_PLACEMENT_3D ( 'NONE', #25377, #22107, #13103 ) ; -#35004 = ORIENTED_EDGE ( 'NONE', *, *, #39983, .T. ) ; -#35005 = DIRECTION ( 'NONE', ( -3.736326840320183149E-15, 0.9743700562689210365, 0.2249510912320714373 ) ) ; -#35006 = DIRECTION ( 'NONE', ( -0.7066903833891088338, -9.361005957775119998E-05, 0.7075229277292088836 ) ) ; -#35007 = CARTESIAN_POINT ( 'NONE', ( -45.14000178829265764, 124.4048192737162424, 91.66408474920166327 ) ) ; -#35008 = CARTESIAN_POINT ( 'NONE', ( -15.99847796691061852, 137.5244930513001975, 94.49161329741416182 ) ) ; -#35009 = CIRCLE ( 'NONE', #16727, 7.500000256701354395 ) ; -#35010 = ORIENTED_EDGE ( 'NONE', *, *, #5892, .T. ) ; -#35011 = ORIENTED_EDGE ( 'NONE', *, *, #39969, .F. ) ; -#35012 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319380485765 ) ) ; -#35013 = CIRCLE ( 'NONE', #19265, 2.499999999403085482 ) ; -#35014 = CARTESIAN_POINT ( 'NONE', ( -18.25047883326706355, 126.3894863778989333, 174.4205395528727252 ) ) ; -#35015 = FACE_OUTER_BOUND ( 'NONE', #25152, .T. ) ; -#35016 = ORIENTED_EDGE ( 'NONE', *, *, #25133, .F. ) ; -#35017 = EDGE_CURVE ( 'NONE', #3655, #4731, #7422, .T. ) ; -#35018 = CARTESIAN_POINT ( 'NONE', ( -21.76110230804757251, 213.2747375211771157, 73.57169191246816808 ) ) ; -#35019 = ORIENTED_EDGE ( 'NONE', *, *, #19852, .F. ) ; -#35020 = CARTESIAN_POINT ( 'NONE', ( -40.55663739063097495, 184.8193262793114684, 102.8594742714778363 ) ) ; -#35021 = CARTESIAN_POINT ( 'NONE', ( -13.47595942998339602, 154.4041677293344321, 95.30807215510701269 ) ) ; -#35022 = ORIENTED_EDGE ( 'NONE', *, *, #37346, .T. ) ; -#35023 = CARTESIAN_POINT ( 'NONE', ( -20.49970645903284705, 184.8492302318938698, 102.8542671896393301 ) ) ; -#35024 = CARTESIAN_POINT ( 'NONE', ( -2.556630992790999812, 191.0097281923000025, 106.4446402598999981 ) ) ; -#35025 = FACE_OUTER_BOUND ( 'NONE', #22367, .T. ) ; -#35026 = ADVANCED_FACE ( 'NONE', ( #38035 ), #22917, .T. ) ; -#35027 = VECTOR ( 'NONE', #15244, 1000.000000000000114 ) ; -#35028 = ORIENTED_EDGE ( 'NONE', *, *, #35865, .F. ) ; -#35029 = CARTESIAN_POINT ( 'NONE', ( -39.03036842895058811, 175.8132598316807105, 136.1868359458795510 ) ) ; -#35030 = CARTESIAN_POINT ( 'NONE', ( -25.00047486325557955, 116.5768236846756452, 87.78270791410004392 ) ) ; -#35031 = AXIS2_PLACEMENT_3D ( 'NONE', #983, #7116, #19590 ) ; -#35032 = CARTESIAN_POINT ( 'NONE', ( -39.69437836998564251, 161.5619712970498085, 197.5056430804474985 ) ) ; -#35033 = CIRCLE ( 'NONE', #17418, 2.500000000016445512 ) ; -#35034 = DIRECTION ( 'NONE', ( -0.0002393071182785117045, -0.2252352986010040525, 0.9743043687658490271 ) ) ; -#35035 = ADVANCED_FACE ( 'NONE', ( #9847 ), #27719, .F. ) ; -#35036 = DIRECTION ( 'NONE', ( 0.0006039748319392653766, -1.164951251755207723E-15, 0.9999998176071847045 ) ) ; -#35037 = CARTESIAN_POINT ( 'NONE', ( 22.49999922077098802, 138.5120027357782817, 91.61734752324643694 ) ) ; -#35038 = VERTEX_POINT ( 'NONE', #19213 ) ; -#35039 = EDGE_CURVE ( 'NONE', #4383, #24627, #22488, .T. ) ; -#35040 = CARTESIAN_POINT ( 'NONE', ( -19.99823943612422994, 184.2798415734382900, 105.2882683904008729 ) ) ; -#35041 = CARTESIAN_POINT ( 'NONE', ( -15.83323121387661025, 126.7633287966969391, 89.09915948006083397 ) ) ; -#35042 = ADVANCED_FACE ( 'NONE', ( #28843 ), #38630, .F. ) ; -#35043 = CARTESIAN_POINT ( 'NONE', ( -35.31151715239000310, 112.3631398901000154, 90.42436770938999757 ) ) ; -#35044 = EDGE_CURVE ( 'NONE', #30145, #7067, #40119, .T. ) ; -#35045 = ORIENTED_EDGE ( 'NONE', *, *, #16778, .F. ) ; -#35046 = LINE ( 'NONE', #4384, #3402 ) ; -#35047 = ORIENTED_EDGE ( 'NONE', *, *, #29310, .T. ) ; -#35048 = CARTESIAN_POINT ( 'NONE', ( 12.40625381042950615, 158.3833092224484744, 96.21109731316822433 ) ) ; -#35049 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#35050 = CARTESIAN_POINT ( 'NONE', ( -28.07003853489823797, 124.9673608855255793, 88.52086302510028304 ) ) ; -#35051 = CARTESIAN_POINT ( 'NONE', ( 23.36759919406680908, 177.7446085781720910, 100.7170137555415579 ) ) ; -#35052 = EDGE_LOOP ( 'NONE', ( #13316, #6517, #25711, #24802 ) ) ; -#35053 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921592953, -0.2249510932971527932 ) ) ; -#35054 = VERTEX_POINT ( 'NONE', #4280 ) ; -#35055 = VERTEX_POINT ( 'NONE', #6954 ) ; -#35056 = VERTEX_POINT ( 'NONE', #25593 ) ; -#35057 = CARTESIAN_POINT ( 'NONE', ( -19.70071604027683065, 149.4445624503525778, 181.7665744593643637 ) ) ; -#35058 = DIRECTION ( 'NONE', ( -0.0002393071182782278061, -0.2252352986010052738, 0.9743043687658489160 ) ) ; -#35059 = PLANE ( 'NONE', #35233 ) ; -#35060 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18018, #12308, #21725, #37254 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35061 = AXIS2_PLACEMENT_3D ( 'NONE', #28667, #13132, #19832 ) ; -#35062 = VERTEX_POINT ( 'NONE', #10036 ) ; -#35063 = CARTESIAN_POINT ( 'NONE', ( -44.46004285478915108, 188.8078265508242168, 105.8352584314367135 ) ) ; -#35064 = FACE_OUTER_BOUND ( 'NONE', #6818, .T. ) ; -#35065 = CARTESIAN_POINT ( 'NONE', ( 36.49023395156999783, 191.9050315565999938, 104.5102437693000041 ) ) ; -#35066 = CARTESIAN_POINT ( 'NONE', ( 19.99905349769186458, 193.8169544161346494, 102.6908434160864800 ) ) ; -#35067 = CIRCLE ( 'NONE', #18753, 2.000000000000011546 ) ; -#35068 = CARTESIAN_POINT ( 'NONE', ( 3.882702609269526928, 148.0331269928592519, 129.7473673639204605 ) ) ; -#35069 = CARTESIAN_POINT ( 'NONE', ( 6.034202883963867059, 177.7957208724328666, 100.6935805729036844 ) ) ; -#35070 = FACE_OUTER_BOUND ( 'NONE', #4054, .T. ) ; -#35071 = EDGE_LOOP ( 'NONE', ( #40133, #7138, #292, #13801 ) ) ; -#35072 = CARTESIAN_POINT ( 'NONE', ( 28.45696154535999867, 125.2413582448000113, 88.54986070440000390 ) ) ; -#35073 = CARTESIAN_POINT ( 'NONE', ( -20.51782960591933147, 207.7397650241700831, 76.53117123266314081 ) ) ; -#35074 = CARTESIAN_POINT ( 'NONE', ( -19.37162053837593945, 124.6261895189692410, 178.2150732946192306 ) ) ; -#35075 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825927797511552, 0.0005734119022056451695 ) ) ; -#35076 = CARTESIAN_POINT ( 'NONE', ( 62.97460868709481474, 92.27946979429643193, 322.5205145037750754 ) ) ; -#35077 = ORIENTED_EDGE ( 'NONE', *, *, #3350, .F. ) ; -#35078 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; -#35079 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971555965 ) ) ; -#35080 = CARTESIAN_POINT ( 'NONE', ( 20.50029380412308555, 187.0408239564538917, 103.3354524056335464 ) ) ; -#35081 = EDGE_CURVE ( 'NONE', #16566, #16326, #19423, .T. ) ; -#35082 = EDGE_CURVE ( 'NONE', #32479, #31880, #10736, .T. ) ; -#35083 = FACE_OUTER_BOUND ( 'NONE', #12370, .T. ) ; -#35084 = ADVANCED_FACE ( 'NONE', ( #16755 ), #31003, .F. ) ; -#35085 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#35086 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559019 ) ) ; -#35087 = CARTESIAN_POINT ( 'NONE', ( -22.49823197369664385, 160.0613479605241878, 99.70157044293461013 ) ) ; -#35088 = CARTESIAN_POINT ( 'NONE', ( 28.26067382423566698, 125.1347711400599110, 91.09124888412546284 ) ) ; -#35089 = ORIENTED_EDGE ( 'NONE', *, *, #22807, .F. ) ; -#35090 = VECTOR ( 'NONE', #31091, 1000.000000000000000 ) ; -#35091 = AXIS2_PLACEMENT_3D ( 'NONE', #12594, #28554, #12812 ) ; -#35092 = DIRECTION ( 'NONE', ( -0.7730662169443226484, -0.5272861007345266415, -0.3526159273084134571 ) ) ; -#35093 = EDGE_CURVE ( 'NONE', #10007, #1363, #35142, .T. ) ; -#35094 = FACE_OUTER_BOUND ( 'NONE', #4726, .T. ) ; -#35095 = CARTESIAN_POINT ( 'NONE', ( -39.03036842907830106, 121.1728496032269078, 123.5553118490896907 ) ) ; -#35096 = CARTESIAN_POINT ( 'NONE', ( -21.82845856935587037, 135.5369429020799146, 93.52303473086848840 ) ) ; -#35097 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971546251 ) ) ; -#35098 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714601725811, 0.5299193037554699170 ) ) ; -#35099 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; -#35100 = CARTESIAN_POINT ( 'NONE', ( 25.99876818124551292, 118.1164810761916470, 87.25208046938912787 ) ) ; -#35101 = ORIENTED_EDGE ( 'NONE', *, *, #12138, .T. ) ; -#35102 = EDGE_CURVE ( 'NONE', #34329, #38824, #17153, .T. ) ; -#35103 = CARTESIAN_POINT ( 'NONE', ( -2.954045212696999823, 209.2037278823000293, 76.12424252725000429 ) ) ; -#35104 = DIRECTION ( 'NONE', ( -0.0002267487151011638629, -0.6230052038431761474, -0.7822176580526309930 ) ) ; -#35105 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#35106 = ORIENTED_EDGE ( 'NONE', *, *, #15195, .F. ) ; -#35107 = LINE ( 'NONE', #19981, #16119 ) ; -#35108 = EDGE_LOOP ( 'NONE', ( #32188, #6226, #14005, #25442 ) ) ; -#35109 = CARTESIAN_POINT ( 'NONE', ( -20.00062605139820704, 196.5784656963837733, 103.8871944330217048 ) ) ; -#35110 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29419, #38789, #10811, #22486 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35111 = CARTESIAN_POINT ( 'NONE', ( 20.50146814542411278, 184.4050074329408915, 104.7795556516932436 ) ) ; -#35112 = CARTESIAN_POINT ( 'NONE', ( -48.00650188892534942, 61.15928328279086656, 282.5875370178958406 ) ) ; -#35113 = CARTESIAN_POINT ( 'NONE', ( -44.59335596552107717, 185.9876800833566790, 106.7142618130726248 ) ) ; -#35114 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3911, #242, #28671, #28867 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35115 = CARTESIAN_POINT ( 'NONE', ( -12.63724133153108120, 130.4695180992949304, 90.25279237546679667 ) ) ; -#35116 = AXIS2_PLACEMENT_3D ( 'NONE', #6017, #25247, #3741 ) ; -#35117 = LINE ( 'NONE', #1200, #26929 ) ; -#35118 = VERTEX_POINT ( 'NONE', #29653 ) ; -#35119 = CARTESIAN_POINT ( 'NONE', ( 41.04644941592703589, 219.0860688542000219, 75.53371351154709146 ) ) ; -#35120 = DIRECTION ( 'NONE', ( -0.6088835995545407442, -0.7728434649458200134, -0.1788120266761852595 ) ) ; -#35121 = CARTESIAN_POINT ( 'NONE', ( -23.02004673814065683, 213.5902071504527839, 73.57250091739375364 ) ) ; -#35122 = EDGE_CURVE ( 'NONE', #14988, #1098, #25782, .T. ) ; -#35123 = CARTESIAN_POINT ( 'NONE', ( -36.43359215879000601, 191.8492174557999874, 104.5507527933000063 ) ) ; -#35124 = EDGE_CURVE ( 'NONE', #30815, #33611, #9681, .T. ) ; -#35125 = VERTEX_POINT ( 'NONE', #14921 ) ; -#35126 = FACE_OUTER_BOUND ( 'NONE', #16173, .T. ) ; -#35127 = ADVANCED_FACE ( 'NONE', ( #1627 ), #38828, .T. ) ; -#35128 = ORIENTED_EDGE ( 'NONE', *, *, #26655, .F. ) ; -#35129 = CARTESIAN_POINT ( 'NONE', ( 36.76043236804844838, 115.8485703968537592, 89.69953496976647500 ) ) ; -#35130 = FACE_OUTER_BOUND ( 'NONE', #1756, .T. ) ; -#35131 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38643, #1648, #20661, #1856 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35132 = EDGE_CURVE ( 'NONE', #33670, #13982, #39422, .T. ) ; -#35133 = DIRECTION ( 'NONE', ( 0.0005884949961252946161, -0.2249510543439068866, 0.9743698870671261281 ) ) ; -#35134 = CARTESIAN_POINT ( 'NONE', ( 25.02082990279377128, 130.0549946889516377, 92.22913080465953328 ) ) ; -#35135 = CARTESIAN_POINT ( 'NONE', ( -28.35055378863404485, 124.9527156439775979, 91.25446313298311907 ) ) ; -#35136 = CARTESIAN_POINT ( 'NONE', ( 12.64386512242256266, 130.3482773188944748, 92.81742853362089818 ) ) ; -#35137 = ADVANCED_FACE ( 'NONE', ( #10850 ), #16579, .F. ) ; -#35138 = CIRCLE ( 'NONE', #4478, 5.500000000097090336 ) ; -#35139 = FACE_OUTER_BOUND ( 'NONE', #29689, .T. ) ; -#35140 = CARTESIAN_POINT ( 'NONE', ( -37.34822902193999994, 190.8540540390999922, 106.4250283690000032 ) ) ; -#35141 = VERTEX_POINT ( 'NONE', #5300 ) ; -#35142 = LINE ( 'NONE', #35537, #22513 ) ; -#35143 = AXIS2_PLACEMENT_3D ( 'NONE', #32494, #12894, #404 ) ; -#35144 = DIRECTION ( 'NONE', ( 0.0006039748319385852566, 1.189165140469103041E-14, 0.9999998176071845934 ) ) ; -#35145 = LINE ( 'NONE', #13706, #20964 ) ; -#35146 = AXIS2_PLACEMENT_3D ( 'NONE', #17038, #32598, #20734 ) ; -#35147 = VECTOR ( 'NONE', #9629, 1000.000000000000000 ) ; -#35149 = EDGE_LOOP ( 'NONE', ( #40409, #30988, #14297, #33203 ) ) ; -#35148 = CARTESIAN_POINT ( 'NONE', ( -20.50049831744469842, 193.8789906621226180, 103.5560030610153035 ) ) ; -#35150 = ORIENTED_EDGE ( 'NONE', *, *, #6433, .F. ) ; -#35151 = EDGE_LOOP ( 'NONE', ( #1182, #17964, #21967 ) ) ; -#35152 = EDGE_CURVE ( 'NONE', #802, #32145, #14729, .T. ) ; -#35153 = ORIENTED_EDGE ( 'NONE', *, *, #36027, .T. ) ; -#35154 = DIRECTION ( 'NONE', ( 0.0006039748319394905654, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#35155 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26227, #13943, #14156, #7796 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35156 = CARTESIAN_POINT ( 'NONE', ( 39.01817161878246054, 208.8753323438758684, 28.69844957298887067 ) ) ; -#35157 = ORIENTED_EDGE ( 'NONE', *, *, #38743, .F. ) ; -#35158 = FACE_BOUND ( 'NONE', #12598, .T. ) ; -#35159 = CARTESIAN_POINT ( 'NONE', ( -38.49678016213000831, 119.1204962500000022, 90.30251346168999760 ) ) ; -#35160 = CARTESIAN_POINT ( 'NONE', ( 28.46953594426098277, 131.0252485042709338, 89.88531577736306133 ) ) ; -#35161 = FACE_OUTER_BOUND ( 'NONE', #28029, .T. ) ; -#35162 = CARTESIAN_POINT ( 'NONE', ( -13.50000077916642560, 160.7384646679227558, 96.77047473222738461 ) ) ; -#35163 = ORIENTED_EDGE ( 'NONE', *, *, #27256, .T. ) ; -#35164 = DIRECTION ( 'NONE', ( 0.0001408373285424074114, -0.2255194992995608605, 0.9742386440706004569 ) ) ; -#35165 = ORIENTED_EDGE ( 'NONE', *, *, #24285, .T. ) ; -#35166 = CARTESIAN_POINT ( 'NONE', ( 41.88489195034309631, 131.9654069037970885, 291.5332465100412378 ) ) ; -#35167 = CYLINDRICAL_SURFACE ( 'NONE', #8989, 6.000000000000001776 ) ; -#35168 = CARTESIAN_POINT ( 'NONE', ( -25.98974790844193805, 191.1599268335846205, 106.8726442723167906 ) ) ; -#35169 = CARTESIAN_POINT ( 'NONE', ( -20.61078737510752035, 183.3266213687619484, 101.9896571849372435 ) ) ; -#35170 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #26582, #39026, #26377, #29846 ), - .UNSPECIFIED., .F., .F. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 2.231945410930857410, 2.405425884341014342 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9974936158455707247, 0.9974936158455707247, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#35171 = CARTESIAN_POINT ( 'NONE', ( 41.45122645698029373, 120.4517748362497116, 90.34423067234534699 ) ) ; -#35172 = ORIENTED_EDGE ( 'NONE', *, *, #5377, .T. ) ; -#35173 = ORIENTED_EDGE ( 'NONE', *, *, #15549, .F. ) ; -#35174 = VECTOR ( 'NONE', #5468, 1000.000000000000000 ) ; -#35175 = CARTESIAN_POINT ( 'NONE', ( -15.83323216943059286, 160.7053846678046511, 96.93530097182505756 ) ) ; -#35176 = CARTESIAN_POINT ( 'NONE', ( -49.68457868370908415, 77.14301703112184327, 322.0012719045439553 ) ) ; -#35177 = CARTESIAN_POINT ( 'NONE', ( -13.54340897191000082, 191.1065010711000127, 28.07991271570000080 ) ) ; -#35178 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474981076715680, 160.6646604414378317, 99.31104281998236161 ) ) ; -#35179 = CIRCLE ( 'NONE', #25475, 5.999999999874873424 ) ; -#35180 = AXIS2_PLACEMENT_3D ( 'NONE', #31313, #35144, #12699 ) ; -#35181 = ORIENTED_EDGE ( 'NONE', *, *, #36409, .F. ) ; -#35182 = ADVANCED_FACE ( 'NONE', ( #26795 ), #35747, .T. ) ; -#35183 = ORIENTED_EDGE ( 'NONE', *, *, #14868, .T. ) ; -#35184 = CARTESIAN_POINT ( 'NONE', ( -25.50801647358826330, 207.5985922142114646, 76.64904513840518518 ) ) ; -#35185 = CARTESIAN_POINT ( 'NONE', ( -20.35337581324051115, 211.0888623383745255, 73.40409155960517751 ) ) ; -#35186 = ADVANCED_FACE ( 'NONE', ( #33104 ), #7445, .T. ) ; -#35187 = EDGE_LOOP ( 'NONE', ( #3571, #19128, #4182, #32462 ) ) ; -#35188 = CIRCLE ( 'NONE', #30672, 39.99999999998085798 ) ; -#35189 = PLANE ( 'NONE', #17981 ) ; -#35190 = ORIENTED_EDGE ( 'NONE', *, *, #9053, .T. ) ; -#35191 = DIRECTION ( 'NONE', ( -0.0002393070154807157670, -0.2243321270833621428, 0.9745127189987858873 ) ) ; -#35192 = CARTESIAN_POINT ( 'NONE', ( -19.99828328446849213, 119.4206128148076971, 90.31427449916516537 ) ) ; -#35193 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#35194 = CARTESIAN_POINT ( 'NONE', ( -20.00012105759590852, 119.3449816728147113, 87.27986393354494510 ) ) ; -#35195 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #36284, #1950 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35196 = EDGE_LOOP ( 'NONE', ( #3278, #2935, #33619, #8140 ) ) ; -#35197 = CARTESIAN_POINT ( 'NONE', ( 26.00563501201460070, 120.2359422930459942, 90.47773590256639409 ) ) ; -#35198 = CARTESIAN_POINT ( 'NONE', ( -15.93427371774434498, 152.6093780528373998, 94.89519699369660088 ) ) ; -#35199 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32826, #1757, #26309, #4806 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35201 = CARTESIAN_POINT ( 'NONE', ( -8.423747253435195148, 151.9722686346081844, 94.74357249814669046 ) ) ; -#35200 = CARTESIAN_POINT ( 'NONE', ( 20.48136443024816344, 209.7093559074854454, 75.54613107284740181 ) ) ; -#35202 = AXIS2_PLACEMENT_3D ( 'NONE', #2176, #20145, #29571 ) ; -#35203 = EDGE_CURVE ( 'NONE', #10734, #8110, #27078, .T. ) ; -#35204 = FACE_OUTER_BOUND ( 'NONE', #28713, .T. ) ; -#35205 = FACE_OUTER_BOUND ( 'NONE', #34861, .T. ) ; -#35206 = EDGE_LOOP ( 'NONE', ( #9287, #33813, #29255, #4345 ) ) ; -#35207 = CARTESIAN_POINT ( 'NONE', ( 29.62444488996374403, 185.2955461510884732, 104.9796392865966652 ) ) ; -#35208 = CIRCLE ( 'NONE', #13690, 4.999999999999990230 ) ; -#35209 = CIRCLE ( 'NONE', #17592, 2.500000000003542056 ) ; -#35210 = DIRECTION ( 'NONE', ( 0.1305263947718645068, -0.9660168729586927627, -0.2231014599391233644 ) ) ; -#35211 = ORIENTED_EDGE ( 'NONE', *, *, #34846, .T. ) ; -#35212 = ORIENTED_EDGE ( 'NONE', *, *, #11536, .T. ) ; -#35213 = CARTESIAN_POINT ( 'NONE', ( 39.06348233968999750, 118.7303302136000127, 89.50758646506000105 ) ) ; -#35214 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#35215 = CARTESIAN_POINT ( 'NONE', ( 5.667983148732107956, 187.2950682004077407, 105.4557345120219480 ) ) ; -#35216 = CARTESIAN_POINT ( 'NONE', ( -2.813949932869999948, 190.8925433558999885, 106.6795638709999992 ) ) ; -#35217 = VERTEX_POINT ( 'NONE', #30061 ) ; -#35218 = EDGE_CURVE ( 'NONE', #34375, #18635, #900, .T. ) ; -#35219 = VERTEX_POINT ( 'NONE', #32711 ) ; -#35220 = CARTESIAN_POINT ( 'NONE', ( 28.45310815370287472, 181.6925917411357148, 101.5827842051393617 ) ) ; -#35221 = CARTESIAN_POINT ( 'NONE', ( -23.36442558744370857, 134.3470799714359885, 93.67172226588378692 ) ) ; -#35222 = FACE_OUTER_BOUND ( 'NONE', #15419, .T. ) ; -#35223 = EDGE_LOOP ( 'NONE', ( #26273, #27195, #18016, #1456, #20744, #39692, #1652, #29428, #22827, #32859, #2142, #32138 ) ) ; -#35224 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #28462, #29057, #6563, #10055 ), - ( #6969, #3898, #13523, #31938 ), - ( #32134, #38053, #7369, #435 ), - ( #16563, #28858, #38447, #10466 ), - ( #37656, #6765, #25407, #12711 ), - ( #28267, #35362, #9655, #28661 ), - ( #234, #12928, #19440, #22131 ), - ( #37856, #9863, #25607, #836 ), - ( #31741, #2424, #4299, #39811 ), - ( #32525, #26404, #36965, #4503 ), - ( #24309, #24511, #30632, #33473 ), - ( #23131, #17724, #14696, #10665 ), - ( #27385, #8351, #13720, #40020 ), - ( #5682, #8761, #20813, #11827 ), - ( #29464, #32331, #1237, #12025 ), - ( #36750, #21226, #19826, #33270 ), - ( #17927, #36555, #16770, #26209 ), - ( #33676, #18130, #38642, #2626 ), - ( #15092, #30218, #35554, #29268 ), - ( #7575, #20038, #38849, #5260 ), - ( #10867, #5466, #16965, #30431 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.0006433392557888000136, 0.000000000000000000, 0.001296682710712999910, 0.002598803319325999894, 0.005203044536554999634, 0.01041152697101000064, 0.01562000940545999958, 0.02082849183991999920, 0.03124545670882999948, 0.04166242157774999871, 0.06249635131556999929, 0.08333028105339999880, 0.1249981405290000042, 0.1666660000046999990, 0.2500017189559000097, 0.3333374379073000271, 0.5000030671676000127, 0.6666686964278000227, 0.9999999999941000528 ), - ( 0.1831668826576000053, 0.8168555497535000542 ), - .UNSPECIFIED. ) ; -#35225 = CARTESIAN_POINT ( 'NONE', ( -25.99151835185281456, 191.8641524188973904, 103.9340199701208292 ) ) ; -#35226 = VERTEX_POINT ( 'NONE', #21061 ) ; -#35227 = EDGE_CURVE ( 'NONE', #14541, #4671, #28475, .T. ) ; -#35228 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -9.100188726436994447E-16, -0.0006039748319385940386 ) ) ; -#35229 = EDGE_CURVE ( 'NONE', #19772, #13769, #33308, .T. ) ; -#35230 = EDGE_LOOP ( 'NONE', ( #4221, #24861, #39070, #12997, #21334 ) ) ; -#35231 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748611833, 132.4103119505575421, 92.77713868752084636 ) ) ; -#35232 = AXIS2_PLACEMENT_3D ( 'NONE', #34334, #15733, #24569 ) ; -#35233 = AXIS2_PLACEMENT_3D ( 'NONE', #4396, #16860, #29364 ) ; -#35234 = FACE_OUTER_BOUND ( 'NONE', #27018, .T. ) ; -#35235 = CARTESIAN_POINT ( 'NONE', ( -0.02657825335728297364, 128.5632152146144449, 291.5585599878308471 ) ) ; -#35236 = VERTEX_POINT ( 'NONE', #17346 ) ; -#35237 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17854, #9091, #24445, #39742 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35238 = CIRCLE ( 'NONE', #2658, 5.999999999999789502 ) ; -#35239 = CARTESIAN_POINT ( 'NONE', ( -25.50125996552617025, 117.7859951928936653, 87.78302187812163027 ) ) ; -#35240 = CARTESIAN_POINT ( 'NONE', ( -38.89729174575438009, 162.5740202740032316, 197.7397972150318424 ) ) ; -#35241 = CARTESIAN_POINT ( 'NONE', ( -35.95586794417999954, 218.5902260770999987, 73.08022052566002458 ) ) ; -#35242 = CARTESIAN_POINT ( 'NONE', ( -23.33162176516600184, 170.5609214779667582, 152.0219650776430740 ) ) ; -#35243 = ORIENTED_EDGE ( 'NONE', *, *, #31895, .T. ) ; -#35244 = CARTESIAN_POINT ( 'NONE', ( 5.666344154416935730, 188.3446284886178717, 103.1322861692058268 ) ) ; -#35245 = CARTESIAN_POINT ( 'NONE', ( -35.31100466289999673, 112.3975524853999985, 90.42448594319000676 ) ) ; -#35246 = ORIENTED_EDGE ( 'NONE', *, *, #35527, .T. ) ; -#35247 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29666, #38644, #14335, #5318 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.0004271504751604244632 ), - .UNSPECIFIED. ) ; -#35248 = ORIENTED_EDGE ( 'NONE', *, *, #26911, .F. ) ; -#35249 = DIRECTION ( 'NONE', ( -0.0005884949961234662175, 0.2249510543439052490, -0.9743698870671265722 ) ) ; -#35250 = CARTESIAN_POINT ( 'NONE', ( 25.70348165864240997, 190.8952330040411312, 106.4458477250591812 ) ) ; -#35251 = CARTESIAN_POINT ( 'NONE', ( -30.48419462517739831, 161.7460374893126414, 187.3626201019992550 ) ) ; -#35252 = CARTESIAN_POINT ( 'NONE', ( -13.50742204590874351, 123.6898730104831117, 91.29604175845440750 ) ) ; -#35253 = ORIENTED_EDGE ( 'NONE', *, *, #27898, .T. ) ; -#35254 = FACE_BOUND ( 'NONE', #5187, .T. ) ; -#35255 = VERTEX_POINT ( 'NONE', #2251 ) ; -#35256 = ORIENTED_EDGE ( 'NONE', *, *, #40373, .F. ) ; -#35257 = DIRECTION ( 'NONE', ( 0.0005884949961246157971, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#35259 = CIRCLE ( 'NONE', #31384, 1.749999999975493381 ) ; -#35258 = FACE_BOUND ( 'NONE', #38733, .T. ) ; -#35260 = VECTOR ( 'NONE', #6667, 1000.000000000000000 ) ; -#35261 = FACE_OUTER_BOUND ( 'NONE', #13466, .T. ) ; -#35262 = EDGE_CURVE ( 'NONE', #1497, #29487, #5768, .T. ) ; -#35263 = VECTOR ( 'NONE', #35154, 1000.000000000000114 ) ; -#35264 = EDGE_LOOP ( 'NONE', ( #20737, #9229, #1546, #4123 ) ) ; -#35265 = FACE_OUTER_BOUND ( 'NONE', #29167, .T. ) ; -#35266 = CARTESIAN_POINT ( 'NONE', ( 35.93134371480000055, 113.3923198079000088, 87.62367743737000580 ) ) ; -#35267 = CARTESIAN_POINT ( 'NONE', ( 36.18548434713000006, 191.5942538933000208, 103.9704995337999947 ) ) ; -#35268 = DIRECTION ( 'NONE', ( 0.0002393071182785538528, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#35269 = ADVANCED_FACE ( 'NONE', ( #20223 ), #14317, .T. ) ; -#35270 = FACE_OUTER_BOUND ( 'NONE', #10174, .T. ) ; -#35271 = EDGE_LOOP ( 'NONE', ( #28256, #11300, #11831, #25651, #10881, #8464, #37593 ) ) ; -#35272 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559296 ) ) ; -#35273 = LINE ( 'NONE', #10572, #36171 ) ; -#35274 = CARTESIAN_POINT ( 'NONE', ( -35.93776700278350233, 192.3813625493561119, 104.4100568030667660 ) ) ; -#35275 = EDGE_CURVE ( 'NONE', #27523, #626, #23146, .T. ) ; -#35276 = FACE_OUTER_BOUND ( 'NONE', #32154, .T. ) ; -#35277 = EDGE_CURVE ( 'NONE', #32551, #38636, #10102, .T. ) ; -#35278 = CARTESIAN_POINT ( 'NONE', ( 4.773610636429394205, 135.2457129246372745, 90.87397125982342061 ) ) ; -#35279 = ORIENTED_EDGE ( 'NONE', *, *, #30331, .F. ) ; -#35280 = LINE ( 'NONE', #38179, #12206 ) ; -#35281 = ADVANCED_FACE ( 'NONE', ( #40048 ), #18162, .F. ) ; -#35282 = CARTESIAN_POINT ( 'NONE', ( 0.8177372182200383088, 189.0164223347565837, 103.6894118143446946 ) ) ; -#35283 = CARTESIAN_POINT ( 'NONE', ( -2.088166312711679407, 189.0044830006292500, 106.3682207543857601 ) ) ; -#35284 = CARTESIAN_POINT ( 'NONE', ( 12.63704587999257356, 130.1783046459918296, 92.54531033006117013 ) ) ; -#35285 = FACE_OUTER_BOUND ( 'NONE', #4559, .T. ) ; -#35286 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825933886502897, 0.0005734119020677233775 ) ) ; -#35287 = CARTESIAN_POINT ( 'NONE', ( -3.537752371395798789, 168.4800613451581910, 98.55175200207808928 ) ) ; -#35288 = AXIS2_PLACEMENT_3D ( 'NONE', #24473, #30796, #40375 ) ; -#35289 = CIRCLE ( 'NONE', #17670, 2.999999999999997335 ) ; -#35290 = CARTESIAN_POINT ( 'NONE', ( -21.21281377555379422, 136.1368903374970500, 93.66117170127317593 ) ) ; -#35291 = DIRECTION ( 'NONE', ( 0.0005884949961255130828, -0.2249510543439061094, 0.9743698870671263501 ) ) ; -#35292 = EDGE_LOOP ( 'NONE', ( #17868, #2360, #34465, #2119 ) ) ; -#35293 = CIRCLE ( 'NONE', #17673, 2.000000000000011546 ) ; -#35294 = CONICAL_SURFACE ( 'NONE', #9891, 2.503171224438736964, 0.7853981633558574371 ) ; -#35295 = CARTESIAN_POINT ( 'NONE', ( -9.584790827646999745, 124.5525812144000071, 88.67051502255999651 ) ) ; -#35296 = EDGE_LOOP ( 'NONE', ( #26838, #9699, #31514, #12365 ) ) ; -#35297 = DIRECTION ( 'NONE', ( 0.6068735732728639531, 0.7743428331745974003, 0.1791581501750992012 ) ) ; -#35298 = CARTESIAN_POINT ( 'NONE', ( 5.667234821329739880, 181.5641799568915076, 104.1756018025407826 ) ) ; -#35299 = CARTESIAN_POINT ( 'NONE', ( 37.54454435905000764, 191.1563387468999906, 106.1841328374000000 ) ) ; -#35300 = CARTESIAN_POINT ( 'NONE', ( -41.29162907220920431, 121.2433985071746605, 87.66910399198238224 ) ) ; -#35301 = CARTESIAN_POINT ( 'NONE', ( -5.659900684199740795, 130.3459505314356477, 92.82798007168634058 ) ) ; -#35302 = CARTESIAN_POINT ( 'NONE', ( -22.32836078412000091, 181.4981852331999903, 104.6474796210000022 ) ) ; -#35303 = CARTESIAN_POINT ( 'NONE', ( 13.50302196691861845, 188.2012266813463555, 103.2180489347859691 ) ) ; -#35304 = VERTEX_POINT ( 'NONE', #2665 ) ; -#35305 = CARTESIAN_POINT ( 'NONE', ( -5.669494960691238816, 181.5159006446741046, 104.2113328898530398 ) ) ; -#35306 = CARTESIAN_POINT ( 'NONE', ( -2.421663575686999970, 209.3771755197000175, 75.56751031131001639 ) ) ; -#35307 = CARTESIAN_POINT ( 'NONE', ( -77.81023841339903413, 193.0606421333745288, 189.3780882460293924 ) ) ; -#35308 = EDGE_CURVE ( 'NONE', #31880, #15231, #14664, .T. ) ; -#35309 = FACE_OUTER_BOUND ( 'NONE', #30161, .T. ) ; -#35310 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30429, #27383, #33673, #2215, #39808, #5878, #39606, #18330, #20809, #5680 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.002613673017241889291, 0.2519602547629314349, 0.5013068365086209566, 0.7506534182543105338, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35311 = ORIENTED_EDGE ( 'NONE', *, *, #23025, .F. ) ; -#35312 = CARTESIAN_POINT ( 'NONE', ( 6.035242028283734683, 177.6060540791196161, 100.8120970415375837 ) ) ; -#35313 = VECTOR ( 'NONE', #5062, 1000.000000000000000 ) ; -#35314 = ORIENTED_EDGE ( 'NONE', *, *, #9697, .T. ) ; -#35315 = AXIS2_PLACEMENT_3D ( 'NONE', #8468, #18043, #20930 ) ; -#35316 = ADVANCED_FACE ( 'NONE', ( #15130 ), #21839, .T. ) ; -#35317 = VECTOR ( 'NONE', #16211, 1000.000000000000114 ) ; -#35318 = CARTESIAN_POINT ( 'NONE', ( 20.50029381459099653, 174.4060969901985345, 100.4185135690063362 ) ) ; -#35319 = ORIENTED_EDGE ( 'NONE', *, *, #29534, .F. ) ; -#35320 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385906776 ) ) ; -#35321 = EDGE_CURVE ( 'NONE', #11123, #36191, #37400, .T. ) ; -#35322 = CARTESIAN_POINT ( 'NONE', ( -15.56569021295148225, 147.2757502908357878, 179.8547186837703293 ) ) ; -#35323 = DIRECTION ( 'NONE', ( -0.6319545750169662801, -0.7750053350989876133, 0.0003816847278651969611 ) ) ; -#35324 = CARTESIAN_POINT ( 'NONE', ( -12.63669129660635271, 130.6696852525088559, 90.12771377329683276 ) ) ; -#35325 = CARTESIAN_POINT ( 'NONE', ( -94.40216589637994105, 221.9412051121879301, 195.0241205818432491 ) ) ; -#35326 = EDGE_CURVE ( 'NONE', #14324, #23012, #11607, .T. ) ; -#35327 = ORIENTED_EDGE ( 'NONE', *, *, #24163, .T. ) ; -#35328 = FACE_OUTER_BOUND ( 'NONE', #13616, .T. ) ; -#35329 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825948087824765, 0.0005734119017360681013 ) ) ; -#35330 = CARTESIAN_POINT ( 'NONE', ( -14.89266236493446094, 176.0557335979108018, 100.6496897840496985 ) ) ; -#35331 = CARTESIAN_POINT ( 'NONE', ( -20.51841363792658157, 206.2670792612280479, 75.17265414788577971 ) ) ; -#35332 = ORIENTED_EDGE ( 'NONE', *, *, #20188, .F. ) ; -#35333 = CARTESIAN_POINT ( 'NONE', ( 30.05084665331233040, 185.2025551396690730, 102.9053044903158849 ) ) ; -#35334 = CARTESIAN_POINT ( 'NONE', ( 2.480477375138003371, 209.5058064405000096, 73.55699242858000275 ) ) ; -#35335 = DIRECTION ( 'NONE', ( 0.9999998268369701959, 0.0001323828034717448464, -0.0005734115650244319892 ) ) ; -#35336 = CIRCLE ( 'NONE', #21023, 2.500000000096262998 ) ; -#35337 = CARTESIAN_POINT ( 'NONE', ( 25.37605402239000085, 191.6202422146000401, 106.2585664214000047 ) ) ; -#35338 = AXIS2_PLACEMENT_3D ( 'NONE', #6693, #31663, #38191 ) ; -#35339 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748613609, 132.4103119505519146, 92.77713868754518955 ) ) ; -#35340 = CARTESIAN_POINT ( 'NONE', ( 20.48054274988260559, 208.2527943622279167, 73.78783556188518844 ) ) ; -#35341 = CARTESIAN_POINT ( 'NONE', ( 38.48474620529000134, 118.5518808382999936, 89.80791548221999676 ) ) ; -#35342 = VERTEX_POINT ( 'NONE', #24343 ) ; -#35343 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498906470, 179.0675991014012425, 104.0619761093222309 ) ) ; -#35344 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#35345 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#35347 = ORIENTED_EDGE ( 'NONE', *, *, #442, .T. ) ; -#35346 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971542365 ) ) ; -#35348 = VERTEX_POINT ( 'NONE', #18972 ) ; -#35349 = EDGE_LOOP ( 'NONE', ( #38723, #30346, #1461, #38704 ) ) ; -#35350 = EDGE_LOOP ( 'NONE', ( #23001, #31322, #32584, #16055 ) ) ; -#35351 = CYLINDRICAL_SURFACE ( 'NONE', #13750, 2.000000000000014655 ) ; -#35352 = EDGE_CURVE ( 'NONE', #35446, #27307, #30867, .T. ) ; -#35353 = EDGE_CURVE ( 'NONE', #11983, #12706, #12064, .T. ) ; -#35354 = CARTESIAN_POINT ( 'NONE', ( -13.66810824591000006, 129.8577187306999861, 92.72010578062001684 ) ) ; -#35355 = CARTESIAN_POINT ( 'NONE', ( 76.10630783110904929, 156.2604783516070768, 96.19568201162677212 ) ) ; -#35356 = ADVANCED_FACE ( 'NONE', ( #178 ), #33709, .T. ) ; -#35357 = EDGE_CURVE ( 'NONE', #13536, #32994, #36177, .T. ) ; -#35358 = VERTEX_POINT ( 'NONE', #33912 ) ; -#35359 = CARTESIAN_POINT ( 'NONE', ( 38.56885418974432866, 118.4610218664272452, 89.66265752007532797 ) ) ; -#35360 = FACE_OUTER_BOUND ( 'NONE', #15580, .T. ) ; -#35361 = CARTESIAN_POINT ( 'NONE', ( 6.271009700395496544, 163.8321258783347787, 97.98591366900288335 ) ) ; -#35362 = CARTESIAN_POINT ( 'NONE', ( -38.13584639906000007, 119.0796675878000030, 87.44109768843999575 ) ) ; -#35363 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319370571820 ) ) ; -#35364 = ORIENTED_EDGE ( 'NONE', *, *, #29013, .F. ) ; -#35365 = EDGE_CURVE ( 'NONE', #1422, #24833, #3234, .T. ) ; -#35366 = CYLINDRICAL_SURFACE ( 'NONE', #8854, 7.000000000000007994 ) ; -#35367 = VERTEX_POINT ( 'NONE', #21672 ) ; -#35368 = CARTESIAN_POINT ( 'NONE', ( -3.169891510579954996, 184.7168900243609926, 102.3001085725441754 ) ) ; -#35369 = CARTESIAN_POINT ( 'NONE', ( -25.99525330005595691, 191.0045489946515147, 106.8444116979025296 ) ) ; -#35370 = CARTESIAN_POINT ( 'NONE', ( -21.44693686545786449, 130.1487540525002657, 89.71308199639462089 ) ) ; -#35371 = EDGE_LOOP ( 'NONE', ( #40250, #23289, #11802, #23490 ) ) ; -#35372 = AXIS2_PLACEMENT_3D ( 'NONE', #28268, #12125, #24610 ) ; -#35373 = EDGE_CURVE ( 'NONE', #34038, #29822, #6107, .T. ) ; -#35374 = ORIENTED_EDGE ( 'NONE', *, *, #20759, .T. ) ; -#35375 = CARTESIAN_POINT ( 'NONE', ( -2.617492821688919946, 189.8265782606199821, 103.4779101626839974 ) ) ; -#35376 = CONICAL_SURFACE ( 'NONE', #34736, 2.502999999816233778, 0.7853981634033742054 ) ; -#35377 = CARTESIAN_POINT ( 'NONE', ( -8.472443769278077852, 160.9680296444896328, 99.38619809799159555 ) ) ; -#35378 = CARTESIAN_POINT ( 'NONE', ( 27.71217996750916512, 149.2638841111731267, 291.5418064729402658 ) ) ; -#35379 = ORIENTED_EDGE ( 'NONE', *, *, #33036, .T. ) ; -#35380 = EDGE_LOOP ( 'NONE', ( #26893, #4894, #18936, #3151 ) ) ; -#35381 = DIRECTION ( 'NONE', ( -0.0005884949961181158967, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#35382 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 177.2079272831676349, 102.1149241508814072 ) ) ; -#35383 = ORIENTED_EDGE ( 'NONE', *, *, #9048, .T. ) ; -#35384 = CARTESIAN_POINT ( 'NONE', ( -42.09262134878026984, 120.7842458853916270, 90.64249682962069699 ) ) ; -#35385 = ORIENTED_EDGE ( 'NONE', *, *, #14172, .F. ) ; -#35386 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#35387 = CARTESIAN_POINT ( 'NONE', ( -5.669876936568486236, 184.1246770555471244, 102.1617171593053399 ) ) ; -#35388 = DIRECTION ( 'NONE', ( -0.4292255961656983310, -0.3880767888785662256, -0.8155745174598710845 ) ) ; -#35389 = VERTEX_POINT ( 'NONE', #3038 ) ; -#35390 = CARTESIAN_POINT ( 'NONE', ( 26.00229951832000097, 120.2367750635000050, 90.47450760225000010 ) ) ; -#35391 = CARTESIAN_POINT ( 'NONE', ( -23.36030038340052428, 176.7386739072689181, 103.0361307674479150 ) ) ; -#35392 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #39630, #5701, #20834, #18146 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35393 = AXIS2_PLACEMENT_3D ( 'NONE', #9169, #11633, #18138 ) ; -#35395 = CARTESIAN_POINT ( 'NONE', ( -13.49052885539015278, 188.3420772061585353, 103.1432726234667427 ) ) ; -#35394 = LINE ( 'NONE', #32561, #857 ) ; -#35396 = CIRCLE ( 'NONE', #1480, 1.999999999958659069 ) ; -#35397 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921589622, -0.2249510932971540422 ) ) ; -#35398 = ORIENTED_EDGE ( 'NONE', *, *, #14176, .F. ) ; -#35399 = CARTESIAN_POINT ( 'NONE', ( -16.54155363837897852, 122.5136119920553739, 174.6120670712284948 ) ) ; -#35400 = CYLINDRICAL_SURFACE ( 'NONE', #18446, 8.999999999999994671 ) ; -#35401 = CARTESIAN_POINT ( 'NONE', ( 39.01961100019079964, 121.1792603210674883, 123.5275808914922209 ) ) ; -#35402 = EDGE_CURVE ( 'NONE', #23549, #22970, #15686, .T. ) ; -#35403 = ORIENTED_EDGE ( 'NONE', *, *, #40461, .F. ) ; -#35404 = EDGE_CURVE ( 'NONE', #21943, #31524, #25141, .T. ) ; -#35405 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #7756, #19813, #4696, #17154 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 5.624397334887860644, 5.624458001010823160 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999996933017776, 0.9999999996933017776, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#35406 = ORIENTED_EDGE ( 'NONE', *, *, #17740, .T. ) ; -#35407 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 77.27946979429634666, 315.0857197240631535 ) ) ; -#35408 = CARTESIAN_POINT ( 'NONE', ( -5.668109640120363224, 183.4491314654635801, 105.0878260507181778 ) ) ; -#35409 = CARTESIAN_POINT ( 'NONE', ( -2.687146238409999999, 191.2630064568000137, 104.0676670321000046 ) ) ; -#35410 = ORIENTED_EDGE ( 'NONE', *, *, #24342, .F. ) ; -#35411 = VERTEX_POINT ( 'NONE', #3830 ) ; -#35412 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921570748, 0.2249510932971625354 ) ) ; -#35413 = CARTESIAN_POINT ( 'NONE', ( -20.01528478583289328, 211.0902260919000355, 76.07370820307239967 ) ) ; -#35414 = ORIENTED_EDGE ( 'NONE', *, *, #1041, .T. ) ; -#35415 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319411744398 ) ) ; -#35416 = CIRCLE ( 'NONE', #21755, 2.250000000020502711 ) ; -#35417 = CARTESIAN_POINT ( 'NONE', ( -38.46044104337040181, 118.4609804511839286, 89.70916240556151422 ) ) ; -#35418 = AXIS2_PLACEMENT_3D ( 'NONE', #26296, #36492, #20963 ) ; -#35419 = CARTESIAN_POINT ( 'NONE', ( 3.080954507411690191, 190.8735473523590258, 106.8151959787420395 ) ) ; -#35420 = ORIENTED_EDGE ( 'NONE', *, *, #23813, .T. ) ; -#35421 = CARTESIAN_POINT ( 'NONE', ( -13.49836187949100896, 187.2925309122496458, 105.4667247227192490 ) ) ; -#35422 = EDGE_CURVE ( 'NONE', #10112, #15231, #1292, .T. ) ; -#35423 = CIRCLE ( 'NONE', #23708, 2.000000000000011546 ) ; -#35424 = CARTESIAN_POINT ( 'NONE', ( -2.252216305542000363, 190.5226222670000027, 106.0270197027000165 ) ) ; -#35425 = CARTESIAN_POINT ( 'NONE', ( 20.06084863214461222, 152.5895191265099413, 94.86887204652431649 ) ) ; -#35426 = CARTESIAN_POINT ( 'NONE', ( -28.52494644200928064, 186.7521494213145559, 105.8641958179564568 ) ) ; -#35427 = EDGE_LOOP ( 'NONE', ( #9724, #201, #12933, #9000 ) ) ; -#35428 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971579558 ) ) ; -#35429 = DIRECTION ( 'NONE', ( -0.7933533411653073131, -0.5931840316265225566, -0.1368326740407718733 ) ) ; -#35430 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041179888821108E-05, -0.0002331579774886881676 ) ) ; -#35431 = PLANE ( 'NONE', #9569 ) ; -#35432 = ORIENTED_EDGE ( 'NONE', *, *, #30227, .F. ) ; -#35433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #4120, #13744, #26432, #1467 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35434 = CARTESIAN_POINT ( 'NONE', ( 44.05412252654215877, 112.8136638115830834, 88.23716000583523567 ) ) ; -#35435 = CARTESIAN_POINT ( 'NONE', ( -36.00659248622000064, 115.9892317533000039, 90.43727891404999752 ) ) ; -#35436 = ORIENTED_EDGE ( 'NONE', *, *, #11434, .F. ) ; -#35437 = CIRCLE ( 'NONE', #19118, 4.999999999999990230 ) ; -#35438 = ORIENTED_EDGE ( 'NONE', *, *, #25115, .T. ) ; -#35439 = FACE_OUTER_BOUND ( 'NONE', #28335, .T. ) ; -#35440 = CARTESIAN_POINT ( 'NONE', ( 25.49922775442078660, 119.7987478901816019, 87.80838759742935906 ) ) ; -#35441 = CARTESIAN_POINT ( 'NONE', ( -13.49994987718039852, 124.0778690969012956, 91.05358209079831511 ) ) ; -#35442 = EDGE_CURVE ( 'NONE', #14988, #9823, #25231, .T. ) ; -#35444 = ORIENTED_EDGE ( 'NONE', *, *, #30788, .F. ) ; -#35443 = CIRCLE ( 'NONE', #17832, 2.500000000044359627 ) ; -#35445 = EDGE_CURVE ( 'NONE', #9915, #28941, #16706, .T. ) ; -#35446 = VERTEX_POINT ( 'NONE', #35095 ) ; -#35447 = CARTESIAN_POINT ( 'NONE', ( -20.49852834234505039, 173.9502348336490059, 102.3906403256567756 ) ) ; -#35448 = ORIENTED_EDGE ( 'NONE', *, *, #25861, .F. ) ; -#35449 = ORIENTED_EDGE ( 'NONE', *, *, #27662, .T. ) ; -#35450 = ORIENTED_EDGE ( 'NONE', *, *, #39623, .F. ) ; -#35451 = CARTESIAN_POINT ( 'NONE', ( -6.036395961976134927, 177.5005587908726739, 100.8839412545769250 ) ) ; -#35452 = DIRECTION ( 'NONE', ( 0.0006039748319394907822, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#35453 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 1.023300813872001534E-14, 0.7066795775160008564 ) ) ; -#35454 = ORIENTED_EDGE ( 'NONE', *, *, #19593, .T. ) ; -#35455 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32660, #11604, #36536, #1786, #38989, #39594, #17301, #17506, #32853, #35909 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 3.469446951953614189E-18, 0.0004333965559159966220, 0.0008667931118319897746, 0.001300189667747982981, 0.001733586223663976080 ), - .UNSPECIFIED. ) ; -#35456 = CARTESIAN_POINT ( 'NONE', ( -45.58331382029645340, 187.5930969719299526, 105.5207863728867892 ) ) ; -#35457 = LINE ( 'NONE', #32234, #16525 ) ; -#35458 = CARTESIAN_POINT ( 'NONE', ( 37.34957747189999822, 117.2309573341999993, 87.81489789069999574 ) ) ; -#35459 = DIRECTION ( 'NONE', ( -0.0005884949961244385300, 0.2249510543439064425, -0.9743698870671262391 ) ) ; -#35460 = CARTESIAN_POINT ( 'NONE', ( -16.89916622456234307, 146.7648798331369164, 183.8224697288354150 ) ) ; -#35461 = ORIENTED_EDGE ( 'NONE', *, *, #5580, .F. ) ; -#35462 = CARTESIAN_POINT ( 'NONE', ( -0.4015627584113334314, 211.0000000000000000, 162.9824824849015670 ) ) ; -#35463 = VERTEX_POINT ( 'NONE', #4032 ) ; -#35464 = CARTESIAN_POINT ( 'NONE', ( -20.51811334323642910, 208.1210146940394452, 76.12436689659175215 ) ) ; -#35465 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; -#35466 = CARTESIAN_POINT ( 'NONE', ( -25.78009354425976696, 116.9859542164271318, 90.28335536971354713 ) ) ; -#35467 = CARTESIAN_POINT ( 'NONE', ( 44.87323697063200001, 186.3386389082236860, 107.7764265916358113 ) ) ; -#35468 = EDGE_LOOP ( 'NONE', ( #5758, #8549, #38478, #15336 ) ) ; -#35469 = CARTESIAN_POINT ( 'NONE', ( -22.59538023922501893, 158.3009455569410022, 96.21322226912832321 ) ) ; -#35470 = EDGE_CURVE ( 'NONE', #35915, #13040, #15945, .T. ) ; -#35471 = CARTESIAN_POINT ( 'NONE', ( 0.6422618799637411779, 189.0014566651755104, 103.6871524997584686 ) ) ; -#35472 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19945, #13240, #38176, #38368 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35473 = CIRCLE ( 'NONE', #21810, 5.500000000097090336 ) ; -#35474 = CYLINDRICAL_SURFACE ( 'NONE', #21512, 2.000000000000014655 ) ; -#35475 = DIRECTION ( 'NONE', ( 0.9999999713660512324, -5.390041178582662422E-05, 0.0002331579774919529443 ) ) ; -#35476 = CONICAL_SURFACE ( 'NONE', #16550, 3.003200675574637657, 0.7854054504739538256 ) ; -#35477 = CARTESIAN_POINT ( 'NONE', ( -25.62261855603000171, 191.5186909694000121, 104.2706622284000133 ) ) ; -#35478 = CARTESIAN_POINT ( 'NONE', ( -3.893460976763133630, 148.0324882894217069, 129.7501302146819171 ) ) ; -#35479 = PLANE ( 'NONE', #1976 ) ; -#35480 = VECTOR ( 'NONE', #10009, 1000.000000000000227 ) ; -#35481 = ORIENTED_EDGE ( 'NONE', *, *, #13429, .T. ) ; -#35482 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1838, #33507, #39843, #11857 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0006366642741689145695, 0.003636664277312400863 ), - .UNSPECIFIED. ) ; -#35483 = EDGE_CURVE ( 'NONE', #81, #20733, #21197, .T. ) ; -#35484 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#35485 = EDGE_CURVE ( 'NONE', #21843, #1318, #29203, .T. ) ; -#35486 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971560684 ) ) ; -#35487 = ORIENTED_EDGE ( 'NONE', *, *, #22058, .T. ) ; -#35488 = CARTESIAN_POINT ( 'NONE', ( 22.99918985293999540, 115.6131156702015801, 87.75369723384940812 ) ) ; -#35489 = DIRECTION ( 'NONE', ( 0.0002393071182785117045, 0.2252352986010040525, -0.9743043687658490271 ) ) ; -#35490 = CARTESIAN_POINT ( 'NONE', ( 38.03365593150000024, 190.8184203288000163, 106.3742049819999949 ) ) ; -#35491 = CARTESIAN_POINT ( 'NONE', ( 36.08477202003000173, 192.3114799085000186, 105.7099035117999932 ) ) ; -#35492 = FACE_OUTER_BOUND ( 'NONE', #12662, .T. ) ; -#35493 = ADVANCED_FACE ( 'NONE', ( #972, #7105 ), #16308, .T. ) ; -#35494 = EDGE_CURVE ( 'NONE', #11054, #21690, #15006, .T. ) ; -#35495 = CARTESIAN_POINT ( 'NONE', ( 35.42398992542000258, 192.6597620198000129, 106.9956823543000013 ) ) ; -#35496 = ORIENTED_EDGE ( 'NONE', *, *, #25685, .F. ) ; -#35497 = AXIS2_PLACEMENT_3D ( 'NONE', #17200, #11285, #29899 ) ; -#35498 = ADVANCED_FACE ( 'NONE', ( #374 ), #1592, .T. ) ; -#35499 = CARTESIAN_POINT ( 'NONE', ( -13.49823342806667803, 137.5174304068248432, 94.49164181115173733 ) ) ; -#35500 = EDGE_CURVE ( 'NONE', #4793, #39471, #23791, .T. ) ; -#35501 = AXIS2_PLACEMENT_3D ( 'NONE', #15114, #21658, #30853 ) ; -#35502 = CARTESIAN_POINT ( 'NONE', ( -15.66509764276284145, 127.1445024449465677, 91.75281491938407896 ) ) ; -#35503 = CONICAL_SURFACE ( 'NONE', #31645, 4.500000040450202299, 0.7854058041405644897 ) ; -#35504 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#35505 = ORIENTED_EDGE ( 'NONE', *, *, #12189, .T. ) ; -#35506 = DIRECTION ( 'NONE', ( 0.0004225984616353902282, -0.2247404086662242728, 0.9744185805510271470 ) ) ; -#35507 = VECTOR ( 'NONE', #19164, 1000.000000000000227 ) ; -#35508 = VERTEX_POINT ( 'NONE', #16115 ) ; -#35509 = LINE ( 'NONE', #26163, #13002 ) ; -#35510 = ORIENTED_EDGE ( 'NONE', *, *, #15273, .F. ) ; -#35511 = CARTESIAN_POINT ( 'NONE', ( 36.26946023011016962, 191.9013689628361874, 106.3928143862155196 ) ) ; -#35512 = DIRECTION ( 'NONE', ( -0.0005884949833308949618, 0.2255194585710127986, -0.9742384859363193428 ) ) ; -#35513 = CARTESIAN_POINT ( 'NONE', ( 21.44693881909371669, 176.9241929811547038, 100.4861407201621120 ) ) ; -#35514 = CARTESIAN_POINT ( 'NONE', ( 39.05471716683091188, 128.1851843108063917, 89.22321456362486458 ) ) ; -#35515 = ORIENTED_EDGE ( 'NONE', *, *, #7444, .T. ) ; -#35516 = CARTESIAN_POINT ( 'NONE', ( 16.56072393625937167, 151.7650864655652185, 183.4529734625197648 ) ) ; -#35517 = LINE ( 'NONE', #4056, #38816 ) ; -#35518 = CARTESIAN_POINT ( 'NONE', ( 4.773550690431221710, 177.4841922203888203, 100.6254943855425097 ) ) ; -#35519 = CARTESIAN_POINT ( 'NONE', ( -22.78255965921956161, 158.2257193261845316, 98.76172871125201880 ) ) ; -#35520 = VERTEX_POINT ( 'NONE', #22472 ) ; -#35521 = CARTESIAN_POINT ( 'NONE', ( 12.63486156935002924, 128.4748385056542190, 89.81919559417828225 ) ) ; -#35522 = CIRCLE ( 'NONE', #36882, 2.500000000030778047 ) ; -#35523 = CARTESIAN_POINT ( 'NONE', ( 36.86608789098717409, 116.0808690289381957, 89.69631361914622403 ) ) ; -#35524 = CONICAL_SURFACE ( 'NONE', #31672, 2.502986258519634966, 0.7853981633282146602 ) ; -#35525 = CONICAL_SURFACE ( 'NONE', #32304, 2.749999999872844381, 0.7853981633697728615 ) ; -#35526 = CARTESIAN_POINT ( 'NONE', ( -2.603735047448787920, 191.4510372720596081, 104.1965523528617155 ) ) ; -#35527 = EDGE_CURVE ( 'NONE', #11101, #1951, #6147, .T. ) ; -#35528 = CARTESIAN_POINT ( 'NONE', ( -37.31520213808180131, 125.3838658331930560, 91.70151751858605849 ) ) ; -#35529 = CIRCLE ( 'NONE', #26447, 8.000001494568982352 ) ; -#35530 = CARTESIAN_POINT ( 'NONE', ( 5.666342391474075590, 184.1261583153890342, 102.1553011192941653 ) ) ; -#35531 = CARTESIAN_POINT ( 'NONE', ( 25.67135618113999840, 190.7771706469999913, 106.3710741544000058 ) ) ; -#35532 = EDGE_CURVE ( 'NONE', #37162, #33439, #9143, .T. ) ; -#35533 = CARTESIAN_POINT ( 'NONE', ( 30.05533545580799881, 109.6131156702000027, 90.24963216972992086 ) ) ; -#35534 = CARTESIAN_POINT ( 'NONE', ( 38.18933094215999802, 118.9523845877999975, 90.39787065528000198 ) ) ; -#35535 = EDGE_LOOP ( 'NONE', ( #10721, #14163, #5656, #2085 ) ) ; -#35536 = EDGE_CURVE ( 'NONE', #5625, #19444, #30141, .T. ) ; -#35537 = CARTESIAN_POINT ( 'NONE', ( 12.35238742145730129, 121.2983238345577348, 152.0219650886938325 ) ) ; -#35538 = CARTESIAN_POINT ( 'NONE', ( -35.93656262315591476, 192.5778422724570191, 106.4045596097014084 ) ) ; -#35539 = FACE_OUTER_BOUND ( 'NONE', #13805, .T. ) ; -#35540 = DIRECTION ( 'NONE', ( 0.0005884949961243378077, -0.2249510543439051935, 0.9743698870671265722 ) ) ; -#35541 = ORIENTED_EDGE ( 'NONE', *, *, #10383, .T. ) ; -#35542 = ORIENTED_EDGE ( 'NONE', *, *, #33397, .T. ) ; -#35543 = EDGE_CURVE ( 'NONE', #32124, #2995, #29807, .T. ) ; -#35544 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32094, #19594, #13480, #25964 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35545 = VERTEX_POINT ( 'NONE', #39385 ) ; -#35546 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319369175368 ) ) ; -#35547 = CARTESIAN_POINT ( 'NONE', ( -21.82963565732912059, 176.4928003187452816, 100.9258332941378455 ) ) ; -#35548 = CARTESIAN_POINT ( 'NONE', ( -2.373302774618340827, 209.5677226285648942, 73.55993759090392814 ) ) ; -#35549 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; -#35550 = ORIENTED_EDGE ( 'NONE', *, *, #40363, .T. ) ; -#35551 = VERTEX_POINT ( 'NONE', #14674 ) ; -#35552 = CARTESIAN_POINT ( 'NONE', ( -15.68256000705214248, 187.1367298994813382, 102.8663136840160348 ) ) ; -#35553 = CARTESIAN_POINT ( 'NONE', ( -38.27698265560000124, 118.7379802187000024, 90.09675852578000388 ) ) ; -#35554 = CARTESIAN_POINT ( 'NONE', ( -39.19119708560000248, 119.7661023014999984, 87.67334507776000407 ) ) ; -#35555 = CONICAL_SURFACE ( 'NONE', #1649, 5.003000016051808885, 0.7853647137435869618 ) ; -#35556 = CONICAL_SURFACE ( 'NONE', #8166, 2.500000093253988087, 0.7853981634347098062 ) ; -#35557 = CARTESIAN_POINT ( 'NONE', ( -19.31068835708127907, 125.9494874673739986, 176.1026865240145867 ) ) ; -#35558 = ORIENTED_EDGE ( 'NONE', *, *, #13104, .T. ) ; -#35559 = DIRECTION ( 'NONE', ( -0.5614015438085974141, 0.5784168556941973183, -0.5918295765320973345 ) ) ; -#35560 = CARTESIAN_POINT ( 'NONE', ( 5.665321241094450677, 124.6813345406426663, 88.86458804117559396 ) ) ; -#35561 = CARTESIAN_POINT ( 'NONE', ( 5.666344154416935730, 188.3446284886178717, 103.1322861692058268 ) ) ; -#35562 = CIRCLE ( 'NONE', #19268, 2.749999999927908334 ) ; -#35563 = CARTESIAN_POINT ( 'NONE', ( -13.73940678091062750, 149.5950516795147962, 180.3890686682271394 ) ) ; -#35564 = DIRECTION ( 'NONE', ( 0.0006039748319110907569, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#35565 = EDGE_LOOP ( 'NONE', ( #36861, #18234, #23062, #12451 ) ) ; -#35566 = CARTESIAN_POINT ( 'NONE', ( -2.616039299157999931, 189.8270603464999908, 103.4795334403000027 ) ) ; -#35567 = CARTESIAN_POINT ( 'NONE', ( -8.189842672704649829, 160.7205385619579090, 99.67099101675637485 ) ) ; -#35568 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, -1.292965734478455239E-10, 0.9999998176071844824 ) ) ; -#35569 = CARTESIAN_POINT ( 'NONE', ( 2.942640810008999797, 190.8795194553999863, 106.6729299489000198 ) ) ; -#35570 = ORIENTED_EDGE ( 'NONE', *, *, #23113, .T. ) ; -#35571 = ORIENTED_EDGE ( 'NONE', *, *, #17156, .F. ) ; -#35572 = CARTESIAN_POINT ( 'NONE', ( -20.49921872406353529, 118.1134456025284152, 89.78002774633898753 ) ) ; -#35573 = CARTESIAN_POINT ( 'NONE', ( -25.41632337319661517, 212.9327801067953772, 76.07227286817062861 ) ) ; -#35574 = ORIENTED_EDGE ( 'NONE', *, *, #20236, .F. ) ; -#35575 = EDGE_CURVE ( 'NONE', #6189, #1454, #37451, .T. ) ; -#35576 = EDGE_CURVE ( 'NONE', #11256, #2373, #35455, .T. ) ; -#35577 = VERTEX_POINT ( 'NONE', #7913 ) ; -#35578 = EDGE_CURVE ( 'NONE', #39629, #24313, #18890, .T. ) ; -#35579 = ORIENTED_EDGE ( 'NONE', *, *, #37502, .T. ) ; -#35580 = EDGE_CURVE ( 'NONE', #275, #4594, #17711, .T. ) ; -#35581 = CONICAL_SURFACE ( 'NONE', #15401, 2.500000073478776841, 0.7853981633461010192 ) ; -#35582 = CARTESIAN_POINT ( 'NONE', ( 22.99060780684998662, 213.5902260770751866, 73.54442216390444287 ) ) ; -#35583 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971553467 ) ) ; -#35584 = ORIENTED_EDGE ( 'NONE', *, *, #6875, .T. ) ; -#35586 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620730239, 0.0004744508866335444284 ) ) ; -#35585 = AXIS2_PLACEMENT_3D ( 'NONE', #40095, #27864, #24592 ) ; -#35587 = CIRCLE ( 'NONE', #29095, 2.250000000000011102 ) ; -#35588 = ORIENTED_EDGE ( 'NONE', *, *, #19062, .F. ) ; -#35589 = AXIS2_PLACEMENT_3D ( 'NONE', #31418, #3382, #6648 ) ; -#35590 = EDGE_CURVE ( 'NONE', #12347, #39877, #10795, .T. ) ; -#35591 = CARTESIAN_POINT ( 'NONE', ( 26.00638047580449452, 120.1083817546529815, 90.45668068452542343 ) ) ; -#35592 = CARTESIAN_POINT ( 'NONE', ( -24.55523628323845386, 213.0895637289104059, 75.57350648182111286 ) ) ; -#35593 = VECTOR ( 'NONE', #8092, 1000.000000000000000 ) ; -#35595 = CARTESIAN_POINT ( 'NONE', ( -44.12605770667196481, 189.0087315190842503, 103.3156785504129118 ) ) ; -#35594 = CYLINDRICAL_SURFACE ( 'NONE', #14597, 10.00000000000000178 ) ; -#35596 = ORIENTED_EDGE ( 'NONE', *, *, #7042, .F. ) ; -#35597 = EDGE_CURVE ( 'NONE', #32939, #11405, #40332, .T. ) ; -#35598 = CARTESIAN_POINT ( 'NONE', ( 30.05382551872584784, 109.6131156702000027, 87.74963262556961752 ) ) ; -#35599 = ORIENTED_EDGE ( 'NONE', *, *, #21607, .F. ) ; -#35600 = CARTESIAN_POINT ( 'NONE', ( -0.7521197190870236859, 188.6099794140578183, 103.1974225847511235 ) ) ; -#35601 = CARTESIAN_POINT ( 'NONE', ( -20.78811499662441875, 115.4347536419673759, 282.5710977942478053 ) ) ; -#35602 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989940797, 0.1373964268091564245 ) ) ; -#35603 = ORIENTED_EDGE ( 'NONE', *, *, #390, .F. ) ; -#35604 = CARTESIAN_POINT ( 'NONE', ( -37.33078358961313370, 118.4311938237343469, 87.29033114988793329 ) ) ; -#35605 = EDGE_CURVE ( 'NONE', #12345, #37005, #8125, .T. ) ; -#35606 = CARTESIAN_POINT ( 'NONE', ( -45.63429964751735923, 124.0250017997251888, 91.62307165259733210 ) ) ; -#35607 = DIRECTION ( 'NONE', ( -0.9999998268367615850, -0.0001323826093066938115, 0.0005734119738014427110 ) ) ; -#35608 = CARTESIAN_POINT ( 'NONE', ( 36.22006362617999997, 191.6153237647999958, 104.0153841014000022 ) ) ; -#35609 = EDGE_LOOP ( 'NONE', ( #27762, #5343, #6581, #18948 ) ) ; -#35610 = ORIENTED_EDGE ( 'NONE', *, *, #4426, .F. ) ; -#35611 = ORIENTED_EDGE ( 'NONE', *, *, #16275, .T. ) ; -#35612 = CARTESIAN_POINT ( 'NONE', ( -23.36362643548601525, 134.3689145912054528, 93.65807808762833986 ) ) ; -#35613 = CIRCLE ( 'NONE', #16028, 2.499999999970668796 ) ; -#35614 = ORIENTED_EDGE ( 'NONE', *, *, #14956, .F. ) ; -#35615 = DIRECTION ( 'NONE', ( 0.0006039748319382907873, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#35616 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9757, #33875, #15871, #18933 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35617 = VECTOR ( 'NONE', #35706, 1000.000000000000114 ) ; -#35618 = CIRCLE ( 'NONE', #23944, 10.00000000000000355 ) ; -#35619 = LINE ( 'NONE', #35829, #7904 ) ; -#35620 = CARTESIAN_POINT ( 'NONE', ( -20.68769432855515333, 105.5805168951702342, 87.28027914095393669 ) ) ; -#35621 = VERTEX_POINT ( 'NONE', #33053 ) ; -#35622 = CARTESIAN_POINT ( 'NONE', ( -12.63650000505050741, 176.7400935530354218, 103.0299816110529747 ) ) ; -#35623 = CARTESIAN_POINT ( 'NONE', ( 18.59950176164737812, 148.9135478570107409, 180.2224150185023177 ) ) ; -#35624 = CARTESIAN_POINT ( 'NONE', ( -14.22268604928681768, 129.0012187111780406, 177.0515306709980052 ) ) ; -#35625 = CARTESIAN_POINT ( 'NONE', ( -23.36013443158915237, 134.2374061052952356, 93.74025200507369959 ) ) ; -#35626 = EDGE_CURVE ( 'NONE', #15089, #35968, #31840, .T. ) ; -#35627 = VERTEX_POINT ( 'NONE', #26540 ) ; -#35628 = EDGE_CURVE ( 'NONE', #39445, #21726, #32339, .T. ) ; -#35629 = CARTESIAN_POINT ( 'NONE', ( 23.68479074154343778, 130.4250414336578956, 90.26276162004360515 ) ) ; -#35630 = EDGE_CURVE ( 'NONE', #8808, #22688, #27518, .T. ) ; -#35631 = CARTESIAN_POINT ( 'NONE', ( -14.22274084689574636, 128.8778062397453539, 177.5848030100378026 ) ) ; -#35632 = DIRECTION ( 'NONE', ( -6.938893903689061992E-16, 0.9743700557921577410, 0.2249510932971592880 ) ) ; -#35633 = ORIENTED_EDGE ( 'NONE', *, *, #26228, .T. ) ; -#35634 = ADVANCED_FACE ( 'NONE', ( #7708 ), #39470, .F. ) ; -#35635 = AXIS2_PLACEMENT_3D ( 'NONE', #28913, #25664, #488 ) ; -#35636 = CARTESIAN_POINT ( 'NONE', ( 8.243287016505872700, 177.7923814586351909, 100.6945832946480266 ) ) ; -#35637 = CIRCLE ( 'NONE', #14798, 30.00000000000001066 ) ; -#35638 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #11622, #8557, #21022, #18332 ), - .UNSPECIFIED., .F., .F. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.841075538901985276, 4.841089743069536766 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999831867825, 0.9999999999831867825, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#35640 = CARTESIAN_POINT ( 'NONE', ( -35.65425197762999687, 113.9226696212000007, 90.16305967816001044 ) ) ; -#35639 = CARTESIAN_POINT ( 'NONE', ( 2.545697083959657991, 209.0000005535759158, 75.65980364788404700 ) ) ; -#35641 = EDGE_CURVE ( 'NONE', #34013, #5512, #22545, .T. ) ; -#35642 = ORIENTED_EDGE ( 'NONE', *, *, #7272, .F. ) ; -#35643 = CARTESIAN_POINT ( 'NONE', ( 38.57881674720375287, 118.4710469142059424, 89.66256680473345853 ) ) ; -#35644 = EDGE_LOOP ( 'NONE', ( #32246, #32886, #13295, #22526 ) ) ; -#35646 = AXIS2_PLACEMENT_3D ( 'NONE', #21385, #26351, #30366 ) ; -#35645 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#35647 = DIRECTION ( 'NONE', ( -0.7942820423213363679, -0.5918950211223027447, -0.1370267171630251690 ) ) ; -#35648 = DIRECTION ( 'NONE', ( -0.6088835995545407442, -0.7728434649458201244, -0.1788120266761852317 ) ) ; -#35649 = CIRCLE ( 'NONE', #16729, 4.750000000028161473 ) ; -#35650 = CARTESIAN_POINT ( 'NONE', ( -8.513636114222510543, 166.3610373950837413, 28.79402947992309336 ) ) ; -#35651 = ORIENTED_EDGE ( 'NONE', *, *, #5918, .T. ) ; -#35652 = ORIENTED_EDGE ( 'NONE', *, *, #6753, .T. ) ; -#35653 = CARTESIAN_POINT ( 'NONE', ( -42.59427139077273949, 120.8410302828149980, 90.84624444726389925 ) ) ; -#35654 = ORIENTED_EDGE ( 'NONE', *, *, #7547, .F. ) ; -#35655 = ORIENTED_EDGE ( 'NONE', *, *, #1147, .F. ) ; -#35656 = FACE_OUTER_BOUND ( 'NONE', #18647, .T. ) ; -#35657 = ADVANCED_FACE ( 'NONE', ( #34254 ), #5452, .T. ) ; -#35658 = CARTESIAN_POINT ( 'NONE', ( -13.83171258125842940, 124.6514559930156594, 174.6056481214619680 ) ) ; -#35659 = CARTESIAN_POINT ( 'NONE', ( -2.874686192646000116, 209.6463030548999882, 76.06021946686999513 ) ) ; -#35660 = VERTEX_POINT ( 'NONE', #37146 ) ; -#35661 = CARTESIAN_POINT ( 'NONE', ( -25.50930529680102055, 206.8620306257938637, 74.56190818570927092 ) ) ; -#35662 = CARTESIAN_POINT ( 'NONE', ( 37.88028376212000126, 118.7501674914000063, 87.34217705218000560 ) ) ; -#35663 = CARTESIAN_POINT ( 'NONE', ( -38.87745381538000089, 118.6696732969000010, 89.55817230021000341 ) ) ; -#35664 = CARTESIAN_POINT ( 'NONE', ( 20.00004282447493864, 191.5259056233101091, 103.8580927373495371 ) ) ; -#35665 = CARTESIAN_POINT ( 'NONE', ( 13.45852275855000180, 176.5968831303999877, 28.07991271570000080 ) ) ; -#35666 = CARTESIAN_POINT ( 'NONE', ( -23.35467185764349907, 177.0821513736807731, 103.5858053495271207 ) ) ; -#35667 = CARTESIAN_POINT ( 'NONE', ( -30.07183102385390328, 134.5651111927130614, 93.53877248162399383 ) ) ; -#35668 = ORIENTED_EDGE ( 'NONE', *, *, #6390, .T. ) ; -#35669 = VECTOR ( 'NONE', #4781, 1000.000000000000000 ) ; -#35670 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#35671 = CARTESIAN_POINT ( 'NONE', ( 24.53561543415755608, 116.1140095870392770, 87.75278364645060947 ) ) ; -#35672 = AXIS2_PLACEMENT_3D ( 'NONE', #5616, #227, #632 ) ; -#35673 = CARTESIAN_POINT ( 'NONE', ( 20.33352119585698503, 191.4503965976574023, 104.1825428129966298 ) ) ; -#35674 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -2.775557055476284060E-15, -0.0006039748319368685309 ) ) ; -#35675 = CONICAL_SURFACE ( 'NONE', #8940, 2.500000189908397452, 0.7853981633778498450 ) ; -#35676 = ORIENTED_EDGE ( 'NONE', *, *, #20691, .T. ) ; -#35677 = CARTESIAN_POINT ( 'NONE', ( -21.44693882331385026, 135.7861819143374760, 91.01458761472625270 ) ) ; -#35678 = CARTESIAN_POINT ( 'NONE', ( 2.150444420076068397, 189.7824041803656883, 103.9092394343438599 ) ) ; -#35679 = CARTESIAN_POINT ( 'NONE', ( 32.56862209514003581, 137.0357280551704946, 91.27044140003587813 ) ) ; -#35680 = VECTOR ( 'NONE', #33372, 1000.000000000000000 ) ; -#35681 = CARTESIAN_POINT ( 'NONE', ( 37.43408832017941990, 187.1561535229247113, 105.9176297419797095 ) ) ; -#35682 = ORIENTED_EDGE ( 'NONE', *, *, #24353, .T. ) ; -#35683 = EDGE_CURVE ( 'NONE', #33088, #29958, #21685, .T. ) ; -#35684 = CARTESIAN_POINT ( 'NONE', ( -25.35555351876000074, 191.8331706769000107, 104.5643529913999998 ) ) ; -#35685 = ADVANCED_FACE ( 'NONE', ( #128 ), #40399, .F. ) ; -#35686 = CARTESIAN_POINT ( 'NONE', ( 20.50147081230003465, 160.1804844999245176, 99.18687941561596233 ) ) ; -#35687 = CARTESIAN_POINT ( 'NONE', ( 25.36963655659999972, 191.8200828733000094, 104.5457702689000001 ) ) ; -#35688 = CARTESIAN_POINT ( 'NONE', ( -32.37225756500890839, 173.7258698620904340, 102.8591651650622936 ) ) ; -#35689 = ORIENTED_EDGE ( 'NONE', *, *, #35785, .F. ) ; -#35690 = CARTESIAN_POINT ( 'NONE', ( 25.46575390506999881, 127.1331156701999987, 32.39311599089000282 ) ) ; -#35691 = CARTESIAN_POINT ( 'NONE', ( 2.546554931011165923, 207.4083916550792424, 77.08013917139633975 ) ) ; -#35692 = CARTESIAN_POINT ( 'NONE', ( 1.447658033476510564, 152.0519508813542302, 130.6788418767396251 ) ) ; -#35693 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26902, #11147, #4593, #29358, #14014, #38945, #39147, #23622, #10955, #39337 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000002220, 0.5000000000000004441, 0.7500000000000002220, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35694 = CARTESIAN_POINT ( 'NONE', ( 37.32760420458339468, 107.6237522301635892, 168.6290816310376783 ) ) ; -#35695 = CARTESIAN_POINT ( 'NONE', ( 20.48555995111231809, 211.0898943587194481, 73.54694346759191603 ) ) ; -#35696 = CIRCLE ( 'NONE', #14205, 22.00000000001092815 ) ; -#35697 = CARTESIAN_POINT ( 'NONE', ( 37.16246192308000218, 191.2833026195000343, 106.1953380436000032 ) ) ; -#35698 = CARTESIAN_POINT ( 'NONE', ( 31.13142491820691404, 177.5650774932047113, 100.6282487300115633 ) ) ; -#35699 = CARTESIAN_POINT ( 'NONE', ( -5.666943220168050743, 130.1021739148860092, 92.43784920459198418 ) ) ; -#35700 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118071, 107.3101052615539714, 174.7154016153159830 ) ) ; -#35701 = VECTOR ( 'NONE', #33455, 1000.000000000000114 ) ; -#35702 = ORIENTED_EDGE ( 'NONE', *, *, #30441, .F. ) ; -#35703 = CARTESIAN_POINT ( 'NONE', ( -44.79177088925157335, 180.8389768040387366, 104.5088566725039527 ) ) ; -#35704 = EDGE_CURVE ( 'NONE', #25194, #31691, #19239, .T. ) ; -#35705 = PLANE ( 'NONE', #2712 ) ; -#35706 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386905326 ) ) ; -#35707 = CARTESIAN_POINT ( 'NONE', ( -39.25176738111546371, 153.0051697192221241, 291.5822510191628680 ) ) ; -#35708 = ORIENTED_EDGE ( 'NONE', *, *, #1588, .T. ) ; -#35709 = LINE ( 'NONE', #26353, #31166 ) ; -#35710 = FACE_OUTER_BOUND ( 'NONE', #23365, .T. ) ; -#35711 = ORIENTED_EDGE ( 'NONE', *, *, #13292, .F. ) ; -#35712 = LINE ( 'NONE', #17314, #29768 ) ; -#35713 = CARTESIAN_POINT ( 'NONE', ( 24.98975941420810898, 212.6265807872101163, 73.54323398625686536 ) ) ; -#35714 = ORIENTED_EDGE ( 'NONE', *, *, #38743, .T. ) ; -#35715 = CARTESIAN_POINT ( 'NONE', ( 36.17763712702846846, 192.0945858402941155, 106.3945039591156672 ) ) ; -#35716 = ADVANCED_FACE ( 'NONE', ( #6062 ), #18511, .F. ) ; -#35717 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921592953, 0.2249510932971531818 ) ) ; -#35718 = CARTESIAN_POINT ( 'NONE', ( 2.463364856792551905, 209.5677208948551993, 75.55701285043443249 ) ) ; -#35719 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#35720 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748615030, 130.2179793250143121, 92.27099872764938482 ) ) ; -#35721 = EDGE_LOOP ( 'NONE', ( #8944, #4814, #7025, #15433 ) ) ; -#35722 = ORIENTED_EDGE ( 'NONE', *, *, #1956, .T. ) ; -#35723 = ADVANCED_FACE ( 'NONE', ( #2608 ), #12011, .F. ) ; -#35724 = CARTESIAN_POINT ( 'NONE', ( 31.79542160255000027, 226.4002260771003137, 75.53930090046030443 ) ) ; -#35725 = CARTESIAN_POINT ( 'NONE', ( -30.07108905527912768, 177.6009053965225348, 100.8330313169720540 ) ) ; -#35726 = CARTESIAN_POINT ( 'NONE', ( 3.535191698069989563, 175.6848863132240979, 100.2108397475080608 ) ) ; -#35727 = CIRCLE ( 'NONE', #7030, 1.999999999999999112 ) ; -#35728 = CARTESIAN_POINT ( 'NONE', ( -48.18983608578390232, 82.56060091850311267, 289.7643016034785433 ) ) ; -#35729 = ORIENTED_EDGE ( 'NONE', *, *, #32669, .F. ) ; -#35730 = EDGE_CURVE ( 'NONE', #13543, #33081, #30409, .T. ) ; -#35731 = ORIENTED_EDGE ( 'NONE', *, *, #17697, .F. ) ; -#35732 = CARTESIAN_POINT ( 'NONE', ( 23.36209697621471193, 182.0666116869439861, 102.1853546028109321 ) ) ; -#35733 = EDGE_CURVE ( 'NONE', #30524, #30873, #15276, .T. ) ; -#35734 = CIRCLE ( 'NONE', #18120, 16.50000000000000000 ) ; -#35736 = ADVANCED_FACE ( 'NONE', ( #12212 ), #14039, .F. ) ; -#35735 = CARTESIAN_POINT ( 'NONE', ( 6.034975439466390590, 134.4313215703540436, 93.60465627050247406 ) ) ; -#35737 = CARTESIAN_POINT ( 'NONE', ( -25.87924003072999923, 120.0237968075000197, 90.33241269644000226 ) ) ; -#35738 = CARTESIAN_POINT ( 'NONE', ( 3.166590160534637377, 128.9107321027200896, 89.41239602999318947 ) ) ; -#35739 = DIRECTION ( 'NONE', ( -0.1064928859749483120, 0.6584501104249200765, 0.7450521574481461240 ) ) ; -#35740 = CARTESIAN_POINT ( 'NONE', ( 37.79411860435257609, 218.5902260770999987, 73.03567738180409208 ) ) ; -#35741 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921587402, 0.2249510932971549582 ) ) ; -#35742 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501098504, 132.2930706491197554, 93.28496646308185802 ) ) ; -#35743 = DIRECTION ( 'NONE', ( 0.9999998268366899756, 0.0001323826366425473087, -0.0005734120921955398629 ) ) ; -#35744 = CARTESIAN_POINT ( 'NONE', ( 27.77617898001813046, 124.7465259774044881, 88.43614954403585671 ) ) ; -#35745 = EDGE_LOOP ( 'NONE', ( #19131, #17858, #30164, #38872 ) ) ; -#35746 = FACE_OUTER_BOUND ( 'NONE', #26547, .T. ) ; -#35747 = PLANE ( 'NONE', #27749 ) ; -#35748 = LINE ( 'NONE', #17348, #26728 ) ; -#35749 = CARTESIAN_POINT ( 'NONE', ( -28.46934164383677768, 181.9348616170655362, 102.0152119563739745 ) ) ; -#35751 = EDGE_LOOP ( 'NONE', ( #22500, #1558, #24023, #6049 ) ) ; -#35750 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#35752 = EDGE_LOOP ( 'NONE', ( #30765, #17898, #38041, #6736 ) ) ; -#35753 = ORIENTED_EDGE ( 'NONE', *, *, #28081, .F. ) ; -#35754 = ORIENTED_EDGE ( 'NONE', *, *, #21258, .F. ) ; -#35755 = CARTESIAN_POINT ( 'NONE', ( -13.50134333678474441, 124.5299559832934619, 88.63738261923552386 ) ) ; -#35756 = VECTOR ( 'NONE', #18942, 1000.000000000000114 ) ; -#35757 = DIRECTION ( 'NONE', ( 0.7933533411653070910, -0.5930537057989907490, -0.1373964268091706076 ) ) ; -#35758 = ORIENTED_EDGE ( 'NONE', *, *, #1641, .F. ) ; -#35759 = AXIS2_PLACEMENT_3D ( 'NONE', #2558, #33195, #11758 ) ; -#35760 = EDGE_LOOP ( 'NONE', ( #3069, #25635, #33742 ) ) ; -#35761 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001011, 118.9382625071999939, 90.21260570929000266 ) ) ; -#35762 = CARTESIAN_POINT ( 'NONE', ( -39.29309565128836113, 161.9833659626246458, 194.3051242015387743 ) ) ; -#35763 = CARTESIAN_POINT ( 'NONE', ( -13.49720193180488614, 187.3531203416616790, 105.5636871951386695 ) ) ; -#35764 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178570903572E-05, -0.0002331579774915885982 ) ) ; -#35765 = CARTESIAN_POINT ( 'NONE', ( -35.56620022681000393, 112.8577151017999967, 87.40717291247999299 ) ) ; -#35766 = VERTEX_POINT ( 'NONE', #12395 ) ; -#35767 = LINE ( 'NONE', #17372, #968 ) ; -#35768 = ORIENTED_EDGE ( 'NONE', *, *, #25160, .F. ) ; -#35769 = CARTESIAN_POINT ( 'NONE', ( -20.52021128088478008, 209.7095522429308119, 78.07090650300916934 ) ) ; -#35770 = CARTESIAN_POINT ( 'NONE', ( -3.668404236352207359, 128.0226348367964988, 91.77725148510558029 ) ) ; -#35771 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.274821093756980468E-14, 0.9999998176071847045 ) ) ; -#35772 = CARTESIAN_POINT ( 'NONE', ( -3.296644428745350464, 186.6752324597403856, 102.7522878028166247 ) ) ; -#35773 = CARTESIAN_POINT ( 'NONE', ( -19.30072366694697195, 148.2625267288300677, 183.5008936541533444 ) ) ; -#35774 = ORIENTED_EDGE ( 'NONE', *, *, #11406, .T. ) ; -#35775 = ORIENTED_EDGE ( 'NONE', *, *, #6554, .T. ) ; -#35776 = ADVANCED_FACE ( 'NONE', ( #24899 ), #15980, .F. ) ; -#35777 = CARTESIAN_POINT ( 'NONE', ( -0.4373743799229999896, 189.0000487688000135, 103.6850551722000091 ) ) ; -#35778 = CARTESIAN_POINT ( 'NONE', ( 25.49273537670449130, 207.4083917605111367, 77.06627999559472642 ) ) ; -#35779 = CARTESIAN_POINT ( 'NONE', ( 26.01884214213044189, 120.5510065312885359, 90.54751165435830274 ) ) ; -#35780 = EDGE_CURVE ( 'NONE', #21313, #18328, #27774, .T. ) ; -#35781 = ORIENTED_EDGE ( 'NONE', *, *, #2452, .T. ) ; -#35782 = CARTESIAN_POINT ( 'NONE', ( -37.26309767763914493, 111.8941053232203160, 150.0343454695379819 ) ) ; -#35783 = CARTESIAN_POINT ( 'NONE', ( 36.04411892353203228, 218.5902260770999987, 73.03673433779063373 ) ) ; -#35784 = EDGE_LOOP ( 'NONE', ( #16725, #228, #16824, #10371, #22148, #3105, #32591, #39397, #29981, #28998, #34117, #19583 ) ) ; -#35785 = EDGE_CURVE ( 'NONE', #39586, #3459, #18112, .T. ) ; -#35786 = EDGE_LOOP ( 'NONE', ( #22420, #5837, #29083, #10886 ) ) ; -#35787 = CONICAL_SURFACE ( 'NONE', #34502, 5.000000000037533532, 0.7853981633991120592 ) ; -#35788 = EDGE_CURVE ( 'NONE', #36967, #40162, #30902, .T. ) ; -#35789 = AXIS2_PLACEMENT_3D ( 'NONE', #8151, #2030, #14096 ) ; -#35790 = VERTEX_POINT ( 'NONE', #5864 ) ; -#35791 = LINE ( 'NONE', #17192, #15836 ) ; -#35792 = VECTOR ( 'NONE', #27611, 1000.000000000000000 ) ; -#35793 = VERTEX_POINT ( 'NONE', #34845 ) ; -#35794 = CARTESIAN_POINT ( 'NONE', ( -27.96587646086999968, 186.7892146652000065, 105.5303139314000020 ) ) ; -#35795 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18299, #17895, #5643, #9323 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35796 = AXIS2_PLACEMENT_3D ( 'NONE', #3339, #9698, #15814 ) ; -#35797 = PLANE ( 'NONE', #5853 ) ; -#35798 = CARTESIAN_POINT ( 'NONE', ( -20.00006126831510400, 120.3902141372887087, 87.45929000627990035 ) ) ; -#35799 = CARTESIAN_POINT ( 'NONE', ( 20.50029381459099653, 160.6303866002982375, 97.23813964974755208 ) ) ; -#35800 = ORIENTED_EDGE ( 'NONE', *, *, #23773, .F. ) ; -#35801 = CARTESIAN_POINT ( 'NONE', ( 25.83435490308000482, 120.1467052683999981, 90.28944886154999949 ) ) ; -#35802 = CARTESIAN_POINT ( 'NONE', ( -23.67312619880860680, 213.5252190068897278, 75.57282641249091171 ) ) ; -#35804 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#35803 = CARTESIAN_POINT ( 'NONE', ( 20.48210507039391359, 207.8175337693571976, 76.41195150568934480 ) ) ; -#35805 = EDGE_LOOP ( 'NONE', ( #37184, #22501, #31693, #12990 ) ) ; -#35806 = ORIENTED_EDGE ( 'NONE', *, *, #3086, .F. ) ; -#35807 = CARTESIAN_POINT ( 'NONE', ( -36.16445409389137211, 191.9130154921125779, 104.4161701276585319 ) ) ; -#35808 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#35809 = ORIENTED_EDGE ( 'NONE', *, *, #10008, .T. ) ; -#35810 = CARTESIAN_POINT ( 'NONE', ( -35.73920245160073250, 115.2227226758066081, 87.28936987476224374 ) ) ; -#35811 = CIRCLE ( 'NONE', #24780, 6.999999999999993783 ) ; -#35812 = PLANE ( 'NONE', #33013 ) ; -#35813 = CARTESIAN_POINT ( 'NONE', ( 5.669396933462909516, 187.4887502807403905, 105.7656896039401317 ) ) ; -#35814 = LINE ( 'NONE', #7824, #22866 ) ; -#35815 = EDGE_CURVE ( 'NONE', #24898, #4634, #30383, .T. ) ; -#35816 = EDGE_LOOP ( 'NONE', ( #16018, #38283, #28912, #28327 ) ) ; -#35817 = EDGE_CURVE ( 'NONE', #20812, #23133, #34268, .T. ) ; -#35818 = ORIENTED_EDGE ( 'NONE', *, *, #35972, .F. ) ; -#35819 = AXIS2_PLACEMENT_3D ( 'NONE', #33184, #30759, #37484 ) ; -#35820 = EDGE_CURVE ( 'NONE', #33506, #25208, #14304, .T. ) ; -#35821 = CARTESIAN_POINT ( 'NONE', ( 22.74078652492754316, 169.1007803562181948, 29.42961925479451324 ) ) ; -#35822 = AXIS2_PLACEMENT_3D ( 'NONE', #5801, #21560, #39728 ) ; -#35823 = ORIENTED_EDGE ( 'NONE', *, *, #807, .F. ) ; -#35824 = EDGE_CURVE ( 'NONE', #25532, #33855, #13396, .T. ) ; -#35825 = CARTESIAN_POINT ( 'NONE', ( -35.43250415655209906, 192.6083200664709807, 106.9089671552009975 ) ) ; -#35826 = CARTESIAN_POINT ( 'NONE', ( -37.85620740011129470, 117.8069959198554386, 89.71719403945294857 ) ) ; -#35827 = ADVANCED_FACE ( 'NONE', ( #25897 ), #13409, .T. ) ; -#35828 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31199, #34830, #34052, #37333 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35829 = CARTESIAN_POINT ( 'NONE', ( 42.53628601435023171, 136.4453753212296760, 337.8539966295136310 ) ) ; -#35830 = CARTESIAN_POINT ( 'NONE', ( 2.730734751406000083, 190.9310048963999975, 106.4668557451999931 ) ) ; -#35831 = ORIENTED_EDGE ( 'NONE', *, *, #22096, .F. ) ; -#35832 = PLANE ( 'NONE', #20996 ) ; -#35833 = EDGE_CURVE ( 'NONE', #11521, #2286, #12809, .T. ) ; -#35834 = DIRECTION ( 'NONE', ( 0.0002393071182782299474, 0.2252352986010034697, -0.9743043687658493601 ) ) ; -#35835 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36667, #30333, #2131, #12142, #15402, #14601, #33386, #15206, #8676, #33174 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999722444, 0.3749999999999583666, 0.4374999999999019118, 0.4999999999998454570, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35836 = DIRECTION ( 'NONE', ( -0.7069397801071900522, 0.6508947121446219120, 0.2767168607153664972 ) ) ; -#35837 = CARTESIAN_POINT ( 'NONE', ( -37.83810969319355166, 191.0388331516561777, 103.7805696149103909 ) ) ; -#35838 = EDGE_LOOP ( 'NONE', ( #5305, #39328, #28111, #38920 ) ) ; -#35839 = FACE_OUTER_BOUND ( 'NONE', #5978, .T. ) ; -#35840 = CARTESIAN_POINT ( 'NONE', ( -2.435788377003461846, 191.0000002182038941, 106.3158216037667358 ) ) ; -#35841 = EDGE_CURVE ( 'NONE', #24833, #35367, #3564, .T. ) ; -#35842 = CIRCLE ( 'NONE', #18226, 54.50273826251000742 ) ; -#35843 = ORIENTED_EDGE ( 'NONE', *, *, #22122, .F. ) ; -#35844 = AXIS2_PLACEMENT_3D ( 'NONE', #12525, #1412, #9888 ) ; -#35845 = CARTESIAN_POINT ( 'NONE', ( 32.91940139443364188, 79.66630585985183188, 290.1140374308924947 ) ) ; -#35846 = AXIS2_PLACEMENT_3D ( 'NONE', #35387, #10691, #35583 ) ; -#35848 = CARTESIAN_POINT ( 'NONE', ( -35.94308550139999880, 115.0615709833000011, 90.15961284037001633 ) ) ; -#35847 = CARTESIAN_POINT ( 'NONE', ( -15.83322826986868392, 127.7069138835006896, 89.31700631985079042 ) ) ; -#35849 = ORIENTED_EDGE ( 'NONE', *, *, #7361, .T. ) ; -#35850 = CARTESIAN_POINT ( 'NONE', ( 25.99899579567804864, 120.3902236066977025, 87.43149108636995948 ) ) ; -#35851 = ORIENTED_EDGE ( 'NONE', *, *, #15643, .T. ) ; -#35852 = DIRECTION ( 'NONE', ( 0.9999998176071844824, -0.000000000000000000, -0.0006039748319385906776 ) ) ; -#35853 = LINE ( 'NONE', #1521, #28456 ) ; -#35854 = LINE ( 'NONE', #20742, #27509 ) ; -#35855 = CYLINDRICAL_SURFACE ( 'NONE', #33836, 16.50000000000000000 ) ; -#35856 = ORIENTED_EDGE ( 'NONE', *, *, #32993, .T. ) ; -#35857 = ORIENTED_EDGE ( 'NONE', *, *, #29310, .F. ) ; -#35858 = CARTESIAN_POINT ( 'NONE', ( 1.222756636386816309, 140.3954820326998458, 157.8542268366375652 ) ) ; -#35859 = EDGE_LOOP ( 'NONE', ( #37988, #4418, #25493, #29627 ) ) ; -#35860 = ORIENTED_EDGE ( 'NONE', *, *, #25816, .T. ) ; -#35861 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#35862 = CARTESIAN_POINT ( 'NONE', ( 47.95588533879620741, 89.40266445833195519, 291.5248371983224729 ) ) ; -#35863 = EDGE_LOOP ( 'NONE', ( #8038, #10899, #1061, #36156 ) ) ; -#35864 = EDGE_CURVE ( 'NONE', #39281, #31407, #10135, .T. ) ; -#35865 = EDGE_CURVE ( 'NONE', #19980, #23892, #16064, .T. ) ; -#35866 = ORIENTED_EDGE ( 'NONE', *, *, #37024, .F. ) ; -#35867 = CARTESIAN_POINT ( 'NONE', ( 40.92173691880906006, 126.8073924708085798, 91.98291144766025695 ) ) ; -#35868 = EDGE_CURVE ( 'NONE', #35915, #15358, #3981, .T. ) ; -#35869 = LINE ( 'NONE', #7464, #29630 ) ; -#35870 = FACE_OUTER_BOUND ( 'NONE', #896, .T. ) ; -#35871 = CARTESIAN_POINT ( 'NONE', ( 26.00189986064203040, 120.0654717175184771, 90.40948441678035863 ) ) ; -#35872 = EDGE_CURVE ( 'NONE', #81, #23946, #25043, .T. ) ; -#35873 = CARTESIAN_POINT ( 'NONE', ( -25.83465933313999940, 120.7504878537999957, 87.71733303230999468 ) ) ; -#35874 = CONICAL_SURFACE ( 'NONE', #22865, 8.499999999995104361, 0.7853981633972997312 ) ; -#35875 = ORIENTED_EDGE ( 'NONE', *, *, #1490, .F. ) ; -#35876 = LINE ( 'NONE', #25716, #37582 ) ; -#35877 = CYLINDRICAL_SURFACE ( 'NONE', #29771, 2.000000000000011546 ) ; -#35878 = CARTESIAN_POINT ( 'NONE', ( -23.35984529070648463, 176.7693366005458984, 103.0852009884378475 ) ) ; -#35879 = VECTOR ( 'NONE', #18279, 1000.000000000000000 ) ; -#35880 = EDGE_LOOP ( 'NONE', ( #685, #34377, #21366, #21749 ) ) ; -#35881 = EDGE_CURVE ( 'NONE', #10753, #11739, #514, .T. ) ; -#35882 = CARTESIAN_POINT ( 'NONE', ( 0.5670577675614898450, 188.6056077384269827, 103.1956165535758885 ) ) ; -#35883 = VECTOR ( 'NONE', #13063, 1000.000000000000227 ) ; -#35884 = CARTESIAN_POINT ( 'NONE', ( -33.95120480059922841, 108.7064547236847432, 175.0201060189330349 ) ) ; -#35885 = CARTESIAN_POINT ( 'NONE', ( 20.50004289353369202, 195.4022624757890583, 104.8282682354084585 ) ) ; -#35886 = CONICAL_SURFACE ( 'NONE', #37770, 3.005918165693955757, 0.7853589131925805544 ) ; -#35887 = PLANE ( 'NONE', #19625 ) ; -#35888 = ORIENTED_EDGE ( 'NONE', *, *, #21656, .F. ) ; -#35890 = ADVANCED_FACE ( 'NONE', ( #13013 ), #12720, .F. ) ; -#35889 = CARTESIAN_POINT ( 'NONE', ( 35.04645050415997787, 226.4002260770639907, 75.53733736050399727 ) ) ; -#35891 = CARTESIAN_POINT ( 'NONE', ( 2.243140848118248876, 189.9153760549866377, 103.9475555346419782 ) ) ; -#35892 = DIRECTION ( 'NONE', ( -0.7075337269147008445, 0.000000000000000000, -0.7066795775160008564 ) ) ; -#35893 = ORIENTED_EDGE ( 'NONE', *, *, #29914, .T. ) ; -#35894 = CARTESIAN_POINT ( 'NONE', ( 35.55533445361766098, 112.4664342211686971, 90.24631030758727945 ) ) ; -#35895 = ORIENTED_EDGE ( 'NONE', *, *, #10916, .T. ) ; -#35896 = CYLINDRICAL_SURFACE ( 'NONE', #6834, 8.000000000000007105 ) ; -#35897 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 2.775557055476284060E-15, 0.0006039748319368685309 ) ) ; -#35898 = CARTESIAN_POINT ( 'NONE', ( 26.14047868689999987, 191.8757300627000006, 103.7755257792000094 ) ) ; -#35899 = DIRECTION ( 'NONE', ( 0.7075227810182288524, -0.1590644129476248281, 0.6885564805256420007 ) ) ; -#35900 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #26379, #22911, #1012, #29243 ), - ( #16941, #35531, #1419, #25984 ), - ( #1622, #10443, #14111, #33099 ), - ( #26789, #13501, #13697, #38821 ), - ( #35337, #29443, #23711, #13899 ), - ( #39032, #20019, #10843, #23312 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 4 ), - ( 4, 4 ), - ( -0.3349633148657999993, 0.000000000000000000, 1.000000000000000000, 1.334874014178000001 ), - ( 3.659027379144000085E-07, 1.000000018766999954 ), - .UNSPECIFIED. ) ; -#35901 = CARTESIAN_POINT ( 'NONE', ( 18.00088274248999909, 130.4429303793676240, 91.29662884054138772 ) ) ; -#35902 = EDGE_LOOP ( 'NONE', ( #28167, #35689, #7973, #29578 ) ) ; -#35903 = LINE ( 'NONE', #4832, #29508 ) ; -#35904 = CARTESIAN_POINT ( 'NONE', ( 20.89285664109717189, 183.1014278315721810, 101.9125999898524242 ) ) ; -#35905 = AXIS2_PLACEMENT_3D ( 'NONE', #4154, #25469, #7031 ) ; -#35906 = CARTESIAN_POINT ( 'NONE', ( -20.49970532896238495, 138.0793279496801631, 92.05657955325195019 ) ) ; -#35907 = AXIS2_PLACEMENT_3D ( 'NONE', #31225, #30830, #27980 ) ; -#35908 = CARTESIAN_POINT ( 'NONE', ( -42.84985459259963392, 114.0190886145072113, 121.9014590159434164 ) ) ; -#35909 = CARTESIAN_POINT ( 'NONE', ( -17.26178222639411430, 121.7713432978476220, 175.3684242141576703 ) ) ; -#35910 = CONICAL_SURFACE ( 'NONE', #2657, 22.50000000000906653, 0.7853981633972855203 ) ; -#35911 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178570922545E-05, 0.0002331579774915894113 ) ) ; -#35912 = CYLINDRICAL_SURFACE ( 'NONE', #5874, 4.999999999999994671 ) ; -#35913 = DIRECTION ( 'NONE', ( -0.1305263947812629610, 0.9660168765824788117, 0.2231014442428325972 ) ) ; -#35914 = CARTESIAN_POINT ( 'NONE', ( -38.37944638082275617, 118.8393675661044000, 87.72093620509961909 ) ) ; -#35915 = VERTEX_POINT ( 'NONE', #25292 ) ; -#35916 = CARTESIAN_POINT ( 'NONE', ( 25.99209716004703097, 210.1698189683999942, 76.04278591111288677 ) ) ; -#35917 = CARTESIAN_POINT ( 'NONE', ( -20.49823408210000153, 153.4269499538000048, 98.16561777664999511 ) ) ; -#35918 = VERTEX_POINT ( 'NONE', #37735 ) ; -#35919 = CARTESIAN_POINT ( 'NONE', ( -8.472443777046803959, 150.6153475619768187, 96.99609267642283328 ) ) ; -#35920 = ADVANCED_FACE ( 'NONE', ( #25494 ), #38819, .T. ) ; -#35921 = EDGE_CURVE ( 'NONE', #28170, #1259, #26472, .T. ) ; -#35922 = ORIENTED_EDGE ( 'NONE', *, *, #4774, .F. ) ; -#35923 = CARTESIAN_POINT ( 'NONE', ( -34.30586824512814559, 218.5902260770999987, 73.07922396718730340 ) ) ; -#35924 = DIRECTION ( 'NONE', ( -0.0005884949961219279515, 0.2249510543439044163, -0.9743698870671267942 ) ) ; -#35925 = ORIENTED_EDGE ( 'NONE', *, *, #34005, .F. ) ; -#35926 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596101196, 128.5887768395678563, 89.32567453973172178 ) ) ; -#35927 = CARTESIAN_POINT ( 'NONE', ( 25.50052104635086536, 120.2145376163999941, 89.95699630689016146 ) ) ; -#35928 = CARTESIAN_POINT ( 'NONE', ( 45.65198572469971339, 124.0200644324655457, 91.33654899623203960 ) ) ; -#35929 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971559296 ) ) ; -#35930 = CARTESIAN_POINT ( 'NONE', ( 25.49919833444198858, 118.8155663768459505, 87.75236248755290092 ) ) ; -#35931 = EDGE_LOOP ( 'NONE', ( #20889, #13446, #35860, #36704 ) ) ; -#35932 = ORIENTED_EDGE ( 'NONE', *, *, #37629, .F. ) ; -#35933 = CONICAL_SURFACE ( 'NONE', #28153, 2.499999999860247790, 0.7853981633778360782 ) ; -#35934 = FACE_OUTER_BOUND ( 'NONE', #14399, .T. ) ; -#35935 = AXIS2_PLACEMENT_3D ( 'NONE', #19692, #32383, #888 ) ; -#35936 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#35937 = CARTESIAN_POINT ( 'NONE', ( 16.00178211024919861, 127.0692136201035680, 92.05841426505114100 ) ) ; -#35938 = AXIS2_PLACEMENT_3D ( 'NONE', #22226, #34657, #13215 ) ; -#35939 = VECTOR ( 'NONE', #32456, 1000.000000000000114 ) ; -#35940 = CARTESIAN_POINT ( 'NONE', ( -45.45405528451752986, 124.2940812332277289, 92.45993501987911145 ) ) ; -#35941 = VERTEX_POINT ( 'NONE', #1520 ) ; -#35942 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#35943 = CARTESIAN_POINT ( 'NONE', ( 20.00179988782546303, 151.3105026749326498, 97.65252212824069034 ) ) ; -#35944 = CARTESIAN_POINT ( 'NONE', ( -28.33045555218999922, 124.2967629910999960, 91.58406576504999919 ) ) ; -#35945 = EDGE_CURVE ( 'NONE', #27558, #33804, #3565, .T. ) ; -#35946 = CARTESIAN_POINT ( 'NONE', ( 2.544461030880475594, 209.0000001909309901, 73.61327617014224245 ) ) ; -#35947 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825906387028845, 0.0005734119026992764556 ) ) ; -#35948 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#35949 = CARTESIAN_POINT ( 'NONE', ( -2.454301921840380096, 209.0000005845445230, 75.66282330657800514 ) ) ; -#35950 = CARTESIAN_POINT ( 'NONE', ( 37.78006692254000143, 118.6320720638999973, 87.34557981016999406 ) ) ; -#35951 = DIRECTION ( 'NONE', ( 0.7066795775160008564, -0.000000000000000000, -0.7075337269147008445 ) ) ; -#35952 = CARTESIAN_POINT ( 'NONE', ( 38.42323727947000123, 119.1365327004000108, 90.40419822697000996 ) ) ; -#35953 = ORIENTED_EDGE ( 'NONE', *, *, #3726, .F. ) ; -#35954 = LINE ( 'NONE', #8176, #30943 ) ; -#35955 = DIRECTION ( 'NONE', ( 0.0005884949961190483105, -0.2249510543439053878, 0.9743698870671265722 ) ) ; -#35956 = CARTESIAN_POINT ( 'NONE', ( 44.24596348240854837, 122.9115719264381710, 88.00256960708196630 ) ) ; -#35957 = DIRECTION ( 'NONE', ( -0.0004270303127820591058, -0.7071067811865883179, -0.7071066522421171063 ) ) ; -#35958 = VECTOR ( 'NONE', #28227, 1000.000000000000114 ) ; -#35959 = DIRECTION ( 'NONE', ( -0.7731297265845318289, -0.5272054548977799238, -0.3525972691291752170 ) ) ; -#35960 = ORIENTED_EDGE ( 'NONE', *, *, #23311, .F. ) ; -#35961 = ORIENTED_EDGE ( 'NONE', *, *, #18751, .F. ) ; -#35962 = AXIS2_PLACEMENT_3D ( 'NONE', #35020, #38127, #13384 ) ; -#35963 = EDGE_CURVE ( 'NONE', #30736, #36135, #8278, .T. ) ; -#35964 = VECTOR ( 'NONE', #10492, 1000.000000000000114 ) ; -#35965 = VERTEX_POINT ( 'NONE', #33191 ) ; -#35966 = DIRECTION ( 'NONE', ( -0.7942820423213363679, -0.5918950211223027447, -0.1370267171630251690 ) ) ; -#35967 = VECTOR ( 'NONE', #1382, 1000.000000000000114 ) ; -#35968 = VERTEX_POINT ( 'NONE', #38936 ) ; -#35969 = DIRECTION ( 'NONE', ( 0.0004161288024537937186, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#35970 = AXIS2_PLACEMENT_3D ( 'NONE', #10467, #26811, #4300 ) ; -#35971 = CARTESIAN_POINT ( 'NONE', ( -43.10573975924778978, 121.2931756425902847, 90.61592751502209353 ) ) ; -#35972 = EDGE_CURVE ( 'NONE', #11781, #10321, #4000, .T. ) ; -#35973 = ORIENTED_EDGE ( 'NONE', *, *, #3853, .F. ) ; -#35974 = EDGE_CURVE ( 'NONE', #37986, #16662, #32959, .T. ) ; -#35975 = ORIENTED_EDGE ( 'NONE', *, *, #8400, .T. ) ; -#35976 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#35977 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#35978 = CARTESIAN_POINT ( 'NONE', ( -37.23494651666909050, 103.9956957637453598, 184.2025836917128174 ) ) ; -#35979 = CARTESIAN_POINT ( 'NONE', ( -26.01494426630450008, 211.0902259182902014, 73.07465174665132679 ) ) ; -#35980 = ORIENTED_EDGE ( 'NONE', *, *, #18835, .F. ) ; -#35981 = EDGE_CURVE ( 'NONE', #10675, #10713, #20119, .T. ) ; -#35982 = CARTESIAN_POINT ( 'NONE', ( 19.33632959910114124, 147.9597651028845462, 183.5586071598492026 ) ) ; -#35983 = ORIENTED_EDGE ( 'NONE', *, *, #36064, .F. ) ; -#35984 = DIRECTION ( 'NONE', ( 0.0005884950107539749361, -0.2249510543548229602, 0.9743698870645971510 ) ) ; -#35985 = CARTESIAN_POINT ( 'NONE', ( 35.67368674445789622, 113.9486398105102580, 90.24623882632185712 ) ) ; -#35986 = CARTESIAN_POINT ( 'NONE', ( -19.54703320420837898, 148.9928018343113933, 183.1147439724198591 ) ) ; -#35987 = VERTEX_POINT ( 'NONE', #7860 ) ; -#35988 = ORIENTED_EDGE ( 'NONE', *, *, #36022, .F. ) ; -#35989 = CARTESIAN_POINT ( 'NONE', ( -0.6436417827288198890, 188.6082569606599861, 103.1943079271519963 ) ) ; -#35990 = CARTESIAN_POINT ( 'NONE', ( 1.112971808851000111, 189.0817780705000075, 103.7152259047999934 ) ) ; -#35991 = CYLINDRICAL_SURFACE ( 'NONE', #30241, 2.000000000000011546 ) ; -#35992 = LINE ( 'NONE', #7996, #40391 ) ; -#35993 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2084, #4931, #23354, #4518, #17184, #11080 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 4 ), - ( 0.000000000000000000, 0.3333326433113111276, 0.6666670495315556444, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35994 = VERTEX_POINT ( 'NONE', #30156 ) ; -#35995 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22774, #19875, #7211, #32372 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#35996 = CARTESIAN_POINT ( 'NONE', ( 17.36823235821892553, 127.5715682803508173, 172.3982060061660775 ) ) ; -#35997 = ORIENTED_EDGE ( 'NONE', *, *, #7867, .F. ) ; -#35998 = ORIENTED_EDGE ( 'NONE', *, *, #4402, .T. ) ; -#35999 = CIRCLE ( 'NONE', #37308, 2.499999999972146725 ) ; -#36000 = EDGE_CURVE ( 'NONE', #26666, #7629, #35529, .T. ) ; -#36001 = CONICAL_SURFACE ( 'NONE', #9267, 6.500001283309376099, 0.7853982200479777687 ) ; -#36002 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25717, #38168, #23846, #10766 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36003 = ORIENTED_EDGE ( 'NONE', *, *, #33484, .T. ) ; -#36004 = LINE ( 'NONE', #9233, #28265 ) ; -#36005 = VERTEX_POINT ( 'NONE', #39330 ) ; -#36006 = CARTESIAN_POINT ( 'NONE', ( -45.01543256409814120, 130.9257504736116289, 89.90670049556989341 ) ) ; -#36007 = CARTESIAN_POINT ( 'NONE', ( 14.35378279688742253, 196.5784924078620293, 103.8663088710679148 ) ) ; -#36008 = PLANE ( 'NONE', #2599 ) ; -#36009 = ORIENTED_EDGE ( 'NONE', *, *, #35122, .F. ) ; -#36010 = FACE_OUTER_BOUND ( 'NONE', #32423, .T. ) ; -#36011 = ORIENTED_EDGE ( 'NONE', *, *, #3309, .T. ) ; -#36012 = EDGE_CURVE ( 'NONE', #32563, #18083, #11142, .T. ) ; -#36013 = CARTESIAN_POINT ( 'NONE', ( 28.22559710222000007, 124.4220533023000144, 91.43995667158999652 ) ) ; -#36014 = CARTESIAN_POINT ( 'NONE', ( 22.95436083522999837, 118.1131156702000169, 13.53038997162000001 ) ) ; -#36016 = CARTESIAN_POINT ( 'NONE', ( -30.18611281846582628, 185.3309324562166864, 102.8002735974070418 ) ) ; -#36015 = DIRECTION ( 'NONE', ( 0.7947975163364137119, -0.5917479692793309320, -0.1346523259333320122 ) ) ; -#36017 = ORIENTED_EDGE ( 'NONE', *, *, #32881, .T. ) ; -#36018 = ADVANCED_FACE ( 'NONE', ( #35439 ), #10549, .F. ) ; -#36019 = ORIENTED_EDGE ( 'NONE', *, *, #15045, .F. ) ; -#36020 = ADVANCED_FACE ( 'NONE', ( #36278 ), #23014, .T. ) ; -#36021 = VECTOR ( 'NONE', #36364, 1000.000000000000114 ) ; -#36022 = EDGE_CURVE ( 'NONE', #29762, #1613, #1736, .T. ) ; -#36023 = ORIENTED_EDGE ( 'NONE', *, *, #10984, .T. ) ; -#36025 = EDGE_CURVE ( 'NONE', #24812, #25693, #15355, .T. ) ; -#36024 = CARTESIAN_POINT ( 'NONE', ( 39.59230100324000290, 119.1504122669000196, 89.56670257055999684 ) ) ; -#36026 = CARTESIAN_POINT ( 'NONE', ( -42.83272783108322557, 107.4558756614410697, 150.2543767220365680 ) ) ; -#36027 = EDGE_CURVE ( 'NONE', #32971, #23892, #25814, .T. ) ; -#36028 = AXIS2_PLACEMENT_3D ( 'NONE', #23675, #5251, #7921 ) ; -#36029 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501094951, 179.0628333272064197, 104.0826189413997440 ) ) ; -#36030 = CARTESIAN_POINT ( 'NONE', ( -26.81689520618117939, 187.6029399509571078, 105.5464327012842318 ) ) ; -#36031 = CARTESIAN_POINT ( 'NONE', ( 36.42232590615000021, 191.8149838951999868, 104.3700011025999999 ) ) ; -#36032 = VERTEX_POINT ( 'NONE', #29352 ) ; -#36033 = ORIENTED_EDGE ( 'NONE', *, *, #22160, .F. ) ; -#36034 = CARTESIAN_POINT ( 'NONE', ( 20.00182604067493131, 190.8514159882993511, 106.7812686061269716 ) ) ; -#36035 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3153, #37506, #28520, #15633 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36036 = CARTESIAN_POINT ( 'NONE', ( 25.49847230246999885, 121.0495832369999931, 88.09734716337999316 ) ) ; -#36037 = ORIENTED_EDGE ( 'NONE', *, *, #31344, .T. ) ; -#36038 = CARTESIAN_POINT ( 'NONE', ( -1.212288473603901240, 143.4871526178525869, 158.5698567282870499 ) ) ; -#36039 = VERTEX_POINT ( 'NONE', #1322 ) ; -#36040 = ORIENTED_EDGE ( 'NONE', *, *, #14913, .T. ) ; -#36041 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480714602456338, 0.5299193037553528995 ) ) ; -#36042 = ORIENTED_EDGE ( 'NONE', *, *, #31857, .T. ) ; -#36043 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#36044 = EDGE_CURVE ( 'NONE', #31750, #36248, #26287, .T. ) ; -#36045 = CARTESIAN_POINT ( 'NONE', ( -2.691512666988662872, 209.6623512938134013, 75.89346368600931214 ) ) ; -#36046 = CARTESIAN_POINT ( 'NONE', ( -5.668107805537519361, 126.1261160540004767, 91.85696217430825072 ) ) ; -#36047 = DIRECTION ( 'NONE', ( 0.0004161288024437542234, -0.8480480898092626063, 0.5299191110043877107 ) ) ; -#36048 = VERTEX_POINT ( 'NONE', #26689 ) ; -#36049 = AXIS2_PLACEMENT_3D ( 'NONE', #5049, #38999, #39800 ) ; -#36050 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36051 = CARTESIAN_POINT ( 'NONE', ( -2.436614782451819838, 191.0000000999000065, 104.9475220120663579 ) ) ; -#36052 = AXIS2_PLACEMENT_3D ( 'NONE', #8730, #21194, #18301 ) ; -#36053 = CIRCLE ( 'NONE', #29569, 1.750000000000001998 ) ; -#36054 = ORIENTED_EDGE ( 'NONE', *, *, #3637, .T. ) ; -#36055 = ADVANCED_FACE ( 'NONE', ( #39142 ), #38188, .F. ) ; -#36056 = FACE_OUTER_BOUND ( 'NONE', #27216, .T. ) ; -#36058 = CARTESIAN_POINT ( 'NONE', ( 15.67412488234288759, 159.4968216871810398, 96.46619825634390111 ) ) ; -#36057 = FACE_OUTER_BOUND ( 'NONE', #5930, .T. ) ; -#36060 = ORIENTED_EDGE ( 'NONE', *, *, #34985, .T. ) ; -#36059 = EDGE_CURVE ( 'NONE', #10082, #20853, #30353, .T. ) ; -#36061 = LINE ( 'NONE', #23208, #24338 ) ; -#36062 = ORIENTED_EDGE ( 'NONE', *, *, #7089, .F. ) ; -#36063 = DIRECTION ( 'NONE', ( 0.5988681445390194868, -0.8008476418498040594, 0.000000000000000000 ) ) ; -#36064 = EDGE_CURVE ( 'NONE', #10990, #34119, #34211, .T. ) ; -#36065 = CARTESIAN_POINT ( 'NONE', ( 77.66065009075275327, 193.3992594998515244, 188.4681838635439419 ) ) ; -#36066 = CARTESIAN_POINT ( 'NONE', ( 15.50147165590422205, 151.4095604219332643, 97.16497155034561217 ) ) ; -#36067 = LINE ( 'NONE', #39952, #17475 ) ; -#36068 = EDGE_LOOP ( 'NONE', ( #6164, #26886, #10211, #14614 ) ) ; -#36069 = ORIENTED_EDGE ( 'NONE', *, *, #1202, .T. ) ; -#36070 = CARTESIAN_POINT ( 'NONE', ( -42.61860293796636512, 120.8482216545914270, 90.95641729975723422 ) ) ; -#36071 = ORIENTED_EDGE ( 'NONE', *, *, #35872, .T. ) ; -#36072 = ORIENTED_EDGE ( 'NONE', *, *, #39856, .T. ) ; -#36073 = ORIENTED_EDGE ( 'NONE', *, *, #37407, .F. ) ; -#36075 = EDGE_CURVE ( 'NONE', #5203, #10712, #4207, .T. ) ; -#36074 = CARTESIAN_POINT ( 'NONE', ( -22.78292978085340081, 157.6260587155269661, 99.13643849004034792 ) ) ; -#36076 = DIRECTION ( 'NONE', ( 0.1695469893270775408, -1.252670582138759641E-14, -0.9855221044756549142 ) ) ; -#36077 = CARTESIAN_POINT ( 'NONE', ( 23.08502856561264593, 148.5869484094654354, 197.0326829874275347 ) ) ; -#36078 = CARTESIAN_POINT ( 'NONE', ( 29.38693461565323872, 112.1844516200949755, 175.8396907018270383 ) ) ; -#36079 = VECTOR ( 'NONE', #1696, 1000.000000000000227 ) ; -#36080 = ORIENTED_EDGE ( 'NONE', *, *, #31396, .F. ) ; -#36081 = CARTESIAN_POINT ( 'NONE', ( 13.36382089992252453, 177.7154036444319729, 100.6736854505625018 ) ) ; -#36082 = FACE_OUTER_BOUND ( 'NONE', #29388, .T. ) ; -#36083 = CARTESIAN_POINT ( 'NONE', ( -35.81398623132000125, 192.3507530278000388, 104.2979901971000061 ) ) ; -#36084 = CARTESIAN_POINT ( 'NONE', ( 37.76913763144000313, 191.3232487601999878, 104.1935076314999975 ) ) ; -#36085 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2998, #18327, #6266, #24709 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36086 = ORIENTED_EDGE ( 'NONE', *, *, #30297, .F. ) ; -#36087 = CARTESIAN_POINT ( 'NONE', ( -26.00144291263000085, 120.7763519191999961, 87.55119131511999342 ) ) ; -#36088 = CARTESIAN_POINT ( 'NONE', ( 41.04644941596783525, 217.7719116456999870, 75.53371351155776381 ) ) ; -#36089 = VECTOR ( 'NONE', #9651, 1000.000000000000227 ) ; -#36090 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 135.6522072397361853, 90.95982947643901184 ) ) ; -#36091 = CARTESIAN_POINT ( 'NONE', ( 28.46561152637903547, 127.9145563911127113, 92.24604361343246239 ) ) ; -#36092 = ORIENTED_EDGE ( 'NONE', *, *, #10429, .F. ) ; -#36093 = CARTESIAN_POINT ( 'NONE', ( -6.037313578920448620, 134.5364664150864087, 93.54487822610151682 ) ) ; -#36094 = CARTESIAN_POINT ( 'NONE', ( -22.78373664921000241, 158.6756214347751097, 96.81298893714118492 ) ) ; -#36095 = LINE ( 'NONE', #8309, #37917 ) ; -#36096 = PLANE ( 'NONE', #61 ) ; -#36097 = EDGE_LOOP ( 'NONE', ( #7657, #37034, #33821, #36935 ) ) ; -#36098 = DIRECTION ( 'NONE', ( 0.1632030863883330296, -0.3417424275059343097, 0.9255143790539797077 ) ) ; -#36099 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#36100 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; -#36101 = ORIENTED_EDGE ( 'NONE', *, *, #21049, .F. ) ; -#36102 = CARTESIAN_POINT ( 'NONE', ( -42.87041437821633139, 121.8978841230586170, 87.86525719409469559 ) ) ; -#36103 = CARTESIAN_POINT ( 'NONE', ( -25.35601378779999848, 191.7662701877000018, 104.5630184056000047 ) ) ; -#36104 = DIRECTION ( 'NONE', ( -0.0004161288024511093967, -0.5299192578742120130, -0.8480479980348188951 ) ) ; -#36105 = CARTESIAN_POINT ( 'NONE', ( 25.68657024044000181, 191.1729245184999968, 104.1504610859000053 ) ) ; -#36106 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364818587623, 136.5649596138779884, 181.4686487119677167 ) ) ; -#36107 = CARTESIAN_POINT ( 'NONE', ( -21.75981387337644080, 213.2747155673518193, 75.57157761709684962 ) ) ; -#36108 = CARTESIAN_POINT ( 'NONE', ( 16.54117632239534430, 152.4851539532401148, 181.7923885842497214 ) ) ; -#36109 = AXIS2_PLACEMENT_3D ( 'NONE', #28493, #31007, #19259 ) ; -#36110 = LINE ( 'NONE', #8119, #10190 ) ; -#36111 = EDGE_CURVE ( 'NONE', #13982, #37303, #2283, .T. ) ; -#36112 = ORIENTED_EDGE ( 'NONE', *, *, #18908, .T. ) ; -#36113 = EDGE_CURVE ( 'NONE', #30592, #14524, #17175, .T. ) ; -#36114 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #18227, #30532, #24606, #30930, #17818, #28071 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36115 = ADVANCED_FACE ( 'NONE', ( #33612 ), #37492, .F. ) ; -#36116 = AXIS2_PLACEMENT_3D ( 'NONE', #37454, #25403, #37852 ) ; -#36117 = CARTESIAN_POINT ( 'NONE', ( 39.85586901997003650, 129.5283103249424244, 336.2586849593528768 ) ) ; -#36118 = AXIS2_PLACEMENT_3D ( 'NONE', #4194, #16863, #9109 ) ; -#36119 = CARTESIAN_POINT ( 'NONE', ( -24.84081799597801421, 115.7102179961852357, 87.28278752364165882 ) ) ; -#36120 = CARTESIAN_POINT ( 'NONE', ( -3.537750984983824232, 137.3463269818849426, 91.36396247942009552 ) ) ; -#36121 = ADVANCED_FACE ( 'NONE', ( #6803 ), #32178, .T. ) ; -#36122 = CARTESIAN_POINT ( 'NONE', ( -40.77069120851000861, 112.8448473173999957, 152.4718672074000381 ) ) ; -#36123 = CARTESIAN_POINT ( 'NONE', ( 32.08164567794030830, 176.8424030107383089, 100.4608322395127260 ) ) ; -#36124 = CARTESIAN_POINT ( 'NONE', ( -25.49003114136341352, 191.3825488810288107, 106.3975518461934371 ) ) ; -#36125 = CARTESIAN_POINT ( 'NONE', ( 29.19927575800447173, 163.6433483284885426, 97.41533068389654204 ) ) ; -#36126 = CARTESIAN_POINT ( 'NONE', ( 22.78196627740044278, 153.3599009982148118, 97.61084599868732425 ) ) ; -#36127 = CARTESIAN_POINT ( 'NONE', ( 20.25403320342156377, 116.9073549109220806, 90.25555191067651606 ) ) ; -#36128 = ORIENTED_EDGE ( 'NONE', *, *, #4043, .F. ) ; -#36129 = EDGE_CURVE ( 'NONE', #38943, #4584, #7918, .T. ) ; -#36130 = CARTESIAN_POINT ( 'NONE', ( -19.99970941558080284, 118.1131156714892114, 90.27986793006986943 ) ) ; -#36131 = DIRECTION ( 'NONE', ( 7.677760455958669993E-18, -1.000000000000000000, 1.271205131337281593E-14 ) ) ; -#36132 = ORIENTED_EDGE ( 'NONE', *, *, #35921, .F. ) ; -#36133 = CARTESIAN_POINT ( 'NONE', ( 37.78025130169015711, 80.42490204549953603, 284.8841145757368167 ) ) ; -#36134 = CARTESIAN_POINT ( 'NONE', ( 3.769207233074749031, 136.7343769535524984, 94.05766322553326120 ) ) ; -#36135 = VERTEX_POINT ( 'NONE', #34604 ) ; -#36136 = ADVANCED_FACE ( 'NONE', ( #31780 ), #16014, .T. ) ; -#36137 = CARTESIAN_POINT ( 'NONE', ( 25.42551241295287667, 211.7445882540852438, 73.54297905658798129 ) ) ; -#36138 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319387907129 ) ) ; -#36139 = ORIENTED_EDGE ( 'NONE', *, *, #39310, .F. ) ; -#36140 = DIRECTION ( 'NONE', ( 0.7933310414247656261, 0.5931044597393390072, 0.1373060761554398823 ) ) ; -#36141 = VECTOR ( 'NONE', #17152, 1000.000000000000114 ) ; -#36142 = CARTESIAN_POINT ( 'NONE', ( -22.78364630492483656, 153.8037711675519859, 95.68823341888959533 ) ) ; -#36143 = CARTESIAN_POINT ( 'NONE', ( -40.95517856241297494, 219.0860688542000219, 75.58324044005291853 ) ) ; -#36144 = AXIS2_PLACEMENT_3D ( 'NONE', #14534, #18380, #27019 ) ; -#36145 = CARTESIAN_POINT ( 'NONE', ( 31.79391164804998127, 225.9002260768332633, 73.03930135632873544 ) ) ; -#36146 = PLANE ( 'NONE', #10601 ) ; -#36147 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #10828, #31705, #28626, #998 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( -9.769962616701377556E-15, 0.1815409218495399601 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9972554596699720886, 0.9972554596699720886, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#36148 = ORIENTED_EDGE ( 'NONE', *, *, #25861, .T. ) ; -#36149 = CARTESIAN_POINT ( 'NONE', ( 39.68496035423999757, 120.3220653550000065, 87.52937166904000321 ) ) ; -#36150 = AXIS2_PLACEMENT_3D ( 'NONE', #1539, #7267, #20136 ) ; -#36151 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21684, #34321, #6120, #18982 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36152 = CARTESIAN_POINT ( 'NONE', ( -20.16659611466318580, 120.3526820203828436, 87.62178027201382235 ) ) ; -#36153 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501097082, 176.3833156737244110, 103.4640034347852975 ) ) ; -#36154 = CARTESIAN_POINT ( 'NONE', ( -20.35076456421905888, 207.5617848265386840, 77.15901428017532737 ) ) ; -#36155 = ORIENTED_EDGE ( 'NONE', *, *, #12836, .F. ) ; -#36156 = ORIENTED_EDGE ( 'NONE', *, *, #27956, .F. ) ; -#36157 = CARTESIAN_POINT ( 'NONE', ( -0.001765484987732086333, 156.3551877983824170, 95.75036263592863861 ) ) ; -#36158 = CARTESIAN_POINT ( 'NONE', ( -42.80211665092759432, 120.8344283343924701, 92.46298830314225370 ) ) ; -#36159 = FACE_OUTER_BOUND ( 'NONE', #38507, .T. ) ; -#36160 = CARTESIAN_POINT ( 'NONE', ( -28.17883134163000491, 124.5573437160000054, 91.38045355701001426 ) ) ; -#36161 = CARTESIAN_POINT ( 'NONE', ( -25.51533646434189961, 211.0902259025884007, 73.57326538444725372 ) ) ; -#36162 = LINE ( 'NONE', #14912, #24786 ) ; -#36163 = EDGE_CURVE ( 'NONE', #31227, #2967, #39126, .T. ) ; -#36164 = EDGE_CURVE ( 'NONE', #11951, #33925, #4131, .T. ) ; -#36165 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3838, #13074, #7516, #38784 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36166 = DIRECTION ( 'NONE', ( -0.0005884949961189345777, 0.2249510543439073862, -0.9743698870671260170 ) ) ; -#36167 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36168 = CARTESIAN_POINT ( 'NONE', ( 20.48035933545727261, 208.8549887208692155, 73.60699811742749432 ) ) ; -#36169 = CARTESIAN_POINT ( 'NONE', ( 38.80823801556999797, 118.5174377607999929, 89.51271477801999765 ) ) ; -#36170 = CIRCLE ( 'NONE', #8103, 4.999999999999990230 ) ; -#36171 = VECTOR ( 'NONE', #32242, 1000.000000000000114 ) ; -#36172 = ORIENTED_EDGE ( 'NONE', *, *, #21942, .T. ) ; -#36173 = LINE ( 'NONE', #27001, #36802 ) ; -#36174 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36175 = CARTESIAN_POINT ( 'NONE', ( -21.21399079302519652, 183.3565551017309190, 102.5100844002234197 ) ) ; -#36176 = CARTESIAN_POINT ( 'NONE', ( -22.22019231403135819, 115.1898461495169812, 87.28120473139716751 ) ) ; -#36177 = CIRCLE ( 'NONE', #2909, 59.40509898897001051 ) ; -#36178 = CARTESIAN_POINT ( 'NONE', ( -20.49975839845215830, 192.0926363215378387, 104.4339699173596756 ) ) ; -#36179 = VERTEX_POINT ( 'NONE', #12964 ) ; -#36180 = ORIENTED_EDGE ( 'NONE', *, *, #27987, .F. ) ; -#36181 = ORIENTED_EDGE ( 'NONE', *, *, #2769, .F. ) ; -#36182 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 2.523234147032834427E-15, 0.0006039748319402993802 ) ) ; -#36183 = DIRECTION ( 'NONE', ( -0.0001408404346092576671, 0.2255194953558363191, -0.9742386449830560124 ) ) ; -#36184 = VERTEX_POINT ( 'NONE', #31975 ) ; -#36185 = CARTESIAN_POINT ( 'NONE', ( -15.93637865429753120, 186.5404220567731954, 102.7287984460090655 ) ) ; -#36186 = EDGE_CURVE ( 'NONE', #16595, #22787, #9904, .T. ) ; -#36187 = CARTESIAN_POINT ( 'NONE', ( -39.69476436410172226, 161.7095167889038692, 196.8665534586947672 ) ) ; -#36188 = FACE_OUTER_BOUND ( 'NONE', #4998, .T. ) ; -#36189 = CARTESIAN_POINT ( 'NONE', ( 14.54953207236175139, 130.1535194663153447, 89.69244121379192336 ) ) ; -#36190 = CARTESIAN_POINT ( 'NONE', ( -36.08997809811999957, 113.3914357756000015, 87.92830918980999400 ) ) ; -#36191 = VERTEX_POINT ( 'NONE', #28697 ) ; -#36192 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#36193 = CARTESIAN_POINT ( 'NONE', ( -15.60630250089785065, 175.8727404917108856, 100.2657702926515242 ) ) ; -#36194 = FACE_OUTER_BOUND ( 'NONE', #6924, .T. ) ; -#36195 = DIRECTION ( 'NONE', ( 0.5986917825334768795, 0.8009794122048727871, -0.0003615948347012565940 ) ) ; -#36196 = CARTESIAN_POINT ( 'NONE', ( -3.191551117751024957, 186.2886659142941710, 102.6629783937155764 ) ) ; -#36197 = CARTESIAN_POINT ( 'NONE', ( -19.99825438583805237, 190.8509747501094580, 106.8052823956111013 ) ) ; -#36198 = AXIS2_PLACEMENT_3D ( 'NONE', #35533, #4691, #4892 ) ; -#36199 = CONICAL_SURFACE ( 'NONE', #8131, 2.503115359310264409, 0.7853981634098280429 ) ; -#36200 = ORIENTED_EDGE ( 'NONE', *, *, #17510, .F. ) ; -#36201 = CARTESIAN_POINT ( 'NONE', ( -1.594832852936999945, 189.0177083714000048, 103.4292051506999996 ) ) ; -#36202 = CARTESIAN_POINT ( 'NONE', ( 0.5623168218902999671, 188.6118872737999936, 103.1964808549000026 ) ) ; -#36203 = AXIS2_PLACEMENT_3D ( 'NONE', #759, #37379, #3417 ) ; -#36204 = AXIS2_PLACEMENT_3D ( 'NONE', #26117, #13034, #25516 ) ; -#36205 = PLANE ( 'NONE', #21761 ) ; -#36206 = CARTESIAN_POINT ( 'NONE', ( -35.64858212982840513, 191.7420658667043654, 106.9375512398736561 ) ) ; -#36207 = ORIENTED_EDGE ( 'NONE', *, *, #21375, .F. ) ; -#36208 = VECTOR ( 'NONE', #13848, 999.9999999999998863 ) ; -#36209 = ORIENTED_EDGE ( 'NONE', *, *, #17365, .T. ) ; -#36210 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282901917, 154.4034317163438175, 95.31352405029051056 ) ) ; -#36211 = VERTEX_POINT ( 'NONE', #31569 ) ; -#36212 = VERTEX_POINT ( 'NONE', #6406 ) ; -#36213 = ORIENTED_EDGE ( 'NONE', *, *, #763, .F. ) ; -#36214 = VERTEX_POINT ( 'NONE', #3938 ) ; -#36215 = EDGE_CURVE ( 'NONE', #21825, #1116, #22375, .T. ) ; -#36216 = ADVANCED_FACE ( 'NONE', ( #7008 ), #38291, .T. ) ; -#36217 = CARTESIAN_POINT ( 'NONE', ( 22.50147045824883918, 160.1804542550550536, 99.18566449512113081 ) ) ; -#36218 = CARTESIAN_POINT ( 'NONE', ( -22.64037623556000156, 157.9259078517000319, 98.94900196435999362 ) ) ; -#36219 = CARTESIAN_POINT ( 'NONE', ( -6.679083190205946056E-14, 150.3212993284946606, 97.43624128390267458 ) ) ; -#36220 = ORIENTED_EDGE ( 'NONE', *, *, #27396, .T. ) ; -#36221 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825875308198743, 0.0005734119034175035826 ) ) ; -#36222 = VERTEX_POINT ( 'NONE', #25446 ) ; -#36223 = CARTESIAN_POINT ( 'NONE', ( 26.24438363001889840, 121.6906080158060206, 90.81567923076639204 ) ) ; -#36224 = CARTESIAN_POINT ( 'NONE', ( -24.42595481105102451, 104.1131156702295186, 90.28253750387099785 ) ) ; -#36226 = CARTESIAN_POINT ( 'NONE', ( -27.18778663116000160, 103.8631156702000027, 87.53420507948000306 ) ) ; -#36225 = DIRECTION ( 'NONE', ( -0.0006039748319384231684, -2.335630580398557718E-15, -0.9999998176071847045 ) ) ; -#36227 = CONICAL_SURFACE ( 'NONE', #20549, 22.50000000000906653, 0.7853981633972855203 ) ; -#36228 = ORIENTED_EDGE ( 'NONE', *, *, #27067, .F. ) ; -#36229 = AXIS2_PLACEMENT_3D ( 'NONE', #32336, #7372, #20041 ) ; -#36230 = AXIS2_PLACEMENT_3D ( 'NONE', #8260, #20723, #8047 ) ; -#36231 = VERTEX_POINT ( 'NONE', #25652 ) ; -#36232 = CARTESIAN_POINT ( 'NONE', ( 21.44870233977301410, 176.2493420812517968, 103.4092482268179936 ) ) ; -#36233 = AXIS2_PLACEMENT_3D ( 'NONE', #7658, #10950, #20530 ) ; -#36234 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #37580, #6490 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36235 = EDGE_LOOP ( 'NONE', ( #30376, #17373, #3196, #16828, #16993 ) ) ; -#36236 = DIRECTION ( 'NONE', ( 4.163336342270463358E-15, 0.9743700557921590732, 0.2249510932971540977 ) ) ; -#36237 = EDGE_CURVE ( 'NONE', #19028, #15849, #7208, .T. ) ; -#36238 = DIRECTION ( 'NONE', ( 0.7933532411131102302, 0.5932638852154232811, 0.1364866195435443241 ) ) ; -#36239 = DIRECTION ( 'NONE', ( -0.9999998268367782384, -0.0001323826467776493491, 0.0005734119359534853039 ) ) ; -#36240 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048996748, 134.2394347309033833, 93.74516030699037117 ) ) ; -#36241 = CARTESIAN_POINT ( 'NONE', ( 36.12836467949000507, 191.5083383925000078, 103.8363012094000055 ) ) ; -#36242 = EDGE_LOOP ( 'NONE', ( #23232, #28023, #7184, #16588 ) ) ; -#36243 = ORIENTED_EDGE ( 'NONE', *, *, #4453, .T. ) ; -#36244 = CARTESIAN_POINT ( 'NONE', ( -0.6019324427172583203, 188.9986941098608781, 103.6847164217354589 ) ) ; -#36245 = DIRECTION ( 'NONE', ( 0.0005884949961215159547, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36246 = CARTESIAN_POINT ( 'NONE', ( 27.15577148128999951, 124.2993249153000050, 88.50433870978000073 ) ) ; -#36247 = ORIENTED_EDGE ( 'NONE', *, *, #623, .T. ) ; -#36248 = VERTEX_POINT ( 'NONE', #82 ) ; -#36249 = FACE_OUTER_BOUND ( 'NONE', #37858, .T. ) ; -#36251 = EDGE_CURVE ( 'NONE', #1155, #8681, #28354, .T. ) ; -#36250 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12736, #19252, #34395, #22557 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 1.757266515702729398E-05, 0.0001596853054049402290 ), - .UNSPECIFIED. ) ; -#36252 = CARTESIAN_POINT ( 'NONE', ( 3.064242084557000201, 190.8511711511999920, 106.7914576077999982 ) ) ; -#36253 = ORIENTED_EDGE ( 'NONE', *, *, #7268, .F. ) ; -#36254 = CARTESIAN_POINT ( 'NONE', ( -20.51878087562336006, 206.7719441278318584, 74.64876841760110437 ) ) ; -#36255 = AXIS2_PLACEMENT_3D ( 'NONE', #38474, #16400, #32357 ) ; -#36256 = ADVANCED_FACE ( 'NONE', ( #12757 ), #37901, .T. ) ; -#36257 = CARTESIAN_POINT ( 'NONE', ( -28.94780665481193793, 110.6131156702000027, 87.78526813307001930 ) ) ; -#36258 = AXIS2_PLACEMENT_3D ( 'NONE', #19443, #34958, #16180 ) ; -#36259 = VECTOR ( 'NONE', #34583, 999.9999999999998863 ) ; -#36260 = DIRECTION ( 'NONE', ( -0.0005884949961257158286, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#36261 = DIRECTION ( 'NONE', ( 0.0005884949961234139590, -0.2249510543439055266, 0.9743698870671265722 ) ) ; -#36262 = ORIENTED_EDGE ( 'NONE', *, *, #33405, .F. ) ; -#36263 = VECTOR ( 'NONE', #872, 1000.000000000000227 ) ; -#36264 = EDGE_CURVE ( 'NONE', #1023, #3379, #9696, .T. ) ; -#36265 = EDGE_CURVE ( 'NONE', #3470, #26904, #34797, .T. ) ; -#36266 = CARTESIAN_POINT ( 'NONE', ( -21.68252898277260954, 177.1920069373947513, 100.5740168946693842 ) ) ; -#36267 = DIRECTION ( 'NONE', ( -0.0005884949961245158337, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#36268 = EDGE_CURVE ( 'NONE', #19698, #10706, #36396, .T. ) ; -#36269 = EDGE_CURVE ( 'NONE', #23150, #38536, #6202, .T. ) ; -#36270 = ORIENTED_EDGE ( 'NONE', *, *, #29590, .F. ) ; -#36271 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7177, #8816, #36193, #29880, #1861, #11264 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36272 = CARTESIAN_POINT ( 'NONE', ( 15.49823494792000034, 187.1838939932000017, 105.9372828411000000 ) ) ; -#36274 = DIRECTION ( 'NONE', ( 0.0002083475567178606162, -0.2252353001617939665, 0.9743043755173853571 ) ) ; -#36273 = CARTESIAN_POINT ( 'NONE', ( 22.50029346827000509, 158.6816162531925158, 96.78702253073828388 ) ) ; -#36275 = EDGE_LOOP ( 'NONE', ( #7066, #22547, #24086, #34671, #13722, #18311 ) ) ; -#36276 = ORIENTED_EDGE ( 'NONE', *, *, #39860, .F. ) ; -#36277 = ORIENTED_EDGE ( 'NONE', *, *, #16896, .T. ) ; -#36278 = FACE_OUTER_BOUND ( 'NONE', #20571, .T. ) ; -#36279 = DIRECTION ( 'NONE', ( -0.6087611434178656911, -0.7731004625493616000, -0.1781166614063267317 ) ) ; -#36280 = CARTESIAN_POINT ( 'NONE', ( 18.90090771971125960, 120.9219860925226300, 173.6350968582803205 ) ) ; -#36281 = ORIENTED_EDGE ( 'NONE', *, *, #21573, .F. ) ; -#36282 = AXIS2_PLACEMENT_3D ( 'NONE', #19815, #35750, #13310 ) ; -#36283 = ORIENTED_EDGE ( 'NONE', *, *, #31431, .F. ) ; -#36284 = CARTESIAN_POINT ( 'NONE', ( 14.27573290317919330, 135.8449083118874228, 91.00656752237129865 ) ) ; -#36285 = ORIENTED_EDGE ( 'NONE', *, *, #11765, .F. ) ; -#36286 = EDGE_LOOP ( 'NONE', ( #26, #12225, #33357 ) ) ; -#36287 = VERTEX_POINT ( 'NONE', #38486 ) ; -#36288 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36289 = EDGE_CURVE ( 'NONE', #2373, #20941, #31321, .T. ) ; -#36290 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.293414132305980107E-14, -0.9999998176071847045 ) ) ; -#36291 = PLANE ( 'NONE', #30755 ) ; -#36292 = CIRCLE ( 'NONE', #25253, 6.499999999993911537 ) ; -#36293 = ORIENTED_EDGE ( 'NONE', *, *, #23080, .F. ) ; -#36294 = ORIENTED_EDGE ( 'NONE', *, *, #16487, .F. ) ; -#36295 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36296 = CARTESIAN_POINT ( 'NONE', ( -35.54466115731000286, 191.7015624462000005, 103.7905865506999987 ) ) ; -#36297 = CARTESIAN_POINT ( 'NONE', ( 36.30644545348000207, 191.5168451883999978, 103.9534424241000181 ) ) ; -#36298 = ORIENTED_EDGE ( 'NONE', *, *, #10172, .T. ) ; -#36299 = CARTESIAN_POINT ( 'NONE', ( -25.66845890388309570, 120.6532999635128931, 87.85646371106152230 ) ) ; -#36300 = DIRECTION ( 'NONE', ( 0.0005734119072324020665, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#36301 = ORIENTED_EDGE ( 'NONE', *, *, #13292, .T. ) ; -#36302 = CARTESIAN_POINT ( 'NONE', ( -3.501646886743174480, 126.2017715745908646, 91.52781443613361034 ) ) ; -#36303 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000092726, 179.7424522644023739, 101.1388664480621884 ) ) ; -#36304 = ORIENTED_EDGE ( 'NONE', *, *, #19046, .T. ) ; -#36305 = EDGE_CURVE ( 'NONE', #21583, #28118, #22060, .T. ) ; -#36306 = CARTESIAN_POINT ( 'NONE', ( -20.51842225234980432, 208.7972206383130356, 75.74176032200549002 ) ) ; -#36307 = FACE_OUTER_BOUND ( 'NONE', #8277, .T. ) ; -#36308 = CARTESIAN_POINT ( 'NONE', ( 37.78115515336936880, 118.8155650090541968, 87.24496173037786662 ) ) ; -#36309 = DIRECTION ( 'NONE', ( 0.0005884949961246861618, -0.2249510543439068866, 0.9743698870671261281 ) ) ; -#36310 = ORIENTED_EDGE ( 'NONE', *, *, #37246, .F. ) ; -#36311 = FACE_OUTER_BOUND ( 'NONE', #16656, .T. ) ; -#36312 = EDGE_CURVE ( 'NONE', #18309, #17075, #11513, .T. ) ; -#36313 = CARTESIAN_POINT ( 'NONE', ( 2.555968269339144339, 190.8015354413785190, 104.2031804828878165 ) ) ; -#36314 = LINE ( 'NONE', #27142, #32597 ) ; -#36315 = EDGE_CURVE ( 'NONE', #11409, #19175, #39652, .T. ) ; -#36316 = VERTEX_POINT ( 'NONE', #27009 ) ; -#36317 = CARTESIAN_POINT ( 'NONE', ( -0.0003589606772235004960, 136.6775772631780796, 180.9814965275865575 ) ) ; -#36318 = ORIENTED_EDGE ( 'NONE', *, *, #2688, .T. ) ; -#36319 = EDGE_LOOP ( 'NONE', ( #18736, #22121, #20781, #29987 ) ) ; -#36320 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422003068, 160.0671381723056754, 99.67809115075311865 ) ) ; -#36321 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35582, #8435, #26839, #5128, #32943, #11489, #23764, #14359, #33143, #29291 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36322 = EDGE_CURVE ( 'NONE', #9576, #11668, #11662, .T. ) ; -#36323 = CARTESIAN_POINT ( 'NONE', ( -15.87151776090180100, 147.4423043082527158, 177.3699030816898699 ) ) ; -#36324 = LINE ( 'NONE', #36528, #13752 ) ; -#36325 = CARTESIAN_POINT ( 'NONE', ( -20.00100377755662961, 193.8169056301028945, 102.7149817412491473 ) ) ; -#36326 = EDGE_CURVE ( 'NONE', #9147, #23621, #30476, .T. ) ; -#36327 = EDGE_CURVE ( 'NONE', #14862, #28384, #26473, .T. ) ; -#36328 = CARTESIAN_POINT ( 'NONE', ( -25.50127375672713725, 118.8155664721400058, 87.78318651355773738 ) ) ; -#36329 = CARTESIAN_POINT ( 'NONE', ( 6.033400168022899912, 135.0731597114094598, 91.04333201587085966 ) ) ; -#36330 = ORIENTED_EDGE ( 'NONE', *, *, #18579, .T. ) ; -#36331 = AXIS2_PLACEMENT_3D ( 'NONE', #33826, #36493, #2764 ) ; -#36332 = DESIGN_CONTEXT ( 'detailed design', #6482, 'design' ) ; -#36333 = PLANE ( 'NONE', #23609 ) ; -#36334 = CIRCLE ( 'NONE', #38279, 3.000000000018959945 ) ; -#36335 = CARTESIAN_POINT ( 'NONE', ( -13.50000253664885719, 154.4078437129245458, 95.30587049155346335 ) ) ; -#36336 = CARTESIAN_POINT ( 'NONE', ( 41.04584544117999911, 219.5549399801000163, 74.53371369385999401 ) ) ; -#36337 = DIRECTION ( 'NONE', ( 0.7855473026356902810, 0.6188014303620728018, -0.0004744508866335557583 ) ) ; -#36338 = CARTESIAN_POINT ( 'NONE', ( 5.666613786283987153, 181.3391778151182336, 104.3161990643648380 ) ) ; -#36339 = CARTESIAN_POINT ( 'NONE', ( 19.01936855422726680, 125.6545233337280223, 175.1462352020453181 ) ) ; -#36340 = CARTESIAN_POINT ( 'NONE', ( -22.78246931443000278, 153.3538690590805516, 97.63697319283785703 ) ) ; -#36341 = CARTESIAN_POINT ( 'NONE', ( -37.29638110713771226, 178.8156383198445667, 136.8789424484697008 ) ) ; -#36342 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921581851, -0.2249510932971571509 ) ) ; -#36343 = VERTEX_POINT ( 'NONE', #16606 ) ; -#36344 = CARTESIAN_POINT ( 'NONE', ( 3.768101781280366769, 144.1625501041019959, 93.17310105376213869 ) ) ; -#36345 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.271205131337281593E-14, -1.000000000000000000 ) ) ; -#36346 = AXIS2_PLACEMENT_3D ( 'NONE', #37705, #9711, #37914 ) ; -#36347 = ORIENTED_EDGE ( 'NONE', *, *, #33642, .F. ) ; -#36348 = DIRECTION ( 'NONE', ( 5.782411586632444827E-15, -1.000000000000000000, 1.387778780791786695E-14 ) ) ; -#36349 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36350 = AXIS2_PLACEMENT_3D ( 'NONE', #24147, #27630, #7976 ) ; -#36351 = ORIENTED_EDGE ( 'NONE', *, *, #10344, .T. ) ; -#36352 = AXIS2_PLACEMENT_3D ( 'NONE', #966, #26537, #38987 ) ; -#36353 = FACE_OUTER_BOUND ( 'NONE', #24384, .T. ) ; -#36354 = DIRECTION ( 'NONE', ( -0.9999998176071847045, -7.515125404477462028E-16, 0.0006039748319388944710 ) ) ; -#36355 = ORIENTED_EDGE ( 'NONE', *, *, #15186, .F. ) ; -#36356 = CARTESIAN_POINT ( 'NONE', ( 77.76878474137986075, 193.3567070688226863, 189.4847442820362176 ) ) ; -#36357 = EDGE_CURVE ( 'NONE', #17219, #37891, #34269, .T. ) ; -#36358 = AXIS2_PLACEMENT_3D ( 'NONE', #22184, #28512, #37309 ) ; -#36359 = EDGE_CURVE ( 'NONE', #26352, #17327, #33513, .T. ) ; -#36360 = FACE_BOUND ( 'NONE', #30349, .T. ) ; -#36361 = EDGE_CURVE ( 'NONE', #4072, #20299, #10507, .T. ) ; -#36362 = FACE_OUTER_BOUND ( 'NONE', #29118, .T. ) ; -#36363 = LINE ( 'NONE', #20614, #24193 ) ; -#36364 = DIRECTION ( 'NONE', ( 0.6087595268730622289, -0.7729404925979503904, -0.1788150814213479156 ) ) ; -#36365 = ORIENTED_EDGE ( 'NONE', *, *, #9697, .F. ) ; -#36366 = CARTESIAN_POINT ( 'NONE', ( -42.55448647980254151, 182.5615766734265719, 104.9051989971102188 ) ) ; -#36367 = FACE_OUTER_BOUND ( 'NONE', #10857, .T. ) ; -#36368 = CARTESIAN_POINT ( 'NONE', ( -36.55077531636867150, 265.2798088768021785, 205.0571533001752584 ) ) ; -#36369 = ADVANCED_FACE ( 'NONE', ( #9806 ), #12073, .F. ) ; -#36370 = ORIENTED_EDGE ( 'NONE', *, *, #7914, .F. ) ; -#36371 = LINE ( 'NONE', #29839, #29506 ) ; -#36372 = ORIENTED_EDGE ( 'NONE', *, *, #17890, .F. ) ; -#36373 = ORIENTED_EDGE ( 'NONE', *, *, #23667, .T. ) ; -#36374 = DIRECTION ( 'NONE', ( 5.204170427930391307E-15, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#36375 = CARTESIAN_POINT ( 'NONE', ( -43.84807852419523755, 120.4163362487306728, 90.70932080257742314 ) ) ; -#36376 = CARTESIAN_POINT ( 'NONE', ( 6.034614391124412336, 134.5699086312019404, 93.51805763178980158 ) ) ; -#36377 = CARTESIAN_POINT ( 'NONE', ( 16.16677578416577532, 152.0066282699150975, 180.9398513676660798 ) ) ; -#36378 = CARTESIAN_POINT ( 'NONE', ( 15.95546908501697558, 121.2205045768968432, 177.4121190822531560 ) ) ; -#36379 = ADVANCED_FACE ( 'NONE', ( #9598 ), #34120, .T. ) ; -#36380 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1405, #17540, #26773, #17332 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36381 = CARTESIAN_POINT ( 'NONE', ( -44.89460993704069836, 182.0197134189947974, 126.4837022849172286 ) ) ; -#36382 = CIRCLE ( 'NONE', #2418, 1.999999999221514280 ) ; -#36383 = LINE ( 'NONE', #11853, #24175 ) ; -#36384 = CONICAL_SURFACE ( 'NONE', #24641, 5.000000000038869352, 0.7853981634009125079 ) ; -#36385 = CARTESIAN_POINT ( 'NONE', ( 8.471855203514563115, 150.6175905705881064, 96.98637658383512417 ) ) ; -#36386 = EDGE_CURVE ( 'NONE', #844, #11929, #18572, .T. ) ; -#36387 = CARTESIAN_POINT ( 'NONE', ( 3.166350703034567449, 184.1264558197564156, 102.1599558388959537 ) ) ; -#36388 = ORIENTED_EDGE ( 'NONE', *, *, #36186, .F. ) ; -#36389 = DIRECTION ( 'NONE', ( 0.6772239534962611884, -0.7357769477300126759, 0.000000000000000000 ) ) ; -#36390 = CARTESIAN_POINT ( 'NONE', ( -14.99833315951566526, 128.8479746833272372, 92.31674066310137050 ) ) ; -#36391 = CARTESIAN_POINT ( 'NONE', ( 28.46284161542680025, 187.5721379928345129, 102.9401731420402939 ) ) ; -#36392 = CARTESIAN_POINT ( 'NONE', ( -29.94629656998989020, 104.1131156706185266, 90.28587165236147882 ) ) ; -#36393 = CARTESIAN_POINT ( 'NONE', ( -15.49852918184222439, 151.4059875814179463, 97.18286991562941068 ) ) ; -#36394 = ORIENTED_EDGE ( 'NONE', *, *, #1246, .F. ) ; -#36395 = ORIENTED_EDGE ( 'NONE', *, *, #26126, .F. ) ; -#36396 = LINE ( 'NONE', #32370, #23851 ) ; -#36397 = ORIENTED_EDGE ( 'NONE', *, *, #768, .T. ) ; -#36398 = FACE_OUTER_BOUND ( 'NONE', #28607, .T. ) ; -#36399 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364886960122, 136.5649596138813706, 181.4686487119530511 ) ) ; -#36400 = ORIENTED_EDGE ( 'NONE', *, *, #19243, .F. ) ; -#36401 = CARTESIAN_POINT ( 'NONE', ( 14.14672431444568090, 135.3083264832294219, 93.79062778484147600 ) ) ; -#36402 = FACE_OUTER_BOUND ( 'NONE', #34469, .T. ) ; -#36403 = DIRECTION ( 'NONE', ( -3.092411411307044243E-16, 0.9743043966640313469, 0.2252353050503803911 ) ) ; -#36404 = CARTESIAN_POINT ( 'NONE', ( -35.66227043188001034, 114.5285734117000089, 87.40209258470000009 ) ) ; -#36405 = EDGE_LOOP ( 'NONE', ( #3185, #36422, #38294, #12237 ) ) ; -#36406 = DIRECTION ( 'NONE', ( 0.7069397808803130623, -0.6508952550417252958, -0.2767155817316080957 ) ) ; -#36407 = EDGE_CURVE ( 'NONE', #24000, #32912, #25843, .T. ) ; -#36408 = AXIS2_PLACEMENT_3D ( 'NONE', #16380, #7580, #28863 ) ; -#36409 = EDGE_CURVE ( 'NONE', #37986, #38350, #3046, .T. ) ; -#36410 = FACE_OUTER_BOUND ( 'NONE', #28350, .T. ) ; -#36411 = ADVANCED_FACE ( 'NONE', ( #21681 ), #37552, .F. ) ; -#36412 = CARTESIAN_POINT ( 'NONE', ( 20.42079989777838733, 184.3877318267062719, 104.8584542328953972 ) ) ; -#36413 = LINE ( 'NONE', #26819, #605 ) ; -#36414 = CIRCLE ( 'NONE', #2482, 5.500000000011062262 ) ; -#36415 = VERTEX_POINT ( 'NONE', #37008 ) ; -#36416 = CARTESIAN_POINT ( 'NONE', ( -26.16810394635999870, 191.1947376692999967, 103.6705749359999942 ) ) ; -#36417 = CARTESIAN_POINT ( 'NONE', ( 0.5945927211446001559, 189.0144201489000011, 103.6920760076999954 ) ) ; -#36418 = CARTESIAN_POINT ( 'NONE', ( 26.45619759317463604, 122.2824172884349707, 90.94697524513031794 ) ) ; -#36419 = EDGE_CURVE ( 'NONE', #21265, #19089, #34926, .T. ) ; -#36420 = ORIENTED_EDGE ( 'NONE', *, *, #21926, .F. ) ; -#36421 = CARTESIAN_POINT ( 'NONE', ( -3.737793663313441428, 136.7241453543145155, 94.09233777841696167 ) ) ; -#36422 = ORIENTED_EDGE ( 'NONE', *, *, #37225, .T. ) ; -#36423 = ADVANCED_FACE ( 'NONE', ( #28016 ), #30384, .F. ) ; -#36424 = VERTEX_POINT ( 'NONE', #6113 ) ; -#36425 = CARTESIAN_POINT ( 'NONE', ( -28.26185612672702518, 125.5768230428473373, 89.17483656727264929 ) ) ; -#36426 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37143, #34252, #9138, #21620 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36427 = ORIENTED_EDGE ( 'NONE', *, *, #9135, .F. ) ; -#36428 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, -1.387778780781445676E-14, 0.9999998176071847045 ) ) ; -#36429 = CARTESIAN_POINT ( 'NONE', ( -15.91639284609066429, 127.7608495146273242, 175.0400872585933882 ) ) ; -#36430 = DIRECTION ( 'NONE', ( 0.9914447795421228449, -0.1270909273342987478, -0.02975139169819295340 ) ) ; -#36431 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#36432 = ADVANCED_FACE ( 'NONE', ( #5919 ), #15136, .T. ) ; -#36433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #56, #26019, #20257, #10480 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.8322599924996976206, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36434 = ORIENTED_EDGE ( 'NONE', *, *, #28664, .F. ) ; -#36435 = CARTESIAN_POINT ( 'NONE', ( -20.49846059232846684, 118.8155328640159070, 89.78014971369738362 ) ) ; -#36436 = ORIENTED_EDGE ( 'NONE', *, *, #7705, .F. ) ; -#36437 = CARTESIAN_POINT ( 'NONE', ( 28.22857880600450287, 124.4169991004199858, 91.44392169599001363 ) ) ; -#36438 = CARTESIAN_POINT ( 'NONE', ( 37.71311666782268190, 212.3970731212147598, 75.53572676091057758 ) ) ; -#36439 = AXIS2_PLACEMENT_3D ( 'NONE', #36691, #15227, #36898 ) ; -#36441 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36440 = CYLINDRICAL_SURFACE ( 'NONE', #2195, 5.249999999999986677 ) ; -#36442 = ORIENTED_EDGE ( 'NONE', *, *, #40182, .F. ) ; -#36443 = ORIENTED_EDGE ( 'NONE', *, *, #507, .F. ) ; -#36444 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825852987664379, 0.0005734119039362157175 ) ) ; -#36445 = EDGE_LOOP ( 'NONE', ( #6313, #27480, #1512, #39986 ) ) ; -#36446 = CARTESIAN_POINT ( 'NONE', ( 39.08375857165000156, 119.3276005580000003, 90.14496493189000148 ) ) ; -#36447 = CARTESIAN_POINT ( 'NONE', ( -11.79199677540114166, 125.9046187772866716, 176.3423774950339862 ) ) ; -#36448 = CARTESIAN_POINT ( 'NONE', ( -31.50053089286999963, 120.4304220373000049, 89.01495634284999880 ) ) ; -#36449 = CARTESIAN_POINT ( 'NONE', ( 41.37348633212936022, 109.4896380203848025, 169.0614224528716818 ) ) ; -#36450 = ORIENTED_EDGE ( 'NONE', *, *, #33366, .T. ) ; -#36451 = ORIENTED_EDGE ( 'NONE', *, *, #24983, .T. ) ; -#36452 = ADVANCED_FACE ( 'NONE', ( #22076 ), #12870, .T. ) ; -#36453 = LINE ( 'NONE', #39510, #5707 ) ; -#36454 = EDGE_CURVE ( 'NONE', #39268, #32939, #12783, .T. ) ; -#36455 = CARTESIAN_POINT ( 'NONE', ( 13.82478458197983073, 188.3446481305931854, 103.1273619351846236 ) ) ; -#36456 = EDGE_LOOP ( 'NONE', ( #3662, #30624 ) ) ; -#36457 = CARTESIAN_POINT ( 'NONE', ( -25.50922756583905837, 191.3757872987501969, 104.3640622938216183 ) ) ; -#36458 = AXIS2_PLACEMENT_3D ( 'NONE', #4616, #1762, #11362 ) ; -#36459 = CARTESIAN_POINT ( 'NONE', ( 2.730805129813000054, 189.5827490002000104, 106.4989638482000061 ) ) ; -#36460 = ORIENTED_EDGE ( 'NONE', *, *, #20419, .F. ) ; -#36461 = FACE_OUTER_BOUND ( 'NONE', #32757, .T. ) ; -#36462 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#36463 = CARTESIAN_POINT ( 'NONE', ( -35.77460950380404370, 171.1392276904801690, 164.9967004675545468 ) ) ; -#36464 = CARTESIAN_POINT ( 'NONE', ( 5.102670828619777055, 148.3404187508898815, 93.89692411454258547 ) ) ; -#36465 = ORIENTED_EDGE ( 'NONE', *, *, #262, .F. ) ; -#36466 = PLANE ( 'NONE', #4879 ) ; -#36467 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452350121, 0.1781166614240801416 ) ) ; -#36468 = ADVANCED_FACE ( 'NONE', ( #19975 ), #9785, .F. ) ; -#36469 = ORIENTED_EDGE ( 'NONE', *, *, #9741, .T. ) ; -#36470 = DIRECTION ( 'NONE', ( 0.0006039748319385826545, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#36471 = ORIENTED_EDGE ( 'NONE', *, *, #12307, .T. ) ; -#36473 = DIRECTION ( 'NONE', ( 0.0005884949961242349169, -0.2249510543439066645, 0.9743698870671261281 ) ) ; -#36472 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825945075553885, 0.0005734119018091926590 ) ) ; -#36474 = ORIENTED_EDGE ( 'NONE', *, *, #16983, .T. ) ; -#36475 = CONICAL_SURFACE ( 'NONE', #12972, 6.499999999895978320, 0.7853981634792253086 ) ; -#36476 = ORIENTED_EDGE ( 'NONE', *, *, #411, .T. ) ; -#36477 = CARTESIAN_POINT ( 'NONE', ( 38.83480492447714738, 118.7067936530172148, 89.66619639117793383 ) ) ; -#36478 = ORIENTED_EDGE ( 'NONE', *, *, #40184, .T. ) ; -#36479 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927771257326, -0.0005734119022076843370 ) ) ; -#36480 = EDGE_CURVE ( 'NONE', #20316, #36559, #13467, .T. ) ; -#36481 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #23499, #23303, #14303, #29642 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36482 = LINE ( 'NONE', #36065, #22266 ) ; -#36483 = CIRCLE ( 'NONE', #39076, 2.500000000015078605 ) ; -#36484 = CARTESIAN_POINT ( 'NONE', ( 12.64002961981943152, 177.6262665254823787, 100.7962259977304882 ) ) ; -#36485 = ORIENTED_EDGE ( 'NONE', *, *, #25823, .T. ) ; -#36486 = ORIENTED_EDGE ( 'NONE', *, *, #12498, .T. ) ; -#36487 = CARTESIAN_POINT ( 'NONE', ( -42.84327062420202026, 120.8099927651375936, 92.42850709477329474 ) ) ; -#36488 = VECTOR ( 'NONE', #2838, 999.9999999999998863 ) ; -#36489 = ORIENTED_EDGE ( 'NONE', *, *, #21607, .T. ) ; -#36490 = ORIENTED_EDGE ( 'NONE', *, *, #18024, .T. ) ; -#36491 = FACE_OUTER_BOUND ( 'NONE', #4449, .T. ) ; -#36492 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178618805657E-05, -0.0002331579774917534240 ) ) ; -#36493 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#36494 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319372081030 ) ) ; -#36495 = ORIENTED_EDGE ( 'NONE', *, *, #30724, .F. ) ; -#36496 = ORIENTED_EDGE ( 'NONE', *, *, #4361, .T. ) ; -#36497 = ORIENTED_EDGE ( 'NONE', *, *, #7470, .T. ) ; -#36498 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091565633 ) ) ; -#36499 = EDGE_CURVE ( 'NONE', #6360, #3422, #15383, .T. ) ; -#36500 = CARTESIAN_POINT ( 'NONE', ( -35.57584641406000259, 192.1220619043999989, 104.0581628891000179 ) ) ; -#36501 = CARTESIAN_POINT ( 'NONE', ( 38.03274256459000213, 191.3252113595999901, 104.1926970713000031 ) ) ; -#36502 = ADVANCED_FACE ( 'NONE', ( #26155 ), #32340, .F. ) ; -#36503 = ORIENTED_EDGE ( 'NONE', *, *, #36000, .F. ) ; -#36504 = CARTESIAN_POINT ( 'NONE', ( -25.83496534220000385, 120.7995788526999945, 87.72842892038001139 ) ) ; -#36505 = EDGE_CURVE ( 'NONE', #29827, #40452, #4447, .T. ) ; -#36506 = EDGE_LOOP ( 'NONE', ( #25548, #6422, #10310, #15863 ) ) ; -#36507 = CARTESIAN_POINT ( 'NONE', ( 1.226688065900417790, 139.2477323444667263, 176.9572749009046220 ) ) ; -#36508 = VERTEX_POINT ( 'NONE', #3638 ) ; -#36509 = CARTESIAN_POINT ( 'NONE', ( -34.95517965684792472, 220.4002260771000294, 75.57961659108507035 ) ) ; -#36510 = FACE_OUTER_BOUND ( 'NONE', #24452, .T. ) ; -#36511 = CARTESIAN_POINT ( 'NONE', ( 40.99498287648146544, 188.9713399934180700, 107.2849007588038575 ) ) ; -#36512 = ORIENTED_EDGE ( 'NONE', *, *, #36407, .T. ) ; -#36513 = CARTESIAN_POINT ( 'NONE', ( 2.467489647358048543, 189.4902148207883954, 103.3986964145526031 ) ) ; -#36514 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#36515 = CARTESIAN_POINT ( 'NONE', ( -14.69744887555976476, 124.6590508092838263, 88.44160731344477711 ) ) ; -#36516 = VERTEX_POINT ( 'NONE', #10606 ) ; -#36517 = CARTESIAN_POINT ( 'NONE', ( -3.336448265352841780, 128.5467635469353525, 89.50334990597771423 ) ) ; -#36518 = CONICAL_SURFACE ( 'NONE', #38483, 2.750000000041938453, 0.7853981633679587571 ) ; -#36519 = CARTESIAN_POINT ( 'NONE', ( 2.413008494521430514, 190.2283635238533748, 104.0378223175451353 ) ) ; -#36520 = CARTESIAN_POINT ( 'NONE', ( 19.71701219870257304, 124.6133069866743455, 177.2811646003819135 ) ) ; -#36521 = AXIS2_PLACEMENT_3D ( 'NONE', #18093, #34049, #9122 ) ; -#36522 = ORIENTED_EDGE ( 'NONE', *, *, #575, .F. ) ; -#36523 = CARTESIAN_POINT ( 'NONE', ( -12.63072017624268106, 177.7897717398484474, 100.7065154983451407 ) ) ; -#36524 = VERTEX_POINT ( 'NONE', #7515 ) ; -#36525 = DIRECTION ( 'NONE', ( 0.0005884949961239145351, -0.2249510543439067201, 0.9743698870671262391 ) ) ; -#36526 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971557076 ) ) ; -#36527 = VECTOR ( 'NONE', #8639, 1000.000000000000227 ) ; -#36528 = CARTESIAN_POINT ( 'NONE', ( -2.935421600793285624, 191.9759150222000130, 106.9232211732562661 ) ) ; -#36529 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21500, #9418, #27641, #21891 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36530 = CARTESIAN_POINT ( 'NONE', ( 6.031586751427973070, 135.0121291300918358, 90.94566406577418149 ) ) ; -#36531 = ORIENTED_EDGE ( 'NONE', *, *, #22527, .T. ) ; -#36532 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11926, #2517, #31133, #33781 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36533 = DIRECTION ( 'NONE', ( -0.7856007465113992172, -0.6187337610642661412, 0.000000000000000000 ) ) ; -#36534 = CARTESIAN_POINT ( 'NONE', ( -37.40113477844868584, 212.8449769292228950, 73.08109343054711360 ) ) ; -#36535 = LINE ( 'NONE', #8538, #21835 ) ; -#36536 = CARTESIAN_POINT ( 'NONE', ( -16.17152365748802723, 122.0555626504313977, 174.5538714920280086 ) ) ; -#36537 = ADVANCED_FACE ( 'NONE', ( #16122 ), #782, .T. ) ; -#36538 = CARTESIAN_POINT ( 'NONE', ( 19.71670472023113518, 125.1331318090227427, 175.0259593520766543 ) ) ; -#36539 = CARTESIAN_POINT ( 'NONE', ( 31.52026657978606394, 177.3554970526973875, 100.5796284133711254 ) ) ; -#36540 = LINE ( 'NONE', #2802, #14235 ) ; -#36541 = CARTESIAN_POINT ( 'NONE', ( -35.93776700278350233, 192.3813625493561119, 104.4100568030667660 ) ) ; -#36542 = VERTEX_POINT ( 'NONE', #16318 ) ; -#36544 = AXIS2_PLACEMENT_3D ( 'NONE', #10276, #32535, #38453 ) ; -#36543 = DIRECTION ( 'NONE', ( 0.0005884949961265558685, -0.2249510543439056931, 0.9743698870671265722 ) ) ; -#36545 = EDGE_CURVE ( 'NONE', #30572, #38012, #573, .T. ) ; -#36546 = CARTESIAN_POINT ( 'NONE', ( 28.46414028889677894, 184.0160272192176762, 102.6323312183167218 ) ) ; -#36547 = CONICAL_SURFACE ( 'NONE', #3870, 2.502986836105446145, 0.7853981633574639298 ) ; -#36548 = ORIENTED_EDGE ( 'NONE', *, *, #20396, .F. ) ; -#36549 = CARTESIAN_POINT ( 'NONE', ( 5.664905786808743571, 181.8314082943285257, 101.8228474347524468 ) ) ; -#36550 = AXIS2_PLACEMENT_3D ( 'NONE', #11606, #11390, #39791 ) ; -#36551 = EDGE_CURVE ( 'NONE', #81, #12152, #31710, .T. ) ; -#36552 = EDGE_CURVE ( 'NONE', #16199, #40349, #22495, .T. ) ; -#36553 = AXIS2_PLACEMENT_3D ( 'NONE', #35530, #32110, #4273 ) ; -#36554 = ORIENTED_EDGE ( 'NONE', *, *, #12689, .T. ) ; -#36555 = CARTESIAN_POINT ( 'NONE', ( -38.59077273876000191, 119.5166102805000037, 87.47846885030999431 ) ) ; -#36556 = ADVANCED_FACE ( 'NONE', ( #393 ), #12886, .T. ) ; -#36557 = DIRECTION ( 'NONE', ( 0.6087616187692346248, -0.7730003051580284223, -0.1785492081725819080 ) ) ; -#36558 = CARTESIAN_POINT ( 'NONE', ( -15.94449010895081642, 152.1461032928982036, 184.5535245782780294 ) ) ; -#36559 = VERTEX_POINT ( 'NONE', #16134 ) ; -#36560 = DIRECTION ( 'NONE', ( 0.0005884949961248230966, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36561 = CARTESIAN_POINT ( 'NONE', ( 46.07705293508445266, 185.2595815743947014, 105.4745506663921475 ) ) ; -#36562 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#36563 = DIRECTION ( 'NONE', ( -0.7856246811335054758, -0.6187033702784218159, 0.000000000000000000 ) ) ; -#36564 = DIRECTION ( 'NONE', ( 0.0005884949961236854432, -0.2249510543439065813, 0.9743698870671262391 ) ) ; -#36565 = ORIENTED_EDGE ( 'NONE', *, *, #38519, .F. ) ; -#36566 = EDGE_LOOP ( 'NONE', ( #11958, #17024, #20229, #33007 ) ) ; -#36567 = DIRECTION ( 'NONE', ( 0.0005884949961259295249, -0.2249510543438812127, 0.9743698870671321233 ) ) ; -#36568 = CARTESIAN_POINT ( 'NONE', ( 12.63704991662151045, 181.8864431108920883, 101.9054465714154958 ) ) ; -#36569 = CARTESIAN_POINT ( 'NONE', ( 28.43929951858842387, 125.3863007536369025, 88.75451113365119227 ) ) ; -#36570 = DIRECTION ( 'NONE', ( -1.868163743362870737E-15, 0.9743700557921586292, 0.2249510932971558463 ) ) ; -#36571 = ORIENTED_EDGE ( 'NONE', *, *, #17512, .T. ) ; -#36572 = LINE ( 'NONE', #40231, #4846 ) ; -#36573 = CARTESIAN_POINT ( 'NONE', ( -43.12191331984786302, 120.9793691103432707, 90.74774789418816567 ) ) ; -#36574 = DIRECTION ( 'NONE', ( -9.300526774670117413E-14, -0.9743700557566449261, -0.2249510934509825477 ) ) ; -#36575 = CARTESIAN_POINT ( 'NONE', ( -28.54869306411000096, 124.7825067222999991, 91.43265992974001222 ) ) ; -#36576 = DIRECTION ( 'NONE', ( -0.0005884949961181158967, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#36577 = AXIS2_PLACEMENT_3D ( 'NONE', #4052, #13281, #22498 ) ; -#36578 = EDGE_CURVE ( 'NONE', #24326, #15091, #35562, .T. ) ; -#36579 = AXIS2_PLACEMENT_3D ( 'NONE', #8455, #29511, #30315 ) ; -#36580 = CARTESIAN_POINT ( 'NONE', ( -22.49852798326972092, 153.3539066485355988, 97.63681037851679889 ) ) ; -#36581 = CONICAL_SURFACE ( 'NONE', #26147, 2.503060577177303347, 0.7853981633905392501 ) ; -#36582 = CARTESIAN_POINT ( 'NONE', ( -25.53470936712000139, 115.6131156702000027, 32.42391899273999911 ) ) ; -#36583 = CARTESIAN_POINT ( 'NONE', ( -30.44899543503618489, 184.9287465216532098, 105.4443919424699487 ) ) ; -#36584 = CARTESIAN_POINT ( 'NONE', ( 33.79411933400908197, 218.5902260770999987, 73.03809328121927535 ) ) ; -#36585 = PERSON_AND_ORGANIZATION ( #18243, #23166 ) ; -#36586 = CARTESIAN_POINT ( 'NONE', ( 39.03228382966999988, 118.7193833912999992, 89.52168887524000240 ) ) ; -#36587 = CARTESIAN_POINT ( 'NONE', ( 20.49930103516235746, 196.1188360154283430, 103.6658478038365558 ) ) ; -#36588 = CARTESIAN_POINT ( 'NONE', ( -21.82845864282945669, 129.2731355035732292, 92.07692058346603403 ) ) ; -#36589 = ADVANCED_FACE ( 'NONE', ( #9613 ), #3649, .T. ) ; -#36590 = DIRECTION ( 'NONE', ( 0.0005884949961279900511, -0.2249510543439064425, 0.9743698870671262391 ) ) ; -#36591 = CARTESIAN_POINT ( 'NONE', ( -6.035968311314003465, 136.6786235697017844, 94.29340140767534706 ) ) ; -#36592 = EDGE_LOOP ( 'NONE', ( #18001, #31749, #25373, #23909, #24814 ) ) ; -#36593 = VERTEX_POINT ( 'NONE', #10012 ) ; -#36594 = DIRECTION ( 'NONE', ( 3.053113317708491105E-14, 0.9743700557921588512, 0.2249510932971550137 ) ) ; -#36595 = ADVANCED_FACE ( 'NONE', ( #28229 ), #40174, .F. ) ; -#36596 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19394, #4047, #32477, #23274, #25961, #29217, #20185, #35312, #31886, #10006 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000001313394, 0.3750000000001315614, 0.4375000000001161848, 0.5000000000001008083, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36597 = ORIENTED_EDGE ( 'NONE', *, *, #25261, .T. ) ; -#36598 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921577410, -0.2249510932971594268 ) ) ; -#36599 = EDGE_CURVE ( 'NONE', #16409, #36222, #24536, .T. ) ; -#36600 = CARTESIAN_POINT ( 'NONE', ( 16.41891712931544589, 151.9118064129741583, 184.3536622585150155 ) ) ; -#36601 = LINE ( 'NONE', #20863, #23967 ) ; -#36602 = ORIENTED_EDGE ( 'NONE', *, *, #32269, .T. ) ; -#36603 = CARTESIAN_POINT ( 'NONE', ( 75.24409552970899995, 195.1322945201532377, 195.0264630372666659 ) ) ; -#36604 = EDGE_CURVE ( 'NONE', #27328, #35918, #21290, .T. ) ; -#36605 = VECTOR ( 'NONE', #36927, 1000.000000000000227 ) ; -#36606 = VECTOR ( 'NONE', #7170, 1000.000000000000000 ) ; -#36607 = CARTESIAN_POINT ( 'NONE', ( -38.24468933979500207, 118.9460514581792268, 87.58040766581414971 ) ) ; -#36608 = CARTESIAN_POINT ( 'NONE', ( 17.97063383949850746, 149.1908938068432917, 179.6779205776419701 ) ) ; -#36609 = CARTESIAN_POINT ( 'NONE', ( -35.95586794418000665, 218.5902260770999987, 73.08022052565414128 ) ) ; -#36610 = FACE_OUTER_BOUND ( 'NONE', #34397, .T. ) ; -#36611 = ORIENTED_EDGE ( 'NONE', *, *, #21841, .F. ) ; -#36612 = CARTESIAN_POINT ( 'NONE', ( -42.22995687933095610, 121.2138566085621392, 92.77075882374926152 ) ) ; -#36613 = AXIS2_PLACEMENT_3D ( 'NONE', #5726, #29867, #36598 ) ; -#36614 = VECTOR ( 'NONE', #35034, 1000.000000000000114 ) ; -#36615 = CARTESIAN_POINT ( 'NONE', ( 3.166376970775131028, 185.9099593149100542, 102.5717182116986521 ) ) ; -#36616 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27582, #21823, #12818, #31221 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36617 = CARTESIAN_POINT ( 'NONE', ( 36.14478326529238927, 115.6623972573988226, 90.24595429582799966 ) ) ; -#36618 = CARTESIAN_POINT ( 'NONE', ( -12.64205312145055160, 181.0622675508112422, 104.4982157022507323 ) ) ; -#36619 = ORIENTED_EDGE ( 'NONE', *, *, #24148, .F. ) ; -#36620 = ORIENTED_EDGE ( 'NONE', *, *, #2853, .T. ) ; -#36621 = CARTESIAN_POINT ( 'NONE', ( -28.27513567697000241, 186.7072156929999949, 103.4268468101000025 ) ) ; -#36622 = CARTESIAN_POINT ( 'NONE', ( 0.5732572692252020374, 188.9953112992759827, 103.7015405370500076 ) ) ; -#36623 = CARTESIAN_POINT ( 'NONE', ( -35.60480366327174551, 191.8468578592914184, 106.9415995840391531 ) ) ; -#36624 = ORIENTED_EDGE ( 'NONE', *, *, #1638, .T. ) ; -#36625 = CARTESIAN_POINT ( 'NONE', ( -3.791406087537913194, 136.7360785785722896, 94.04013485213239676 ) ) ; -#36626 = ORIENTED_EDGE ( 'NONE', *, *, #21748, .F. ) ; -#36627 = ORIENTED_EDGE ( 'NONE', *, *, #1126, .T. ) ; -#36628 = ORIENTED_EDGE ( 'NONE', *, *, #34709, .T. ) ; -#36629 = ORIENTED_EDGE ( 'NONE', *, *, #30745, .F. ) ; -#36630 = CARTESIAN_POINT ( 'NONE', ( -37.60556535410999857, 191.2771512838999968, 104.9429279799000199 ) ) ; -#36631 = DIRECTION ( 'NONE', ( -0.9914446600486547245, 0.1270322995875323713, 0.03000468167654852733 ) ) ; -#36632 = VECTOR ( 'NONE', #37124, 1000.000000000000000 ) ; -#36633 = CARTESIAN_POINT ( 'NONE', ( 20.50160081845057292, 118.3470577740523453, 89.75560736965167052 ) ) ; -#36634 = EDGE_LOOP ( 'NONE', ( #14815, #27583, #27247, #35444, #14068, #14835, #7983, #8251, #28544, #3583, #10067, #832, #16317, #6654, #37967, #31345, #11999, #12572, #8856 ) ) ; -#36635 = DIRECTION ( 'NONE', ( 0.0005884950004019305191, -0.2249510543438543730, 0.9743698870671356760 ) ) ; -#36636 = ORIENTED_EDGE ( 'NONE', *, *, #37267, .F. ) ; -#36637 = EDGE_CURVE ( 'NONE', #7200, #18386, #34513, .T. ) ; -#36638 = CIRCLE ( 'NONE', #23588, 2.500000000021942448 ) ; -#36639 = CARTESIAN_POINT ( 'NONE', ( 25.52787147563000048, 120.8002881346999970, 90.09213692394999384 ) ) ; -#36640 = EDGE_CURVE ( 'NONE', #35054, #7159, #3484, .T. ) ; -#36641 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #18076, #20183 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36642 = CIRCLE ( 'NONE', #31420, 1.999999999975517140 ) ; -#36643 = CARTESIAN_POINT ( 'NONE', ( 37.49119510912425568, 212.8449757119041408, 76.03586094040831256 ) ) ; -#36644 = EDGE_CURVE ( 'NONE', #12760, #33382, #31891, .T. ) ; -#36645 = EDGE_CURVE ( 'NONE', #20406, #3835, #9521, .T. ) ; -#36647 = CARTESIAN_POINT ( 'NONE', ( 40.13009284222664519, 84.66001446739429070, 280.9279456820921723 ) ) ; -#36646 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921585181, 0.2249510932971559851 ) ) ; -#36648 = ORIENTED_EDGE ( 'NONE', *, *, #7893, .F. ) ; -#36649 = ORIENTED_EDGE ( 'NONE', *, *, #7867, .T. ) ; -#36650 = EDGE_CURVE ( 'NONE', #24453, #31462, #40265, .T. ) ; -#36651 = ORIENTED_EDGE ( 'NONE', *, *, #13073, .F. ) ; -#36652 = CARTESIAN_POINT ( 'NONE', ( 39.18856086534000838, 118.8423561804000173, 89.52524955641000304 ) ) ; -#36653 = CARTESIAN_POINT ( 'NONE', ( 25.75482679541795150, 122.6126732673081108, 88.45788671451953178 ) ) ; -#36654 = EDGE_CURVE ( 'NONE', #25158, #21126, #30417, .T. ) ; -#36655 = DIRECTION ( 'NONE', ( -0.0005559617641560631865, 0.3907311285147092583, -0.9205046855481717749 ) ) ; -#36656 = CARTESIAN_POINT ( 'NONE', ( -13.49823529424112145, 160.0636115298041204, 99.69358428540749628 ) ) ; -#36657 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422822324, 151.2971058965562747, 97.65336929384294251 ) ) ; -#36658 = ORIENTED_EDGE ( 'NONE', *, *, #27345, .F. ) ; -#36659 = ORIENTED_EDGE ( 'NONE', *, *, #29537, .F. ) ; -#36660 = AXIS2_PLACEMENT_3D ( 'NONE', #37609, #34511, #1808 ) ; -#36661 = CARTESIAN_POINT ( 'NONE', ( 26.94931025350999931, 123.8033451839999941, 88.21882234612999696 ) ) ; -#36662 = ORIENTED_EDGE ( 'NONE', *, *, #37011, .F. ) ; -#36663 = CARTESIAN_POINT ( 'NONE', ( 35.80362116183528087, 209.7096537765151822, 75.77985605454678364 ) ) ; -#36664 = VECTOR ( 'NONE', #38982, 1000.000000000000000 ) ; -#36665 = CARTESIAN_POINT ( 'NONE', ( 28.90951000791340064, 225.0820812894944822, 76.04104400993735169 ) ) ; -#36666 = CARTESIAN_POINT ( 'NONE', ( 2.896678850647000036, 190.7891276940999887, 106.6032229042999973 ) ) ; -#36667 = CARTESIAN_POINT ( 'NONE', ( 5.666787591738080110, 130.4226561615404023, 90.27309335817682268 ) ) ; -#36668 = FACE_OUTER_BOUND ( 'NONE', #39177, .T. ) ; -#36669 = CARTESIAN_POINT ( 'NONE', ( 20.00153077817512326, 137.8436319123526914, 94.54354600521399732 ) ) ; -#36670 = DIRECTION ( 'NONE', ( 0.0005884949961258187194, -0.2249510543439062760, 0.9743698870671264611 ) ) ; -#36671 = ORIENTED_EDGE ( 'NONE', *, *, #29394, .T. ) ; -#36672 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921580740, 0.2249510932971577615 ) ) ; -#36673 = DIRECTION ( 'NONE', ( 0.0002393071041605206672, 0.2255699564796173062, -0.9742269435125952004 ) ) ; -#36674 = ORIENTED_EDGE ( 'NONE', *, *, #12053, .F. ) ; -#36675 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36676 = ORIENTED_EDGE ( 'NONE', *, *, #40132, .T. ) ; -#36677 = EDGE_CURVE ( 'NONE', #645, #31462, #22600, .T. ) ; -#36678 = CONICAL_SURFACE ( 'NONE', #19040, 5.499999999948422591, 0.7853981634197699790 ) ; -#36679 = EDGE_CURVE ( 'NONE', #39966, #29610, #38125, .T. ) ; -#36681 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36680 = CARTESIAN_POINT ( 'NONE', ( 12.63633457232399593, 127.9117860165607823, 92.25804342146548720 ) ) ; -#36682 = VERTEX_POINT ( 'NONE', #6327 ) ; -#36683 = CIRCLE ( 'NONE', #3372, 17.00000000000409273 ) ; -#36684 = VERTEX_POINT ( 'NONE', #197 ) ; -#36685 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#36686 = CIRCLE ( 'NONE', #30153, 5.500000000011062262 ) ; -#36687 = ORIENTED_EDGE ( 'NONE', *, *, #10406, .F. ) ; -#36688 = CARTESIAN_POINT ( 'NONE', ( 2.333980040545999834, 209.5255334567000034, 75.42062080793000689 ) ) ; -#36689 = CC_DESIGN_DATE_AND_TIME_ASSIGNMENT ( #8587, #24340, ( #26440 ) ) ; -#36690 = CARTESIAN_POINT ( 'NONE', ( 23.68152057461877291, 135.0471255678871216, 90.98781015170069963 ) ) ; -#36691 = CARTESIAN_POINT ( 'NONE', ( -38.94691154124904386, 128.1851843107897650, 89.27032559287691527 ) ) ; -#36692 = ORIENTED_EDGE ( 'NONE', *, *, #17669, .F. ) ; -#36693 = ORIENTED_EDGE ( 'NONE', *, *, #7047, .F. ) ; -#36694 = CARTESIAN_POINT ( 'NONE', ( -34.95668959393805864, 220.4002260770999726, 73.07961704685790494 ) ) ; -#36695 = ORIENTED_EDGE ( 'NONE', *, *, #4858, .F. ) ; -#36696 = VERTEX_POINT ( 'NONE', #15925 ) ; -#36697 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000094857, 179.7424522644951139, 101.1388664480936512 ) ) ; -#36698 = CARTESIAN_POINT ( 'NONE', ( 23.39351881373000097, 163.2729245447999915, 152.4718672074000381 ) ) ; -#36699 = FACE_OUTER_BOUND ( 'NONE', #24500, .T. ) ; -#36700 = ORIENTED_EDGE ( 'NONE', *, *, #32049, .T. ) ; -#36701 = ORIENTED_EDGE ( 'NONE', *, *, #1026, .T. ) ; -#36702 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567068 ) ) ; -#36703 = CARTESIAN_POINT ( 'NONE', ( -36.02597112483999808, 191.6140443079000022, 104.0170653400000020 ) ) ; -#36704 = ORIENTED_EDGE ( 'NONE', *, *, #38840, .F. ) ; -#36705 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099476, 179.7424522643767375, 101.1388664481733173 ) ) ; -#36706 = ADVANCED_FACE ( 'NONE', ( #28419 ), #37810, .T. ) ; -#36707 = ORIENTED_EDGE ( 'NONE', *, *, #22858, .F. ) ; -#36708 = FACE_OUTER_BOUND ( 'NONE', #29554, .T. ) ; -#36709 = CARTESIAN_POINT ( 'NONE', ( 30.07023774425934803, 176.7457471811506764, 103.0054930552473564 ) ) ; -#36710 = ORIENTED_EDGE ( 'NONE', *, *, #9413, .F. ) ; -#36711 = CARTESIAN_POINT ( 'NONE', ( 0.7489280117216963184, 188.6199951984629593, 103.1988283159848976 ) ) ; -#36712 = AXIS2_PLACEMENT_3D ( 'NONE', #29474, #7783, #26620 ) ; -#36713 = DIRECTION ( 'NONE', ( -0.0002393071182786170347, -0.2252352986010032754, 0.9743043687658493601 ) ) ; -#36714 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971561517 ) ) ; -#36715 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, -0.000000000000000000, 0.9999998176071847045 ) ) ; -#36716 = CIRCLE ( 'NONE', #16446, 4.999999999999994671 ) ; -#36717 = CARTESIAN_POINT ( 'NONE', ( -39.40714599703678545, 119.2344330321841710, 89.77271684653095463 ) ) ; -#36718 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9380918495502710286, 0.3463866074307025977 ) ) ; -#36719 = VERTEX_POINT ( 'NONE', #19184 ) ; -#36720 = CARTESIAN_POINT ( 'NONE', ( -6.031620047117566052, 177.7903949882438042, 100.7027583919079063 ) ) ; -#36721 = ORIENTED_EDGE ( 'NONE', *, *, #39386, .F. ) ; -#36722 = ORIENTED_EDGE ( 'NONE', *, *, #9927, .T. ) ; -#36723 = CARTESIAN_POINT ( 'NONE', ( 4.034499242442382894, 168.3851528797071921, 99.03841376523669737 ) ) ; -#36724 = CARTESIAN_POINT ( 'NONE', ( -2.391432910531668288, 209.5064440074542063, 73.55993817204769414 ) ) ; -#36725 = CARTESIAN_POINT ( 'NONE', ( 36.31854185129000001, 115.9249462840000007, 90.11330909800000200 ) ) ; -#36726 = CARTESIAN_POINT ( 'NONE', ( -22.36444088267160879, 213.5251368776724235, 75.57194279665978343 ) ) ; -#36727 = CARTESIAN_POINT ( 'NONE', ( 6.033427729241307880, 135.1029758574788104, 91.09104781574347953 ) ) ; -#36728 = EDGE_LOOP ( 'NONE', ( #8237, #28536, #40068, #15996 ) ) ; -#36729 = EDGE_CURVE ( 'NONE', #11222, #22073, #18649, .T. ) ; -#36730 = ADVANCED_FACE ( 'NONE', ( #791 ), #35877, .F. ) ; -#36731 = CARTESIAN_POINT ( 'NONE', ( 18.08289561727003658, 152.6324032069051384, 184.7487331658680887 ) ) ; -#36732 = DIRECTION ( 'NONE', ( -0.7066775280921691049, -9.360549773399602300E-05, 0.7075357676665912088 ) ) ; -#36733 = VECTOR ( 'NONE', #26711, 1000.000000000000227 ) ; -#36734 = ORIENTED_EDGE ( 'NONE', *, *, #12514, .F. ) ; -#36735 = DIRECTION ( 'NONE', ( 0.0005884949961259295249, -0.2249510543438812127, 0.9743698870671321233 ) ) ; -#36736 = EDGE_CURVE ( 'NONE', #14670, #6456, #26509, .T. ) ; -#36737 = FACE_OUTER_BOUND ( 'NONE', #6238, .T. ) ; -#36738 = CARTESIAN_POINT ( 'NONE', ( -77.55907816203951199, 192.6399520080828438, 194.4127632364133547 ) ) ; -#36739 = CARTESIAN_POINT ( 'NONE', ( -0.001471237489670575160, 156.2427122712107348, 96.23754757946103666 ) ) ; -#36740 = CIRCLE ( 'NONE', #19100, 2.249999999963666397 ) ; -#36741 = CARTESIAN_POINT ( 'NONE', ( -37.62060996692224535, 118.3102565143506126, 90.29050674493437612 ) ) ; -#36742 = ORIENTED_EDGE ( 'NONE', *, *, #31578, .F. ) ; -#36743 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#36744 = VECTOR ( 'NONE', #21513, 1000.000000000000227 ) ; -#36745 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; -#36746 = ORIENTED_EDGE ( 'NONE', *, *, #8930, .T. ) ; -#36747 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971564015 ) ) ; -#36748 = DIRECTION ( 'NONE', ( 0.0006039748319391170578, 1.156482106403593688E-14, 0.9999998176071845934 ) ) ; -#36749 = EDGE_LOOP ( 'NONE', ( #2511, #28494, #31848, #24689 ) ) ; -#36751 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #7254, #29154, #26094, #32222 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.533316785306447549, 4.712388980384685233 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973295471489362907, 0.9973295471489362907, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#36750 = CARTESIAN_POINT ( 'NONE', ( -38.33420530578000296, 119.5218683286999948, 87.32636249672000872 ) ) ; -#36752 = ADVANCED_FACE ( 'NONE', ( #39159 ), #24050, .F. ) ; -#36753 = CARTESIAN_POINT ( 'NONE', ( -2.373302774618340827, 209.5677226285648942, 73.55993759090392814 ) ) ; -#36754 = CARTESIAN_POINT ( 'NONE', ( -5.668429626480980588, 130.7562800546890855, 90.07018407237876545 ) ) ; -#36755 = ORIENTED_EDGE ( 'NONE', *, *, #6618, .F. ) ; -#36756 = PLANE ( 'NONE', #87 ) ; -#36757 = CARTESIAN_POINT ( 'NONE', ( -4.036264726510437661, 174.7924093550697080, 102.5751288755980255 ) ) ; -#36758 = CYLINDRICAL_SURFACE ( 'NONE', #28617, 2.000000000000001332 ) ; -#36759 = CARTESIAN_POINT ( 'NONE', ( -22.99922046160000022, 115.1130721137993191, 90.28167579205376114 ) ) ; -#36760 = DIRECTION ( 'NONE', ( -0.0002393071182782277790, -0.2252352986010052460, 0.9743043687658488050 ) ) ; -#36761 = ORIENTED_EDGE ( 'NONE', *, *, #35881, .F. ) ; -#36762 = VERTEX_POINT ( 'NONE', #26923 ) ; -#36763 = CARTESIAN_POINT ( 'NONE', ( 39.51726248239999961, 120.5822590371000018, 87.31942780059999620 ) ) ; -#36764 = FACE_OUTER_BOUND ( 'NONE', #39680, .T. ) ; -#36765 = CIRCLE ( 'NONE', #33516, 7.500000216081117443 ) ; -#36766 = CARTESIAN_POINT ( 'NONE', ( -17.15357717400076965, 121.6231103600700294, 177.7751830457494577 ) ) ; -#36767 = EDGE_CURVE ( 'NONE', #33034, #21775, #7885, .T. ) ; -#36768 = CARTESIAN_POINT ( 'NONE', ( -15.81543425957540983, 151.8937953670794343, 180.3140900142980456 ) ) ; -#36769 = ORIENTED_EDGE ( 'NONE', *, *, #13054, .T. ) ; -#36770 = AXIS2_PLACEMENT_3D ( 'NONE', #34216, #6215, #1082 ) ; -#36771 = CARTESIAN_POINT ( 'NONE', ( 1.222756100067673435, 140.3958132876599620, 157.8527939211185753 ) ) ; -#36772 = CARTESIAN_POINT ( 'NONE', ( -41.97653375836684830, 120.7581393263851623, 90.63639953958796980 ) ) ; -#36773 = CYLINDRICAL_SURFACE ( 'NONE', #3904, 3.000000000000000888 ) ; -#36774 = EDGE_CURVE ( 'NONE', #11241, #26453, #14033, .T. ) ; -#36775 = CONICAL_SURFACE ( 'NONE', #6730, 5.999999999897309699, 0.7853981634347277918 ) ; -#36776 = CARTESIAN_POINT ( 'NONE', ( 8.621115833165445608, 209.7097103552968633, 73.05329714473079150 ) ) ; -#36777 = CARTESIAN_POINT ( 'NONE', ( -36.21030856760999939, 191.7503831536999996, 104.2843867992999947 ) ) ; -#36778 = CARTESIAN_POINT ( 'NONE', ( 16.00173003433196328, 160.0551282760237086, 99.67379390875994716 ) ) ; -#36779 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#36780 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25794, #25993, #38242, #20028, #19623, #32320, #22524 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 4 ), - ( 0.000000000000000000, 0.001269605364445955441, 0.002539209452862989467, 0.003808813541279514568, 0.005078416946097733670 ), - .UNSPECIFIED. ) ; -#36781 = EDGE_CURVE ( 'NONE', #8209, #1388, #35199, .T. ) ; -#36782 = ADVANCED_FACE ( 'NONE', ( #32630 ), #23913, .T. ) ; -#36783 = CARTESIAN_POINT ( 'NONE', ( 0.05270753573806398473, 83.21792371834001756, 87.26775245801255210 ) ) ; -#36784 = EDGE_CURVE ( 'NONE', #14180, #27040, #12784, .T. ) ; -#36785 = CARTESIAN_POINT ( 'NONE', ( -6.000971308231505930, 121.2983238328714606, 152.0219651029707677 ) ) ; -#36786 = EDGE_CURVE ( 'NONE', #30287, #31566, #2990, .T. ) ; -#36787 =( NAMED_UNIT ( * ) PLANE_ANGLE_UNIT ( ) SI_UNIT ( $, .RADIAN. ) ); -#36788 = FACE_OUTER_BOUND ( 'NONE', #15809, .T. ) ; -#36789 = VERTEX_POINT ( 'NONE', #38960 ) ; -#36790 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748612543, 132.4103119505556663, 92.77713868752903181 ) ) ; -#36791 = LINE ( 'NONE', #23930, #26360 ) ; -#36792 = CARTESIAN_POINT ( 'NONE', ( -35.96311564216326673, 218.5902260770998282, 61.08022271437000938 ) ) ; -#36793 = CARTESIAN_POINT ( 'NONE', ( -24.42776678989819672, 109.6131156702000027, 87.28253805071517490 ) ) ; -#36794 = CARTESIAN_POINT ( 'NONE', ( 43.53522437658520516, 122.0089638388456592, 87.79461534120677868 ) ) ; -#36795 = ORIENTED_EDGE ( 'NONE', *, *, #36012, .T. ) ; -#36796 = CARTESIAN_POINT ( 'NONE', ( -20.49986301875108907, 192.5783218835306911, 104.3636470540474619 ) ) ; -#36797 = ORIENTED_EDGE ( 'NONE', *, *, #20236, .T. ) ; -#36798 = ORIENTED_EDGE ( 'NONE', *, *, #38018, .T. ) ; -#36799 = CARTESIAN_POINT ( 'NONE', ( -2.214589778089559591, 189.3541584552398263, 103.3701131804680671 ) ) ; -#36800 = ORIENTED_EDGE ( 'NONE', *, *, #1083, .T. ) ; -#36801 = CARTESIAN_POINT ( 'NONE', ( 20.27377773143900086, 126.8226760903316546, 91.71957867363825301 ) ) ; -#36802 = VECTOR ( 'NONE', #39435, 1000.000000000000114 ) ; -#36803 = CARTESIAN_POINT ( 'NONE', ( -1.458415330454428505, 152.0517121853154379, 130.6798743964100993 ) ) ; -#36804 = CARTESIAN_POINT ( 'NONE', ( 18.74192140635615544, 125.0674350211571380, 178.6426924340655091 ) ) ; -#36805 = CYLINDRICAL_SURFACE ( 'NONE', #36350, 6.000000000000001776 ) ; -#36806 = AXIS2_PLACEMENT_3D ( 'NONE', #5565, #12122, #21536 ) ; -#36807 = ORIENTED_EDGE ( 'NONE', *, *, #6753, .F. ) ; -#36808 = CARTESIAN_POINT ( 'NONE', ( 30.05503346856145086, 103.6131156702632410, 89.74963226087875512 ) ) ; -#36809 = AXIS2_PLACEMENT_3D ( 'NONE', #26505, #38954, #10964 ) ; -#36810 = CARTESIAN_POINT ( 'NONE', ( -20.00016507732883753, 192.7547116735289308, 103.8164558568720821 ) ) ; -#36811 = CARTESIAN_POINT ( 'NONE', ( 17.33193682145239478, 121.2642060194173155, 177.4241976613194822 ) ) ; -#36812 = ORIENTED_EDGE ( 'NONE', *, *, #34054, .F. ) ; -#36813 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#36814 = CARTESIAN_POINT ( 'NONE', ( -29.30090432678149170, 112.1830789903917349, 175.8249585680744644 ) ) ; -#36815 = DIRECTION ( 'NONE', ( 0.0005884949961212385073, -0.2249510543439022514, 0.9743698870671273493 ) ) ; -#36816 = CARTESIAN_POINT ( 'NONE', ( -5.038866276848922965, 188.2844575509515721, 103.1248590148407089 ) ) ; -#36817 = CARTESIAN_POINT ( 'NONE', ( 23.00070175390608895, 118.1131156702000169, 90.25694839687047022 ) ) ; -#36818 = ORIENTED_EDGE ( 'NONE', *, *, #29260, .F. ) ; -#36819 = CARTESIAN_POINT ( 'NONE', ( -19.70055405364098533, 149.1723619494412389, 182.9474843209757751 ) ) ; -#36820 = CARTESIAN_POINT ( 'NONE', ( 0.8184195450825001439, 189.0214314598999863, 103.6983566510999992 ) ) ; -#36821 = CARTESIAN_POINT ( 'NONE', ( -42.86870032173014522, 121.2410338499262537, 90.70283413665809746 ) ) ; -#36822 = EDGE_CURVE ( 'NONE', #9665, #1393, #17268, .T. ) ; -#36823 = ORIENTED_EDGE ( 'NONE', *, *, #19418, .T. ) ; -#36824 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, -1.387778780753556918E-14 ) ) ; -#36825 = ORIENTED_EDGE ( 'NONE', *, *, #10304, .T. ) ; -#36826 = ADVANCED_FACE ( 'NONE', ( #1548 ), #2175, .F. ) ; -#36827 = CARTESIAN_POINT ( 'NONE', ( 25.49062502244311190, 209.7098837966309475, 73.54308088453358039 ) ) ; -#36828 = AXIS2_PLACEMENT_3D ( 'NONE', #2225, #26362, #39615 ) ; -#36829 = ADVANCED_FACE ( 'NONE', ( #36510 ), #10834, .T. ) ; -#36830 = ORIENTED_EDGE ( 'NONE', *, *, #4429, .F. ) ; -#36831 = CARTESIAN_POINT ( 'NONE', ( -38.86369644165072401, 118.8228811219059793, 89.72077589445396484 ) ) ; -#36832 = VERTEX_POINT ( 'NONE', #36090 ) ; -#36833 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #11673, #14944, #39869, #18186 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.583415276538783445, 4.583429485978318674 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999999831743480, 0.9999999999831743480, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#36834 = CARTESIAN_POINT ( 'NONE', ( 76.10777906860903386, 155.6827192487132834, 98.62805563713989443 ) ) ; -#36835 = CARTESIAN_POINT ( 'NONE', ( -36.06229575586999658, 192.0270778780000001, 105.8316978152000019 ) ) ; -#36836 = CARTESIAN_POINT ( 'NONE', ( -20.01777344647963730, 205.1071326358727163, 76.11698016271346035 ) ) ; -#36837 = CARTESIAN_POINT ( 'NONE', ( -37.24386107733144513, 191.0482304107956963, 106.3386760581659303 ) ) ; -#36838 = AXIS2_PLACEMENT_3D ( 'NONE', #18381, #17772, #8810 ) ; -#36839 = ORIENTED_EDGE ( 'NONE', *, *, #20380, .T. ) ; -#36840 = CARTESIAN_POINT ( 'NONE', ( 28.45671713553771909, 181.8174855791934874, 101.7826687346213532 ) ) ; -#36841 = CARTESIAN_POINT ( 'NONE', ( -12.63747358844825541, 134.5694263371505315, 93.52752121235565141 ) ) ; -#36842 = EDGE_LOOP ( 'NONE', ( #7256, #19712, #35379, #37064 ) ) ; -#36843 = CARTESIAN_POINT ( 'NONE', ( 26.94028454027959896, 123.1544169881439927, 91.15149743865801213 ) ) ; -#36844 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#36846 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250095806, 181.8175435884122919, 102.1528341835786193 ) ) ; -#36845 = LINE ( 'NONE', #18013, #4284 ) ; -#36847 = ORIENTED_EDGE ( 'NONE', *, *, #10888, .F. ) ; -#36848 = EDGE_LOOP ( 'NONE', ( #18379, #4412, #15740 ) ) ; -#36849 = ORIENTED_EDGE ( 'NONE', *, *, #28383, .F. ) ; -#36851 = VERTEX_POINT ( 'NONE', #29782 ) ; -#36850 = VECTOR ( 'NONE', #30299, 1000.000000000000227 ) ; -#36852 = CARTESIAN_POINT ( 'NONE', ( 38.97395985376000027, 118.9659225868000192, 89.82047495415000071 ) ) ; -#36853 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971537369 ) ) ; -#36854 = LINE ( 'NONE', #30117, #16754 ) ; -#36855 = CARTESIAN_POINT ( 'NONE', ( 30.87813405534166478, 129.2310469067220708, 89.46960946475260812 ) ) ; -#36856 = CIRCLE ( 'NONE', #38171, 2.000000000000011546 ) ; -#36857 = AXIS2_PLACEMENT_3D ( 'NONE', #23236, #4414, #29377 ) ; -#36858 = DIRECTION ( 'NONE', ( 0.6087611434179116543, 0.7731004625452352341, 0.1781166614240801416 ) ) ; -#36859 = ORIENTED_EDGE ( 'NONE', *, *, #21577, .F. ) ; -#36860 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17091, #11598, #27360, #26532, #36108, #17705, #8118, #11380, #5035, #2194 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 3.469446951953614189E-18, 0.0004333472065303912014, 0.0008666944130607789334, 0.001300041619591166611, 0.001733388826121554397 ), - .UNSPECIFIED. ) ; -#36861 = ORIENTED_EDGE ( 'NONE', *, *, #1941, .T. ) ; -#36862 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7071067167008887600, 0.7071068456722005013 ) ) ; -#36863 = AXIS2_PLACEMENT_3D ( 'NONE', #3428, #8795, #9391 ) ; -#36864 = LINE ( 'NONE', #12320, #9218 ) ; -#36865 = CARTESIAN_POINT ( 'NONE', ( -44.76913686494872735, 106.7077356584182866, 169.4235275077028291 ) ) ; -#36866 = ORIENTED_EDGE ( 'NONE', *, *, #39344, .T. ) ; -#36867 = CARTESIAN_POINT ( 'NONE', ( -36.40301216257000760, 191.2749683209000295, 106.5434778884000053 ) ) ; -#36868 = EDGE_CURVE ( 'NONE', #28821, #11816, #20144, .T. ) ; -#36869 = ADVANCED_FACE ( 'NONE', ( #20552 ), #369, .F. ) ; -#36870 = EDGE_CURVE ( 'NONE', #4731, #17805, #37616, .T. ) ; -#36871 = EDGE_CURVE ( 'NONE', #29005, #17707, #14438, .T. ) ; -#36872 = CARTESIAN_POINT ( 'NONE', ( 2.474132579723000269, 190.3636575362999963, 106.1296058884999951 ) ) ; -#36873 = ORIENTED_EDGE ( 'NONE', *, *, #23637, .T. ) ; -#36874 = CARTESIAN_POINT ( 'NONE', ( 6.034498894405830427, 137.2432952343929173, 91.84754016128890441 ) ) ; -#36875 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319350647437 ) ) ; -#36876 = DIRECTION ( 'NONE', ( 0.0005884949961228995051, -0.2249510543439057486, 0.9743698870671265722 ) ) ; -#36877 = PLANE ( 'NONE', #7817 ) ; -#36878 = EDGE_CURVE ( 'NONE', #38501, #23382, #21994, .T. ) ; -#36879 = ORIENTED_EDGE ( 'NONE', *, *, #26355, .T. ) ; -#36880 = CARTESIAN_POINT ( 'NONE', ( -20.49823408210000153, 174.8433562657000095, 103.1099856640999946 ) ) ; -#36881 = CARTESIAN_POINT ( 'NONE', ( 0.05451946023390214641, 83.21792371834001756, 90.26775191081762273 ) ) ; -#36882 = AXIS2_PLACEMENT_3D ( 'NONE', #14666, #35897, #7902 ) ; -#36883 = EDGE_CURVE ( 'NONE', #29484, #32574, #30026, .T. ) ; -#36884 = CONICAL_SURFACE ( 'NONE', #1618, 2.503002883974063231, 0.7853981633885572800 ) ; -#36885 = CIRCLE ( 'NONE', #6801, 2.000000000000011546 ) ; -#36886 = ORIENTED_EDGE ( 'NONE', *, *, #36305, .F. ) ; -#36887 = CARTESIAN_POINT ( 'NONE', ( 15.94114414956070114, 127.7634661670421821, 175.0287683583358671 ) ) ; -#36888 = VERTEX_POINT ( 'NONE', #27738 ) ; -#36889 = AXIS2_PLACEMENT_3D ( 'NONE', #11333, #17049, #29750 ) ; -#36891 = DIRECTION ( 'NONE', ( 0.9914447795421228449, 0.1272537940604324957, 0.02904687618137882441 ) ) ; -#36890 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319391911088 ) ) ; -#36892 = ORIENTED_EDGE ( 'NONE', *, *, #7399, .T. ) ; -#36893 = EDGE_CURVE ( 'NONE', #6123, #33385, #39975, .T. ) ; -#36894 = ORIENTED_EDGE ( 'NONE', *, *, #32402, .F. ) ; -#36895 = ORIENTED_EDGE ( 'NONE', *, *, #5092, .F. ) ; -#36896 = CARTESIAN_POINT ( 'NONE', ( 2.367289706466999988, 209.3890111512000090, 75.42794202579000284 ) ) ; -#36897 = CARTESIAN_POINT ( 'NONE', ( 19.99579756797234253, 191.9758059840616227, 101.9094256439181407 ) ) ; -#36898 = DIRECTION ( 'NONE', ( -7.401486830846876174E-15, -0.9743700557921587402, -0.2249510932971549027 ) ) ; -#36899 = ORIENTED_EDGE ( 'NONE', *, *, #35039, .T. ) ; -#36900 = VERTEX_POINT ( 'NONE', #12371 ) ; -#36901 = DIRECTION ( 'NONE', ( 0.0005884949961233809992, -0.2249510543439078580, 0.9743698870671259060 ) ) ; -#36902 = VERTEX_POINT ( 'NONE', #31186 ) ; -#36903 = ORIENTED_EDGE ( 'NONE', *, *, #13297, .T. ) ; -#36904 = DIRECTION ( 'NONE', ( -0.0005559617641685796500, 0.3907311284661838524, -0.9205046855687695206 ) ) ; -#36905 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.274821093756980468E-14, 0.9999998176071847045 ) ) ; -#36906 = CARTESIAN_POINT ( 'NONE', ( -11.79198343374907054, 125.9681876107315333, 176.0676422622361770 ) ) ; -#36907 = DIRECTION ( 'NONE', ( 0.0005884949961258157921, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#36908 = CARTESIAN_POINT ( 'NONE', ( 35.72711796422999697, 192.3360894857999881, 104.0326477243000198 ) ) ; -#36909 = ORIENTED_EDGE ( 'NONE', *, *, #35815, .F. ) ; -#36910 = ORIENTED_EDGE ( 'NONE', *, *, #24781, .T. ) ; -#36911 = CARTESIAN_POINT ( 'NONE', ( -5.669685120243074472, 123.9705640544748064, 91.11679149625278740 ) ) ; -#36912 = DIRECTION ( 'NONE', ( -0.0005884949961224448991, 0.2249510543439060262, -0.9743698870671263501 ) ) ; -#36913 = CARTESIAN_POINT ( 'NONE', ( -36.17494636288999743, 191.7742163892000065, 104.2876465562000021 ) ) ; -#36914 = VERTEX_POINT ( 'NONE', #34229 ) ; -#36915 = CARTESIAN_POINT ( 'NONE', ( 15.60948512045867531, 183.6109006041976102, 102.0334120927841468 ) ) ; -#36916 = CIRCLE ( 'NONE', #10790, 2.000000000183533633 ) ; -#36917 = ORIENTED_EDGE ( 'NONE', *, *, #36027, .F. ) ; -#36918 = CARTESIAN_POINT ( 'NONE', ( -40.45668859034989140, 206.4002260771000010, 73.08293890854348263 ) ) ; -#36919 = CARTESIAN_POINT ( 'NONE', ( 40.49834802958050517, 188.0236428059193656, 107.9681252167849692 ) ) ; -#36920 = ORIENTED_EDGE ( 'NONE', *, *, #34467, .T. ) ; -#36921 = CONICAL_SURFACE ( 'NONE', #4226, 2.503079361258633284, 0.7853981634253369704 ) ; -#36922 = AXIS2_PLACEMENT_3D ( 'NONE', #22450, #40427, #15500 ) ; -#36923 = EDGE_CURVE ( 'NONE', #40324, #18764, #34301, .T. ) ; -#36924 = ADVANCED_FACE ( 'NONE', ( #36708 ), #14754, .T. ) ; -#36925 = VECTOR ( 'NONE', #28112, 1000.000000000000227 ) ; -#36926 = ADVANCED_FACE ( 'NONE', ( #6227 ), #3627, .F. ) ; -#36927 = DIRECTION ( 'NONE', ( -0.7933533175743878729, 0.5931616988744193852, 0.1369295895054284395 ) ) ; -#36928 = LINE ( 'NONE', #37326, #26198 ) ; -#36929 = DIRECTION ( 'NONE', ( 0.0005884949961249387809, -0.2249510543439043608, 0.9743698870671267942 ) ) ; -#36930 = CARTESIAN_POINT ( 'NONE', ( 47.95567328239271632, 139.9374889060051146, 291.1737358715798791 ) ) ; -#36931 = DIRECTION ( 'NONE', ( 3.053113317719186166E-14, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#36932 = EDGE_CURVE ( 'NONE', #8063, #18309, #9513, .T. ) ; -#36933 = ORIENTED_EDGE ( 'NONE', *, *, #7089, .T. ) ; -#36934 = CARTESIAN_POINT ( 'NONE', ( -25.51388077191477066, 211.0902258580313742, 75.57405363378009611 ) ) ; -#36935 = ORIENTED_EDGE ( 'NONE', *, *, #7968, .F. ) ; -#36936 = CARTESIAN_POINT ( 'NONE', ( -15.99825118274618063, 184.2885608609500423, 105.2878711035513817 ) ) ; -#36937 = CARTESIAN_POINT ( 'NONE', ( -37.47670858587999732, 118.7990821089999969, 87.16573600921000775 ) ) ; -#36938 = CARTESIAN_POINT ( 'NONE', ( 35.54174622234999958, 114.2816361784999941, 90.38793632835000835 ) ) ; -#36939 = EDGE_CURVE ( 'NONE', #25492, #12177, #21597, .T. ) ; -#36940 = ORIENTED_EDGE ( 'NONE', *, *, #6519, .T. ) ; -#36941 = CARTESIAN_POINT ( 'NONE', ( 22.78190537993189224, 157.8319756168561980, 98.98540907879944939 ) ) ; -#36942 = ORIENTED_EDGE ( 'NONE', *, *, #20665, .F. ) ; -#36943 = CONICAL_SURFACE ( 'NONE', #25864, 17.00000000000406430, 0.7853981633972577647 ) ; -#36944 = CARTESIAN_POINT ( 'NONE', ( -19.31458322240165870, 148.9716893160552331, 180.9720018909554540 ) ) ; -#36945 = CONICAL_SURFACE ( 'NONE', #39547, 2.499999999942582818, 0.7853981634397246836 ) ; -#36946 = AXIS2_PLACEMENT_3D ( 'NONE', #24073, #14259, #8740 ) ; -#36947 = CARTESIAN_POINT ( 'NONE', ( -6.038610453718359139, 135.2156387069402683, 91.28082590629979620 ) ) ; -#36948 = EDGE_CURVE ( 'NONE', #33855, #38290, #25390, .T. ) ; -#36949 = CARTESIAN_POINT ( 'NONE', ( 15.83342845893534090, 151.9301612465557980, 94.89025465113299163 ) ) ; -#36950 = VECTOR ( 'NONE', #7193, 1000.000000000000114 ) ; -#36951 = VERTEX_POINT ( 'NONE', #33637 ) ; -#36953 = VECTOR ( 'NONE', #8302, 1000.000000000000000 ) ; -#36952 = DIRECTION ( 'NONE', ( -0.0005884949961206199700, 0.2249510543439050825, -0.9743698870671266832 ) ) ; -#36954 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#36955 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971569011 ) ) ; -#36956 = CARTESIAN_POINT ( 'NONE', ( -35.88612293872638759, 115.2662337474595375, 90.28945915823193502 ) ) ; -#36957 = ORIENTED_EDGE ( 'NONE', *, *, #34539, .T. ) ; -#36958 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#36959 = DIRECTION ( 'NONE', ( -0.6086215548477215131, -0.7730393818215735013, -0.1788572534946828996 ) ) ; -#36960 = ORIENTED_EDGE ( 'NONE', *, *, #17182, .F. ) ; -#36961 = CARTESIAN_POINT ( 'NONE', ( 30.06880003763514964, 134.6508487161554797, 93.45568730988300388 ) ) ; -#36962 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31957, #6782, #3916, #13541, #6579, #28677, #26022, #19051, #3508, #656 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36963 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11323, #29938, #7650, #4776 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#36964 = VERTEX_POINT ( 'NONE', #12185 ) ; -#36965 = CARTESIAN_POINT ( 'NONE', ( -38.28238216209000200, 118.9845237992000051, 87.58241103861999477 ) ) ; -#36966 = CARTESIAN_POINT ( 'NONE', ( 35.89625689025860567, 194.1237596711137314, 102.8114730549799134 ) ) ; -#36967 = VERTEX_POINT ( 'NONE', #27550 ) ; -#36968 = CARTESIAN_POINT ( 'NONE', ( -76.10954455358901782, 156.3374217179836023, 95.79222820379374070 ) ) ; -#36969 = CYLINDRICAL_SURFACE ( 'NONE', #29650, 1.999999999999989564 ) ; -#36970 = CARTESIAN_POINT ( 'NONE', ( -25.38428316918999883, 190.8232025961000033, 106.1489432646000068 ) ) ; -#36971 = ADVANCED_FACE ( 'NONE', ( #24671 ), #25876, .F. ) ; -#36972 = EDGE_CURVE ( 'NONE', #3655, #40149, #5635, .T. ) ; -#36973 = VECTOR ( 'NONE', #23935, 1000.000000000000227 ) ; -#36974 = CARTESIAN_POINT ( 'NONE', ( -3.537750984983824232, 137.3463269818849426, 91.36396247942009552 ) ) ; -#36975 = FACE_OUTER_BOUND ( 'NONE', #7858, .T. ) ; -#36976 = CIRCLE ( 'NONE', #12169, 1.749999999999998446 ) ; -#36977 = ORIENTED_EDGE ( 'NONE', *, *, #23025, .T. ) ; -#36978 = CARTESIAN_POINT ( 'NONE', ( 38.79215607118000264, 119.3019797381000018, 87.60142219187000023 ) ) ; -#36979 = DIRECTION ( 'NONE', ( 0.0002083475567178144834, -0.2252353001617939388, 0.9743043755173853571 ) ) ; -#36980 = CARTESIAN_POINT ( 'NONE', ( 36.51445440182627777, 191.7487767046791021, 104.3532581982114493 ) ) ; -#36981 = VECTOR ( 'NONE', #31127, 1000.000000000000114 ) ; -#36982 = CARTESIAN_POINT ( 'NONE', ( -16.53154831419982074, 121.8638204742738367, 177.6006876565568575 ) ) ; -#36983 = EDGE_LOOP ( 'NONE', ( #19624, #17293, #38209, #21870 ) ) ; -#36984 = EDGE_CURVE ( 'NONE', #21279, #28866, #21927, .T. ) ; -#36985 = EDGE_LOOP ( 'NONE', ( #34241, #13771, #2529, #25135, #36554, #6952 ) ) ; -#36986 = CARTESIAN_POINT ( 'NONE', ( -31.73518137046647780, 115.2741031936126177, 176.5389297272637634 ) ) ; -#36987 = CARTESIAN_POINT ( 'NONE', ( -24.38839408367715222, 103.6131156702000027, 152.4718672074091330 ) ) ; -#36988 = CARTESIAN_POINT ( 'NONE', ( -19.44498994767157996, 147.7083494500389236, 183.5267648320292437 ) ) ; -#36989 = CARTESIAN_POINT ( 'NONE', ( 12.63245678305150044, 181.0156363297572000, 104.5149566212380989 ) ) ; -#36990 = CARTESIAN_POINT ( 'NONE', ( 25.49929013439215808, 120.2777482667009536, 87.91897806052588749 ) ) ; -#36991 = CARTESIAN_POINT ( 'NONE', ( -25.75631448573786031, 212.3218413124795916, 73.07406025094472568 ) ) ; -#36992 = CARTESIAN_POINT ( 'NONE', ( 20.45461275351677699, 105.2139170029073085, 89.75543067447466683 ) ) ; -#36993 = CARTESIAN_POINT ( 'NONE', ( 19.31133681887892095, 126.0954225582447634, 175.4729931450506513 ) ) ; -#36994 = EDGE_CURVE ( 'NONE', #7260, #12828, #26504, .T. ) ; -#36995 = CARTESIAN_POINT ( 'NONE', ( 5.035983838893847597, 181.7480468442998074, 101.6097244662869912 ) ) ; -#36996 = CARTESIAN_POINT ( 'NONE', ( 13.55367211394599458, 164.6398026302437927, 97.65175096769451102 ) ) ; -#36997 = CARTESIAN_POINT ( 'NONE', ( -20.45744622554683545, 184.3896479590997899, 104.8428823281020925 ) ) ; -#36998 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#36999 = CARTESIAN_POINT ( 'NONE', ( 37.96379516814999988, 191.4215591583999867, 104.2996976466999968 ) ) ; -#37000 = ORIENTED_EDGE ( 'NONE', *, *, #6808, .F. ) ; -#37001 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1040, #10274, #16183, #25612, #38060, #22743, #38648, #15979, #19238, #10062 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37002 = CARTESIAN_POINT ( 'NONE', ( 36.46784510777001032, 191.0154516242999989, 106.6747793348999949 ) ) ; -#37003 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #35057, #9349, #31025, #15479 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.585050951137079167, 4.585089182115460460 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999998781993193, 0.9999999998781993193, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#37004 = CONICAL_SURFACE ( 'NONE', #23310, 5.250000000007735146, 0.7853981634220036367 ) ; -#37005 = VERTEX_POINT ( 'NONE', #24869 ) ; -#37006 = ORIENTED_EDGE ( 'NONE', *, *, #19502, .T. ) ; -#37007 = ORIENTED_EDGE ( 'NONE', *, *, #23313, .F. ) ; -#37008 = CARTESIAN_POINT ( 'NONE', ( 17.36823235821892553, 127.5715682803508173, 172.3982060061660775 ) ) ; -#37009 = CARTESIAN_POINT ( 'NONE', ( 20.25014673412999855, 167.5741656236999972, 98.58481265140000005 ) ) ; -#37010 = AXIS2_PLACEMENT_3D ( 'NONE', #4241, #981, #10214 ) ; -#37011 = EDGE_CURVE ( 'NONE', #26453, #2464, #27336, .T. ) ; -#37012 = CARTESIAN_POINT ( 'NONE', ( 31.81422328508812924, 154.4985510624152312, 201.1972672685601538 ) ) ; -#37013 = AXIS2_PLACEMENT_3D ( 'NONE', #19192, #37424, #18784 ) ; -#37014 = EDGE_LOOP ( 'NONE', ( #18538, #16717, #7529, #21534, #32833 ) ) ; -#37015 = CARTESIAN_POINT ( 'NONE', ( -39.68267445646999647, 119.5205277319000032, 89.96097260070999369 ) ) ; -#37016 = EDGE_CURVE ( 'NONE', #34239, #26640, #5896, .T. ) ; -#37017 = CARTESIAN_POINT ( 'NONE', ( -38.36106832263448752, 118.8212171802660606, 87.72011982685570786 ) ) ; -#37018 = CARTESIAN_POINT ( 'NONE', ( -42.45956536336885989, 185.1121152691760301, 127.1961689306145900 ) ) ; -#37019 = CARTESIAN_POINT ( 'NONE', ( 2.562971096584431230, 190.9999997793927093, 104.2603522665603890 ) ) ; -#37020 = EDGE_LOOP ( 'NONE', ( #1611, #13701, #24387, #33898 ) ) ; -#37021 = CARTESIAN_POINT ( 'NONE', ( 3.168112933839599688, 185.2356858264948301, 105.4949491227606870 ) ) ; -#37022 = CARTESIAN_POINT ( 'NONE', ( 25.39110728864075028, 212.9334982812408725, 76.04317957727111832 ) ) ; -#37023 = EDGE_CURVE ( 'NONE', #8699, #1973, #15637, .T. ) ; -#37024 = EDGE_CURVE ( 'NONE', #17741, #21690, #31, .T. ) ; -#37025 = CARTESIAN_POINT ( 'NONE', ( -22.54148966027999990, 176.5965135413000269, 28.07991271570000080 ) ) ; -#37026 = DIRECTION ( 'NONE', ( 0.7075059952394668894, 1.630340059807711576E-15, 0.7067073416204273650 ) ) ; -#37027 = EDGE_CURVE ( 'NONE', #14988, #18841, #25201, .T. ) ; -#37028 = ORIENTED_EDGE ( 'NONE', *, *, #1041, .F. ) ; -#37029 = CARTESIAN_POINT ( 'NONE', ( 22.78222448925487953, 157.6320878318682901, 99.11031268573603370 ) ) ; -#37030 = CARTESIAN_POINT ( 'NONE', ( 3.063416923924000113, 191.1126416495999933, 103.7721432255000025 ) ) ; -#37031 = CARTESIAN_POINT ( 'NONE', ( 16.00176583131026575, 118.9451395335793649, 90.18281804087270359 ) ) ; -#37032 = VERTEX_POINT ( 'NONE', #7026 ) ; -#37033 = CARTESIAN_POINT ( 'NONE', ( -3.805127989129743593, 136.7391389931145511, 94.02677512615100852 ) ) ; -#37034 = ORIENTED_EDGE ( 'NONE', *, *, #3853, .T. ) ; -#37035 = AXIS2_PLACEMENT_3D ( 'NONE', #20169, #32656, #17907 ) ; -#37036 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #37439, #37044, #31115, #9437, #9634, #31310, #34159, #215, #31505, #15176, #21913, #34353, #18410, #21315, #12908, #12696, #18212, #37240, #3277, #30913, #19016, #3088, #9034, #25380 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 1, 2, 2, 2, 2, 2, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000219824, 0.3125000000000324185, 0.3750000000000428546, 0.4375000000000532907, 0.4687500000000501266, 0.5000000000000468514, 0.6250000000000341949, 0.6875000000000338618, 0.7187500000000390799, 0.7343750000000408562, 0.7500000000000425215, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37037 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22252, #12840, #37975, #27992 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37038 = DIRECTION ( 'NONE', ( 0.9999998176071847045, -0.000000000000000000, -0.0006039748319385907860 ) ) ; -#37039 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24600, #3094, #30921, #2895, #15376, #15568, #27875 ), - .UNSPECIFIED., .F., .F., - ( 4, 3, 4 ), - ( 2.775557561562891351E-17, 0.002000000000002750446, 0.002556132323769710283 ), - .UNSPECIFIED. ) ; -#37040 = LINE ( 'NONE', #24181, #9432 ) ; -#37041 = FACE_OUTER_BOUND ( 'NONE', #39565, .T. ) ; -#37042 = DIRECTION ( 'NONE', ( 0.7933533411653073131, 0.5931840316265175606, 0.1368326740407942721 ) ) ; -#37043 = CARTESIAN_POINT ( 'NONE', ( 30.06443600138266703, 134.9229365128052507, 90.78414315763292564 ) ) ; -#37044 = CARTESIAN_POINT ( 'NONE', ( -2.431666151064473258, 190.6984111013711640, 106.2266867397790406 ) ) ; -#37045 = ORIENTED_EDGE ( 'NONE', *, *, #18573, .T. ) ; -#37046 = CARTESIAN_POINT ( 'NONE', ( -10.32191354246705117, 181.6874635934578919, 101.6050416412066113 ) ) ; -#37047 = CARTESIAN_POINT ( 'NONE', ( 20.00182604067493131, 190.8514159882993511, 106.7812686061269716 ) ) ; -#37048 = CARTESIAN_POINT ( 'NONE', ( -31.70535868461000462, 226.4002260771000010, 73.57765341571000306 ) ) ; -#37050 = CARTESIAN_POINT ( 'NONE', ( 24.81837490432999971, 199.3006038172999865, 28.07991271570000080 ) ) ; -#37049 = CARTESIAN_POINT ( 'NONE', ( 22.78075325035302257, 164.5278737158889726, 98.13656827166707330 ) ) ; -#37051 = ORIENTED_EDGE ( 'NONE', *, *, #28438, .T. ) ; -#37052 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22511, #20210, #31912, #23302 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37053 = ADVANCED_FACE ( 'NONE', ( #6621 ), #38316, .F. ) ; -#37054 = CIRCLE ( 'NONE', #22059, 2.749999999947594809 ) ; -#37055 = CARTESIAN_POINT ( 'NONE', ( -36.27950425524976907, 191.8188495074159334, 104.4051415298545180 ) ) ; -#37056 = CARTESIAN_POINT ( 'NONE', ( 15.94060032687233353, 152.3729576450454317, 183.5874236705277838 ) ) ; -#37057 = CONICAL_SURFACE ( 'NONE', #8341, 4.999999999857982935, 0.7853981633778843729 ) ; -#37058 = ORIENTED_EDGE ( 'NONE', *, *, #16534, .T. ) ; -#37059 = CARTESIAN_POINT ( 'NONE', ( -28.22497418263295899, 124.4143361401367116, 91.47219364137306741 ) ) ; -#37060 = EDGE_CURVE ( 'NONE', #10259, #25706, #18040, .T. ) ; -#37061 = FACE_OUTER_BOUND ( 'NONE', #34972, .T. ) ; -#37062 = FACE_OUTER_BOUND ( 'NONE', #4899, .T. ) ; -#37063 = CARTESIAN_POINT ( 'NONE', ( 40.79509051822999766, 220.4002260892000038, 73.28386491556000237 ) ) ; -#37064 = ORIENTED_EDGE ( 'NONE', *, *, #29532, .F. ) ; -#37065 = EDGE_LOOP ( 'NONE', ( #11132, #37469, #31630 ) ) ; -#37066 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; -#37067 = ADVANCED_FACE ( 'NONE', ( #16624 ), #6903, .F. ) ; -#37068 = CARTESIAN_POINT ( 'NONE', ( 13.50176809758824703, 123.6896930292991783, 91.28289196659790150 ) ) ; -#37069 = EDGE_CURVE ( 'NONE', #27116, #5506, #25467, .T. ) ; -#37070 = ORIENTED_EDGE ( 'NONE', *, *, #20320, .T. ) ; -#37071 = CARTESIAN_POINT ( 'NONE', ( -39.80682244857173657, 74.92336540073860363, 323.7074831990058215 ) ) ; -#37072 = EDGE_CURVE ( 'NONE', #16013, #43, #16235, .T. ) ; -#37073 = CARTESIAN_POINT ( 'NONE', ( -3.537752371395798789, 168.4800613451581910, 98.55175200207808928 ) ) ; -#37074 = CARTESIAN_POINT ( 'NONE', ( 3.062273563952057298, 190.5167726273855635, 106.7325697143036365 ) ) ; -#37075 = CARTESIAN_POINT ( 'NONE', ( -11.64506987747589761, 126.0683930970590581, 176.1346534169651932 ) ) ; -#37076 = CARTESIAN_POINT ( 'NONE', ( -2.531803760470723308, 209.6150367273567383, 75.72670025133220406 ) ) ; -#37077 = DIRECTION ( 'NONE', ( -0.0005884949961246178571, 0.2249510543523500772, -0.9743698870651767985 ) ) ; -#37078 = CARTESIAN_POINT ( 'NONE', ( 3.588014096441977330, 145.1508611148875048, 93.16147139303190272 ) ) ; -#37079 = AXIS2_PLACEMENT_3D ( 'NONE', #7731, #4863, #20195 ) ; -#37080 = EDGE_LOOP ( 'NONE', ( #40369, #11558, #13254, #15689, #19288 ) ) ; -#37081 = CARTESIAN_POINT ( 'NONE', ( 45.29398665750001385, 181.0941504656715608, 101.9475978871965651 ) ) ; -#37082 = FACE_OUTER_BOUND ( 'NONE', #35296, .T. ) ; -#37083 = AXIS2_PLACEMENT_3D ( 'NONE', #30005, #30622, #2004 ) ; -#37084 = CARTESIAN_POINT ( 'NONE', ( -63.18510824492874889, 77.27946979429611929, 297.5967072516833127 ) ) ; -#37085 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5461, #30423, #1584, #14070 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.005622273453351230368, 0.006578684328568076833 ), - .UNSPECIFIED. ) ; -#37086 = ORIENTED_EDGE ( 'NONE', *, *, #8263, .T. ) ; -#37087 = FACE_OUTER_BOUND ( 'NONE', #29283, .T. ) ; -#37088 = ORIENTED_EDGE ( 'NONE', *, *, #17090, .F. ) ; -#37090 = CARTESIAN_POINT ( 'NONE', ( 35.57142872079925411, 192.1870033824226596, 103.8888500649391204 ) ) ; -#37089 = CARTESIAN_POINT ( 'NONE', ( -15.83166473606552671, 185.2693417633693684, 105.3431436966540389 ) ) ; -#37091 = VERTEX_POINT ( 'NONE', #29128 ) ; -#37092 = ORIENTED_EDGE ( 'NONE', *, *, #29239, .T. ) ; -#37093 = ORIENTED_EDGE ( 'NONE', *, *, #29825, .T. ) ; -#37094 = EDGE_CURVE ( 'NONE', #14154, #32568, #21449, .T. ) ; -#37095 = CARTESIAN_POINT ( 'NONE', ( 2.411605089786999834, 208.9943232422999984, 75.51511931384000320 ) ) ; -#37096 = EDGE_CURVE ( 'NONE', #36039, #6809, #35618, .T. ) ; -#37097 = CARTESIAN_POINT ( 'NONE', ( 42.89072085005058454, 184.8658444924963078, 107.3903155990774536 ) ) ; -#37098 = EDGE_CURVE ( 'NONE', #1259, #31494, #20501, .T. ) ; -#37099 = DIRECTION ( 'NONE', ( 1.328421402153733269E-20, -0.9743043966640312359, -0.2252353050503803356 ) ) ; -#37100 = ORIENTED_EDGE ( 'NONE', *, *, #20329, .T. ) ; -#37101 = ORIENTED_EDGE ( 'NONE', *, *, #37488, .F. ) ; -#37102 = ORIENTED_EDGE ( 'NONE', *, *, #11674, .T. ) ; -#37103 = ORIENTED_EDGE ( 'NONE', *, *, #1878, .F. ) ; -#37104 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#37105 = EDGE_CURVE ( 'NONE', #27040, #18169, #697, .T. ) ; -#37106 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21223, #36133, #39807, #39002, #29819, #18128, #39204, #8349 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 4 ), - ( 1.962615573354718958E-17, 0.003451407961357079099, 0.005177111942035635128, 0.006902815922714191157 ), - .UNSPECIFIED. ) ; -#37107 = CARTESIAN_POINT ( 'NONE', ( -19.46394794124172023, 125.6806896231740751, 178.4345049239138064 ) ) ; -#37108 = CARTESIAN_POINT ( 'NONE', ( 2.462157157005000041, 209.5677245651999954, 73.55701709327000515 ) ) ; -#37109 = ORIENTED_EDGE ( 'NONE', *, *, #31076, .T. ) ; -#37110 = ADVANCED_FACE ( 'NONE', ( #290 ), #21320, .F. ) ; -#37111 = ORIENTED_EDGE ( 'NONE', *, *, #20389, .F. ) ; -#37112 = CONICAL_SURFACE ( 'NONE', #1196, 2.499999999987588595, 0.7853981634197695350 ) ; -#37113 = VERTEX_POINT ( 'NONE', #15829 ) ; -#37114 = DIRECTION ( 'NONE', ( -0.000000000000000000, -1.000000000000000000, -0.000000000000000000 ) ) ; -#37115 = CARTESIAN_POINT ( 'NONE', ( 20.00016034875645943, 127.4394136103090887, 89.06260552501319694 ) ) ; -#37116 = ORIENTED_EDGE ( 'NONE', *, *, #23617, .F. ) ; -#37117 = CARTESIAN_POINT ( 'NONE', ( -26.79953445320000327, 123.8790405098999940, 88.43988500796000096 ) ) ; -#37118 = EDGE_CURVE ( 'NONE', #2594, #17666, #5379, .T. ) ; -#37119 = VERTEX_POINT ( 'NONE', #10327 ) ; -#37120 = DIRECTION ( 'NONE', ( -7.677760455957277161E-18, 1.000000000000000000, -1.271205131337255403E-14 ) ) ; -#37121 = CARTESIAN_POINT ( 'NONE', ( -40.89369055242008244, 189.6827382460760418, 106.9036850101785205 ) ) ; -#37122 = ORIENTED_EDGE ( 'NONE', *, *, #38510, .T. ) ; -#37123 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; -#37124 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; -#37125 = DIRECTION ( 'NONE', ( 0.0005884949961241580469, -0.2249510543439066090, 0.9743698870671262391 ) ) ; -#37126 = CARTESIAN_POINT ( 'NONE', ( -4.036264725700203115, 136.7920597759830628, 93.80205530682346193 ) ) ; -#37127 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28747, #13216, #20532, #20331 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37128 = ORIENTED_EDGE ( 'NONE', *, *, #18800, .F. ) ; -#37129 = CARTESIAN_POINT ( 'NONE', ( 21.85661045747963271, 129.3623300076286284, 92.41322950560527261 ) ) ; -#37130 = VERTEX_POINT ( 'NONE', #28325 ) ; -#37131 = ORIENTED_EDGE ( 'NONE', *, *, #35229, .F. ) ; -#37132 = CARTESIAN_POINT ( 'NONE', ( 39.70946675458673525, 77.58522061945927817, 290.6159063730808612 ) ) ; -#37133 = CARTESIAN_POINT ( 'NONE', ( -38.18996268803999783, 119.2077463964999993, 87.40560705097000493 ) ) ; -#37134 = CARTESIAN_POINT ( 'NONE', ( 38.33443754462000186, 118.7533610134000099, 90.10310419729999865 ) ) ; -#37135 = CIRCLE ( 'NONE', #25378, 2.500000000028141489 ) ; -#37136 = ORIENTED_EDGE ( 'NONE', *, *, #4304, .T. ) ; -#37137 = DIRECTION ( 'NONE', ( -0.0002393071182785117045, -0.2252352986010040525, 0.9743043687658490271 ) ) ; -#37138 = VERTEX_POINT ( 'NONE', #28918 ) ; -#37139 = AXIS2_PLACEMENT_3D ( 'NONE', #21089, #32932, #23541 ) ; -#37140 = VECTOR ( 'NONE', #13352, 999.9999999999998863 ) ; -#37141 = CONICAL_SURFACE ( 'NONE', #33175, 2.503197955275930031, 0.7853981634052017435 ) ; -#37142 = CARTESIAN_POINT ( 'NONE', ( -38.55162595008999915, 118.3743277683000059, 89.56038587743999813 ) ) ; -#37143 = CARTESIAN_POINT ( 'NONE', ( 16.00178153260169722, 185.2344458670014831, 105.4869183982072371 ) ) ; -#37144 = ORIENTED_EDGE ( 'NONE', *, *, #39911, .F. ) ; -#37145 = EDGE_CURVE ( 'NONE', #27723, #372, #6287, .T. ) ; -#37146 = CARTESIAN_POINT ( 'NONE', ( -43.18873574177671770, 147.7379676372972881, 291.5846288494005876 ) ) ; -#37147 = ADVANCED_FACE ( 'NONE', ( #13983 ), #23185, .F. ) ; -#37148 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #9883, #6987, #25628, #32157 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37149 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927200853413, 0.0005734119022208531650 ) ) ; -#37150 = CARTESIAN_POINT ( 'NONE', ( 46.04942073387295665, 125.5491642319759791, 88.61041671179513912 ) ) ; -#37151 = ADVANCED_FACE ( 'NONE', ( #27082 ), #10927, .F. ) ; -#37152 = DIRECTION ( 'NONE', ( -0.0005884949961181158967, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#37153 = EDGE_CURVE ( 'NONE', #27146, #5373, #1495, .T. ) ; -#37154 = CARTESIAN_POINT ( 'NONE', ( -39.69379533597580689, 119.8651493286000687, 87.86309706269757669 ) ) ; -#37155 = VERTEX_POINT ( 'NONE', #17017 ) ; -#37156 = CARTESIAN_POINT ( 'NONE', ( -17.99823451501096017, 132.2930706492104207, 93.28496646311234031 ) ) ; -#37157 = CARTESIAN_POINT ( 'NONE', ( -26.85975184320017561, 120.0694837154507439, 171.4904642190294055 ) ) ; -#37158 = EDGE_CURVE ( 'NONE', #38882, #6653, #24463, .T. ) ; -#37159 = ORIENTED_EDGE ( 'NONE', *, *, #29674, .T. ) ; -#37160 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 2.710505431213761687E-20, -0.0006039748319392908554 ) ) ; -#37161 = CARTESIAN_POINT ( 'NONE', ( 15.99988529162822992, 142.9897646997318930, 92.65516457330386402 ) ) ; -#37162 = VERTEX_POINT ( 'NONE', #20304 ) ; -#37163 = DIRECTION ( 'NONE', ( -0.7763856147932157725, 0.5343480027610243432, 0.3342118924985533757 ) ) ; -#37164 = EDGE_CURVE ( 'NONE', #33382, #12519, #19964, .T. ) ; -#37165 = DIRECTION ( 'NONE', ( 0.0005884949961259295249, -0.2249510543438812127, 0.9743698870671321233 ) ) ; -#37166 = CYLINDRICAL_SURFACE ( 'NONE', #25416, 10.00000000000000355 ) ; -#37167 = VERTEX_POINT ( 'NONE', #1714 ) ; -#37168 = CARTESIAN_POINT ( 'NONE', ( -21.21281377555379422, 136.1368903374970500, 93.66117170127317593 ) ) ; -#37169 = VECTOR ( 'NONE', #24681, 1000.000000000000000 ) ; -#37170 = DIRECTION ( 'NONE', ( 0.0005884949961263758909, -0.2249510543439055821, 0.9743698870671265722 ) ) ; -#37171 = VECTOR ( 'NONE', #19621, 1000.000000000000000 ) ; -#37172 = CARTESIAN_POINT ( 'NONE', ( -25.86921758744999877, 191.4610772821999944, 106.7890348773999989 ) ) ; -#37173 = CARTESIAN_POINT ( 'NONE', ( 18.73223105748837725, 125.8794445655114203, 175.0685815650430470 ) ) ; -#37174 = VECTOR ( 'NONE', #34343, 1000.000000000000000 ) ; -#37175 = DIRECTION ( 'NONE', ( -0.0006039748319378811757, -1.385389704782810608E-14, -0.9999998176071845934 ) ) ; -#37176 = ORIENTED_EDGE ( 'NONE', *, *, #27403, .T. ) ; -#37177 = ORIENTED_EDGE ( 'NONE', *, *, #31574, .F. ) ; -#37178 = EDGE_CURVE ( 'NONE', #22040, #34652, #11526, .T. ) ; -#37179 = CARTESIAN_POINT ( 'NONE', ( -19.99823416866533776, 118.9403737594142996, 90.20346087292678305 ) ) ; -#37180 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; -#37181 = CARTESIAN_POINT ( 'NONE', ( -29.41449785468654810, 161.0344709224577571, 187.1181755728296423 ) ) ; -#37182 = CARTESIAN_POINT ( 'NONE', ( -45.98416322616978391, 186.8584405881918542, 105.3861271832789583 ) ) ; -#37183 = ORIENTED_EDGE ( 'NONE', *, *, #8815, .F. ) ; -#37184 = ORIENTED_EDGE ( 'NONE', *, *, #3663, .T. ) ; -#37185 = CARTESIAN_POINT ( 'NONE', ( 38.60351697648751212, 119.1187903609922785, 90.25579952397890793 ) ) ; -#37186 = LINE ( 'NONE', #12046, #34922 ) ; -#37187 = DIRECTION ( 'NONE', ( -0.0006039748319394907822, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#37188 = CARTESIAN_POINT ( 'NONE', ( -20.50011546390365780, 195.6232239793727672, 104.6210501281420591 ) ) ; -#37189 = LINE ( 'NONE', #21662, #10272 ) ; -#37190 = ORIENTED_EDGE ( 'NONE', *, *, #14019, .T. ) ; -#37191 = CARTESIAN_POINT ( 'NONE', ( -25.50306166618090131, 190.9267346374540182, 106.3078661562249891 ) ) ; -#37192 = DIRECTION ( 'NONE', ( 0.0002393071182785538528, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#37193 = CIRCLE ( 'NONE', #28069, 4.999999999999994671 ) ; -#37194 = APPROVAL_ROLE ( '' ) ; -#37195 = FACE_OUTER_BOUND ( 'NONE', #20489, .T. ) ; -#37196 = CARTESIAN_POINT ( 'NONE', ( -22.46513725335000089, 138.6416257239000061, 152.4718672074000381 ) ) ; -#37197 = CARTESIAN_POINT ( 'NONE', ( -36.03995056947305642, 114.4593242826029211, 87.76863778157522233 ) ) ; -#37198 = CARTESIAN_POINT ( 'NONE', ( -20.39533962340643214, 184.3752265020850700, 104.9032181557475809 ) ) ; -#37199 = AXIS2_PLACEMENT_3D ( 'NONE', #15003, #11533, #24008 ) ; -#37200 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930882020 ) ) ; -#37201 = CARTESIAN_POINT ( 'NONE', ( 36.36654887128020164, 191.7212231514119765, 106.4089556652880049 ) ) ; -#37202 = AXIS2_PLACEMENT_3D ( 'NONE', #1923, #1300, #4977 ) ; -#37203 = EDGE_CURVE ( 'NONE', #18856, #11663, #36334, .T. ) ; -#37204 = ADVANCED_FACE ( 'NONE', ( #39312 ), #13380, .F. ) ; -#37206 = ORIENTED_EDGE ( 'NONE', *, *, #10254, .T. ) ; -#37205 = CARTESIAN_POINT ( 'NONE', ( 36.81547264312000323, 191.5047199901999875, 106.2223202966000031 ) ) ; -#37207 = ORIENTED_EDGE ( 'NONE', *, *, #38424, .F. ) ; -#37208 = VERTEX_POINT ( 'NONE', #11729 ) ; -#37209 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 103.5647597712388261, 168.7177032462348620 ) ) ; -#37210 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 0.000000000000000000, 0.0006039748319053226929 ) ) ; -#37211 = DIRECTION ( 'NONE', ( -0.0006039748319382907873, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#37212 = ORIENTED_EDGE ( 'NONE', *, *, #32262, .T. ) ; -#37213 = CARTESIAN_POINT ( 'NONE', ( -39.05736483137000192, 119.1152016881000009, 89.88366530550999300 ) ) ; -#37214 = DIRECTION ( 'NONE', ( -0.9999998268368058829, -0.0001323825923297300314, 0.0005734119002798992570 ) ) ; -#37215 = CARTESIAN_POINT ( 'NONE', ( 26.01073959733328067, 191.4239670711786516, 106.8751801458234496 ) ) ; -#37216 = CARTESIAN_POINT ( 'NONE', ( -38.23431137947999758, 118.4009997958000042, 87.63106613149000168 ) ) ; -#37217 = VERTEX_POINT ( 'NONE', #5579 ) ; -#37218 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672195685, 160.1796136994820188, 99.19090620720055540 ) ) ; -#37219 = CARTESIAN_POINT ( 'NONE', ( 35.11870792466202573, 88.60542317626236297, 280.9309724330075255 ) ) ; -#37220 = DIRECTION ( 'NONE', ( 0.0005884949961172263088, -0.2249510543439070254, 0.9743698870671261281 ) ) ; -#37221 = DIRECTION ( 'NONE', ( -0.7075227875441107983, 0.1589708073325023507, -0.6885780910847103531 ) ) ; -#37222 = ORIENTED_EDGE ( 'NONE', *, *, #12056, .F. ) ; -#37223 = ORIENTED_EDGE ( 'NONE', *, *, #33405, .T. ) ; -#37224 = AXIS2_PLACEMENT_3D ( 'NONE', #3808, #6882, #22249 ) ; -#37225 = EDGE_CURVE ( 'NONE', #19053, #3089, #39927, .T. ) ; -#37226 = CARTESIAN_POINT ( 'NONE', ( -26.40530067702999872, 188.8820921157000043, 103.6641521443000187 ) ) ; -#37227 = CIRCLE ( 'NONE', #24838, 5.500000000023937297 ) ; -#37228 = CARTESIAN_POINT ( 'NONE', ( 2.452308076451000129, 189.9363398959999927, 103.8103614717999932 ) ) ; -#37229 = DIRECTION ( 'NONE', ( -0.9914446424033068750, -0.1273124132179996593, -0.02879358418794632571 ) ) ; -#37230 = AXIS2_PLACEMENT_3D ( 'NONE', #5455, #38993, #2002 ) ; -#37231 = AXIS2_PLACEMENT_3D ( 'NONE', #30335, #21352, #18045 ) ; -#37232 = ORIENTED_EDGE ( 'NONE', *, *, #38604, .T. ) ; -#37233 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, -1.261220487827980678E-14, -0.9999998176071847045 ) ) ; -#37234 = ORIENTED_EDGE ( 'NONE', *, *, #7098, .T. ) ; -#37235 = CARTESIAN_POINT ( 'NONE', ( -36.06327032790999709, 192.0058469960000025, 104.2181114514999933 ) ) ; -#37236 = CARTESIAN_POINT ( 'NONE', ( -48.18511098082099409, 82.27946979429611929, 297.5876476292040707 ) ) ; -#37237 = CARTESIAN_POINT ( 'NONE', ( 20.50156975035513440, 118.5813318771761828, 89.75551271367082506 ) ) ; -#37238 = DIRECTION ( 'NONE', ( 0.0002359917676625108811, 0.9205048534524425952, 0.3907310572227180590 ) ) ; -#37239 = CARTESIAN_POINT ( 'NONE', ( 27.93628726423925812, 134.9227324293656238, 90.78539832649367725 ) ) ; -#37240 = CARTESIAN_POINT ( 'NONE', ( -1.288178592179473281, 189.1901137174187113, 105.7932474174069029 ) ) ; -#37241 = ORIENTED_EDGE ( 'NONE', *, *, #39029, .F. ) ; -#37242 = CARTESIAN_POINT ( 'NONE', ( 5.667964583422318015, 129.9727540549875187, 92.22183312941298539 ) ) ; -#37243 = CARTESIAN_POINT ( 'NONE', ( -16.55812367624396586, 121.7577634206059827, 178.0415208806314240 ) ) ; -#37244 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#37245 = ADVANCED_FACE ( 'NONE', ( #5374 ), #34333, .F. ) ; -#37246 = EDGE_CURVE ( 'NONE', #27090, #24177, #8465, .T. ) ; -#37248 = FACE_OUTER_BOUND ( 'NONE', #16392, .T. ) ; -#37247 = CARTESIAN_POINT ( 'NONE', ( -2.955836285853710610, 208.9211498072354800, 73.12285454242802984 ) ) ; -#37249 = ORIENTED_EDGE ( 'NONE', *, *, #24892, .T. ) ; -#37250 = AXIS2_PLACEMENT_3D ( 'NONE', #6828, #25679, #899 ) ; -#37251 = AXIS2_PLACEMENT_3D ( 'NONE', #15874, #22243, #2815 ) ; -#37252 = ORIENTED_EDGE ( 'NONE', *, *, #1368, .T. ) ; -#37253 = VECTOR ( 'NONE', #25397, 1000.000000000000000 ) ; -#37254 = CARTESIAN_POINT ( 'NONE', ( -3.537744320960331645, 175.3497732290038300, 100.1377481765469355 ) ) ; -#37255 = AXIS2_PLACEMENT_3D ( 'NONE', #738, #35453, #13225 ) ; -#37256 = ORIENTED_EDGE ( 'NONE', *, *, #15230, .F. ) ; -#37257 = CARTESIAN_POINT ( 'NONE', ( -25.99908199189640357, 120.4516993851283786, 90.55600231170684822 ) ) ; -#37258 = CARTESIAN_POINT ( 'NONE', ( -37.61311534121512068, 218.5902260770998282, 61.08121927284271635 ) ) ; -#37259 = CARTESIAN_POINT ( 'NONE', ( -5.631746571662000100, 114.0103269030000064, 152.4718672074000381 ) ) ; -#37260 = FACE_OUTER_BOUND ( 'NONE', #3477, .T. ) ; -#37261 = CARTESIAN_POINT ( 'NONE', ( -12.63881147185363929, 135.0944381253359268, 91.09204730616018253 ) ) ; -#37262 = ORIENTED_EDGE ( 'NONE', *, *, #32662, .T. ) ; -#37263 = ORIENTED_EDGE ( 'NONE', *, *, #24946, .F. ) ; -#37264 = CARTESIAN_POINT ( 'NONE', ( 16.16729401867695515, 152.0078996042194603, 180.9416867539977716 ) ) ; -#37265 = CARTESIAN_POINT ( 'NONE', ( -15.49970618540931788, 138.0805224084985809, 92.05383544148618569 ) ) ; -#37266 = VERTEX_POINT ( 'NONE', #34183 ) ; -#37267 = EDGE_CURVE ( 'NONE', #1726, #11222, #23943, .T. ) ; -#37268 = CARTESIAN_POINT ( 'NONE', ( -36.41573719211999816, 191.0204961844000024, 106.6712136290999950 ) ) ; -#37269 = CARTESIAN_POINT ( 'NONE', ( 2.942908067099000213, 190.9184233608000056, 106.6821566891999993 ) ) ; -#37270 = ORIENTED_EDGE ( 'NONE', *, *, #31375, .T. ) ; -#37271 = CARTESIAN_POINT ( 'NONE', ( 2.714797524005000184, 190.6465356628000052, 106.3910463972000002 ) ) ; -#37272 = VECTOR ( 'NONE', #22523, 1000.000000000000000 ) ; -#37273 = CARTESIAN_POINT ( 'NONE', ( -2.372094777808882782, 209.5677220771418376, 75.55993702015497604 ) ) ; -#37274 = CARTESIAN_POINT ( 'NONE', ( 38.15045221970718359, 118.4868570840783377, 87.66883015867043127 ) ) ; -#37275 = DIRECTION ( 'NONE', ( -0.0005884949961269095352, 0.2249510543439041110, -0.9743698870671267942 ) ) ; -#37276 = EDGE_CURVE ( 'NONE', #11663, #4266, #27871, .T. ) ; -#37277 = VECTOR ( 'NONE', #10560, 1000.000000000000000 ) ; -#37278 = EDGE_LOOP ( 'NONE', ( #2148, #36476, #20129, #8203 ) ) ; -#37279 = AXIS2_PLACEMENT_3D ( 'NONE', #31742, #3699, #19640 ) ; -#37280 = DIRECTION ( 'NONE', ( -0.0002393071182776102175, -0.2252352986010028590, 0.9743043687658493601 ) ) ; -#37281 = DIRECTION ( 'NONE', ( 0.6087614810001780175, -0.7729390313185915407, -0.1788147452386051883 ) ) ; -#37282 = CARTESIAN_POINT ( 'NONE', ( -20.18700074617595064, 127.1092214739749977, 91.89588428313297186 ) ) ; -#37283 = EDGE_CURVE ( 'NONE', #34249, #12120, #31145, .T. ) ; -#37284 = ORIENTED_EDGE ( 'NONE', *, *, #23772, .T. ) ; -#37285 = CARTESIAN_POINT ( 'NONE', ( -5.666853951127361455, 188.1985683830214384, 103.2291164934064795 ) ) ; -#37286 = VERTEX_POINT ( 'NONE', #2913 ) ; -#37287 = EDGE_CURVE ( 'NONE', #37554, #17741, #7836, .T. ) ; -#37288 = EDGE_CURVE ( 'NONE', #24000, #16151, #14671, .T. ) ; -#37290 = CARTESIAN_POINT ( 'NONE', ( 0.5624172216153647819, 188.7416494960859552, 103.3595988756643322 ) ) ; -#37289 = CARTESIAN_POINT ( 'NONE', ( 36.33811150393685097, 191.8669705167701522, 104.3681120017585187 ) ) ; -#37291 = EDGE_CURVE ( 'NONE', #8802, #6135, #16589, .T. ) ; -#37292 = ORIENTED_EDGE ( 'NONE', *, *, #21723, .F. ) ; -#37293 = ORIENTED_EDGE ( 'NONE', *, *, #35044, .T. ) ; -#37294 = CARTESIAN_POINT ( 'NONE', ( 25.49179459016677995, 205.9694998783333233, 75.50271276408311394 ) ) ; -#37295 = EDGE_CURVE ( 'NONE', #19918, #27876, #35114, .T. ) ; -#37296 = CARTESIAN_POINT ( 'NONE', ( -13.78555796877717121, 149.9402637631540074, 180.4518122125792274 ) ) ; -#37297 = ORIENTED_EDGE ( 'NONE', *, *, #16321, .T. ) ; -#37298 = CARTESIAN_POINT ( 'NONE', ( 2.917186392815999785, 209.2977915612000004, 75.96992808251999918 ) ) ; -#37299 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251387102, 132.4055461763545907, 92.79778151957364685 ) ) ; -#37300 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #3295, #21535, #6167, #37453 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37301 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971545141 ) ) ; -#37302 = CARTESIAN_POINT ( 'NONE', ( 3.166376970775131028, 185.9099593149100542, 102.5717182116986521 ) ) ; -#37303 = VERTEX_POINT ( 'NONE', #21127 ) ; -#37304 = CIRCLE ( 'NONE', #2140, 2.000000000000011546 ) ; -#37305 = ORIENTED_EDGE ( 'NONE', *, *, #39368, .F. ) ; -#37306 = CARTESIAN_POINT ( 'NONE', ( 15.50176591790000025, 188.7039117600999987, 106.2882045247999940 ) ) ; -#37308 = AXIS2_PLACEMENT_3D ( 'NONE', #11735, #24422, #39720 ) ; -#37307 = DIRECTION ( 'NONE', ( -0.0006039748319382906789, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#37309 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971556243 ) ) ; -#37310 = CYLINDRICAL_SURFACE ( 'NONE', #19573, 1.750000000000001998 ) ; -#37311 = CARTESIAN_POINT ( 'NONE', ( 35.55404263687999844, 192.3143419058999939, 103.8603455618000027 ) ) ; -#37312 = ORIENTED_EDGE ( 'NONE', *, *, #32715, .T. ) ; -#37313 = ORIENTED_EDGE ( 'NONE', *, *, #36357, .T. ) ; -#37314 = ORIENTED_EDGE ( 'NONE', *, *, #34263, .T. ) ; -#37315 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749905971, 132.8602140592046794, 90.82839891342722183 ) ) ; -#37316 = DIRECTION ( 'NONE', ( 0.0005884949961243997156, -0.2249510543439061094, 0.9743698870671263501 ) ) ; -#37317 = CARTESIAN_POINT ( 'NONE', ( -26.06116861371999960, 121.5718545594999966, 87.73565837146999513 ) ) ; -#37318 = ORIENTED_EDGE ( 'NONE', *, *, #27811, .T. ) ; -#37319 = ORIENTED_EDGE ( 'NONE', *, *, #20420, .F. ) ; -#37320 = DIRECTION ( 'NONE', ( -0.9999998176017698137, -2.069755753680284935E-09, 0.0006039837970576557649 ) ) ; -#37321 = CARTESIAN_POINT ( 'NONE', ( 40.37954014455926455, 190.1842379730972254, 106.6726557211464694 ) ) ; -#37322 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32977, #19699, #10531, #22799, #32398, #32588, #4365, #14201, #38705, #26464, #16632 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999998852029, 0.3749999999998278044, 0.4374999999997640221, 0.4687499999997247202, 0.4999999999996853628, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37323 = ORIENTED_EDGE ( 'NONE', *, *, #39333, .T. ) ; -#37324 = CARTESIAN_POINT ( 'NONE', ( -31.49061741747999932, 191.6070539478000114, 105.4286762605999996 ) ) ; -#37325 = DIRECTION ( 'NONE', ( 0.7857167656192538541, -0.6185862421878155493, -0.0004745532380132038808 ) ) ; -#37326 = CARTESIAN_POINT ( 'NONE', ( 39.72966417989118781, 165.7683690613958731, 188.2295199183388377 ) ) ; -#37327 = CARTESIAN_POINT ( 'NONE', ( 12.63986376651774890, 183.4515543678114966, 105.0773313099631139 ) ) ; -#37328 = LINE ( 'NONE', #28141, #33886 ) ; -#37329 = EDGE_CURVE ( 'NONE', #12388, #12363, #3311, .T. ) ; -#37330 = ORIENTED_EDGE ( 'NONE', *, *, #3305, .T. ) ; -#37331 = CARTESIAN_POINT ( 'NONE', ( -35.43878503103840671, 193.8169247151014645, 102.7243139109006194 ) ) ; -#37332 = ORIENTED_EDGE ( 'NONE', *, *, #37601, .T. ) ; -#37333 = CARTESIAN_POINT ( 'NONE', ( -23.37153626856268218, 181.6857280266875421, 101.6124992246220842 ) ) ; -#37334 = AXIS2_PLACEMENT_3D ( 'NONE', #37462, #12321, #30938 ) ; -#37335 = DIRECTION ( 'NONE', ( -0.0005884949961241158715, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#37336 = CARTESIAN_POINT ( 'NONE', ( 38.18496905104999684, 118.9607085922999943, 90.40243278587001896 ) ) ; -#37337 = AXIS2_PLACEMENT_3D ( 'NONE', #27144, #13837, #26940 ) ; -#37338 = ADVANCED_FACE ( 'NONE', ( #34386 ), #30451, .T. ) ; -#37339 = AXIS2_PLACEMENT_3D ( 'NONE', #35134, #28833, #38233 ) ; -#37340 = ORIENTED_EDGE ( 'NONE', *, *, #28750, .F. ) ; -#37341 = CARTESIAN_POINT ( 'NONE', ( 20.45461275351677699, 105.2139170029073085, 89.75543067447466683 ) ) ; -#37342 = VERTEX_POINT ( 'NONE', #845 ) ; -#37343 = EDGE_CURVE ( 'NONE', #32145, #645, #1995, .T. ) ; -#37344 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27607, #40233, #9178, #12432 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37345 = CARTESIAN_POINT ( 'NONE', ( 21.83022412997393502, 182.7623874074516266, 102.3469123272103189 ) ) ; -#37346 = EDGE_CURVE ( 'NONE', #27991, #25669, #25903, .T. ) ; -#37347 = ORIENTED_EDGE ( 'NONE', *, *, #17597, .F. ) ; -#37348 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825928029561446, -0.0005734119023360420564 ) ) ; -#37349 = CARTESIAN_POINT ( 'NONE', ( -35.95496198192999771, 218.5902260770999987, 74.58022025207000638 ) ) ; -#37350 = CARTESIAN_POINT ( 'NONE', ( 23.36310281678468925, 177.4440130396671691, 100.9048489206809904 ) ) ; -#37351 = FACE_OUTER_BOUND ( 'NONE', #11211, .T. ) ; -#37352 = VERTEX_POINT ( 'NONE', #9666 ) ; -#37353 = CARTESIAN_POINT ( 'NONE', ( -29.33473203001190655, 191.5260128509293338, 103.8879052539893024 ) ) ; -#37354 = CARTESIAN_POINT ( 'NONE', ( -39.74907094618137648, 128.0257196899142116, 94.36551623669089395 ) ) ; -#37355 = ORIENTED_EDGE ( 'NONE', *, *, #25673, .F. ) ; -#37356 = LINE ( 'NONE', #9354, #9535 ) ; -#37357 = EDGE_LOOP ( 'NONE', ( #13709, #11395, #30541, #9361 ) ) ; -#37358 = CARTESIAN_POINT ( 'NONE', ( 14.24259403095196319, 124.1280741090887574, 175.6403682132716426 ) ) ; -#37359 = AXIS2_PLACEMENT_3D ( 'NONE', #29270, #16376, #10269 ) ; -#37360 = VECTOR ( 'NONE', #11393, 1000.000000000000114 ) ; -#37361 = DIRECTION ( 'NONE', ( 0.0002393070154807156044, 0.2243321270822452584, -0.9745127189990429040 ) ) ; -#37362 = CARTESIAN_POINT ( 'NONE', ( -17.99999999999894129, 182.4172041432880462, 101.7781247867910395 ) ) ; -#37363 = ORIENTED_EDGE ( 'NONE', *, *, #17746, .F. ) ; -#37364 = CARTESIAN_POINT ( 'NONE', ( 36.44436247437651133, 190.8511614233640330, 106.7712946021073606 ) ) ; -#37365 = CARTESIAN_POINT ( 'NONE', ( 4.035676232561270282, 167.9352507711567171, 100.9871535387873962 ) ) ; -#37366 = CARTESIAN_POINT ( 'NONE', ( -25.87112522472000009, 191.5254626433000169, 106.7952437010000040 ) ) ; -#37367 = CARTESIAN_POINT ( 'NONE', ( -1.217044208918286685, 139.0119017283902565, 177.9285297249669782 ) ) ; -#37368 = CARTESIAN_POINT ( 'NONE', ( 4.213781954923014439, 124.8077010108359701, 88.46450401330118041 ) ) ; -#37369 = ORIENTED_EDGE ( 'NONE', *, *, #23858, .T. ) ; -#37370 = FACE_OUTER_BOUND ( 'NONE', #35931, .T. ) ; -#37371 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37372 = CARTESIAN_POINT ( 'NONE', ( 36.83544183102883807, 191.6000745761645305, 104.3427389016375031 ) ) ; -#37373 = ADVANCED_FACE ( 'NONE', ( #15780 ), #14783, .F. ) ; -#37374 = EDGE_CURVE ( 'NONE', #27950, #23218, #19449, .T. ) ; -#37375 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20178, #24707, #33260, #2413 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37376 = CARTESIAN_POINT ( 'NONE', ( -45.92783482638418491, 124.8424006619797098, 91.58171271578800088 ) ) ; -#37377 = EDGE_CURVE ( 'NONE', #29960, #27558, #22142, .T. ) ; -#37378 = EDGE_LOOP ( 'NONE', ( #31274, #27043, #26099, #14129 ) ) ; -#37379 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#37380 = EDGE_CURVE ( 'NONE', #26486, #14356, #3651, .T. ) ; -#37381 = DIRECTION ( 'NONE', ( 0.0005884949961246126529, -0.2249510515334658955, 0.9743698877159676641 ) ) ; -#37382 = CARTESIAN_POINT ( 'NONE', ( 25.79670600115087709, 212.1502502800587706, 73.04292351838113007 ) ) ; -#37383 = CARTESIAN_POINT ( 'NONE', ( 12.63859106734261140, 181.5182822141926806, 104.2008611223816956 ) ) ; -#37384 = DIRECTION ( 'NONE', ( -0.0004161288024545937514, 0.8480480897973873278, -0.5299191110233921753 ) ) ; -#37385 = ORIENTED_EDGE ( 'NONE', *, *, #14212, .F. ) ; -#37386 = CARTESIAN_POINT ( 'NONE', ( -25.50364383179312711, 190.9618642916203157, 106.3193978424590114 ) ) ; -#37387 = ADVANCED_FACE ( 'NONE', ( #22748 ), #12938, .T. ) ; -#37388 = CARTESIAN_POINT ( 'NONE', ( -30.94549661354466963, 183.7382141536517963, 102.0909227894106124 ) ) ; -#37389 = VECTOR ( 'NONE', #33685, 1000.000000000000114 ) ; -#37390 = AXIS2_PLACEMENT_3D ( 'NONE', #35926, #20400, #32869 ) ; -#37391 = CARTESIAN_POINT ( 'NONE', ( -12.64112683475350352, 181.7729531356305870, 101.7436747511642636 ) ) ; -#37392 = ADVANCED_FACE ( 'NONE', ( #31751 ), #37845, .F. ) ; -#37393 = CIRCLE ( 'NONE', #19739, 5.249999999999986677 ) ; -#37394 = DIRECTION ( 'NONE', ( 0.1632030863883311977, -0.3417424275059330885, 0.9255143790539803739 ) ) ; -#37395 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5221, #24876, #15056, #30994 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37396 = APPLICATION_PROTOCOL_DEFINITION ( 'international standard', 'config_control_design', 1994, #6482 ) ; -#37397 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#37398 = EDGE_LOOP ( 'NONE', ( #5207, #29359, #12393, #30257 ) ) ; -#37399 = CARTESIAN_POINT ( 'NONE', ( 23.35635955975471134, 181.6919812636757285, 101.5857449861623110 ) ) ; -#37400 = LINE ( 'NONE', #24542, #20524 ) ; -#37401 = CARTESIAN_POINT ( 'NONE', ( -13.50000254341547468, 185.9068427740967593, 102.5779769526163960 ) ) ; -#37402 = CARTESIAN_POINT ( 'NONE', ( 37.96419449340999819, 191.2689178647999881, 104.9608596072000068 ) ) ; -#37403 = ORIENTED_EDGE ( 'NONE', *, *, #20008, .T. ) ; -#37404 = LINE ( 'NONE', #40052, #21976 ) ; -#37405 = VERTEX_POINT ( 'NONE', #29280 ) ; -#37406 = ORIENTED_EDGE ( 'NONE', *, *, #21614, .T. ) ; -#37407 = EDGE_CURVE ( 'NONE', #30211, #23690, #38534, .T. ) ; -#37408 = DIRECTION ( 'NONE', ( 0.0005884949961205877692, -0.2249510543439036392, 0.9743698870671270162 ) ) ; -#37409 = DIRECTION ( 'NONE', ( -0.0005884949961229519804, 0.2249510543439058041, -0.9743698870671265722 ) ) ; -#37410 = CARTESIAN_POINT ( 'NONE', ( 45.26975122592565270, 124.1481352483489360, 92.21575753250833429 ) ) ; -#37411 = EDGE_LOOP ( 'NONE', ( #12839, #27952, #36101, #12478 ) ) ; -#37412 = CARTESIAN_POINT ( 'NONE', ( 36.21512884357999695, 191.5734286125999972, 103.9649898384000153 ) ) ; -#37413 = DIRECTION ( 'NONE', ( -0.0005884932957440756505, 0.2249510543440633170, -0.9743698870681170021 ) ) ; -#37414 = LINE ( 'NONE', #31277, #17022 ) ; -#37415 = CARTESIAN_POINT ( 'NONE', ( -18.73195124491515884, 125.9123345718518578, 175.0519872679635114 ) ) ; -#37416 = VECTOR ( 'NONE', #31518, 999.9999999999998863 ) ; -#37417 = ORIENTED_EDGE ( 'NONE', *, *, #3209, .T. ) ; -#37418 = DIRECTION ( 'NONE', ( 0.7069397808361403968, -0.6508952239913371463, -0.2767156548817158446 ) ) ; -#37419 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569046374228, -0.8480481632227490074 ) ) ; -#37420 = CIRCLE ( 'NONE', #15861, 6.000000000000001776 ) ; -#37421 = CARTESIAN_POINT ( 'NONE', ( 37.43779685826063286, 117.9749952902482448, 90.24517334801807067 ) ) ; -#37422 = CARTESIAN_POINT ( 'NONE', ( -14.29749313982478931, 129.8659757931446279, 89.98558075341080098 ) ) ; -#37423 = ORIENTED_EDGE ( 'NONE', *, *, #6758, .F. ) ; -#37424 = DIRECTION ( 'NONE', ( -0.6087611434179116543, -0.7731004625452350121, -0.1781166614240801416 ) ) ; -#37425 = AXIS2_PLACEMENT_3D ( 'NONE', #37699, #9300, #21777 ) ; -#37426 = CARTESIAN_POINT ( 'NONE', ( 3.065142597748999886, 190.8985884971000075, 103.7227387430999954 ) ) ; -#37427 = CARTESIAN_POINT ( 'NONE', ( 16.21957306974138291, 152.0331141172343621, 181.0156715975031716 ) ) ; -#37428 = EDGE_LOOP ( 'NONE', ( #5204, #36285, #37625, #25611 ) ) ; -#37429 = EDGE_CURVE ( 'NONE', #31968, #37032, #27365, .T. ) ; -#37430 = VERTEX_POINT ( 'NONE', #4721 ) ; -#37431 = PLANE ( 'NONE', #18533 ) ; -#37432 = ADVANCED_FACE ( 'NONE', ( #26622 ), #7161, .F. ) ; -#37433 = ORIENTED_EDGE ( 'NONE', *, *, #22444, .F. ) ; -#37434 = FACE_OUTER_BOUND ( 'NONE', #27925, .T. ) ; -#37435 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26840, #38876, #39283, #1262 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37436 = CARTESIAN_POINT ( 'NONE', ( -16.89138068276333016, 152.4445295977603223, 182.0512411146230818 ) ) ; -#37437 = DIRECTION ( 'NONE', ( 0.0005884949961231158034, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37438 = CARTESIAN_POINT ( 'NONE', ( -12.63854544869962382, 134.4047710097786990, 93.63040981667991502 ) ) ; -#37439 = CARTESIAN_POINT ( 'NONE', ( -2.435581690730916016, 190.9709058671855360, 106.3075837308457352 ) ) ; -#37440 = VERTEX_POINT ( 'NONE', #5746 ) ; -#37441 = FACE_OUTER_BOUND ( 'NONE', #15410, .T. ) ; -#37442 = CARTESIAN_POINT ( 'NONE', ( -20.01829689993581596, 209.7096928646539880, 76.07061354826153377 ) ) ; -#37443 = CARTESIAN_POINT ( 'NONE', ( 39.73086071548257792, 108.4362817545589905, 169.8438797714867405 ) ) ; -#37444 = CONICAL_SURFACE ( 'NONE', #27016, 2.503115359310264409, 0.7853981634098280429 ) ; -#37446 = CARTESIAN_POINT ( 'NONE', ( 15.50029466670349620, 151.8594625334012278, 95.21623178078017702 ) ) ; -#37445 = FACE_OUTER_BOUND ( 'NONE', #17183, .T. ) ; -#37447 = ORIENTED_EDGE ( 'NONE', *, *, #171, .F. ) ; -#37448 = EDGE_CURVE ( 'NONE', #15910, #34777, #34616, .T. ) ; -#37449 = CIRCLE ( 'NONE', #24423, 2.500000000000002220 ) ; -#37450 = ORIENTED_EDGE ( 'NONE', *, *, #15867, .T. ) ; -#37451 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27162, #14061, #17098, #33250 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37452 = VERTEX_POINT ( 'NONE', #8622 ) ; -#37453 = CARTESIAN_POINT ( 'NONE', ( 8.471855298021594649, 160.9702727382075125, 99.37648202509593887 ) ) ; -#37454 = CARTESIAN_POINT ( 'NONE', ( 36.04796026505000128, 209.7096538831000032, 78.03673292965000030 ) ) ; -#37455 = DIRECTION ( 'NONE', ( -0.6771712326825871653, 0.7358254695422994374, 0.000000000000000000 ) ) ; -#37456 = CARTESIAN_POINT ( 'NONE', ( 30.80313644631934622, 129.4492109585081039, 89.52002191062021552 ) ) ; -#37457 = CARTESIAN_POINT ( 'NONE', ( 26.00056762447263026, 118.1139028608674408, 90.25209678512123901 ) ) ; -#37458 = ORIENTED_EDGE ( 'NONE', *, *, #29573, .F. ) ; -#37459 = CARTESIAN_POINT ( 'NONE', ( -20.46175974694933331, 113.1258758035523329, 152.4706876829759210 ) ) ; -#37460 = ORIENTED_EDGE ( 'NONE', *, *, #1224, .T. ) ; -#37461 = CARTESIAN_POINT ( 'NONE', ( 5.665001372474884000, 124.5325149493340007, 88.62642709471825242 ) ) ; -#37462 = CARTESIAN_POINT ( 'NONE', ( -13.78572884413053323, 150.0031063907798625, 180.1798338070967418 ) ) ; -#37463 = VERTEX_POINT ( 'NONE', #8422 ) ; -#37464 = CARTESIAN_POINT ( 'NONE', ( -2.942325969950079667, 191.1136005232059745, 103.7716195718440133 ) ) ; -#37465 = CARTESIAN_POINT ( 'NONE', ( 0.8111558242224019555, 188.6256192453763276, 103.2000891457199572 ) ) ; -#37466 = VECTOR ( 'NONE', #20461, 1000.000000000000000 ) ; -#37467 = CIRCLE ( 'NONE', #16545, 47.99999999999142375 ) ; -#37468 = LINE ( 'NONE', #40125, #6416 ) ; -#37469 = ORIENTED_EDGE ( 'NONE', *, *, #24285, .F. ) ; -#37470 = EDGE_CURVE ( 'NONE', #13325, #27876, #34980, .T. ) ; -#37471 = AXIS2_PLACEMENT_3D ( 'NONE', #25988, #34937, #32118 ) ; -#37472 = ORIENTED_EDGE ( 'NONE', *, *, #39052, .F. ) ; -#37473 = FACE_OUTER_BOUND ( 'NONE', #1759, .T. ) ; -#37474 = EDGE_CURVE ( 'NONE', #30526, #33415, #28279, .T. ) ; -#37475 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971569288 ) ) ; -#37476 = CARTESIAN_POINT ( 'NONE', ( 36.45779463145590427, 191.3327406263113062, 103.8035477994775562 ) ) ; -#37477 = CARTESIAN_POINT ( 'NONE', ( -39.49580106672456736, 114.5726794337774237, 151.3694230698880290 ) ) ; -#37478 = ORIENTED_EDGE ( 'NONE', *, *, #10528, .T. ) ; -#37479 = CARTESIAN_POINT ( 'NONE', ( 25.99891797325151543, 119.8743747107293842, 87.31240407691905148 ) ) ; -#37480 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971567900 ) ) ; -#37481 = CARTESIAN_POINT ( 'NONE', ( 19.99905349769186458, 193.8169544161346494, 102.6908434160864800 ) ) ; -#37482 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557741681312, -0.2249510933750812069 ) ) ; -#37483 = EDGE_LOOP ( 'NONE', ( #11702, #224, #39091, #10270 ) ) ; -#37484 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; -#37486 = CARTESIAN_POINT ( 'NONE', ( 4.035676232561270282, 167.9352507711567171, 100.9871535387873962 ) ) ; -#37485 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624403437, -0.1792657018023854076 ) ) ; -#37487 = ORIENTED_EDGE ( 'NONE', *, *, #39770, .F. ) ; -#37488 = EDGE_CURVE ( 'NONE', #20595, #26011, #2077, .T. ) ; -#37489 = VECTOR ( 'NONE', #7541, 1000.000000000000114 ) ; -#37490 = CIRCLE ( 'NONE', #11369, 2.000000000000011546 ) ; -#37491 = ORIENTED_EDGE ( 'NONE', *, *, #6567, .T. ) ; -#37492 = CYLINDRICAL_SURFACE ( 'NONE', #27807, 2.000000000000011546 ) ; -#37493 = CARTESIAN_POINT ( 'NONE', ( 37.35388853291757982, 168.2165014478888168, 182.6366471215059448 ) ) ; -#37495 = ORIENTED_EDGE ( 'NONE', *, *, #30101, .F. ) ; -#37494 = VECTOR ( 'NONE', #25339, 1000.000000000000227 ) ; -#37496 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29622, #7939, #19993, #14088 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37497 = ORIENTED_EDGE ( 'NONE', *, *, #40131, .F. ) ; -#37498 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#37499 = DIRECTION ( 'NONE', ( -0.6087614115774527823, 0.7730004600455669950, 0.1785492440296760075 ) ) ; -#37500 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363196004925E-14, 0.9999998176071845934 ) ) ; -#37501 = ORIENTED_EDGE ( 'NONE', *, *, #30795, .F. ) ; -#37502 = EDGE_CURVE ( 'NONE', #7652, #30359, #22627, .T. ) ; -#37503 = ORIENTED_EDGE ( 'NONE', *, *, #38166, .F. ) ; -#37504 = LINE ( 'NONE', #18478, #31781 ) ; -#37505 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#37506 = CARTESIAN_POINT ( 'NONE', ( -3.334859946289175703, 185.2690421836657606, 105.3355436155169684 ) ) ; -#37507 = CARTESIAN_POINT ( 'NONE', ( 45.03858804126006277, 180.7763372603838832, 104.2690891899409706 ) ) ; -#37508 = EDGE_CURVE ( 'NONE', #22242, #10930, #21086, .T. ) ; -#37509 = EDGE_LOOP ( 'NONE', ( #33893, #2946, #22288, #21222 ) ) ; -#37510 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37511 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #5958, #12106, #27865, #12488 ), - ( #6544, #12298, #24989, #24593 ), - ( #15950, #40295, #24791, #28249 ), - ( #28444, #420, #21715, #6152 ), - ( #34741, #22715, #35140, #13503 ), - ( #32315, #6743, #32115, #7153 ), - ( #38429, #26382, #22518, #34935 ), - ( #13902, #20021, #22915, #10643 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.07810317900020000148, 0.000000000000000000, 0.3333394298244000131, 0.6666766092639999641, 1.000000000000000000, 1.071387485245000049 ), - ( -1.136779366749999998E-06, 0.9999977618324999984 ), - .UNSPECIFIED. ) ; -#37512 = DIRECTION ( 'NONE', ( -0.0005884949961266395689, 0.2249510543439048882, -0.9743698870671267942 ) ) ; -#37513 = DIRECTION ( 'NONE', ( -0.7933533411653341805, -0.5931840316264885837, -0.1368326740407639630 ) ) ; -#37514 = VERTEX_POINT ( 'NONE', #21298 ) ; -#37515 = EDGE_CURVE ( 'NONE', #2503, #5869, #15442, .T. ) ; -#37516 = CARTESIAN_POINT ( 'NONE', ( 3.827148334468458923, 174.7479281440749617, 102.7742494057653744 ) ) ; -#37517 = EDGE_CURVE ( 'NONE', #23911, #19715, #24574, .T. ) ; -#37518 = LINE ( 'NONE', #704, #14461 ) ; -#37519 = PRODUCT_DEFINITION_FORMATION_WITH_SPECIFIED_SOURCE ( '', '', #16623, .NOT_KNOWN. ) ; -#37520 = VECTOR ( 'NONE', #22661, 1000.000000000000227 ) ; -#37521 = EDGE_CURVE ( 'NONE', #21872, #572, #39439, .T. ) ; -#37522 = CARTESIAN_POINT ( 'NONE', ( -2.452854086982368287, 209.7096538831000032, 78.05998645676569936 ) ) ; -#37523 = AXIS2_PLACEMENT_3D ( 'NONE', #36320, #5851, #30604 ) ; -#37524 = VECTOR ( 'NONE', #17274, 1000.000000000000000 ) ; -#37525 = CARTESIAN_POINT ( 'NONE', ( -19.70071604027683065, 149.4445624503525778, 181.7665744593643637 ) ) ; -#37526 = VERTEX_POINT ( 'NONE', #10230 ) ; -#37527 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 0.000000000000000000, -0.0006039748319383117124 ) ) ; -#37528 = ORIENTED_EDGE ( 'NONE', *, *, #37276, .T. ) ; -#37529 = AXIS2_PLACEMENT_3D ( 'NONE', #30967, #33409, #14829 ) ; -#37530 = CARTESIAN_POINT ( 'NONE', ( 36.28487897179775246, 77.14301703113186193, 291.5366287775435126 ) ) ; -#37531 = DIRECTION ( 'NONE', ( -0.0005884949961258157921, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#37532 = CARTESIAN_POINT ( 'NONE', ( 94.27346847287640230, 222.2365666497040024, 195.1387431474686309 ) ) ; -#37533 = CARTESIAN_POINT ( 'NONE', ( 15.99998354046833526, 185.2802125521836274, 102.4185673416719595 ) ) ; -#37534 = VERTEX_POINT ( 'NONE', #13286 ) ; -#37535 = DIRECTION ( 'NONE', ( 3.466267702402558037E-10, 0.9743700558702499404, 0.2249510929589051966 ) ) ; -#37536 = ORIENTED_EDGE ( 'NONE', *, *, #10704, .T. ) ; -#37537 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971559019 ) ) ; -#37538 = CARTESIAN_POINT ( 'NONE', ( 21.57469945311886406, 182.6285438479031029, 101.9740652419444444 ) ) ; -#37539 = EDGE_CURVE ( 'NONE', #16448, #33199, #25769, .T. ) ; -#37540 = ORIENTED_EDGE ( 'NONE', *, *, #1302, .T. ) ; -#37541 = CARTESIAN_POINT ( 'NONE', ( 35.79347699833099483, 148.9204335778105133, 291.5369255720340220 ) ) ; -#37542 = CARTESIAN_POINT ( 'NONE', ( -45.39636767568900666, 130.6771924050837868, 92.41530714614147257 ) ) ; -#37543 = CARTESIAN_POINT ( 'NONE', ( -21.60222517327440883, 158.4634865330191076, 96.25014797633018304 ) ) ; -#37544 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319299392864 ) ) ; -#37545 = ORIENTED_EDGE ( 'NONE', *, *, #35626, .F. ) ; -#37546 = ORIENTED_EDGE ( 'NONE', *, *, #6248, .T. ) ; -#37547 = CARTESIAN_POINT ( 'NONE', ( 17.33255171641533110, 121.2645175805946138, 177.4250592562015925 ) ) ; -#37548 = CARTESIAN_POINT ( 'NONE', ( 13.46662727487878719, 154.4076626936201251, 95.29260641077831906 ) ) ; -#37549 = AXIS2_PLACEMENT_3D ( 'NONE', #8102, #32643, #4622 ) ; -#37550 = VERTEX_POINT ( 'NONE', #6935 ) ; -#37551 = CARTESIAN_POINT ( 'NONE', ( 24.53318176556000196, 104.1131156702031291, 87.25296686499314092 ) ) ; -#37552 = CONICAL_SURFACE ( 'NONE', #21255, 2.499999999403085482, 0.7853981633778843729 ) ; -#37553 = CARTESIAN_POINT ( 'NONE', ( 4.035676231712624684, 167.9352507713281568, 100.9871535380448790 ) ) ; -#37554 = VERTEX_POINT ( 'NONE', #31489 ) ; -#37555 = CARTESIAN_POINT ( 'NONE', ( 5.776391476381944386E-13, 155.6803346353095492, 98.67347229713607248 ) ) ; -#37556 = EDGE_CURVE ( 'NONE', #17270, #36424, #30224, .T. ) ; -#37557 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 130.2931719330197211, 89.72259846333707856 ) ) ; -#37558 = ORIENTED_EDGE ( 'NONE', *, *, #5944, .T. ) ; -#37559 = CARTESIAN_POINT ( 'NONE', ( 28.31864702441999881, 125.4665321470999970, 88.94399801561999652 ) ) ; -#37560 = EDGE_CURVE ( 'NONE', #13652, #9483, #6136, .T. ) ; -#37561 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.261220487827980362E-14, 0.9999998176071844824 ) ) ; -#37562 = CARTESIAN_POINT ( 'NONE', ( -12.63662703291899625, 136.7909212374734977, 93.80698685772726719 ) ) ; -#37563 = DIRECTION ( 'NONE', ( 0.1305262373691798983, -0.9659583596717404852, -0.2233547598295697878 ) ) ; -#37564 = EDGE_CURVE ( 'NONE', #39475, #32051, #2433, .T. ) ; -#37565 = CARTESIAN_POINT ( 'NONE', ( 20.31489494964546694, 159.5155431624664004, 96.46771754143387057 ) ) ; -#37566 = ADVANCED_FACE ( 'NONE', ( #28039 ), #15930, .T. ) ; -#37567 = ORIENTED_EDGE ( 'NONE', *, *, #22963, .F. ) ; -#37568 = CARTESIAN_POINT ( 'NONE', ( -20.89113403792100598, 128.9341314247968455, 92.51124259315015763 ) ) ; -#37569 = EDGE_CURVE ( 'NONE', #10713, #5648, #19907, .T. ) ; -#37570 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#37571 = CARTESIAN_POINT ( 'NONE', ( -15.94440703681848959, 121.4361576967349805, 176.4277666190321270 ) ) ; -#37572 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #19083, #6216, #18876, #21586 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.0007153166800046975365, 0.0007171796110761329175 ), - .UNSPECIFIED. ) ; -#37573 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566790 ) ) ; -#37574 = EDGE_LOOP ( 'NONE', ( #8204, #17465, #15866, #22075, #28502, #20365 ) ) ; -#37575 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37576 = CARTESIAN_POINT ( 'NONE', ( 19.38593967614783153, 149.1387850987350134, 181.1979322825702639 ) ) ; -#37577 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319377938974 ) ) ; -#37578 = VECTOR ( 'NONE', #8227, 1000.000000000000114 ) ; -#37579 = AXIS2_PLACEMENT_3D ( 'NONE', #13988, #4568, #1504 ) ; -#37580 = CARTESIAN_POINT ( 'NONE', ( -14.91027384103292874, 124.4773777159772550, 171.6934768334666899 ) ) ; -#37581 = ORIENTED_EDGE ( 'NONE', *, *, #8213, .F. ) ; -#37582 = VECTOR ( 'NONE', #10569, 1000.000000000000227 ) ; -#37583 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319383098692 ) ) ; -#37584 = VECTOR ( 'NONE', #18583, 1000.000000000000227 ) ; -#37585 = CARTESIAN_POINT ( 'NONE', ( 39.06349078196001301, 191.0388279120988670, 103.7341189576915355 ) ) ; -#37586 = CARTESIAN_POINT ( 'NONE', ( -14.55306309020423505, 135.7870933973037211, 91.01063163966807679 ) ) ; -#37587 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 132.6304972307000014, 91.82341163249999738 ) ) ; -#37588 = CARTESIAN_POINT ( 'NONE', ( -20.32205136248488841, 184.3585806804883873, 104.9745027317775481 ) ) ; -#37589 = FACE_OUTER_BOUND ( 'NONE', #36286, .T. ) ; -#37590 = CARTESIAN_POINT ( 'NONE', ( 37.18343360016979915, 191.4782479266900168, 104.3069991309919970 ) ) ; -#37591 = CARTESIAN_POINT ( 'NONE', ( 36.23010250326999682, 191.7113666676000037, 106.5063430098000055 ) ) ; -#37592 = ORIENTED_EDGE ( 'NONE', *, *, #35788, .F. ) ; -#37593 = ORIENTED_EDGE ( 'NONE', *, *, #12049, .T. ) ; -#37594 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -3.519737327345223780E-16, 0.0006039748319385488274 ) ) ; -#37595 = DIRECTION ( 'NONE', ( -0.6087614115774885315, 0.7730004600455400166, 0.1785492440296710670 ) ) ; -#37596 = ADVANCED_FACE ( 'NONE', ( #25169 ), #34519, .F. ) ; -#37597 = EDGE_CURVE ( 'NONE', #407, #16596, #20954, .T. ) ; -#37598 = CARTESIAN_POINT ( 'NONE', ( 20.49930103516235746, 196.1188360154283430, 103.6658478038365558 ) ) ; -#37599 = AXIS2_PLACEMENT_3D ( 'NONE', #17469, #1752, #36498 ) ; -#37600 = DIRECTION ( 'NONE', ( -0.7933535320750288999, 0.5931614265262136199, 0.1369295264925108890 ) ) ; -#37601 = EDGE_CURVE ( 'NONE', #27115, #27579, #27281, .T. ) ; -#37602 = AXIS2_PLACEMENT_3D ( 'NONE', #6158, #28449, #25393 ) ; -#37603 = ORIENTED_EDGE ( 'NONE', *, *, #16628, .F. ) ; -#37604 = CARTESIAN_POINT ( 'NONE', ( 18.08127464052524758, 152.6344612320365286, 184.7492086203702115 ) ) ; -#37605 = EDGE_CURVE ( 'NONE', #32124, #30211, #22095, .T. ) ; -#37606 = LINE ( 'NONE', #31480, #35480 ) ; -#37607 = CARTESIAN_POINT ( 'NONE', ( -20.00002391410913560, 191.9758546681010785, 103.9335315410770448 ) ) ; -#37608 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24959, #384, #22282, #18576, #9007, #5923, #33924, #31081, #6713, #19176 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.002027470929952764501, 0.2515206031974627221, 0.5010137354649751851, 0.7505068677324875370, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37609 = CARTESIAN_POINT ( 'NONE', ( 20.25012552873999994, 118.4641756272000066, 87.50539960479001422 ) ) ; -#37610 = VERTEX_POINT ( 'NONE', #3656 ) ; -#37611 = AXIS2_PLACEMENT_3D ( 'NONE', #11108, #36238, #8241 ) ; -#37612 = EDGE_CURVE ( 'NONE', #17689, #39586, #16144, .T. ) ; -#37613 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927781006472, -0.0005734119022075028415 ) ) ; -#37614 = CARTESIAN_POINT ( 'NONE', ( 23.68440750596101196, 131.0247019790142815, 89.88805227296677458 ) ) ; -#37615 = CARTESIAN_POINT ( 'NONE', ( 23.36469433561273235, 176.8669516480852337, 103.2047264528809194 ) ) ; -#37616 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11358, #36302, #8303, #24468 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37617 = AXIS2_PLACEMENT_3D ( 'NONE', #6379, #6981, #32149 ) ; -#37618 = DIRECTION ( 'NONE', ( 0.0006039748319392990953, 2.305558552177526877E-15, 0.9999998176071847045 ) ) ; -#37619 = ORIENTED_EDGE ( 'NONE', *, *, #16268, .F. ) ; -#37620 = ADVANCED_FACE ( 'NONE', ( #22502 ), #18041, .T. ) ; -#37621 = ORIENTED_EDGE ( 'NONE', *, *, #40, .F. ) ; -#37622 = CARTESIAN_POINT ( 'NONE', ( 12.64068429172691665, 176.9138758412513255, 103.2882421082539963 ) ) ; -#37623 = CARTESIAN_POINT ( 'NONE', ( 2.548040970592790444, 190.9966390957640101, 104.2749172799330069 ) ) ; -#37624 = CARTESIAN_POINT ( 'NONE', ( 21.72592390767327686, 135.1711755393868941, 93.92543662762206225 ) ) ; -#37625 = ORIENTED_EDGE ( 'NONE', *, *, #6026, .T. ) ; -#37626 = FACE_OUTER_BOUND ( 'NONE', #26463, .T. ) ; -#37627 = ORIENTED_EDGE ( 'NONE', *, *, #21132, .T. ) ; -#37628 = DIRECTION ( 'NONE', ( 0.6087611427424929333, 0.7731004630501246977, 0.1781166615410725018 ) ) ; -#37629 = EDGE_CURVE ( 'NONE', #21533, #28516, #17300, .T. ) ; -#37630 = FACE_OUTER_BOUND ( 'NONE', #32815, .T. ) ; -#37631 = VECTOR ( 'NONE', #6951, 1000.000000000000227 ) ; -#37632 = AXIS2_PLACEMENT_3D ( 'NONE', #14734, #39444, #32911 ) ; -#37633 = DIRECTION ( 'NONE', ( -0.0002393071182785117045, -0.2252352986010040525, 0.9743043687658490271 ) ) ; -#37634 = CARTESIAN_POINT ( 'NONE', ( -5.659900684199740795, 130.3459505314356477, 92.82798007168634058 ) ) ; -#37635 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#37636 = CARTESIAN_POINT ( 'NONE', ( -20.49852830327300879, 119.8277974066376999, 89.89548907266683386 ) ) ; -#37637 = EDGE_LOOP ( 'NONE', ( #14142, #40197, #16522, #39077 ) ) ; -#37638 = AXIS2_PLACEMENT_3D ( 'NONE', #38208, #19174, #22079 ) ; -#37639 = PLANE ( 'NONE', #14626 ) ; -#37640 = CARTESIAN_POINT ( 'NONE', ( 19.33916236813157141, 149.2574392882847576, 181.2554555184128446 ) ) ; -#37641 = CARTESIAN_POINT ( 'NONE', ( 23.68440576545748755, 137.3587804155124843, 91.34731897728055117 ) ) ; -#37642 = VECTOR ( 'NONE', #3455, 1000.000000000000114 ) ; -#37643 = CARTESIAN_POINT ( 'NONE', ( 15.50029467790899496, 185.7974155947267718, 103.0514270424844483 ) ) ; -#37644 = ORIENTED_EDGE ( 'NONE', *, *, #27108, .F. ) ; -#37645 = VERTEX_POINT ( 'NONE', #29836 ) ; -#37646 = ORIENTED_EDGE ( 'NONE', *, *, #14871, .T. ) ; -#37647 = CARTESIAN_POINT ( 'NONE', ( -30.09883670037504189, 202.4139200980250166, 28.35470564401785865 ) ) ; -#37648 = ADVANCED_FACE ( 'NONE', ( #35934 ), #10426, .F. ) ; -#37649 = CARTESIAN_POINT ( 'NONE', ( 35.54678039743919271, 205.1071296091639056, 76.08337964661465946 ) ) ; -#37650 = EDGE_CURVE ( 'NONE', #7935, #24453, #4869, .T. ) ; -#37651 = VERTEX_POINT ( 'NONE', #16924 ) ; -#37652 = ADVANCED_FACE ( 'NONE', ( #35328 ), #40173, .F. ) ; -#37653 = ORIENTED_EDGE ( 'NONE', *, *, #4637, .F. ) ; -#37654 = DIRECTION ( 'NONE', ( -0.9999998176071820399, 0.000000000000000000, 0.0006039748360328516322 ) ) ; -#37655 = CARTESIAN_POINT ( 'NONE', ( -38.54565934514999981, 119.1564762388999981, 90.30561916639000231 ) ) ; -#37656 = CARTESIAN_POINT ( 'NONE', ( -38.01592745802000195, 119.2010240264000061, 87.30145059880000247 ) ) ; -#37657 = DIRECTION ( 'NONE', ( 0.1779895592101686796, 0.3532431349384635433, -0.9184437949221587738 ) ) ; -#37658 = ORIENTED_EDGE ( 'NONE', *, *, #20759, .F. ) ; -#37659 = CARTESIAN_POINT ( 'NONE', ( 5.667983148732107956, 187.2950682004077407, 105.4557345120219480 ) ) ; -#37660 = ORIENTED_EDGE ( 'NONE', *, *, #5719, .T. ) ; -#37661 = VECTOR ( 'NONE', #21592, 1000.000000000000114 ) ; -#37662 = DIRECTION ( 'NONE', ( -0.0005884949961242402295, 0.2249510543439063315, -0.9743698870671264611 ) ) ; -#37663 = VECTOR ( 'NONE', #30246, 1000.000000000000114 ) ; -#37664 = CARTESIAN_POINT ( 'NONE', ( 3.166376970775131028, 185.9099593149100542, 102.5717182116986521 ) ) ; -#37665 = ADVANCED_FACE ( 'NONE', ( #26170 ), #14292, .F. ) ; -#37666 = ORIENTED_EDGE ( 'NONE', *, *, #22412, .F. ) ; -#37667 = CARTESIAN_POINT ( 'NONE', ( -20.00062605139820704, 196.5784656963837733, 103.8871944330217048 ) ) ; -#37668 = CARTESIAN_POINT ( 'NONE', ( 1.993582469418050174, 189.0625797058357307, 103.3002552791548965 ) ) ; -#37669 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.2249510932970937294, 0.9743700557921729510 ) ) ; -#37670 = VECTOR ( 'NONE', #4141, 1000.000000000000227 ) ; -#37671 = ORIENTED_EDGE ( 'NONE', *, *, #4883, .T. ) ; -#37672 = ADVANCED_FACE ( 'NONE', ( #38609 ), #30482, .F. ) ; -#37673 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498907891, 132.2978364233970581, 93.26432363115026192 ) ) ; -#37674 = CARTESIAN_POINT ( 'NONE', ( -25.50129508846853099, 118.1132512059233335, 87.78307593003776788 ) ) ; -#37675 = EDGE_LOOP ( 'NONE', ( #33020, #2647, #3416, #19304, #25707, #29366, #15370, #12680, #19983, #22543, #9619, #12299 ) ) ; -#37676 = CARTESIAN_POINT ( 'NONE', ( 20.81604738696258039, 116.8538761181823133, 89.75547759989828478 ) ) ; -#37677 = CARTESIAN_POINT ( 'NONE', ( 36.24124945375172047, 191.4454296738790333, 103.8296949086555543 ) ) ; -#37678 = CARTESIAN_POINT ( 'NONE', ( -26.83585668902999899, 123.2446041209999947, 91.07657256299999915 ) ) ; -#37679 = ORIENTED_EDGE ( 'NONE', *, *, #37203, .T. ) ; -#37680 = CARTESIAN_POINT ( 'NONE', ( 2.102344972559205161, 188.8904649364737054, 106.3393666415465191 ) ) ; -#37681 = LINE ( 'NONE', #19857, #21246 ) ; -#37682 = DIRECTION ( 'NONE', ( 0.7933533411653072021, 0.5931840316265227786, 0.1368326740407719844 ) ) ; -#37683 = ORIENTED_EDGE ( 'NONE', *, *, #40413, .T. ) ; -#37684 = VECTOR ( 'NONE', #23135, 1000.000000000000000 ) ; -#37685 = LINE ( 'NONE', #9686, #23450 ) ; -#37686 = CARTESIAN_POINT ( 'NONE', ( 36.06343484178082548, 196.1181868591233410, 103.6579563381249471 ) ) ; -#37687 = AXIS2_PLACEMENT_3D ( 'NONE', #18658, #25441, #3136 ) ; -#37689 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37688 = CARTESIAN_POINT ( 'NONE', ( 19.46059643144436535, 126.3442427331793141, 175.5385488862945635 ) ) ; -#37690 = ORIENTED_EDGE ( 'NONE', *, *, #26731, .F. ) ; -#37691 = LINE ( 'NONE', #27921, #35317 ) ; -#37692 = EDGE_LOOP ( 'NONE', ( #18418, #17770, #21701, #30992, #7679, #20050, #17658, #32363, #13210, #25357 ) ) ; -#37693 = DIRECTION ( 'NONE', ( -0.7933533411653072021, -0.5931840316265228896, -0.1368326740407719011 ) ) ; -#37694 = CARTESIAN_POINT ( 'NONE', ( 38.25240742236346847, 118.6016279957657673, 87.66725807459630460 ) ) ; -#37695 = CARTESIAN_POINT ( 'NONE', ( -16.15354643030308424, 152.0177870148501427, 180.9315030652959422 ) ) ; -#37696 = EDGE_CURVE ( 'NONE', #23754, #26491, #40258, .T. ) ; -#37697 = ORIENTED_EDGE ( 'NONE', *, *, #9089, .T. ) ; -#37698 = ORIENTED_EDGE ( 'NONE', *, *, #9281, .F. ) ; -#37699 = CARTESIAN_POINT ( 'NONE', ( -25.49734792034949038, 118.8155664120999973, 94.28318532801205265 ) ) ; -#37700 = CARTESIAN_POINT ( 'NONE', ( 45.66847487909335257, 187.6390301656441579, 105.4819989478330058 ) ) ; -#37701 = FACE_OUTER_BOUND ( 'NONE', #20936, .T. ) ; -#37702 = CARTESIAN_POINT ( 'NONE', ( -3.070807994882999825, 190.8479820821999908, 106.9334771579000005 ) ) ; -#37703 = VERTEX_POINT ( 'NONE', #16524 ) ; -#37704 = ORIENTED_EDGE ( 'NONE', *, *, #2088, .F. ) ; -#37705 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251387812, 132.4055461763574328, 92.79778151956126919 ) ) ; -#37706 = CARTESIAN_POINT ( 'NONE', ( 35.80487162792000078, 199.6921533858000259, 89.47993692238999586 ) ) ; -#37707 = CARTESIAN_POINT ( 'NONE', ( 13.55396812693271791, 164.5266522499701409, 98.14185902086070712 ) ) ; -#37708 = ORIENTED_EDGE ( 'NONE', *, *, #31570, .F. ) ; -#37709 = CARTESIAN_POINT ( 'NONE', ( -19.99825438583805237, 190.8509747501094580, 106.8052823956111013 ) ) ; -#37710 = CARTESIAN_POINT ( 'NONE', ( -30.07215349799573900, 175.3514230958744520, 100.1541516780990406 ) ) ; -#37711 = VERTEX_POINT ( 'NONE', #10826 ) ; -#37712 = AXIS2_PLACEMENT_3D ( 'NONE', #14946, #5935, #37419 ) ; -#37713 = CARTESIAN_POINT ( 'NONE', ( 25.45436037924796224, 118.1131156702000169, 13.52888003454015298 ) ) ; -#37714 = ORIENTED_EDGE ( 'NONE', *, *, #13177, .T. ) ; -#37715 = CARTESIAN_POINT ( 'NONE', ( -13.50718409113456886, 124.3648481134796242, 88.37302201493642428 ) ) ; -#37716 = VECTOR ( 'NONE', #23165, 1000.000000000000000 ) ; -#37717 = EDGE_CURVE ( 'NONE', #37352, #17526, #35649, .T. ) ; -#37718 = CARTESIAN_POINT ( 'NONE', ( -0.3660935641670999829, 188.8524035398000080, 105.8564355347999992 ) ) ; -#37719 = CARTESIAN_POINT ( 'NONE', ( -3.503019623618541800, 126.7262776985570127, 89.25421175367505100 ) ) ; -#37720 = ORIENTED_EDGE ( 'NONE', *, *, #11675, .F. ) ; -#37721 = FACE_OUTER_BOUND ( 'NONE', #8386, .T. ) ; -#37722 = CARTESIAN_POINT ( 'NONE', ( 36.79222982050293922, 77.14301703112145958, 291.5363223503569543 ) ) ; -#37723 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178570903572E-05, -0.0002331579774915885982 ) ) ; -#37724 = DIRECTION ( 'NONE', ( 0.7066795775144187886, 2.423636307971748040E-16, -0.7075337269162810250 ) ) ; -#37725 = VERTEX_POINT ( 'NONE', #20200 ) ; -#37726 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37727 = ORIENTED_EDGE ( 'NONE', *, *, #38301, .T. ) ; -#37728 = ADVANCED_FACE ( 'NONE', ( #4463 ), #17125, .F. ) ; -#37729 = CARTESIAN_POINT ( 'NONE', ( 20.06673176399057823, 211.8719179876182466, 76.04897356089666971 ) ) ; -#37730 = CARTESIAN_POINT ( 'NONE', ( 22.59299433171564431, 158.3069224608609886, 96.18730950046148109 ) ) ; -#37731 = CARTESIAN_POINT ( 'NONE', ( -38.37885564745000977, 118.5498700796999998, 89.85180666872000188 ) ) ; -#37732 = ORIENTED_EDGE ( 'NONE', *, *, #12396, .F. ) ; -#37733 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #33446, #15260, #37129, #6239 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37734 = ORIENTED_EDGE ( 'NONE', *, *, #5055, .T. ) ; -#37735 = CARTESIAN_POINT ( 'NONE', ( -14.16977585978846754, 176.4938143369288355, 100.9214410357033529 ) ) ; -#37736 = CARTESIAN_POINT ( 'NONE', ( -26.23387527696571198, 122.3264975654227698, 87.91006257957754144 ) ) ; -#37737 = CARTESIAN_POINT ( 'NONE', ( -20.18587004200604085, 159.8158404907537431, 96.56150810225138059 ) ) ; -#37738 = EDGE_CURVE ( 'NONE', #27892, #7971, #38804, .T. ) ; -#37739 = ADVANCED_FACE ( 'NONE', ( #10628 ), #3143, .F. ) ; -#37740 = VERTEX_POINT ( 'NONE', #7531 ) ; -#37741 = CARTESIAN_POINT ( 'NONE', ( 25.83405065666187639, 120.1395552130028932, 90.28158168838656650 ) ) ; -#37742 = CIRCLE ( 'NONE', #24046, 2.000000000527294208 ) ; -#37743 = ORIENTED_EDGE ( 'NONE', *, *, #695, .F. ) ; -#37744 = ORIENTED_EDGE ( 'NONE', *, *, #2980, .T. ) ; -#37745 = FACE_OUTER_BOUND ( 'NONE', #33328, .T. ) ; -#37746 = CARTESIAN_POINT ( 'NONE', ( -44.79353637294777002, 181.5138299656995287, 101.5857470109101399 ) ) ; -#37747 = LINE ( 'NONE', #12220, #31417 ) ; -#37748 = CARTESIAN_POINT ( 'NONE', ( -26.00898928064792059, 209.7096528057114710, 76.07444037909847623 ) ) ; -#37749 = EDGE_CURVE ( 'NONE', #38350, #10050, #16005, .T. ) ; -#37750 = VERTEX_POINT ( 'NONE', #14093 ) ; -#37751 = CARTESIAN_POINT ( 'NONE', ( 15.99999411728631671, 174.5114300543024513, 99.93239967722463746 ) ) ; -#37752 = DIRECTION ( 'NONE', ( -0.9999998176071845934, 5.029100215316657124E-18, 0.0006039748319386160479 ) ) ; -#37753 = EDGE_LOOP ( 'NONE', ( #25351, #11141, #25047, #37660 ) ) ; -#37754 = FACE_OUTER_BOUND ( 'NONE', #24039, .T. ) ; -#37755 = CARTESIAN_POINT ( 'NONE', ( 14.55129770294257341, 129.4786662571763998, 92.61555079168689986 ) ) ; -#37756 = ORIENTED_EDGE ( 'NONE', *, *, #191, .F. ) ; -#37757 = DIRECTION ( 'NONE', ( 0.7933310414247660702, 0.5931044597393384521, 0.1373060761554397435 ) ) ; -#37758 = CARTESIAN_POINT ( 'NONE', ( 25.75082660724000405, 201.9934155195000187, 90.46283731303999787 ) ) ; -#37759 = FACE_OUTER_BOUND ( 'NONE', #28601, .T. ) ; -#37760 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7393, #28291, #15795, #22560 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37761 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971554578 ) ) ; -#37762 = CARTESIAN_POINT ( 'NONE', ( 3.534086375177905914, 137.3581944094399603, 91.36238397499714381 ) ) ; -#37763 = EDGE_LOOP ( 'NONE', ( #2563, #11468, #40426, #20640 ) ) ; -#37764 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319379894875 ) ) ; -#37765 = CIRCLE ( 'NONE', #1216, 2.500000000050627946 ) ; -#37766 = CARTESIAN_POINT ( 'NONE', ( 0.8775314245327620055, 189.0249473761942909, 103.6920809060072628 ) ) ; -#37767 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37768 = VECTOR ( 'NONE', #3807, 1000.000000000000227 ) ; -#37769 = CARTESIAN_POINT ( 'NONE', ( 25.99885467711333931, 118.5825379493838341, 87.25211441482672114 ) ) ; -#37770 = AXIS2_PLACEMENT_3D ( 'NONE', #23010, #510, #6642 ) ; -#37771 = CARTESIAN_POINT ( 'NONE', ( 15.94114414956070114, 147.2998714242159224, 179.5451065918014422 ) ) ; -#37772 = CARTESIAN_POINT ( 'NONE', ( 19.37944463171710296, 148.4918504680572369, 180.6383071375771010 ) ) ; -#37773 = AXIS2_PLACEMENT_3D ( 'NONE', #15616, #28116, #12548 ) ; -#37774 = CARTESIAN_POINT ( 'NONE', ( -40.70502761438000050, 219.0860688542000219, 75.83308940067000492 ) ) ; -#37775 = LINE ( 'NONE', #28783, #3347 ) ; -#37776 = CARTESIAN_POINT ( 'NONE', ( -25.50530527114885615, 190.9616050397809772, 106.3210494999302540 ) ) ; -#37777 = ORIENTED_EDGE ( 'NONE', *, *, #4249, .F. ) ; -#37778 = EDGE_CURVE ( 'NONE', #29879, #19255, #15592, .T. ) ; -#37779 = CARTESIAN_POINT ( 'NONE', ( -16.41310484999783981, 121.9323406599082062, 177.7806045521944043 ) ) ; -#37780 = ADVANCED_FACE ( 'NONE', ( #33082 ), #18344, .T. ) ; -#37781 = CARTESIAN_POINT ( 'NONE', ( -20.02016821360482268, 211.0854730039747267, 73.07052224373646254 ) ) ; -#37782 = LINE ( 'NONE', #6697, #19979 ) ; -#37783 = ORIENTED_EDGE ( 'NONE', *, *, #16875, .T. ) ; -#37784 = CARTESIAN_POINT ( 'NONE', ( 42.93322021095036689, 121.2550468398670631, 90.69983607254528124 ) ) ; -#37785 = CARTESIAN_POINT ( 'NONE', ( 46.51720693556681852, 124.8110556520572771, 91.00548902218217506 ) ) ; -#37786 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15802, #37289, #12538, #21766, #18657, #3135, #15607, #28301, #28108, #76, #34405, #25241, #22169, #869 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000001889600, 0.3750000000002450817, 0.4375000000002627343, 0.4687500000002153833, 0.4843750000001907918, 0.5000000000001662004, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37787 = CARTESIAN_POINT ( 'NONE', ( 20.50029383489984980, 127.3219018132126479, 89.54826866284827247 ) ) ; -#37788 = CARTESIAN_POINT ( 'NONE', ( 37.68744279206340764, 191.4246164574499858, 104.2866415772560060 ) ) ; -#37789 = EDGE_CURVE ( 'NONE', #37005, #21678, #27601, .T. ) ; -#37790 = EDGE_CURVE ( 'NONE', #40179, #24908, #1386, .T. ) ; -#37791 = CARTESIAN_POINT ( 'NONE', ( 36.37271987246000293, 191.1008199325999897, 106.6920003910999952 ) ) ; -#37792 = EDGE_LOOP ( 'NONE', ( #36347, #2718, #36209 ) ) ; -#37793 = EDGE_CURVE ( 'NONE', #17075, #36516, #14382, .T. ) ; -#37794 = VERTEX_POINT ( 'NONE', #40223 ) ; -#37796 = CIRCLE ( 'NONE', #14983, 2.000000000000011546 ) ; -#37795 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37797 = EDGE_CURVE ( 'NONE', #8372, #36951, #21454, .T. ) ; -#37798 = CARTESIAN_POINT ( 'NONE', ( -20.11930665488561942, 184.9326558166844450, 102.4826600882946082 ) ) ; -#37799 = AXIS2_PLACEMENT_3D ( 'NONE', #17128, #11226, #11638 ) ; -#37800 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971547084 ) ) ; -#37801 = ORIENTED_EDGE ( 'NONE', *, *, #37225, .F. ) ; -#37802 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.293414132305979792E-14, 0.9999998176071844824 ) ) ; -#37803 = AXIS2_PLACEMENT_3D ( 'NONE', #35434, #13007, #28546 ) ; -#37804 = CIRCLE ( 'NONE', #6446, 2.500000000000002220 ) ; -#37805 = VERTEX_POINT ( 'NONE', #15303 ) ; -#37806 = FACE_OUTER_BOUND ( 'NONE', #32355, .T. ) ; -#37807 = CARTESIAN_POINT ( 'NONE', ( -4.472739938169342899, 130.7266529636161749, 89.83624843479562116 ) ) ; -#37808 = CARTESIAN_POINT ( 'NONE', ( -25.76127051822999903, 210.3999399800999868, 73.32280028488999335 ) ) ; -#37809 = ORIENTED_EDGE ( 'NONE', *, *, #31513, .F. ) ; -#37810 = PLANE ( 'NONE', #27167 ) ; -#37811 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30197, #29991, #39580, #39989 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37812 = CARTESIAN_POINT ( 'NONE', ( -94.47778922392247125, 77.18266397892847408, 291.6156061525086898 ) ) ; -#37813 = CARTESIAN_POINT ( 'NONE', ( 22.50176647123733886, 126.7590398625532089, 91.98595248688171466 ) ) ; -#37814 = CARTESIAN_POINT ( 'NONE', ( -43.55091172766087482, 114.1088728472931138, 121.9228533734353306 ) ) ; -#37815 = ORIENTED_EDGE ( 'NONE', *, *, #14023, .F. ) ; -#37816 = CARTESIAN_POINT ( 'NONE', ( 21.49510836992397955, 129.8183861006403106, 89.61087453915679646 ) ) ; -#37817 = EDGE_CURVE ( 'NONE', #18309, #4383, #12038, .T. ) ; -#37818 = CARTESIAN_POINT ( 'NONE', ( 2.156482154607000101, 189.5564015033000373, 103.7090349261000028 ) ) ; -#37819 = CARTESIAN_POINT ( 'NONE', ( -14.78542622577100119, 175.8938623147257374, 100.7833030093998303 ) ) ; -#37820 = CARTESIAN_POINT ( 'NONE', ( -35.77829887421999899, 191.5311805108999863, 103.7655102736000146 ) ) ; -#37821 = VERTEX_POINT ( 'NONE', #24322 ) ; -#37822 = ORIENTED_EDGE ( 'NONE', *, *, #13067, .T. ) ; -#37823 = CARTESIAN_POINT ( 'NONE', ( -6.957132718426895401, 133.0026170453613190, 282.5627442275269914 ) ) ; -#37824 = ORIENTED_EDGE ( 'NONE', *, *, #25083, .F. ) ; -#37825 = DIRECTION ( 'NONE', ( 0.0005884949961242684187, -0.2249510543439056376, 0.9743698870671265722 ) ) ; -#37826 = ADVANCED_FACE ( 'NONE', ( #2231 ), #22859, .F. ) ; -#37827 = AXIS2_PLACEMENT_3D ( 'NONE', #4978, #11130, #1924 ) ; -#37828 = LINE ( 'NONE', #19009, #36744 ) ; -#37829 = VECTOR ( 'NONE', #16997, 1000.000000000000227 ) ; -#37830 = CARTESIAN_POINT ( 'NONE', ( -12.63338249442217354, 177.0290861143981545, 103.4924640678001282 ) ) ; -#37831 = CARTESIAN_POINT ( 'NONE', ( 15.50147166558119594, 185.3474886484798390, 105.0001610792874942 ) ) ; -#37832 = EDGE_CURVE ( 'NONE', #38178, #23972, #21238, .T. ) ; -#37833 = DIRECTION ( 'NONE', ( -0.0005884949961238158727, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#37834 = CARTESIAN_POINT ( 'NONE', ( 25.65719135372745185, 209.7100065642696904, 73.37632326619605294 ) ) ; -#37835 = VERTEX_POINT ( 'NONE', #30645 ) ; -#37836 = EDGE_CURVE ( 'NONE', #23012, #25669, #2639, .T. ) ; -#37837 = LINE ( 'NONE', #21717, #29656 ) ; -#37838 = CARTESIAN_POINT ( 'NONE', ( -21.99952075582729094, 137.4670866173397314, 177.5663017614061232 ) ) ; -#37839 = DIRECTION ( 'NONE', ( 0.0005884949961228158046, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37840 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34099, #6097, #18548, #31453, #37576, #15892, #9579, #22054, #37772, #9782 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.0004309827303015496499, 0.0008619654606030992998, 0.001292948190904649004, 0.001723930921206198600 ), - .UNSPECIFIED. ) ; -#37841 = FACE_OUTER_BOUND ( 'NONE', #32337, .T. ) ; -#37842 = ORIENTED_EDGE ( 'NONE', *, *, #33823, .T. ) ; -#37843 = EDGE_LOOP ( 'NONE', ( #11591, #21608, #17905, #27006 ) ) ; -#37844 = EDGE_CURVE ( 'NONE', #26238, #27254, #3847, .T. ) ; -#37845 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #37464, #19045, #9873, #31951, #38266, #4102, #31540 ), - ( #3499, #15984, #34772, #3712, #16188, #10281, #4925 ), - ( #13937, #14344, #32928, #11074, #29886, #1869, #26018 ), - ( #20674, #39269, #35375, #35566, #17382, #23347, #32345 ), - ( #26824, #20052, #10479, #26418, #1450, #19838, #23141 ), - ( #39063, #29681, #11270, #16785, #36201, #33133, #38863 ), - ( #23749, #29476, #1664, #16976, #7586, #7382, #8205 ), - ( #32540, #35989, #5117, #26220, #29074, #1049, #4512 ), - ( #23538, #10877, #13537, #1247, #38459, #22947, #35777 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 4 ), - ( 4, 3, 4 ), - ( -3.193576140566999920E-12, 0.1666665328658999967, 0.3333330550477999754, 0.4999995772299999919, 0.6666660994122000083, 0.8333326215941999626, 1.000000000000000000 ), - ( 0.1842143742207019985, 0.1904063628586999957, 0.8096052266584999879 ), - .UNSPECIFIED. ) ; -#37846 = VERTEX_POINT ( 'NONE', #16291 ) ; -#37847 = CARTESIAN_POINT ( 'NONE', ( -19.44498994767157996, 147.7083494500389236, 183.5267648320292437 ) ) ; -#37848 = CARTESIAN_POINT ( 'NONE', ( -20.49588010179244790, 118.8154963149460741, 94.28014888049614228 ) ) ; -#37849 = DIRECTION ( 'NONE', ( 0.7072735235669668219, 0.6508952434164523293, 0.2758614597202816432 ) ) ; -#37850 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31291, #3458, #3065, #21506 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37851 = ORIENTED_EDGE ( 'NONE', *, *, #11765, .T. ) ; -#37852 = DIRECTION ( 'NONE', ( 0.0006039748319391903498, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#37853 = VECTOR ( 'NONE', #2481, 1000.000000000000000 ) ; -#37854 = AXIS2_PLACEMENT_3D ( 'NONE', #1958, #33421, #11564 ) ; -#37855 = CARTESIAN_POINT ( 'NONE', ( 39.79988895049328335, 119.8651423291884726, 87.81508310122019623 ) ) ; -#37856 = CARTESIAN_POINT ( 'NONE', ( -38.03165849778999785, 119.2179435290000100, 87.30229350380000142 ) ) ; -#37857 = CARTESIAN_POINT ( 'NONE', ( 2.943104451508621544, 209.7096517725655644, 76.05672380837390278 ) ) ; -#37858 = EDGE_LOOP ( 'NONE', ( #24171, #32539, #33998, #40104 ) ) ; -#37859 = CARTESIAN_POINT ( 'NONE', ( -32.37402305083713827, 138.3010815212902855, 91.60179504951790364 ) ) ; -#37860 = VECTOR ( 'NONE', #35957, 1000.000000000000000 ) ; -#37861 = AXIS2_PLACEMENT_3D ( 'NONE', #15405, #39520, #21555 ) ; -#37862 = ORIENTED_EDGE ( 'NONE', *, *, #20511, .F. ) ; -#37863 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178536755269E-05, 0.0002331579774905574406 ) ) ; -#37864 = CIRCLE ( 'NONE', #18263, 2.500000004121103903 ) ; -#37865 = CARTESIAN_POINT ( 'NONE', ( 3.333123914796359166, 185.8719596943319061, 102.7338991239209491 ) ) ; -#37866 = VERTEX_POINT ( 'NONE', #6885 ) ; -#37867 = EDGE_LOOP ( 'NONE', ( #9126, #523, #24990, #10248 ) ) ; -#37868 = CARTESIAN_POINT ( 'NONE', ( 22.22396017645197830, 150.3172372291888905, 34.69005226938929809 ) ) ; -#37869 = CARTESIAN_POINT ( 'NONE', ( 2.624500613330938315, 189.6988974143776545, 103.4467797655522503 ) ) ; -#37870 = CARTESIAN_POINT ( 'NONE', ( -8.050307609250221930, 161.2716461841048101, 96.89027781497259184 ) ) ; -#37871 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #27761, #38720, #13603, #28942 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37872 = ORIENTED_EDGE ( 'NONE', *, *, #18385, .T. ) ; -#37873 = VERTEX_POINT ( 'NONE', #9978 ) ; -#37874 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363196006660E-14, -0.9999998176071844824 ) ) ; -#37875 = CARTESIAN_POINT ( 'NONE', ( -20.51998460911297784, 211.0905570173818546, 73.57089872868714053 ) ) ; -#37876 = ORIENTED_EDGE ( 'NONE', *, *, #21296, .T. ) ; -#37877 = DIRECTION ( 'NONE', ( -0.0006039748319385908944, -1.271205363195980786E-14, -0.9999998176071845934 ) ) ; -#37878 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37879 = CARTESIAN_POINT ( 'NONE', ( -26.29003513620000376, 122.2754973729000199, 90.85250693771000385 ) ) ; -#37880 = EDGE_CURVE ( 'NONE', #5869, #24036, #7759, .T. ) ; -#37881 = EDGE_CURVE ( 'NONE', #8275, #5335, #547, .T. ) ; -#37882 = EDGE_LOOP ( 'NONE', ( #20710, #31793, #3681, #25942 ) ) ; -#37883 = DIRECTION ( 'NONE', ( -0.0001408404346092596458, 0.2249510911124608936, -0.9743700461176365568 ) ) ; -#37884 = EDGE_CURVE ( 'NONE', #11575, #30783, #14060, .T. ) ; -#37885 = EDGE_CURVE ( 'NONE', #4758, #35038, #37037, .T. ) ; -#37886 = CARTESIAN_POINT ( 'NONE', ( -37.79864283955629389, 118.7059682267879026, 87.43197624523921263 ) ) ; -#37887 = FACE_OUTER_BOUND ( 'NONE', #25872, .T. ) ; -#37888 = CARTESIAN_POINT ( 'NONE', ( -2.689645513499154816, 191.0567932042151540, 104.0175265168841463 ) ) ; -#37889 = AXIS2_PLACEMENT_3D ( 'NONE', #39617, #11024, #35929 ) ; -#37890 = AXIS2_PLACEMENT_3D ( 'NONE', #36705, #5208, #32824 ) ; -#37891 = VERTEX_POINT ( 'NONE', #37568 ) ; -#37892 = EDGE_CURVE ( 'NONE', #3242, #11953, #12615, .T. ) ; -#37893 = VECTOR ( 'NONE', #25495, 1000.000000000000227 ) ; -#37894 = CIRCLE ( 'NONE', #33946, 5.499999999738637513 ) ; -#37895 = CARTESIAN_POINT ( 'NONE', ( -15.99970515225999179, 151.9770228117144484, 94.74935186622352035 ) ) ; -#37896 = CARTESIAN_POINT ( 'NONE', ( -19.99848660742553008, 137.5076853405834072, 94.48997979116353463 ) ) ; -#37898 = CARTESIAN_POINT ( 'NONE', ( -2.602132166127285373, 190.9309786092318006, 106.4700758378154575 ) ) ; -#37897 = CARTESIAN_POINT ( 'NONE', ( 28.46531727888168817, 183.5661251107103169, 104.5810709919272057 ) ) ; -#37899 = EDGE_CURVE ( 'NONE', #37835, #3089, #35013, .T. ) ; -#37900 = ORIENTED_EDGE ( 'NONE', *, *, #30589, .F. ) ; -#37901 = CYLINDRICAL_SURFACE ( 'NONE', #1004, 5.249999999999986677 ) ; -#37902 = CARTESIAN_POINT ( 'NONE', ( 38.15045221970718359, 118.4868570840783377, 87.66883015867043127 ) ) ; -#37903 = PLANE ( 'NONE', #28920 ) ; -#37904 = FACE_OUTER_BOUND ( 'NONE', #5037, .T. ) ; -#37905 = VERTEX_POINT ( 'NONE', #31234 ) ; -#37906 = ORIENTED_EDGE ( 'NONE', *, *, #20374, .T. ) ; -#37907 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#37908 = CARTESIAN_POINT ( 'NONE', ( 22.78152163348013914, 158.3817186398727017, 98.08602157056807869 ) ) ; -#37909 = EDGE_CURVE ( 'NONE', #18185, #30562, #20430, .T. ) ; -#37910 = CARTESIAN_POINT ( 'NONE', ( 44.83277154663306874, 186.3180907337439578, 107.7244483083414508 ) ) ; -#37911 = DIRECTION ( 'NONE', ( 0.0005884949961217976304, -0.2249510543439088295, 0.9743698870671256840 ) ) ; -#37912 = ORIENTED_EDGE ( 'NONE', *, *, #22899, .T. ) ; -#37913 = ORIENTED_EDGE ( 'NONE', *, *, #44, .T. ) ; -#37914 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#37915 = DIRECTION ( 'NONE', ( 0.9999998268368047727, 0.0001323825927642897275, -0.0005734119021573578405 ) ) ; -#37916 = CARTESIAN_POINT ( 'NONE', ( 36.04442091094806244, 218.5902260770999987, 73.53673424655958968 ) ) ; -#37917 = VECTOR ( 'NONE', #14040, 1000.000000000000114 ) ; -#37918 = ORIENTED_EDGE ( 'NONE', *, *, #38342, .T. ) ; -#37919 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#37920 = VECTOR ( 'NONE', #24796, 1000.000000000000114 ) ; -#37921 = ORIENTED_EDGE ( 'NONE', *, *, #9189, .T. ) ; -#37922 = VECTOR ( 'NONE', #32324, 1000.000000000000341 ) ; -#37923 = ORIENTED_EDGE ( 'NONE', *, *, #23772, .F. ) ; -#37924 = DIRECTION ( 'NONE', ( -0.0006039748319383847876, -4.625770492314939281E-15, -0.9999998176071847045 ) ) ; -#37925 = ORIENTED_EDGE ( 'NONE', *, *, #8015, .F. ) ; -#37926 = CARTESIAN_POINT ( 'NONE', ( -5.666761810104184782, 187.4494786681063374, 105.7117437973159468 ) ) ; -#37927 = CARTESIAN_POINT ( 'NONE', ( -0.9122130542470999748, 189.2064119769000001, 105.6188406109999960 ) ) ; -#37928 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921585181, -0.2249510932971559019 ) ) ; -#37929 = ORIENTED_EDGE ( 'NONE', *, *, #9328, .T. ) ; -#37930 = CARTESIAN_POINT ( 'NONE', ( -16.56167515404295543, 123.1153088213665114, 172.1613468014946022 ) ) ; -#37931 = ADVANCED_FACE ( 'NONE', ( #19360 ), #8947, .F. ) ; -#37932 = CARTESIAN_POINT ( 'NONE', ( -20.49971785407188563, 191.7873341492787915, 104.4341925847197672 ) ) ; -#37933 = ADVANCED_FACE ( 'NONE', ( #37370 ), #38854, .F. ) ; -#37934 = CARTESIAN_POINT ( 'NONE', ( -38.09728523723426008, 163.5897765857678792, 197.9748090961729190 ) ) ; -#37935 = CARTESIAN_POINT ( 'NONE', ( 13.49986192253402351, 124.0960645453589990, 91.02896376973610870 ) ) ; -#37936 = CARTESIAN_POINT ( 'NONE', ( -29.78153341548664912, 126.4887808801478428, 91.43890526668431562 ) ) ; -#37937 = ORIENTED_EDGE ( 'NONE', *, *, #37556, .T. ) ; -#37938 = CARTESIAN_POINT ( 'NONE', ( 22.59955204320912969, 214.0902768579945530, 76.04506448788464468 ) ) ; -#37939 = DIRECTION ( 'NONE', ( 0.0001408373285424074114, -0.2255194992995608605, 0.9742386440706004569 ) ) ; -#37940 = CARTESIAN_POINT ( 'NONE', ( 26.80533604871084208, 110.6131156702000027, 90.25159508784216200 ) ) ; -#37941 = AXIS2_PLACEMENT_3D ( 'NONE', #25677, #32394, #28923 ) ; -#37942 = VERTEX_POINT ( 'NONE', #31044 ) ; -#37943 = DIRECTION ( 'NONE', ( -0.0006039748319386907495, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#37944 = CIRCLE ( 'NONE', #14462, 2.000000000021383340 ) ; -#37945 = ORIENTED_EDGE ( 'NONE', *, *, #32556, .T. ) ; -#37946 = CARTESIAN_POINT ( 'NONE', ( 31.79542158357201487, 220.4002260771000294, 75.53930090045915335 ) ) ; -#37947 = AXIS2_PLACEMENT_3D ( 'NONE', #8958, #22032, #34461 ) ; -#37948 = CARTESIAN_POINT ( 'NONE', ( 16.23201905896638308, 152.0606143167149185, 181.0564827348360382 ) ) ; -#37949 = CARTESIAN_POINT ( 'NONE', ( 30.06906075427000502, 177.1956492926942985, 101.0567532828530233 ) ) ; -#37950 = CIRCLE ( 'NONE', #20308, 1.749999999939591433 ) ; -#37951 = DIRECTION ( 'NONE', ( 0.0006039748319380209294, 1.272479560138527092E-14, 0.9999998176071845934 ) ) ; -#37952 = CARTESIAN_POINT ( 'NONE', ( -4.036264727041273481, 174.7924093549539180, 102.5751288760997966 ) ) ; -#37953 = LINE ( 'NONE', #22630, #6923 ) ; -#37954 = ORIENTED_EDGE ( 'NONE', *, *, #25648, .F. ) ; -#37955 = VERTEX_POINT ( 'NONE', #6089 ) ; -#37956 = FACE_BOUND ( 'NONE', #15889, .T. ) ; -#37957 = EDGE_CURVE ( 'NONE', #23072, #36964, #22047, .T. ) ; -#37958 = DIRECTION ( 'NONE', ( -0.0005884949961242684187, 0.2249510543439056376, -0.9743698870671265722 ) ) ; -#37959 = CARTESIAN_POINT ( 'NONE', ( -35.45487758071271855, 209.7096534091000137, 76.07991848633032816 ) ) ; -#37960 = ORIENTED_EDGE ( 'NONE', *, *, #28102, .F. ) ; -#37961 = LINE ( 'NONE', #38162, #4960 ) ; -#37962 = ORIENTED_EDGE ( 'NONE', *, *, #4164, .T. ) ; -#37963 = CARTESIAN_POINT ( 'NONE', ( -45.08822124451242530, 123.2541779049768280, 91.19028666418968498 ) ) ; -#37964 = LINE ( 'NONE', #35069, #33880 ) ; -#37965 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1938, #20946, #27519, #27101 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#37966 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 3.427539337001264681E-16, -0.0006039748319384838837 ) ) ; -#37967 = ORIENTED_EDGE ( 'NONE', *, *, #18528, .T. ) ; -#37968 = CARTESIAN_POINT ( 'NONE', ( 21.26009108512010570, 128.3999477444776574, 91.84930485354649932 ) ) ; -#37969 = DIRECTION ( 'NONE', ( -0.0005884949961247776685, 0.2249510543439061094, -0.9743698870671263501 ) ) ; -#37970 = DIRECTION ( 'NONE', ( 0.9914448496449769221, -0.1271493821533873914, -0.02949821571656870492 ) ) ; -#37971 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#37972 = CARTESIAN_POINT ( 'NONE', ( 22.49960432933178822, 158.3069096095373993, 96.18736459073451783 ) ) ; -#37973 = ORIENTED_EDGE ( 'NONE', *, *, #849, .F. ) ; -#37974 = CIRCLE ( 'NONE', #17703, 48.00000000000002132 ) ; -#37975 = CARTESIAN_POINT ( 'NONE', ( 20.15079215819618241, 211.0873987128438500, 75.87692249624042518 ) ) ; -#37976 = CIRCLE ( 'NONE', #18376, 4.999999999999990230 ) ; -#37977 = CARTESIAN_POINT ( 'NONE', ( 0.5626164669235433902, 188.9999987160578598, 103.6843922204118940 ) ) ; -#37978 = CARTESIAN_POINT ( 'NONE', ( -1.963506278948965011, 188.9017754806783103, 106.3444335591781851 ) ) ; -#37979 = DIRECTION ( 'NONE', ( 0.7069397808360943225, -0.6508952239913948778, -0.2767156548816978590 ) ) ; -#37980 = EDGE_CURVE ( 'NONE', #23210, #19682, #18539, .T. ) ; -#37981 = CARTESIAN_POINT ( 'NONE', ( -38.94661729375095405, 128.0727087836083911, 89.75751053645129218 ) ) ; -#37982 = ADVANCED_FACE ( 'NONE', ( #31652 ), #17399, .F. ) ; -#37983 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#37984 = DIRECTION ( 'NONE', ( -0.0006039748319392653766, -3.841674172953530792E-18, -0.9999998176071845934 ) ) ; -#37985 = CARTESIAN_POINT ( 'NONE', ( -26.28989206232940035, 188.3523932612100111, 105.7157182448219856 ) ) ; -#37986 = VERTEX_POINT ( 'NONE', #9774 ) ; -#37987 = CARTESIAN_POINT ( 'NONE', ( -19.00228709110520953, 148.6728657431648628, 182.7289924287499900 ) ) ; -#37988 = ORIENTED_EDGE ( 'NONE', *, *, #25972, .F. ) ; -#37989 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323825927781006472, 0.0005734119022075028415 ) ) ; -#37990 = DIRECTION ( 'NONE', ( 0.0005884949961296528920, -0.2249510543439046939, 0.9743698870671267942 ) ) ; -#37991 = CARTESIAN_POINT ( 'NONE', ( -20.01777344647963730, 205.1071326358727163, 76.11698016271346035 ) ) ; -#37992 = CARTESIAN_POINT ( 'NONE', ( 36.06507414729499317, 192.5944866880060147, 106.3721272616880071 ) ) ; -#37993 = AXIS2_PLACEMENT_3D ( 'NONE', #36817, #37618, #12469 ) ; -#37994 = CARTESIAN_POINT ( 'NONE', ( 22.45974714935999828, 167.3597764858999994, 28.07991271570000080 ) ) ; -#37995 = ORIENTED_EDGE ( 'NONE', *, *, #21096, .T. ) ; -#37996 = CARTESIAN_POINT ( 'NONE', ( 75.24056455973224899, 196.4820008462166641, 189.1802437148639058 ) ) ; -#37997 = VECTOR ( 'NONE', #4069, 999.9999999999998863 ) ; -#37998 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364886824597, 136.5649596138813706, 181.4686487119530511 ) ) ; -#37999 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36558, #1596, #17726, #5261, #11014, #23688, #26970, #4855 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 4 ), - ( 1.154700540210073570E-15, 0.0004329834460427705472, 0.0008659668920843864191, 0.001731933784167665868 ), - .UNSPECIFIED. ) ; -#38000 = DIRECTION ( 'NONE', ( -0.0004161288024487093526, -0.5299192578742120130, -0.8480479980348188951 ) ) ; -#38001 = ORIENTED_EDGE ( 'NONE', *, *, #20290, .T. ) ; -#38002 = FACE_OUTER_BOUND ( 'NONE', #1805, .T. ) ; -#38003 = ORIENTED_EDGE ( 'NONE', *, *, #39679, .F. ) ; -#38004 = CARTESIAN_POINT ( 'NONE', ( 22.30994511369541655, 117.4496609881286844, 177.0551398655643709 ) ) ; -#38005 = CARTESIAN_POINT ( 'NONE', ( 3.856354911035337896, 168.4251820707296190, 98.86504003729989165 ) ) ; -#38006 = CARTESIAN_POINT ( 'NONE', ( -36.60686137602164791, 191.6395055713826423, 104.3895888317887568 ) ) ; -#38007 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971541810 ) ) ; -#38008 = EDGE_CURVE ( 'NONE', #15536, #26493, #11182, .T. ) ; -#38009 = DIRECTION ( 'NONE', ( -0.6087614115774879764, 0.7730004600455407937, 0.1785492440296699013 ) ) ; -#38010 = PLANE ( 'NONE', #36577 ) ; -#38011 = CARTESIAN_POINT ( 'NONE', ( -44.90705422830284732, 186.7765192746497291, 105.8797162406083174 ) ) ; -#38012 = VERTEX_POINT ( 'NONE', #26123 ) ; -#38013 = EDGE_CURVE ( 'NONE', #11548, #37352, #6321, .T. ) ; -#38014 = CARTESIAN_POINT ( 'NONE', ( 12.64071457670788057, 176.8991890015799697, 103.2647382212043539 ) ) ; -#38015 = CARTESIAN_POINT ( 'NONE', ( -20.26858147528999865, 210.4001054583000041, 75.82073865856999362 ) ) ; -#38016 = FACE_OUTER_BOUND ( 'NONE', #10969, .T. ) ; -#38017 = CARTESIAN_POINT ( 'NONE', ( -37.65075021393000299, 191.3226513556000157, 104.2390354988000070 ) ) ; -#38018 = EDGE_CURVE ( 'NONE', #18856, #17411, #20358, .T. ) ; -#38019 = ORIENTED_EDGE ( 'NONE', *, *, #4222, .T. ) ; -#38020 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178573076042E-05, -0.0002331579774916825443 ) ) ; -#38021 = VERTEX_POINT ( 'NONE', #7894 ) ; -#38022 = EDGE_CURVE ( 'NONE', #4942, #35551, #6869, .T. ) ; -#38023 = EDGE_CURVE ( 'NONE', #12808, #5169, #8282, .T. ) ; -#38024 = DIRECTION ( 'NONE', ( 0.7856637149787890628, -0.6186538021912806329, -2.803352852331656654E-15 ) ) ; -#38025 = EDGE_CURVE ( 'NONE', #13780, #31100, #39477, .T. ) ; -#38026 = VECTOR ( 'NONE', #11805, 1000.000000000000000 ) ; -#38027 = CARTESIAN_POINT ( 'NONE', ( 36.73294452760477213, 115.7847013455190535, 89.70041604681827607 ) ) ; -#38028 = CARTESIAN_POINT ( 'NONE', ( 19.99963098261158123, 196.3881442804596702, 104.3113798016861580 ) ) ; -#38029 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#38030 = CARTESIAN_POINT ( 'NONE', ( -12.63562338462310741, 176.7996745866113315, 103.1253305348305105 ) ) ; -#38031 = CARTESIAN_POINT ( 'NONE', ( -15.66516191008950010, 160.1415665644281887, 99.37085485008498154 ) ) ; -#38032 = PLANE ( 'NONE', #25196 ) ; -#38033 = CARTESIAN_POINT ( 'NONE', ( 38.32695982823999969, 118.7440985934999986, 90.10258810038000377 ) ) ; -#38034 = ORIENTED_EDGE ( 'NONE', *, *, #25624, .T. ) ; -#38035 = FACE_OUTER_BOUND ( 'NONE', #23545, .T. ) ; -#38036 = CARTESIAN_POINT ( 'NONE', ( 25.25244696082440754, 117.1946158480437248, 170.8386649222292704 ) ) ; -#38037 = CARTESIAN_POINT ( 'NONE', ( -40.95638651216200543, 219.5549399801000163, 73.58324080466002215 ) ) ; -#38038 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #7006, #870, #35201, #13354, #19672, #28693, #25846, #19866, #677, #4336, #10904, #32172, #4535, #25647, #31973, #4128, #17001, #38094 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 2, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999945599, 0.1874999999999868994, 0.2187499999999872047, 0.2499999999999875100, 0.4999999999999995559, 0.6250000000000022204, 0.6875000000000041078, 0.7187500000000051070, 0.7500000000000061062, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#38039 = DIRECTION ( 'NONE', ( 0.0005884949961235717104, -0.2249510543439064147, 0.9743698870671262391 ) ) ; -#38040 = ORIENTED_EDGE ( 'NONE', *, *, #26991, .T. ) ; -#38041 = ORIENTED_EDGE ( 'NONE', *, *, #1544, .T. ) ; -#38042 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12418, #30434, #28180, #21638, #34276, #24512 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.0008096972284214351513, 0.001619394456842870303 ), - .UNSPECIFIED. ) ; -#38043 = ORIENTED_EDGE ( 'NONE', *, *, #6944, .T. ) ; -#38044 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#38045 = VECTOR ( 'NONE', #24879, 1000.000000000000227 ) ; -#38046 = CARTESIAN_POINT ( 'NONE', ( 22.99909745638999681, 115.1133511170128969, 87.25389341346352978 ) ) ; -#38047 = DIRECTION ( 'NONE', ( 0.0006039748319384539597, 1.295170900108887039E-14, 0.9999998176071845934 ) ) ; -#38048 = CIRCLE ( 'NONE', #28922, 1.999999999963394837 ) ; -#38049 = ORIENTED_EDGE ( 'NONE', *, *, #37832, .F. ) ; -#38050 = DIRECTION ( 'NONE', ( 0.6087614115774502288, 0.7729348350655650401, 0.1788331191820961841 ) ) ; -#38051 = VECTOR ( 'NONE', #19665, 1000.000000000000000 ) ; -#38052 = CARTESIAN_POINT ( 'NONE', ( -38.25695912633000262, 118.9336418487000060, 90.29207677415999456 ) ) ; -#38053 = CARTESIAN_POINT ( 'NONE', ( -38.12891303324000347, 119.0716168431000170, 87.44155862881000019 ) ) ; -#38054 = CARTESIAN_POINT ( 'NONE', ( -22.49823187728737395, 151.2919806023961939, 97.67717024395707881 ) ) ; -#38055 = CYLINDRICAL_SURFACE ( 'NONE', #19738, 2.000000000000000000 ) ; -#38056 = ORIENTED_EDGE ( 'NONE', *, *, #25307, .T. ) ; -#38057 = CARTESIAN_POINT ( 'NONE', ( -20.49921872406353529, 118.1134456025284152, 89.78002774633898753 ) ) ; -#38058 = EDGE_CURVE ( 'NONE', #17966, #4210, #23049, .T. ) ; -#38059 = ORIENTED_EDGE ( 'NONE', *, *, #24581, .T. ) ; -#38060 = CARTESIAN_POINT ( 'NONE', ( -24.99919627279852463, 116.5767028336385636, 89.78285475179252728 ) ) ; -#38061 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24249, #9103, #2942, #14840, #28119, #40158 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 1.133930764694885689E-15, 0.0005038667338457266482, 0.001007733467690319221 ), - .UNSPECIFIED. ) ; -#38062 = CARTESIAN_POINT ( 'NONE', ( -20.39154081812865371, 183.6048944875886377, 102.0537691888108043 ) ) ; -#38063 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #27224, #39654, #24143, #11664 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.712388980384689674, 4.994529182805674594 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9933774026859373274, 0.9933774026859373274, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#38064 = CARTESIAN_POINT ( 'NONE', ( -2.455538055765680738, 209.0000002601700544, 73.61629604161946361 ) ) ; -#38065 = VERTEX_POINT ( 'NONE', #10182 ) ; -#38066 = EDGE_CURVE ( 'NONE', #13870, #29201, #11618, .T. ) ; -#38067 = CARTESIAN_POINT ( 'NONE', ( -25.91302100391000351, 181.3103559555999880, 104.3497047787000156 ) ) ; -#38068 = CARTESIAN_POINT ( 'NONE', ( 6.042308921164076807, 177.7921139377573638, 100.6958234779730645 ) ) ; -#38069 = DIRECTION ( 'NONE', ( -0.0003200578985547136018, 0.8480480961564359488, -0.5299191675797225720 ) ) ; -#38070 = CARTESIAN_POINT ( 'NONE', ( 8.046776639317595681, 161.2737771581006996, 96.88104755365348808 ) ) ; -#38071 = ADVANCED_FACE ( 'NONE', ( #23443 ), #7482, .F. ) ; -#38072 = ORIENTED_EDGE ( 'NONE', *, *, #7046, .T. ) ; -#38073 = VERTEX_POINT ( 'NONE', #4815 ) ; -#38074 = LINE ( 'NONE', #3718, #16544 ) ; -#38075 = DIRECTION ( 'NONE', ( -0.6087611483135560997, 0.7728367167708899421, 0.1792575619457988101 ) ) ; -#38076 = EDGE_CURVE ( 'NONE', #40029, #16264, #33029, .T. ) ; -#38077 = ORIENTED_EDGE ( 'NONE', *, *, #35470, .F. ) ; -#38078 = EDGE_CURVE ( 'NONE', #23754, #3145, #24816, .T. ) ; -#38079 = CYLINDRICAL_SURFACE ( 'NONE', #19929, 22.50000000000000000 ) ; -#38080 = FACE_OUTER_BOUND ( 'NONE', #31075, .T. ) ; -#38081 = CARTESIAN_POINT ( 'NONE', ( -39.69814225588821444, 114.9854446628631450, 150.7514082625260130 ) ) ; -#38082 = VECTOR ( 'NONE', #30608, 999.9999999999997726 ) ; -#38083 = ORIENTED_EDGE ( 'NONE', *, *, #30279, .T. ) ; -#38084 = AXIS2_PLACEMENT_3D ( 'NONE', #16073, #36288, #14633 ) ; -#38085 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#38086 = CARTESIAN_POINT ( 'NONE', ( -3.669944098339545935, 125.3049322094074114, 88.58406047461089372 ) ) ; -#38087 = CYLINDRICAL_SURFACE ( 'NONE', #15886, 2.000000000000000000 ) ; -#38088 = VECTOR ( 'NONE', #11560, 1000.000000000000000 ) ; -#38089 = ORIENTED_EDGE ( 'NONE', *, *, #3762, .T. ) ; -#38090 = CARTESIAN_POINT ( 'NONE', ( 25.66719153581999890, 120.2149646579000120, 90.12512969946000396 ) ) ; -#38091 = CARTESIAN_POINT ( 'NONE', ( -15.99850559934605521, 152.2995707326747947, 94.82371111949458964 ) ) ; -#38092 = CARTESIAN_POINT ( 'NONE', ( 24.53469179838298331, 103.6131156702338671, 89.75296640900199918 ) ) ; -#38094 = CARTESIAN_POINT ( 'NONE', ( -13.46391575659845685, 154.4039982810205629, 95.30803284751881677 ) ) ; -#38093 = CARTESIAN_POINT ( 'NONE', ( 12.63611452238018984, 129.9736765176137965, 92.21783751031847487 ) ) ; -#38095 = ORIENTED_EDGE ( 'NONE', *, *, #14062, .T. ) ; -#38096 = DIRECTION ( 'NONE', ( -0.1782640835105700761, -0.3528946327679922113, 0.9185245204640322125 ) ) ; -#38097 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #31437, #28573, #32052, #37968 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#38098 = ORIENTED_EDGE ( 'NONE', *, *, #7825, .F. ) ; -#38099 = CARTESIAN_POINT ( 'NONE', ( -14.99990232847155625, 129.4478439323167436, 89.71842115305724974 ) ) ; -#38100 = CARTESIAN_POINT ( 'NONE', ( 22.50006375536335312, 158.5567136586353740, 96.58713672006965112 ) ) ; -#38101 = ORIENTED_EDGE ( 'NONE', *, *, #210, .F. ) ; -#38102 = ORIENTED_EDGE ( 'NONE', *, *, #37011, .T. ) ; -#38103 = CARTESIAN_POINT ( 'NONE', ( 38.69099149694999795, 119.0634568547999947, 90.12535802993001255 ) ) ; -#38104 = CARTESIAN_POINT ( 'NONE', ( -41.54213446450223302, 190.5842469323372086, 103.6778548217435372 ) ) ; -#38105 = LINE ( 'NONE', #3946, #16124 ) ; -#38106 = CARTESIAN_POINT ( 'NONE', ( 43.53522452129121945, 122.0089640226160981, 87.79461538354614447 ) ) ; -#38107 = ORIENTED_EDGE ( 'NONE', *, *, #5150, .F. ) ; -#38108 = CIRCLE ( 'NONE', #33547, 5.999999999929131356 ) ; -#38109 = EDGE_CURVE ( 'NONE', #20831, #5670, #16439, .T. ) ; -#38110 = EDGE_LOOP ( 'NONE', ( #12329, #68, #10364, #7514, #24164, #22221, #21794, #3960 ) ) ; -#38111 = EDGE_CURVE ( 'NONE', #32145, #27892, #4621, .T. ) ; -#38112 = VERTEX_POINT ( 'NONE', #25728 ) ; -#38113 = DIRECTION ( 'NONE', ( 0.1943643238945209628, -0.07321898756438961764, 0.9781929714821464561 ) ) ; -#38114 = EDGE_CURVE ( 'NONE', #3943, #5068, #29384, .T. ) ; -#38115 = CARTESIAN_POINT ( 'NONE', ( 35.04524256069632315, 217.7719116313981544, 73.53733772525205836 ) ) ; -#38116 = AXIS2_PLACEMENT_3D ( 'NONE', #13970, #32771, #20485 ) ; -#38117 = EDGE_CURVE ( 'NONE', #37155, #1289, #35280, .T. ) ; -#38118 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#38119 = VERTEX_POINT ( 'NONE', #10777 ) ; -#38120 = PLANE ( 'NONE', #32818 ) ; -#38121 = ORIENTED_EDGE ( 'NONE', *, *, #15590, .F. ) ; -#38122 = CARTESIAN_POINT ( 'NONE', ( -20.52004672817496100, 211.4177853712151034, 73.57089035650061248 ) ) ; -#38123 = EDGE_LOOP ( 'NONE', ( #33472, #28391, #27401, #29254 ) ) ; -#38124 = EDGE_CURVE ( 'NONE', #20598, #31048, #4211, .T. ) ; -#38125 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #34718, #15538, #24966, #21889 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999992929045289358 ), - .UNSPECIFIED. ) ; -#38126 = ORIENTED_EDGE ( 'NONE', *, *, #36679, .T. ) ; -#38127 = DIRECTION ( 'NONE', ( 0.0005884949961229053597, -0.2249510543439064147, 0.9743698870671262391 ) ) ; -#38128 = LINE ( 'NONE', #12786, #11126 ) ; -#38129 = ORIENTED_EDGE ( 'NONE', *, *, #26829, .T. ) ; -#38130 = CARTESIAN_POINT ( 'NONE', ( -0.03494995457974003905, -32.89481530046831637, 142.2936922234670760 ) ) ; -#38131 = EDGE_CURVE ( 'NONE', #10087, #11263, #7692, .T. ) ; -#38132 = CARTESIAN_POINT ( 'NONE', ( -2.818102608662000019, 190.7172409561999871, 106.6369364776000026 ) ) ; -#38133 = CARTESIAN_POINT ( 'NONE', ( -20.49852833623671700, 173.9502348347849363, 102.3906403207337945 ) ) ; -#38134 = ORIENTED_EDGE ( 'NONE', *, *, #7547, .T. ) ; -#38135 = CARTESIAN_POINT ( 'NONE', ( 23.36232515670999987, 177.1947614372178919, 101.0605990067274860 ) ) ; -#38136 = PLANE ( 'NONE', #6172 ) ; -#38137 = CARTESIAN_POINT ( 'NONE', ( 21.64659700640633844, 213.7792641208693283, 73.04543008022091044 ) ) ; -#38138 = CARTESIAN_POINT ( 'NONE', ( -25.98970585344537199, 191.9759150222000130, 106.9371459003730820 ) ) ; -#38139 = ADVANCED_FACE ( 'NONE', ( #32642 ), #20464, .F. ) ; -#38140 = CIRCLE ( 'NONE', #21809, 4.749999999995120348 ) ; -#38141 = VECTOR ( 'NONE', #30839, 1000.000000000000000 ) ; -#38142 = CARTESIAN_POINT ( 'NONE', ( 45.12699821176128978, 130.9347303581116364, 89.85432989627193479 ) ) ; -#38143 = ORIENTED_EDGE ( 'NONE', *, *, #10107, .T. ) ; -#38144 = CARTESIAN_POINT ( 'NONE', ( -0.001765484988446460639, 156.3551877982853000, 95.75036263590625651 ) ) ; -#38145 = FACE_OUTER_BOUND ( 'NONE', #401, .T. ) ; -#38146 = CARTESIAN_POINT ( 'NONE', ( -35.82577198247000183, 112.4014516645000157, 89.91121576333999599 ) ) ; -#38147 = EDGE_LOOP ( 'NONE', ( #512, #12824, #13957, #10748 ) ) ; -#38148 = CARTESIAN_POINT ( 'NONE', ( 41.55397567426885530, 120.6681361272677577, 87.99940985657048031 ) ) ; -#38149 = DIRECTION ( 'NONE', ( 0.0006039748319292908250, 1.314021223879979801E-14, 0.9999998176071847045 ) ) ; -#38150 = VERTEX_POINT ( 'NONE', #17889 ) ; -#38151 = CARTESIAN_POINT ( 'NONE', ( 8.861833597925741657, 160.2547524075112904, 96.64529483589464576 ) ) ; -#38152 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.8480480527206264441, 0.5299193337450082142 ) ) ; -#38153 = CARTESIAN_POINT ( 'NONE', ( 23.36294425673206732, 177.5614284443948918, 100.8314797030197809 ) ) ; -#38154 = CARTESIAN_POINT ( 'NONE', ( -35.93807696457169953, 196.5784392894729820, 103.8968090370881896 ) ) ; -#38155 = ORIENTED_EDGE ( 'NONE', *, *, #18754, .T. ) ; -#38156 = ORIENTED_EDGE ( 'NONE', *, *, #29573, .T. ) ; -#38157 = DIRECTION ( 'NONE', ( 0.0004161288024355817784, 0.5299192579128034764, 0.8480479980107041849 ) ) ; -#38158 = CARTESIAN_POINT ( 'NONE', ( -10.03626368673904246, 167.9332148063899410, 100.9951825985159957 ) ) ; -#38159 = ORIENTED_EDGE ( 'NONE', *, *, #38342, .F. ) ; -#38160 = EDGE_CURVE ( 'NONE', #37645, #16377, #13066, .T. ) ; -#38161 = VERTEX_POINT ( 'NONE', #29982 ) ; -#38162 = CARTESIAN_POINT ( 'NONE', ( -18.46843443665382978, 153.9052539544929914, 180.6508572568318414 ) ) ; -#38163 = EDGE_CURVE ( 'NONE', #206, #11332, #2847, .T. ) ; -#38164 = PLANE ( 'NONE', #12634 ) ; -#38165 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971564570 ) ) ; -#38166 = EDGE_CURVE ( 'NONE', #9311, #18814, #23758, .T. ) ; -#38167 = CARTESIAN_POINT ( 'NONE', ( 3.046005780481993774, 209.2052046650086083, 76.12019302384355512 ) ) ; -#38168 = CARTESIAN_POINT ( 'NONE', ( -15.49931385541658457, 185.6434956935997889, 103.7188176754347779 ) ) ; -#38169 = ORIENTED_EDGE ( 'NONE', *, *, #8007, .T. ) ; -#38170 = CARTESIAN_POINT ( 'NONE', ( 75.33799679939463090, 195.3233842313971707, 195.0706613604953930 ) ) ; -#38171 = AXIS2_PLACEMENT_3D ( 'NONE', #39421, #23915, #36374 ) ; -#38172 = CIRCLE ( 'NONE', #26443, 1.999999999912203341 ) ; -#38173 = EDGE_CURVE ( 'NONE', #19312, #7165, #11792, .T. ) ; -#38174 = CARTESIAN_POINT ( 'NONE', ( -20.51774922679897983, 207.6505144753610352, 76.65074302234292247 ) ) ; -#38175 = DIRECTION ( 'NONE', ( 0.0005884949961231158034, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#38176 = CARTESIAN_POINT ( 'NONE', ( 20.16676214620377294, 120.3527716555780529, 87.59741557435995674 ) ) ; -#38177 = FACE_OUTER_BOUND ( 'NONE', #94, .T. ) ; -#38178 = VERTEX_POINT ( 'NONE', #20564 ) ; -#38180 = EDGE_CURVE ( 'NONE', #7061, #19255, #12030, .T. ) ; -#38179 = CARTESIAN_POINT ( 'NONE', ( 50.01144718627692498, 67.27946979429627561, 310.0857197240632104 ) ) ; -#38181 = CARTESIAN_POINT ( 'NONE', ( 0.5732175548287413713, 188.9999392055002261, 103.6969148967344552 ) ) ; -#38182 = CARTESIAN_POINT ( 'NONE', ( 36.42166835727676499, 191.8075644629787746, 104.3595393062645797 ) ) ; -#38183 = CARTESIAN_POINT ( 'NONE', ( -26.00133086711789687, 118.1131156701862892, 87.28349311522542564 ) ) ; -#38184 = CARTESIAN_POINT ( 'NONE', ( 38.48136045787376247, 119.0247563911853632, 90.24990605984262970 ) ) ; -#38185 = CARTESIAN_POINT ( 'NONE', ( 10.03596943924904039, 143.5399299914107587, 95.86457705219089576 ) ) ; -#38186 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 1.092943067225001162E-14, 0.7075337269147008445 ) ) ; -#38187 = EDGE_CURVE ( 'NONE', #11904, #40156, #16016, .T. ) ; -#38188 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #32995, #4992, #17456, #29951 ), - ( #1944, #14411, #26897, #36688 ), - ( #40345, #5605, #30766, #21579 ), - ( #15613, #11755, #6208, #18662 ), - ( #12162, #31173, #27923, #27524 ), - ( #12348, #8700, #11552, #20951 ), - ( #39740, #27715, #24851, #5403 ), - ( #39949, #27313, #30567, #24647 ), - ( #11961, #3140, #24444, #36896 ), - ( #15224, #24240, #8897, #21371 ), - ( #39541, #37298, #33814, #18464 ), - ( #5817, #8489, #18063, #37095 ), - ( #9088, #24024, #2756, #9296 ), - ( #21157, #40150, #21772, #17853 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -8.226917624016999464E-05, 0.01033686631024999941, 0.02075600179673000104, 0.04159427276969999976, 0.08327081471564999615, 0.1249473566616000064, 0.1666238986074999873, 0.2499769824994000078, 0.3333300663912999728, 0.6666654435796000033, 1.000000000000000000, 1.160103838099999951 ), - ( 8.741884557905999614E-08, 1.000000307112000053 ), - .UNSPECIFIED. ) ; -#38189 = CARTESIAN_POINT ( 'NONE', ( 25.50051830703121780, 120.2145355607603534, 89.95699753438390189 ) ) ; -#38190 = VERTEX_POINT ( 'NONE', #33645 ) ; -#38191 = DIRECTION ( 'NONE', ( -4.163336342338107392E-15, 0.9743700557921585181, 0.2249510932971564015 ) ) ; -#38192 = CIRCLE ( 'NONE', #24499, 58.90509898899682639 ) ; -#38193 = CARTESIAN_POINT ( 'NONE', ( -19.00244483772789295, 148.9001918165677125, 181.7428417728492605 ) ) ; -#38194 = LINE ( 'NONE', #31671, #21358 ) ; -#38195 = CIRCLE ( 'NONE', #30998, 2.000000000000011546 ) ; -#38196 = CIRCLE ( 'NONE', #14720, 2.000000000000011546 ) ; -#38197 = ORIENTED_EDGE ( 'NONE', *, *, #38885, .T. ) ; -#38198 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250614502, 179.6252109630515861, 101.6466942236996545 ) ) ; -#38199 = CARTESIAN_POINT ( 'NONE', ( 18.99779093548555409, 149.2112913899639466, 180.2913438554751622 ) ) ; -#38200 = CARTESIAN_POINT ( 'NONE', ( -14.31059678795166867, 190.8510141132511819, 106.8019081697394483 ) ) ; -#38201 = CARTESIAN_POINT ( 'NONE', ( -17.99852876250903932, 179.1753088543885610, 103.5954339978220275 ) ) ; -#38202 = AXIS2_PLACEMENT_3D ( 'NONE', #40198, #33863, #27370 ) ; -#38203 = CARTESIAN_POINT ( 'NONE', ( 36.54765335729929632, 115.9165150380169820, 87.70490190100063899 ) ) ; -#38204 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921572969, -0.2249510932971618138 ) ) ; -#38205 = ORIENTED_EDGE ( 'NONE', *, *, #34366, .F. ) ; -#38206 = CARTESIAN_POINT ( 'NONE', ( 10.03449820175210050, 144.1023076273136212, 93.42865233452057794 ) ) ; -#38207 = CARTESIAN_POINT ( 'NONE', ( 35.72133043294194721, 114.6570628451127618, 87.24620950355091509 ) ) ; -#38208 = CARTESIAN_POINT ( 'NONE', ( 22.50147045825027092, 126.8721902444253971, 91.49584442702865772 ) ) ; -#38209 = ORIENTED_EDGE ( 'NONE', *, *, #2494, .F. ) ; -#38210 = DIRECTION ( 'NONE', ( -4.376840770101431617E-14, 0.9743700557921589622, 0.2249510932971541810 ) ) ; -#38211 = EDGE_CURVE ( 'NONE', #33670, #16617, #28976, .T. ) ; -#38212 = ADVANCED_FACE ( 'NONE', ( #26721 ), #17850, .F. ) ; -#38213 = VERTEX_POINT ( 'NONE', #8726 ) ; -#38214 = CARTESIAN_POINT ( 'NONE', ( -35.44445577042502293, 86.86693592215954141, 286.9319308200167029 ) ) ; -#38215 = CARTESIAN_POINT ( 'NONE', ( -3.668796569718617562, 128.1725765626999021, 91.12766564069485753 ) ) ; -#38216 = CARTESIAN_POINT ( 'NONE', ( -44.99234402510556663, 186.0463934164131672, 106.3673110047960506 ) ) ; -#38217 = DIRECTION ( 'NONE', ( -0.7933533411653072021, 0.5930537057989907490, 0.1373964268091705798 ) ) ; -#38218 = CYLINDRICAL_SURFACE ( 'NONE', #32769, 5.000000000000022204 ) ; -#38219 = ORIENTED_EDGE ( 'NONE', *, *, #20944, .F. ) ; -#38220 = CARTESIAN_POINT ( 'NONE', ( 37.31693588142861273, 172.3309151562380919, 164.9673944986862466 ) ) ; -#38221 = CARTESIAN_POINT ( 'NONE', ( -5.072027095213130998, 177.6015855243536237, 100.6585432524953916 ) ) ; -#38222 = AXIS2_PLACEMENT_3D ( 'NONE', #21351, #30950, #17837 ) ; -#38223 = CARTESIAN_POINT ( 'NONE', ( 5.384453718119554644, 177.7301722179466026, 100.6819143828688397 ) ) ; -#38224 = CONICAL_SURFACE ( 'NONE', #1001, 17.00000000000409273, 0.7853981633973132759 ) ; -#38225 = DIRECTION ( 'NONE', ( -0.7066795775160008564, 0.000000000000000000, 0.7075337269147008445 ) ) ; -#38226 = ORIENTED_EDGE ( 'NONE', *, *, #7380, .T. ) ; -#38227 = AXIS2_PLACEMENT_3D ( 'NONE', #10806, #25550, #34705 ) ; -#38228 = ORIENTED_EDGE ( 'NONE', *, *, #38889, .F. ) ; -#38229 = FACE_OUTER_BOUND ( 'NONE', #9563, .T. ) ; -#38230 = ORIENTED_EDGE ( 'NONE', *, *, #30017, .F. ) ; -#38231 = EDGE_CURVE ( 'NONE', #9860, #29667, #23855, .T. ) ; -#38232 = LINE ( 'NONE', #10238, #7095 ) ; -#38233 = DIRECTION ( 'NONE', ( 0.5399741663421816495, -0.8200377969059812200, -0.1896468067979279470 ) ) ; -#38234 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.7071067167009886800, 0.7071068456721004702 ) ) ; -#38235 = CARTESIAN_POINT ( 'NONE', ( -2.576359560463000076, 208.9113141535999887, 73.50994362621000278 ) ) ; -#38236 = CARTESIAN_POINT ( 'NONE', ( 38.51934278294999814, 118.5830806632000076, 89.80757908325999495 ) ) ; -#38237 = ORIENTED_EDGE ( 'NONE', *, *, #20668, .F. ) ; -#38238 = ADVANCED_FACE ( 'NONE', ( #36311 ), #5641, .F. ) ; -#38239 = CIRCLE ( 'NONE', #31812, 10.00000000000072831 ) ; -#38240 = FACE_OUTER_BOUND ( 'NONE', #2761, .T. ) ; -#38241 = FACE_OUTER_BOUND ( 'NONE', #20747, .T. ) ; -#38242 = CARTESIAN_POINT ( 'NONE', ( -26.20112735025328377, 189.6309894264402942, 106.5274248102679593 ) ) ; -#38243 = AXIS2_PLACEMENT_3D ( 'NONE', #36429, #13743, #38669 ) ; -#38244 = ORIENTED_EDGE ( 'NONE', *, *, #35868, .T. ) ; -#38245 = EDGE_LOOP ( 'NONE', ( #13973, #35047, #29087, #37403 ) ) ; -#38246 = VERTEX_POINT ( 'NONE', #39573 ) ; -#38247 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921576300, 0.2249510932971610366 ) ) ; -#38248 = CONICAL_SURFACE ( 'NONE', #8914, 8.499999999972359888, 0.7853981633972975107 ) ; -#38249 = CARTESIAN_POINT ( 'NONE', ( 5.666881758531304492, 123.8790441587746614, 91.16841673835540405 ) ) ; -#38250 = AXIS2_PLACEMENT_3D ( 'NONE', #8511, #27132, #7680 ) ; -#38251 = ADVANCED_FACE ( 'NONE', ( #11175 ), #8314, .F. ) ; -#38252 = ORIENTED_EDGE ( 'NONE', *, *, #3082, .T. ) ; -#38253 = ORIENTED_EDGE ( 'NONE', *, *, #17037, .T. ) ; -#38254 = EDGE_CURVE ( 'NONE', #30803, #5465, #31107, .T. ) ; -#38255 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474974863243018, 155.7928101624827946, 98.18628735359689585 ) ) ; -#38256 = CARTESIAN_POINT ( 'NONE', ( 20.16836658598267817, 118.8155847327597030, 90.08898221329239675 ) ) ; -#38257 = CARTESIAN_POINT ( 'NONE', ( 6.271598195383973895, 163.6071748240002250, 98.96028355598751602 ) ) ; -#38258 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#38259 = EDGE_LOOP ( 'NONE', ( #30029, #13762, #39650, #38001 ) ) ; -#38260 = CYLINDRICAL_SURFACE ( 'NONE', #25838, 7.999999999999993783 ) ; -#38261 = ORIENTED_EDGE ( 'NONE', *, *, #11119, .F. ) ; -#38262 = CARTESIAN_POINT ( 'NONE', ( 19.98244285516242869, 208.9307805169470100, 76.16354082693111138 ) ) ; -#38263 = FACE_OUTER_BOUND ( 'NONE', #38245, .T. ) ; -#38264 = DIRECTION ( 'NONE', ( 0.0005884949961233868539, -0.2249510543439054988, 0.9743698870671265722 ) ) ; -#38265 = ORIENTED_EDGE ( 'NONE', *, *, #29027, .F. ) ; -#38266 = CARTESIAN_POINT ( 'NONE', ( -2.770536616719000200, 191.0749790456000028, 103.9388038315000102 ) ) ; -#38267 = CARTESIAN_POINT ( 'NONE', ( 15.50029468041041980, 185.7974155947003112, 103.0514270425986325 ) ) ; -#38268 = CARTESIAN_POINT ( 'NONE', ( 2.685595935758000596, 190.9413773800000058, 106.4228114910000045 ) ) ; -#38269 = CIRCLE ( 'NONE', #24584, 2.000000000000011546 ) ; -#38270 = ORIENTED_EDGE ( 'NONE', *, *, #37717, .F. ) ; -#38271 = DIRECTION ( 'NONE', ( -0.7716293354502457014, 0.6291556465476403348, -0.09354860282138378891 ) ) ; -#38272 = CARTESIAN_POINT ( 'NONE', ( -25.50006284340070906, 118.1130153187805689, 89.78316558933853742 ) ) ; -#38273 = ORIENTED_EDGE ( 'NONE', *, *, #18840, .T. ) ; -#38274 = CIRCLE ( 'NONE', #4966, 5.499999999884110480 ) ; -#38275 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319385907860 ) ) ; -#38276 = CARTESIAN_POINT ( 'NONE', ( 6.035116358040530038, 134.7953873012855297, 93.37716266042390600 ) ) ; -#38277 = CIRCLE ( 'NONE', #20654, 2.499999999981690646 ) ; -#38278 = ORIENTED_EDGE ( 'NONE', *, *, #35326, .T. ) ; -#38279 = AXIS2_PLACEMENT_3D ( 'NONE', #32585, #32387, #4360 ) ; -#38280 = CARTESIAN_POINT ( 'NONE', ( 2.978288450619526184, 190.2180736835273365, 106.6453402794937233 ) ) ; -#38281 = DIRECTION ( 'NONE', ( 0.0005884949961245158337, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#38282 = LINE ( 'NONE', #34589, #4522 ) ; -#38283 = ORIENTED_EDGE ( 'NONE', *, *, #36186, .T. ) ; -#38284 = CARTESIAN_POINT ( 'NONE', ( 26.00589438745670634, 120.1009206316479947, 90.44882784922441488 ) ) ; -#38285 = CARTESIAN_POINT ( 'NONE', ( 1.447658035571014024, 144.9407251426433447, 129.0349007182348657 ) ) ; -#38287 = CARTESIAN_POINT ( 'NONE', ( 27.29350369004999877, 103.8631156702000027, 87.50129974532001143 ) ) ; -#38286 = CARTESIAN_POINT ( 'NONE', ( 20.48137403145198476, 209.5894841463820342, 75.54614556716059326 ) ) ; -#38288 = ORIENTED_EDGE ( 'NONE', *, *, #18385, .F. ) ; -#38289 = EDGE_CURVE ( 'NONE', #38119, #15715, #33441, .T. ) ; -#38290 = VERTEX_POINT ( 'NONE', #29080 ) ; -#38291 = PLANE ( 'NONE', #21901 ) ; -#38292 = CARTESIAN_POINT ( 'NONE', ( -28.26067782467530520, 125.1269179218217857, 91.12357580992288320 ) ) ; -#38293 = FACE_OUTER_BOUND ( 'NONE', #26821, .T. ) ; -#38294 = ORIENTED_EDGE ( 'NONE', *, *, #26632, .T. ) ; -#38295 = EDGE_CURVE ( 'NONE', #11374, #1723, #10710, .T. ) ; -#38296 = AXIS2_PLACEMENT_3D ( 'NONE', #19725, #26098, #3582 ) ; -#38297 = EDGE_CURVE ( 'NONE', #22792, #26158, #26754, .T. ) ; -#38298 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #14204, #29333, #11320, #7846 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.532607311606953182, 4.712388980384698556 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9973083591495172096, 0.9973083591495172096, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#38299 = ORIENTED_EDGE ( 'NONE', *, *, #26866, .T. ) ; -#38301 = EDGE_CURVE ( 'NONE', #28925, #12094, #38074, .T. ) ; -#38300 = CARTESIAN_POINT ( 'NONE', ( 38.85612909692999750, 118.8963570784000012, 89.83544490924001025 ) ) ; -#38302 = CARTESIAN_POINT ( 'NONE', ( -35.44810745619992787, 112.9281708664996984, 87.28919406064997588 ) ) ; -#38303 = EDGE_CURVE ( 'NONE', #23127, #23715, #36962, .T. ) ; -#38304 = CARTESIAN_POINT ( 'NONE', ( -35.94634188049001011, 134.2394347309543434, 93.74516030700213776 ) ) ; -#38305 = CARTESIAN_POINT ( 'NONE', ( -44.97035487161856793, 124.6095424173942803, 91.35670517576666327 ) ) ; -#38306 = PLANE ( 'NONE', #13058 ) ; -#38307 = CIRCLE ( 'NONE', #20024, 4.499999999969428011 ) ; -#38308 = ORIENTED_EDGE ( 'NONE', *, *, #33448, .T. ) ; -#38309 = ORIENTED_EDGE ( 'NONE', *, *, #11295, .T. ) ; -#38310 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #28008, #5497, #40443, #30463 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#38311 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251384259, 130.2132135508113038, 92.29164155970235583 ) ) ; -#38312 = DIRECTION ( 'NONE', ( -0.0005884949961254158299, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#38313 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#38314 = ORIENTED_EDGE ( 'NONE', *, *, #6659, .F. ) ; -#38315 = ORIENTED_EDGE ( 'NONE', *, *, #3629, .T. ) ; -#38316 = PLANE ( 'NONE', #20623 ) ; -#38317 = EDGE_LOOP ( 'NONE', ( #17664, #9154, #36960, #19063 ) ) ; -#38318 = CARTESIAN_POINT ( 'NONE', ( -37.56294621074515305, 117.4321712499414758, 89.72245835561675165 ) ) ; -#38319 = ORIENTED_EDGE ( 'NONE', *, *, #21748, .T. ) ; -#38320 = CARTESIAN_POINT ( 'NONE', ( -16.00000031268763934, 184.9628657724767606, 102.3646292465979855 ) ) ; -#38321 = VERTEX_POINT ( 'NONE', #38465 ) ; -#38322 = CARTESIAN_POINT ( 'NONE', ( -20.49970531044686695, 189.2256923798826449, 103.8646662894091151 ) ) ; -#38323 = DIRECTION ( 'NONE', ( 3.469446952062275440E-15, 0.9743700557921587402, 0.2249510932971553467 ) ) ; -#38324 = DIRECTION ( 'NONE', ( 0.7933535320750499942, -0.5931614265261869745, -0.1369295264925045885 ) ) ; -#38325 = AXIS2_PLACEMENT_3D ( 'NONE', #24235, #5598, #11545 ) ; -#38326 = ORIENTED_EDGE ( 'NONE', *, *, #14619, .F. ) ; -#38327 = CARTESIAN_POINT ( 'NONE', ( -20.49970532950636937, 191.6000458281059764, 104.4127958363113606 ) ) ; -#38328 = VECTOR ( 'NONE', #36183, 999.9999999999998863 ) ; -#38329 = DIRECTION ( 'NONE', ( 0.0006039748319386907495, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#38330 = CIRCLE ( 'NONE', #37035, 2.000000000000011546 ) ; -#38331 = PLANE ( 'NONE', #10500 ) ; -#38332 = CARTESIAN_POINT ( 'NONE', ( -20.01839840245581570, 211.0893415776789936, 76.07059839062316087 ) ) ; -#38333 = ORIENTED_EDGE ( 'NONE', *, *, #4637, .T. ) ; -#38334 = EDGE_CURVE ( 'NONE', #37942, #15550, #13339, .T. ) ; -#38336 = ADVANCED_FACE ( 'NONE', ( #22952 ), #31546, .T. ) ; -#38335 = DIRECTION ( 'NONE', ( 0.9999998176071845934, 0.000000000000000000, -0.0006039748319411731388 ) ) ; -#38337 = CARTESIAN_POINT ( 'NONE', ( -37.76416279167000312, 117.8877880277999992, 89.85641046381000763 ) ) ; -#38339 = ORIENTED_EDGE ( 'NONE', *, *, #19681, .F. ) ; -#38338 = EDGE_CURVE ( 'NONE', #38686, #1598, #32903, .T. ) ; -#38340 = VERTEX_POINT ( 'NONE', #19248 ) ; -#38341 = DIRECTION ( 'NONE', ( -0.7066795775021793569, 8.797476192434283764E-15, 0.7075337269285058017 ) ) ; -#38342 = EDGE_CURVE ( 'NONE', #40361, #38835, #31346, .T. ) ; -#38343 = DIRECTION ( 'NONE', ( -0.0005884949961221076038, 0.2249510543439052768, -0.9743698870671265722 ) ) ; -#38344 = DIRECTION ( 'NONE', ( 0.0005884949950032587751, -0.2249510543438477117, 0.9743698870671404499 ) ) ; -#38345 = CARTESIAN_POINT ( 'NONE', ( 13.50147201672065478, 127.1823533459056961, 91.57288700727464459 ) ) ; -#38346 = DIRECTION ( 'NONE', ( -0.0004161288024530142857, 0.8480480897951311325, -0.5299191110270028426 ) ) ; -#38347 = EDGE_LOOP ( 'NONE', ( #560, #9231, #32754, #28144 ) ) ; -#38348 = FACE_BOUND ( 'NONE', #9399, .T. ) ; -#38349 = EDGE_LOOP ( 'NONE', ( #38409, #9872, #10343, #10650 ) ) ; -#38350 = VERTEX_POINT ( 'NONE', #10285 ) ; -#38352 = EDGE_CURVE ( 'NONE', #24492, #34116, #1562, .T. ) ; -#38351 = CARTESIAN_POINT ( 'NONE', ( 5.670201816268967576, 188.2581808524728331, 103.1863035028179780 ) ) ; -#38353 = CARTESIAN_POINT ( 'NONE', ( 29.78094704533299364, 126.4966686442676149, 91.40475157444033982 ) ) ; -#38354 = CARTESIAN_POINT ( 'NONE', ( -13.55720484940897030, 164.6355387680630429, 97.67021978066252075 ) ) ; -#38355 = AXIS2_PLACEMENT_3D ( 'NONE', #38115, #25867, #10324 ) ; -#38356 = ORIENTED_EDGE ( 'NONE', *, *, #30327, .T. ) ; -#38357 = CARTESIAN_POINT ( 'NONE', ( -25.50995787358820266, 209.2762579043570099, 73.57326757446821830 ) ) ; -#38358 = CARTESIAN_POINT ( 'NONE', ( -25.50991579498579398, 209.7152486954105086, 73.57374465072240355 ) ) ; -#38359 = CARTESIAN_POINT ( 'NONE', ( 36.89736173421999865, 117.5051806407000043, 87.34911898881000525 ) ) ; -#38360 = CARTESIAN_POINT ( 'NONE', ( -38.38010894157000052, 119.1894012325000034, 90.45925847721001389 ) ) ; -#38361 = FACE_OUTER_BOUND ( 'NONE', #28124, .T. ) ; -#38362 = FACE_OUTER_BOUND ( 'NONE', #31250, .T. ) ; -#38363 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099121, 132.9726895863780385, 90.34121396988766151 ) ) ; -#38364 = EDGE_LOOP ( 'NONE', ( #35758, #38635, #15656, #12117 ) ) ; -#38365 = CARTESIAN_POINT ( 'NONE', ( 25.87290347845999960, 122.7597973085000120, 88.49195514234999393 ) ) ; -#38366 = CARTESIAN_POINT ( 'NONE', ( -41.44647100807553386, 120.2182348193094015, 89.99828044825905238 ) ) ; -#38367 = LINE ( 'NONE', #10374, #24075 ) ; -#38368 = CARTESIAN_POINT ( 'NONE', ( 19.99999382154498662, 120.3902235794415816, 87.43511282661482653 ) ) ; -#38369 = CARTESIAN_POINT ( 'NONE', ( 19.99902741543100859, 160.4248104870491716, 96.67782925827370377 ) ) ; -#38370 = VERTEX_POINT ( 'NONE', #15785 ) ; -#38371 = CARTESIAN_POINT ( 'NONE', ( -13.46215051151162889, 153.7291600434821532, 98.23113887026609348 ) ) ; -#38372 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#38373 = CARTESIAN_POINT ( 'NONE', ( -29.78271044658185218, 126.9386829446179377, 89.49016549083705740 ) ) ; -#38374 = CARTESIAN_POINT ( 'NONE', ( -2.695942817310999828, 199.6921533858000259, 89.50319044955999459 ) ) ; -#38375 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #6889, #13445, #19751, #25525 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.1766062648735380325, 0.3157706852075154447 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9983867564016681850, 0.9983867564016681850, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#38376 = CARTESIAN_POINT ( 'NONE', ( -25.35823072494000030, 191.6420941174999939, 104.5491859340999952 ) ) ; -#38377 = FACE_OUTER_BOUND ( 'NONE', #40387, .T. ) ; -#38378 = DIRECTION ( 'NONE', ( 0.7075337269147008445, 0.000000000000000000, 0.7066795775160008564 ) ) ; -#38379 = CARTESIAN_POINT ( 'NONE', ( -15.49970617362840919, 138.0805224087925751, 92.05383544148693886 ) ) ; -#38380 = EDGE_CURVE ( 'NONE', #27146, #7306, #457, .T. ) ; -#38381 = ORIENTED_EDGE ( 'NONE', *, *, #39628, .T. ) ; -#38382 = EDGE_CURVE ( 'NONE', #5749, #1845, #38140, .T. ) ; -#38383 = VECTOR ( 'NONE', #35512, 1000.000000000000000 ) ; -#38384 = ADVANCED_FACE ( 'NONE', ( #10076 ), #22553, .F. ) ; -#38385 = EDGE_CURVE ( 'NONE', #10328, #5648, #27705, .T. ) ; -#38386 = VECTOR ( 'NONE', #40003, 1000.000000000000114 ) ; -#38387 = DIRECTION ( 'NONE', ( 0.5634794340701355653, -0.8261300910752492621, 0.000000000000000000 ) ) ; -#38388 = CARTESIAN_POINT ( 'NONE', ( 19.99339512836239052, 197.5803468065060713, 93.82480951519328016 ) ) ; -#38389 = ORIENTED_EDGE ( 'NONE', *, *, #39117, .F. ) ; -#38390 = CARTESIAN_POINT ( 'NONE', ( 37.33254290421506028, 104.0199313033473345, 184.2130203058457880 ) ) ; -#38391 = DIRECTION ( 'NONE', ( 0.0006039748319391171662, 1.156185249762965862E-14, 0.9999998176071845934 ) ) ; -#38392 = EDGE_CURVE ( 'NONE', #34191, #19444, #6240, .T. ) ; -#38393 = CARTESIAN_POINT ( 'NONE', ( -2.938441474952925514, 191.9759150222000130, 101.9232220853079411 ) ) ; -#38394 = DIRECTION ( 'NONE', ( -0.0005884949961234662175, 0.2249510543439052490, -0.9743698870671265722 ) ) ; -#38395 = FACE_OUTER_BOUND ( 'NONE', #14990, .T. ) ; -#38396 = EDGE_LOOP ( 'NONE', ( #20333, #26511, #36849, #19939 ) ) ; -#38397 = CARTESIAN_POINT ( 'NONE', ( 21.10880003438571251, 175.5356891742621031, 102.9025923018732271 ) ) ; -#38398 = ORIENTED_EDGE ( 'NONE', *, *, #24062, .T. ) ; -#38399 = ORIENTED_EDGE ( 'NONE', *, *, #18065, .F. ) ; -#38401 = EDGE_CURVE ( 'NONE', #39205, #89, #20057, .T. ) ; -#38400 = CARTESIAN_POINT ( 'NONE', ( -5.669849310683051868, 181.2163897477299201, 104.3984882632009743 ) ) ; -#38402 = DIRECTION ( 'NONE', ( 0.0005884949961264505924, -0.2249510543439044719, 0.9743698870671267942 ) ) ; -#38403 = CARTESIAN_POINT ( 'NONE', ( 18.98509384253694421, 148.2879009998192714, 184.3674135999851273 ) ) ; -#38404 = CARTESIAN_POINT ( 'NONE', ( -16.28346717914184438, 122.9046764926519302, 174.0189578531147276 ) ) ; -#38405 = ORIENTED_EDGE ( 'NONE', *, *, #12266, .T. ) ; -#38406 = CARTESIAN_POINT ( 'NONE', ( -35.95405601968204223, 218.5902260770999987, 76.08021997845068540 ) ) ; -#38407 = ORIENTED_EDGE ( 'NONE', *, *, #9506, .T. ) ; -#38408 = DIRECTION ( 'NONE', ( 0.9999998176071847045, 7.515125404477462028E-16, -0.0006039748319388944710 ) ) ; -#38409 = ORIENTED_EDGE ( 'NONE', *, *, #1989, .T. ) ; -#38410 = LINE ( 'NONE', #3251, #35958 ) ; -#38411 = VECTOR ( 'NONE', #12614, 999.9999999999998863 ) ; -#38412 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971554023 ) ) ; -#38413 = FACE_OUTER_BOUND ( 'NONE', #31095, .T. ) ; -#38414 = LINE ( 'NONE', #25363, #30183 ) ; -#38415 = ORIENTED_EDGE ( 'NONE', *, *, #7920, .F. ) ; -#38416 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#38417 = CARTESIAN_POINT ( 'NONE', ( -30.07064833235158474, 177.3992996866407736, 100.9590083430528580 ) ) ; -#38418 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282898364, 148.0700263536679984, 93.85134194391106632 ) ) ; -#38419 = CARTESIAN_POINT ( 'NONE', ( -36.02886085861999987, 191.3486044203000347, 103.7195778210000014 ) ) ; -#38420 = ORIENTED_EDGE ( 'NONE', *, *, #8633, .F. ) ; -#38421 = LINE ( 'NONE', #20625, #6144 ) ; -#38422 = CARTESIAN_POINT ( 'NONE', ( 8.048542121204103950, 160.5989240000510279, 99.80415721606205182 ) ) ; -#38423 = EDGE_CURVE ( 'NONE', #7887, #37534, #30093, .T. ) ; -#38424 = EDGE_CURVE ( 'NONE', #19923, #11505, #4698, .T. ) ; -#38425 = FACE_OUTER_BOUND ( 'NONE', #19196, .T. ) ; -#38426 = CARTESIAN_POINT ( 'NONE', ( 20.33489173372807457, 119.7903715517339407, 90.03324753095370170 ) ) ; -#38427 = AXIS2_PLACEMENT_3D ( 'NONE', #30931, #19031, #30731 ) ; -#38428 = CARTESIAN_POINT ( 'NONE', ( -2.831545756241999889, 208.8168945399000052, 73.26525557386000287 ) ) ; -#38429 = CARTESIAN_POINT ( 'NONE', ( -37.92530404122999954, 190.2020722073000059, 106.8053324585000041 ) ) ; -#38430 = VERTEX_POINT ( 'NONE', #1873 ) ; -#38431 = VECTOR ( 'NONE', #6732, 1000.000000000000000 ) ; -#38432 = CARTESIAN_POINT ( 'NONE', ( 47.97461142298704573, 82.27946979429644614, 322.5295741262542606 ) ) ; -#38433 = VECTOR ( 'NONE', #9947, 1000.000000000000000 ) ; -#38434 = AXIS2_PLACEMENT_3D ( 'NONE', #6540, #18599, #209 ) ; -#38435 = CARTESIAN_POINT ( 'NONE', ( -15.99999411491280199, 138.1989450468032601, 91.56832761027415302 ) ) ; -#38436 = ORIENTED_EDGE ( 'NONE', *, *, #6897, .F. ) ; -#38437 = ORIENTED_EDGE ( 'NONE', *, *, #7401, .F. ) ; -#38438 = ORIENTED_EDGE ( 'NONE', *, *, #3518, .T. ) ; -#38439 = CARTESIAN_POINT ( 'NONE', ( -13.50514475104697532, 124.4029596900451082, 88.43414899398538864 ) ) ; -#38440 = FACE_OUTER_BOUND ( 'NONE', #2493, .T. ) ; -#38441 = CARTESIAN_POINT ( 'NONE', ( 5.666570111846160884, 124.1682743494144177, 90.98768579075735374 ) ) ; -#38442 = ORIENTED_EDGE ( 'NONE', *, *, #14071, .T. ) ; -#38443 = VERTEX_POINT ( 'NONE', #14557 ) ; -#38444 = LINE ( 'NONE', #39051, #15299 ) ; -#38445 = EDGE_CURVE ( 'NONE', #20110, #33611, #16938, .T. ) ; -#38446 = CARTESIAN_POINT ( 'NONE', ( -38.39983396593000720, 119.0472737981999956, 90.29717073674000005 ) ) ; -#38447 = CARTESIAN_POINT ( 'NONE', ( -38.24620936299999840, 118.9481072208999990, 87.58021371626999496 ) ) ; -#38448 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825887818095019, 0.0005734119031303735623 ) ) ; -#38449 = EDGE_LOOP ( 'NONE', ( #39998, #21093, #19492, #25574, #23929, #28875, #30870, #33279, #1747, #10885 ) ) ; -#38450 = LINE ( 'NONE', #23338, #23848 ) ; -#38451 = ORIENTED_EDGE ( 'NONE', *, *, #26552, .F. ) ; -#38452 = CARTESIAN_POINT ( 'NONE', ( -3.535986895436823207, 167.8052092920482039, 101.4748507491612912 ) ) ; -#38453 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#38454 = CARTESIAN_POINT ( 'NONE', ( -37.83658322688275888, 190.9636381155321203, 106.3289620680116343 ) ) ; -#38455 = CARTESIAN_POINT ( 'NONE', ( -3.535851989103623971, 143.5328828484186943, 95.87118806634899215 ) ) ; -#38456 = ORIENTED_EDGE ( 'NONE', *, *, #5141, .T. ) ; -#38457 = VERTEX_POINT ( 'NONE', #38868 ) ; -#38458 = CIRCLE ( 'NONE', #19514, 22.50000000000000000 ) ; -#38459 = CARTESIAN_POINT ( 'NONE', ( -0.4375701469493999962, 188.7416664959999935, 103.3602241911000021 ) ) ; -#38460 = CARTESIAN_POINT ( 'NONE', ( 25.49182901039327831, 209.7089661076149127, 75.54314178666862745 ) ) ; -#38461 = CARTESIAN_POINT ( 'NONE', ( 18.98506067126258046, 148.2070439170772431, 184.7168109706149721 ) ) ; -#38462 = CIRCLE ( 'NONE', #28674, 4.999999999999990230 ) ; -#38463 = AXIS2_PLACEMENT_3D ( 'NONE', #26241, #1894, #8231 ) ; -#38464 = ORIENTED_EDGE ( 'NONE', *, *, #8406, .T. ) ; -#38465 = CARTESIAN_POINT ( 'NONE', ( 44.24772793393911030, 122.2367175089034959, 90.92567871579780103 ) ) ; -#38466 = CARTESIAN_POINT ( 'NONE', ( -26.01326056281665089, 211.0902258159713085, 76.07393268928584007 ) ) ; -#38467 = ORIENTED_EDGE ( 'NONE', *, *, #9636, .T. ) ; -#38468 = AXIS2_PLACEMENT_3D ( 'NONE', #33395, #5391, #17842 ) ; -#38469 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624402326, -0.1792657018023851301 ) ) ; -#38470 = EDGE_LOOP ( 'NONE', ( #6411, #38261, #38389, #3789 ) ) ; -#38471 = EDGE_CURVE ( 'NONE', #39651, #14192, #16792, .T. ) ; -#38472 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13819, #5631, #14435, #39353 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#38473 = EDGE_CURVE ( 'NONE', #33399, #15062, #23109, .T. ) ; -#38474 = CARTESIAN_POINT ( 'NONE', ( 13.55543936468217581, 147.3999835650271848, 96.75361558816608465 ) ) ; -#38475 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#38476 = CARTESIAN_POINT ( 'NONE', ( 22.50170152449286221, 153.4847644705970424, 97.81088946422735830 ) ) ; -#38477 = ORIENTED_EDGE ( 'NONE', *, *, #27288, .F. ) ; -#38478 = ORIENTED_EDGE ( 'NONE', *, *, #27414, .F. ) ; -#38479 = CARTESIAN_POINT ( 'NONE', ( 25.50057794482474449, 120.1935418996727805, 89.93170405457649963 ) ) ; -#38480 = DIRECTION ( 'NONE', ( 0.7933533411653058698, -0.5930537057989958560, -0.1373964268091568131 ) ) ; -#38482 = CARTESIAN_POINT ( 'NONE', ( 3.061557431404703156, 191.9759150222000130, 101.9195982364082056 ) ) ; -#38481 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.5299191569047542183, -0.8480481632226759547 ) ) ; -#38483 = AXIS2_PLACEMENT_3D ( 'NONE', #36303, #11359, #17068 ) ; -#38484 = CARTESIAN_POINT ( 'NONE', ( 0.0004786142366335115412, 137.4659008082779792, 177.5714312369215975 ) ) ; -#38485 = ORIENTED_EDGE ( 'NONE', *, *, #2515, .F. ) ; -#38486 = CARTESIAN_POINT ( 'NONE', ( -3.669581222364402873, 126.6894591277509221, 89.41685568663245931 ) ) ; -#38487 = AXIS2_PLACEMENT_3D ( 'NONE', #14319, #14522, #26797 ) ; -#38488 = AXIS2_PLACEMENT_3D ( 'NONE', #36122, #30003, #5663 ) ; -#38489 = DIRECTION ( 'NONE', ( -0.7933535320750506603, 0.5931614265261859753, 0.1369295264925043665 ) ) ; -#38490 = ORIENTED_EDGE ( 'NONE', *, *, #13981, .T. ) ; -#38491 = VECTOR ( 'NONE', #34448, 1000.000000000000000 ) ; -#38492 = ORIENTED_EDGE ( 'NONE', *, *, #30138, .F. ) ; -#38493 = DIRECTION ( 'NONE', ( 0.7066795775160008564, 0.000000000000000000, -0.7075337269147008445 ) ) ; -#38494 = DIRECTION ( 'NONE', ( -0.0005884949961253164085, 0.2249510543439028898, -0.9743698870671272383 ) ) ; -#38495 = CARTESIAN_POINT ( 'NONE', ( -3.070531973001000114, 190.8181423560999974, 106.9269511051000023 ) ) ; -#38496 = ORIENTED_EDGE ( 'NONE', *, *, #18518, .T. ) ; -#38497 = ORIENTED_EDGE ( 'NONE', *, *, #31456, .T. ) ; -#38498 = LINE ( 'NONE', #13576, #28504 ) ; -#38499 = DIRECTION ( 'NONE', ( -0.7933531821952553020, 0.5930539076840665169, 0.1373964733219922574 ) ) ; -#38500 = FACE_OUTER_BOUND ( 'NONE', #12181, .T. ) ; -#38501 = VERTEX_POINT ( 'NONE', #35782 ) ; -#38502 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #6059, #12207, #2983, #37142 ), - ( #18507, #125, #37731, #9338 ), - ( #21618, #9137, #31012, #13009 ), - ( #15469, #40395, #318, #9744 ), - ( #21813, #34251, #18915, #6643 ), - ( #22220, #6252, #31412, #10946 ), - ( #3976, #20113, #26480, #25893 ), - ( #4581, #7248, #10737, #32217 ), - ( #38527, #38932, #7052, #1119 ), - ( #26088, #32802, #23206, #4173 ), - ( #10545, #10348, #38718, #13600 ), - ( #29347, #1316, #38337, #28742 ), - ( #32602, #25696, #16649, #17042 ), - ( #32016, #19521, #22817, #13405 ), - ( #13209, #23408, #13799, #20323 ), - ( #35435, #4782, #16452, #23011 ), - ( #26284, #35848, #7855, #14003 ), - ( #7447, #35640, #10146, #19908 ), - ( #29543, #22619, #32414, #721 ), - ( #35245, #4382, #38146, #16842 ), - ( #35043, #28940, #919, #7655 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.0007490278349774999933, 0.000000000000000000, 3.474638108047999990E-05, 0.001983274684462999881, 0.003936385303643000211, 0.007842606542005000139, 0.01565504901873999988, 0.03127993397217999905, 0.06252970387907000327, 0.09377947378598000538, 0.1250292436927999962, 0.1875287835065999886, 0.2500283233205000122, 0.3750236086952000170, 0.5000188940699999973, 0.6250141794446000265, 0.7500094648192999758, 1.000000000000000000, 1.014439647481000017 ), - ( -0.0001383384667056999950, 1.000650266732000082 ), - .UNSPECIFIED. ) ; -#38503 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927856766183, 0.0005734119022057102217 ) ) ; -#38504 = ORIENTED_EDGE ( 'NONE', *, *, #5013, .F. ) ; -#38505 = EDGE_CURVE ( 'NONE', #9915, #14771, #39472, .T. ) ; -#38506 = DIRECTION ( 'NONE', ( 0.0006039748319385906776, 1.274821093756980153E-14, 0.9999998176071844824 ) ) ; -#38507 = EDGE_LOOP ( 'NONE', ( #6861, #8942, #6524, #11965 ) ) ; -#38508 = CARTESIAN_POINT ( 'NONE', ( -17.99911725751000091, 134.8228298562323744, 92.32955159241861054 ) ) ; -#38509 = CONICAL_SURFACE ( 'NONE', #2652, 3.002820406140098264, 0.7853589219061751781 ) ; -#38510 = EDGE_CURVE ( 'NONE', #36415, #32868, #4271, .T. ) ; -#38511 = VECTOR ( 'NONE', #7263, 1000.000000000000000 ) ; -#38512 = CARTESIAN_POINT ( 'NONE', ( -0.5631384182448999631, 189.1604183121999938, 105.6044017097000136 ) ) ; -#38513 = CARTESIAN_POINT ( 'NONE', ( 37.32819269845482069, 107.3988016090549422, 169.6034496416073409 ) ) ; -#38514 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -1.676366911794336136E-18, -0.0006039748319371601813 ) ) ; -#38515 = ORIENTED_EDGE ( 'NONE', *, *, #14548, .T. ) ; -#38516 = CONICAL_SURFACE ( 'NONE', #18934, 6.500000000082327034, 0.7853981634697572156 ) ; -#38518 = EDGE_CURVE ( 'NONE', #11248, #20347, #27039, .T. ) ; -#38517 = LINE ( 'NONE', #26474, #32332 ) ; -#38519 = EDGE_CURVE ( 'NONE', #1188, #25578, #35993, .T. ) ; -#38520 = DIRECTION ( 'NONE', ( -0.9999998268368619492, -0.0001323825708487058237, 0.0005734118074949707536 ) ) ; -#38521 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#38522 = EDGE_CURVE ( 'NONE', #29530, #21600, #19847, .T. ) ; -#38523 = ADVANCED_FACE ( 'NONE', ( #5121 ), #33138, .T. ) ; -#38524 = DIRECTION ( 'NONE', ( 0.6087604435314231122, 0.7731012422272365292, 0.1781156693222946674 ) ) ; -#38525 = ORIENTED_EDGE ( 'NONE', *, *, #14530, .T. ) ; -#38526 = LINE ( 'NONE', #13404, #38433 ) ; -#38527 = CARTESIAN_POINT ( 'NONE', ( -37.84200445841999993, 118.7313177170999978, 90.44745268466000709 ) ) ; -#38528 = ORIENTED_EDGE ( 'NONE', *, *, #39725, .T. ) ; -#38529 = DIRECTION ( 'NONE', ( 0.0005884949961247222657, -0.2249510543439059984, 0.9743698870671263501 ) ) ; -#38530 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #6661, #2811, #15289, #6463, #2621, #12822, #15671, #3396, #142, #28364 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#38531 = VERTEX_POINT ( 'NONE', #17388 ) ; -#38532 = CARTESIAN_POINT ( 'NONE', ( 37.31639193983529879, 111.9096183688354245, 150.0649592369359766 ) ) ; -#38533 = LINE ( 'NONE', #10355, #39834 ) ; -#38534 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13731, #38656, #20256, #10676 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#38535 = CARTESIAN_POINT ( 'NONE', ( -40.55516615315095663, 184.2569486434040869, 105.2953989892096445 ) ) ; -#38536 = VERTEX_POINT ( 'NONE', #36210 ) ; -#38537 = ORIENTED_EDGE ( 'NONE', *, *, #14646, .T. ) ; -#38538 = CARTESIAN_POINT ( 'NONE', ( 25.66728632891432582, 120.1770448847769757, 90.11928726968523051 ) ) ; -#38539 = ORIENTED_EDGE ( 'NONE', *, *, #40094, .F. ) ; -#38540 = VERTEX_POINT ( 'NONE', #23965 ) ; -#38541 = EDGE_LOOP ( 'NONE', ( #26429, #14495, #8935, #18286 ) ) ; -#38542 = CARTESIAN_POINT ( 'NONE', ( 22.11658946403013815, 136.0358612623089982, 91.55906883338052182 ) ) ; -#38543 = CARTESIAN_POINT ( 'NONE', ( -15.10537794304822512, 128.9348610681433911, 92.50791545010099526 ) ) ; -#38544 = VECTOR ( 'NONE', #14890, 1000.000000000000000 ) ; -#38545 = CARTESIAN_POINT ( 'NONE', ( -20.49852807266789867, 190.9630690214611946, 106.3183227610936541 ) ) ; -#38546 = VECTOR ( 'NONE', #39143, 1000.000000000000227 ) ; -#38547 = ORIENTED_EDGE ( 'NONE', *, *, #1065, .T. ) ; -#38548 = CARTESIAN_POINT ( 'NONE', ( -48.18873482981263123, 89.47423874572474745, 291.5876487235610171 ) ) ; -#38549 = AXIS2_PLACEMENT_3D ( 'NONE', #25327, #37984, #13251 ) ; -#38550 = LINE ( 'NONE', #32432, #21542 ) ; -#38551 = CARTESIAN_POINT ( 'NONE', ( 36.06619636834999909, 191.4156479609000314, 103.6926474936999938 ) ) ; -#38552 = DIRECTION ( 'NONE', ( -0.7933533175743878729, 0.5931616988744193852, 0.1369295895054284395 ) ) ; -#38553 = ORIENTED_EDGE ( 'NONE', *, *, #16578, .F. ) ; -#38554 = FACE_OUTER_BOUND ( 'NONE', #15064, .T. ) ; -#38555 = ORIENTED_EDGE ( 'NONE', *, *, #15527, .F. ) ; -#38556 = EDGE_CURVE ( 'NONE', #39608, #23183, #2340, .T. ) ; -#38557 = DIRECTION ( 'NONE', ( 0.7933531821952553020, -0.5930539076840665169, -0.1373964733219922574 ) ) ; -#38558 = CARTESIAN_POINT ( 'NONE', ( 39.60379206711759537, 77.57075965540369111, 291.0398443752740718 ) ) ; -#38559 = CARTESIAN_POINT ( 'NONE', ( 3.655476994516294376, 175.3312194581858421, 100.2535053625421142 ) ) ; -#38560 = CARTESIAN_POINT ( 'NONE', ( 45.11849344886014990, 186.2994542042779074, 106.5243038294286180 ) ) ; -#38561 = EDGE_LOOP ( 'NONE', ( #35676, #37708, #208, #13112 ) ) ; -#38562 = CARTESIAN_POINT ( 'NONE', ( 21.05331647436627307, 136.0919339282447709, 93.96736470811812580 ) ) ; -#38563 = EDGE_CURVE ( 'NONE', #14638, #6589, #26383, .T. ) ; -#38564 = CARTESIAN_POINT ( 'NONE', ( 0.9394191060261165571, 189.0348601105310138, 103.6946623460256944 ) ) ; -#38565 = CARTESIAN_POINT ( 'NONE', ( 40.02829803166415701, 120.8820227754755905, 90.61547142951589251 ) ) ; -#38566 = ADVANCED_FACE ( 'NONE', ( #38662 ), #10682, .T. ) ; -#38567 = CARTESIAN_POINT ( 'NONE', ( 12.63719627440727677, 130.1455350695279662, 92.49286791247519091 ) ) ; -#38568 = CARTESIAN_POINT ( 'NONE', ( -26.13641317868000158, 191.6419861777999927, 103.7719022052999946 ) ) ; -#38569 = FACE_OUTER_BOUND ( 'NONE', #641, .T. ) ; -#38570 = DIRECTION ( 'NONE', ( 0.0005884949961247609718, -0.2249510543439061094, 0.9743698870671263501 ) ) ; -#38571 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#38572 = EDGE_CURVE ( 'NONE', #25314, #1172, #27249, .T. ) ; -#38573 = VECTOR ( 'NONE', #40176, 1000.000000000000000 ) ; -#38574 = AXIS2_PLACEMENT_3D ( 'NONE', #26061, #38118, #38313 ) ; -#38575 = CARTESIAN_POINT ( 'NONE', ( -15.99798258269242623, 173.8482551488953050, 102.8774467584792802 ) ) ; -#38576 = ORIENTED_EDGE ( 'NONE', *, *, #36064, .T. ) ; -#38577 = AXIS2_PLACEMENT_3D ( 'NONE', #37009, #9006, #27825 ) ; -#38578 = DIRECTION ( 'NONE', ( -0.0005884949961222141809, 0.2249510543439070531, -0.9743698870671262391 ) ) ; -#38579 = CARTESIAN_POINT ( 'NONE', ( -19.99931527105535878, 118.1256151686936420, 90.27945241601419468 ) ) ; -#38580 = ORIENTED_EDGE ( 'NONE', *, *, #7029, .T. ) ; -#38581 = DIRECTION ( 'NONE', ( -0.9999998268368046617, -0.0001323825927736883238, 0.0005734119022084779730 ) ) ; -#38582 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, 1.271205363195980786E-14, 0.9999998176071847045 ) ) ; -#38583 = CARTESIAN_POINT ( 'NONE', ( 37.38080420394999948, 190.2420884969000383, 106.7700743806000077 ) ) ; -#38584 = CARTESIAN_POINT ( 'NONE', ( 36.08394658407680566, 192.1911192938459862, 104.3432420703000076 ) ) ; -#38585 = CARTESIAN_POINT ( 'NONE', ( -1.762796035792233207, 151.6652447683722471, 130.5904578368917441 ) ) ; -#38586 = CARTESIAN_POINT ( 'NONE', ( -21.21399076556896546, 136.5867924462192207, 91.71243192711530412 ) ) ; -#38587 = ORIENTED_EDGE ( 'NONE', *, *, #9878, .F. ) ; -#38588 = CARTESIAN_POINT ( 'NONE', ( -45.35096104214093060, 123.9731305825091709, 91.38067696071810531 ) ) ; -#38589 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11473, #18782, #37422, #15543 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#38590 = CARTESIAN_POINT ( 'NONE', ( 20.50107847364380831, 184.5549759110466255, 104.1299709246699052 ) ) ; -#38591 = CARTESIAN_POINT ( 'NONE', ( 24.33241291692780806, 117.2920445016514748, 170.8609620625155117 ) ) ; -#38592 = CYLINDRICAL_SURFACE ( 'NONE', #22015, 2.000000000000014655 ) ; -#38593 = ORIENTED_EDGE ( 'NONE', *, *, #37291, .F. ) ; -#38594 = PLANE ( 'NONE', #4936 ) ; -#38595 = ORIENTED_EDGE ( 'NONE', *, *, #7545, .F. ) ; -#38596 = AXIS2_PLACEMENT_3D ( 'NONE', #3764, #10333, #18894 ) ; -#38597 = AXIS2_PLACEMENT_3D ( 'NONE', #9294, #28695, #80 ) ; -#38598 = CARTESIAN_POINT ( 'NONE', ( -34.28801115370752228, 89.15625349133107136, 280.9732277762227000 ) ) ; -#38599 = ORIENTED_EDGE ( 'NONE', *, *, #16135, .T. ) ; -#38600 = DIRECTION ( 'NONE', ( -0.0005884949961258157921, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#38601 = ADVANCED_FACE ( 'NONE', ( #15551 ), #2223, .F. ) ; -#38602 = ADVANCED_FACE ( 'NONE', ( #3070 ), #33341, .F. ) ; -#38604 = EDGE_CURVE ( 'NONE', #33023, #25308, #22340, .T. ) ; -#38603 = CARTESIAN_POINT ( 'NONE', ( 25.66578042932543013, 118.1143697066197262, 87.58559124276200691 ) ) ; -#38605 = CARTESIAN_POINT ( 'NONE', ( -23.36033136076990502, 129.9689112135512232, 92.23847830418463900 ) ) ; -#38606 = ADVANCED_FACE ( 'NONE', ( #14764 ), #24579, .F. ) ; -#38607 = FACE_OUTER_BOUND ( 'NONE', #1807, .T. ) ; -#38608 = ORIENTED_EDGE ( 'NONE', *, *, #18612, .F. ) ; -#38609 = FACE_OUTER_BOUND ( 'NONE', #38147, .T. ) ; -#38610 = CARTESIAN_POINT ( 'NONE', ( -4.973729523541181585, 177.5597541351575046, 100.6488263443078068 ) ) ; -#38611 = DIRECTION ( 'NONE', ( -0.6974473308752756617, 0.000000000000000000, 0.7166360447639747999 ) ) ; -#38612 = EDGE_CURVE ( 'NONE', #24320, #14055, #5539, .T. ) ; -#38613 = CARTESIAN_POINT ( 'NONE', ( -6.272775202316941190, 163.3805630214683333, 99.94184687166684000 ) ) ; -#38614 = ORIENTED_EDGE ( 'NONE', *, *, #35817, .T. ) ; -#38615 = VERTEX_POINT ( 'NONE', #39883 ) ; -#38616 = FACE_OUTER_BOUND ( 'NONE', #20393, .T. ) ; -#38617 = EDGE_CURVE ( 'NONE', #16126, #22698, #21155, .T. ) ; -#38618 = CARTESIAN_POINT ( 'NONE', ( -20.00135284697726590, 137.8251893417238136, 91.48445388004111578 ) ) ; -#38619 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971552357 ) ) ; -#38620 = CIRCLE ( 'NONE', #1417, 1.999999999792658079 ) ; -#38621 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13411, #10550, #924, #32419 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#38622 = CARTESIAN_POINT ( 'NONE', ( -28.26067782467530520, 125.1269179218217857, 91.12357580992288320 ) ) ; -#38623 = AXIS2_PLACEMENT_3D ( 'NONE', #20622, #10833, #33087 ) ; -#38624 = CARTESIAN_POINT ( 'NONE', ( 28.46433317244940753, 130.4256741595737310, 90.26002097211915043 ) ) ; -#38625 = EDGE_CURVE ( 'NONE', #6048, #25223, #20797, .T. ) ; -#38626 = CIRCLE ( 'NONE', #117, 22.50000000000899902 ) ; -#38627 = CARTESIAN_POINT ( 'NONE', ( 82.74177079105341193, 105.0784892597221614, 24.20931121009731157 ) ) ; -#38628 = CARTESIAN_POINT ( 'NONE', ( 38.73759991229999855, 118.4494500935000048, 89.51229521514001419 ) ) ; -#38629 = EDGE_LOOP ( 'NONE', ( #25629, #9730, #19160, #20924 ) ) ; -#38630 = PLANE ( 'NONE', #14001 ) ; -#38631 = PLANE ( 'NONE', #608 ) ; -#38632 = DIRECTION ( 'NONE', ( 0.0006039748319395907457, 1.291365685536980287E-14, 0.9999998176071847045 ) ) ; -#38633 = DIRECTION ( 'NONE', ( 0.0005884949961246861618, -0.2249510543439068866, 0.9743698870671261281 ) ) ; -#38634 = ORIENTED_EDGE ( 'NONE', *, *, #1555, .T. ) ; -#38635 = ORIENTED_EDGE ( 'NONE', *, *, #5376, .T. ) ; -#38636 = VERTEX_POINT ( 'NONE', #11895 ) ; -#38637 = CARTESIAN_POINT ( 'NONE', ( 36.05442839919999898, 109.6131156806000035, 88.74600859430999833 ) ) ; -#38638 = LINE ( 'NONE', #35156, #12199 ) ; -#38639 = EDGE_LOOP ( 'NONE', ( #15552, #20049, #27076, #28399 ) ) ; -#38640 = FACE_BOUND ( 'NONE', #33285, .T. ) ; -#38641 = CARTESIAN_POINT ( 'NONE', ( -38.50870567158000313, 118.9338527051999961, 90.10241371018000223 ) ) ; -#38642 = CARTESIAN_POINT ( 'NONE', ( -38.88297749613000320, 119.5273426671000152, 87.63529162099999326 ) ) ; -#38643 = CARTESIAN_POINT ( 'NONE', ( 20.49908935505346719, 194.2769733015968541, 102.8866291927022303 ) ) ; -#38644 = CARTESIAN_POINT ( 'NONE', ( 16.57143971460371645, 121.7462941270641608, 177.4474421254334970 ) ) ; -#38645 = VERTEX_POINT ( 'NONE', #24379 ) ; -#38646 = CARTESIAN_POINT ( 'NONE', ( -19.46376836227414486, 126.0579724767783318, 176.8041766879045440 ) ) ; -#38647 = EDGE_CURVE ( 'NONE', #8964, #34749, #294, .T. ) ; -#38648 = CARTESIAN_POINT ( 'NONE', ( -24.25908385616899920, 115.9286338645677432, 89.78240454819975014 ) ) ; -#38649 = AXIS2_PLACEMENT_3D ( 'NONE', #26366, #29834, #19996 ) ; -#38650 = EDGE_CURVE ( 'NONE', #17689, #39586, #30286, .T. ) ; -#38651 = DIRECTION ( 'NONE', ( -0.0005884949961255136249, 0.2249510543439060539, -0.9743698870671263501 ) ) ; -#38652 = FACE_OUTER_BOUND ( 'NONE', #17943, .T. ) ; -#38653 = ORIENTED_EDGE ( 'NONE', *, *, #17414, .T. ) ; -#38654 = VECTOR ( 'NONE', #18627, 1000.000000000000227 ) ; -#38655 = EDGE_LOOP ( 'NONE', ( #34731, #35403, #163, #19472 ) ) ; -#38656 = CARTESIAN_POINT ( 'NONE', ( -20.16763707502682479, 193.9703149646331326, 102.7801441390361958 ) ) ; -#38657 = VECTOR ( 'NONE', #18509, 1000.000000000000114 ) ; -#38658 = LINE ( 'NONE', #29682, #32931 ) ; -#38659 = CARTESIAN_POINT ( 'NONE', ( -116.6809178989064293, 205.2853165843886245, 191.1682151682985307 ) ) ; -#38660 = EDGE_CURVE ( 'NONE', #27307, #16595, #24228, .T. ) ; -#38661 = VERTEX_POINT ( 'NONE', #9026 ) ; -#38662 = FACE_OUTER_BOUND ( 'NONE', #35838, .T. ) ; -#38663 = CARTESIAN_POINT ( 'NONE', ( -23.41147556997512780, 214.0900415524863263, 76.07246192447139777 ) ) ; -#38664 = ORIENTED_EDGE ( 'NONE', *, *, #15556, .F. ) ; -#38665 = EDGE_CURVE ( 'NONE', #32373, #34215, #34870, .T. ) ; -#38666 = ORIENTED_EDGE ( 'NONE', *, *, #442, .F. ) ; -#38667 = ORIENTED_EDGE ( 'NONE', *, *, #28430, .T. ) ; -#38668 = CARTESIAN_POINT ( 'NONE', ( -26.38221732644195328, 189.9151541007786648, 103.5142258954548993 ) ) ; -#38669 = DIRECTION ( 'NONE', ( -0.9914447795421099663, 0.1270909273343945323, 0.02975139169821508847 ) ) ; -#38670 = CARTESIAN_POINT ( 'NONE', ( 24.86314881519125919, 182.1858644890795063, 102.2119796893761503 ) ) ; -#38671 = CARTESIAN_POINT ( 'NONE', ( -20.00004361580415591, 118.8155695144462669, 87.27991261026372172 ) ) ; -#38672 = EDGE_CURVE ( 'NONE', #20371, #30524, #30904, .T. ) ; -#38673 = EDGE_LOOP ( 'NONE', ( #35973, #6788 ) ) ; -#38674 = AXIS2_PLACEMENT_3D ( 'NONE', #30925, #40307, #36444 ) ; -#38675 = ORIENTED_EDGE ( 'NONE', *, *, #9840, .F. ) ; -#38676 = CARTESIAN_POINT ( 'NONE', ( 26.01213538887559906, 120.4375336583399871, 90.52293421452910138 ) ) ; -#38677 = CARTESIAN_POINT ( 'NONE', ( -26.00133086711789687, 118.1131156701862892, 87.28349311522542564 ) ) ; -#38678 = AXIS2_PLACEMENT_3D ( 'NONE', #4209, #15882, #13039 ) ; -#38680 = CARTESIAN_POINT ( 'NONE', ( -13.49836365434320484, 188.0284789784863619, 103.3392430051065531 ) ) ; -#38679 = CARTESIAN_POINT ( 'NONE', ( 20.48253891412411321, 207.4083879957671002, 77.06951181954761410 ) ) ; -#38681 = ORIENTED_EDGE ( 'NONE', *, *, #6909, .T. ) ; -#38682 = ORIENTED_EDGE ( 'NONE', *, *, #20945, .F. ) ; -#38683 = CARTESIAN_POINT ( 'NONE', ( -36.09391041316947479, 191.9872661771537139, 104.4222228648927739 ) ) ; -#38684 = PLANE ( 'NONE', #13613 ) ; -#38685 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13400, #16839, #38332, #10342 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.0005627318540861992423 ), - .UNSPECIFIED. ) ; -#38686 = VERTEX_POINT ( 'NONE', #12291 ) ; -#38687 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#38688 = CARTESIAN_POINT ( 'NONE', ( 15.50147165555466522, 173.9550007109359342, 102.3699975152791239 ) ) ; -#38689 = CARTESIAN_POINT ( 'NONE', ( -20.51870197069307977, 210.1700258258141503, 75.57088353280735760 ) ) ; -#38690 = CARTESIAN_POINT ( 'NONE', ( -45.44849478851434554, 124.1418171532125712, 91.75068805776987801 ) ) ; -#38691 = DIRECTION ( 'NONE', ( 0.9999998268368046617, 0.0001323825927757477116, -0.0005734119022080025503 ) ) ; -#38692 = VERTEX_POINT ( 'NONE', #24778 ) ; -#38693 = VERTEX_POINT ( 'NONE', #9230 ) ; -#38694 = ORIENTED_EDGE ( 'NONE', *, *, #27708, .T. ) ; -#38695 = FACE_OUTER_BOUND ( 'NONE', #18605, .T. ) ; -#38696 = ADVANCED_FACE ( 'NONE', ( #12898 ), #22100, .F. ) ; -#38697 = ORIENTED_EDGE ( 'NONE', *, *, #34371, .T. ) ; -#38698 = ORIENTED_EDGE ( 'NONE', *, *, #20290, .F. ) ; -#38699 = CARTESIAN_POINT ( 'NONE', ( -35.76980907163999746, 192.7327729514000225, 106.5479348372000032 ) ) ; -#38700 = CIRCLE ( 'NONE', #13276, 59.40509898896999630 ) ; -#38701 = CARTESIAN_POINT ( 'NONE', ( -38.24380932803833844, 118.2428607222824297, 89.71149949636749454 ) ) ; -#38702 = VECTOR ( 'NONE', #27724, 1000.000000000000114 ) ; -#38703 = CARTESIAN_POINT ( 'NONE', ( 3.069914059221602542, 190.8760762271834039, 106.8043974371660738 ) ) ; -#38704 = ORIENTED_EDGE ( 'NONE', *, *, #6875, .F. ) ; -#38705 = CARTESIAN_POINT ( 'NONE', ( -30.07340899595924100, 135.1666636124964498, 91.22132312044659841 ) ) ; -#38706 = CARTESIAN_POINT ( 'NONE', ( 29.20104124104027576, 148.3999055379004517, 96.97501579703776997 ) ) ; -#38707 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.5299191569046374228, 0.8480481632227490074 ) ) ; -#38708 = DIRECTION ( 'NONE', ( 0.0006039748319361434165, 0.000000000000000000, 0.9999998176071844824 ) ) ; -#38709 = EDGE_LOOP ( 'NONE', ( #12580, #28065, #23400, #12988 ) ) ; -#38710 = EDGE_LOOP ( 'NONE', ( #5388, #10891, #27644, #19130 ) ) ; -#38711 = DIRECTION ( 'NONE', ( 0.0005884949961216828134, -0.2249510543439096344, 0.9743698870671254619 ) ) ; -#38712 = CARTESIAN_POINT ( 'NONE', ( -22.98725314475650450, 177.7874483475983709, 100.7122734217378053 ) ) ; -#38713 = CARTESIAN_POINT ( 'NONE', ( 26.00894374567046441, 191.9425530329557716, 103.9054621679136261 ) ) ; -#38714 = ADVANCED_FACE ( 'NONE', ( #7139 ), #10026, .F. ) ; -#38715 = CARTESIAN_POINT ( 'NONE', ( -42.47220679908992480, 189.9442792002049316, 106.2657712603332385 ) ) ; -#38716 = ORIENTED_EDGE ( 'NONE', *, *, #35093, .F. ) ; -#38717 = CARTESIAN_POINT ( 'NONE', ( 32.50483906253111144, 78.62122269805516339, 290.8219053273109012 ) ) ; -#38718 = CARTESIAN_POINT ( 'NONE', ( -37.94605339308999703, 118.0983039059999982, 89.85439327327999592 ) ) ; -#38719 = VERTEX_POINT ( 'NONE', #13294 ) ; -#38720 = CARTESIAN_POINT ( 'NONE', ( -20.16498553255008730, 118.8155446846155030, 90.11323255110787045 ) ) ; -#38721 = VECTOR ( 'NONE', #28199, 1000.000000000000227 ) ; -#38722 = CARTESIAN_POINT ( 'NONE', ( 38.57273346403590608, 118.4650864938980277, 89.66263907190824511 ) ) ; -#38723 = ORIENTED_EDGE ( 'NONE', *, *, #18967, .F. ) ; -#38724 = CARTESIAN_POINT ( 'NONE', ( 46.08267618988084280, 184.7865884867546242, 107.4179575081553253 ) ) ; -#38725 = ADVANCED_FACE ( 'NONE', ( #28829 ), #3665, .F. ) ; -#38726 = FACE_OUTER_BOUND ( 'NONE', #29561, .T. ) ; -#38727 = CARTESIAN_POINT ( 'NONE', ( -17.99852876251395983, 176.9829762288560744, 103.0892940378084432 ) ) ; -#38729 = ORIENTED_EDGE ( 'NONE', *, *, #18862, .T. ) ; -#38728 = AXIS2_PLACEMENT_3D ( 'NONE', #4751, #30116, #13763 ) ; -#38730 = ORIENTED_EDGE ( 'NONE', *, *, #2538, .F. ) ; -#38731 = CARTESIAN_POINT ( 'NONE', ( -42.58663445218865462, 120.8392962345444062, 90.80939073592341515 ) ) ; -#38732 = VERTEX_POINT ( 'NONE', #24976 ) ; -#38733 = EDGE_LOOP ( 'NONE', ( #16072, #14169, #31126, #36795 ) ) ; -#38734 = CARTESIAN_POINT ( 'NONE', ( 46.08149919947196338, 185.2364907546973711, 105.4692170442124279 ) ) ; -#38735 = ADVANCED_FACE ( 'NONE', ( #13096 ), #16150, .T. ) ; -#38736 = AXIS2_PLACEMENT_3D ( 'NONE', #1039, #17173, #7374 ) ; -#38737 = DIRECTION ( 'NONE', ( -0.0004272100170959573784, 0.7071067811864920616, -0.7071066521336647481 ) ) ; -#38738 = ORIENTED_EDGE ( 'NONE', *, *, #4544, .T. ) ; -#38739 = PLANE ( 'NONE', #23932 ) ; -#38740 = ADVANCED_FACE ( 'NONE', ( #32106 ), #15934, .T. ) ; -#38741 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743043966640313469, -0.2252353050503803911 ) ) ; -#38742 = CARTESIAN_POINT ( 'NONE', ( -25.49000752893273614, 191.9759150222000130, 106.4368436005040479 ) ) ; -#38743 = EDGE_CURVE ( 'NONE', #30903, #7054, #25775, .T. ) ; -#38744 = DIRECTION ( 'NONE', ( -0.7933530821293339752, -0.5932640870757631690, -0.1364866662427065558 ) ) ; -#38745 = ADVANCED_FACE ( 'NONE', ( #38229 ), #6534, .F. ) ; -#38746 = ORIENTED_EDGE ( 'NONE', *, *, #15653, .T. ) ; -#38747 = CARTESIAN_POINT ( 'NONE', ( -82.80843920860921514, 105.1411378422745315, 24.32376295616780482 ) ) ; -#38748 = DIRECTION ( 'NONE', ( 0.000000000000000000, -1.000000000000000000, 0.000000000000000000 ) ) ; -#38749 = CARTESIAN_POINT ( 'NONE', ( -28.70758035546699460, 163.1500623791996816, 99.90218165579484833 ) ) ; -#38750 = ORIENTED_EDGE ( 'NONE', *, *, #27808, .T. ) ; -#38751 = CARTESIAN_POINT ( 'NONE', ( -6.042234299931061869, 134.2432640563548318, 93.72802809502178434 ) ) ; -#38752 = CARTESIAN_POINT ( 'NONE', ( 14.42706621632168229, 176.1815076080119127, 103.2267775782339925 ) ) ; -#38753 = CARTESIAN_POINT ( 'NONE', ( -12.60649365401999944, 163.2729245447999915, 152.4718672074000381 ) ) ; -#38754 = CARTESIAN_POINT ( 'NONE', ( 44.93442337153953758, 186.4047720418488723, 107.1349748693987038 ) ) ; -#38755 = ORIENTED_EDGE ( 'NONE', *, *, #15074, .T. ) ; -#38756 = DIRECTION ( 'NONE', ( -7.677760455958671534E-18, 1.000000000000000000, -1.271205131337281593E-14 ) ) ; -#38757 = CARTESIAN_POINT ( 'NONE', ( 2.039013461118012849, 189.6457011487741511, 103.8698668457489021 ) ) ; -#38758 = AXIS2_PLACEMENT_3D ( 'NONE', #29402, #37989, #32071 ) ; -#38759 = CARTESIAN_POINT ( 'NONE', ( -15.99992728601997527, 142.7916292484897838, 92.62870526400769222 ) ) ; -#38760 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#38761 = CIRCLE ( 'NONE', #6122, 4.999999999999990230 ) ; -#38762 = CARTESIAN_POINT ( 'NONE', ( -25.61429564027000083, 191.7252838869000016, 104.3010191375000062 ) ) ; -#38763 = CARTESIAN_POINT ( 'NONE', ( 23.36366901687428310, 174.6829506628683930, 103.0496233664125754 ) ) ; -#38764 = CARTESIAN_POINT ( 'NONE', ( 25.37591215464999905, 192.1184558962999915, 104.5441819273000021 ) ) ; -#38765 = CARTESIAN_POINT ( 'NONE', ( -35.95405601968200671, 218.5902260770999987, 76.08021997850752882 ) ) ; -#38766 = AXIS2_PLACEMENT_3D ( 'NONE', #37324, #11022, #5266 ) ; -#38767 = FACE_OUTER_BOUND ( 'NONE', #4595, .T. ) ; -#38768 = ORIENTED_EDGE ( 'NONE', *, *, #26039, .F. ) ; -#38769 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17028, #23195, #38918, #4369 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 4.196392522635492678E-05, 0.004030228606235266263 ), - .UNSPECIFIED. ) ; -#38770 = DIRECTION ( 'NONE', ( -0.7933533411653070910, 0.5930537057989941907, 0.1373964268091566465 ) ) ; -#38771 = DIRECTION ( 'NONE', ( -0.9914446600486714889, 0.1270322995874082761, 0.03000468167652007440 ) ) ; -#38772 = CARTESIAN_POINT ( 'NONE', ( -20.16502541160679485, 119.7528545781853779, 90.22005970173493949 ) ) ; -#38773 = ADVANCED_FACE ( 'NONE', ( #35126 ), #34524, .T. ) ; -#38774 = LINE ( 'NONE', #4230, #18260 ) ; -#38775 = CARTESIAN_POINT ( 'NONE', ( 36.08395067039340631, 192.1917151384730005, 104.3500077209999972 ) ) ; -#38776 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -4.622231866529367416E-33, 0.0006039748319394906738 ) ) ; -#38777 = CARTESIAN_POINT ( 'NONE', ( 13.50184736293237542, 188.1187807092373987, 103.2695674776543484 ) ) ; -#38778 = ORIENTED_EDGE ( 'NONE', *, *, #28394, .T. ) ; -#38779 = VECTOR ( 'NONE', #10642, 1000.000000000000114 ) ; -#38780 = ORIENTED_EDGE ( 'NONE', *, *, #13073, .T. ) ; -#38781 = CARTESIAN_POINT ( 'NONE', ( -2.370968452985501962, 209.5715231741518210, 75.55993778019829676 ) ) ; -#38782 = EDGE_CURVE ( 'NONE', #1537, #25244, #13332, .T. ) ; -#38783 = VECTOR ( 'NONE', #24327, 1000.000000000000114 ) ; -#38784 = CARTESIAN_POINT ( 'NONE', ( 19.99933118494021755, 196.5785306413737601, 103.8628508136982731 ) ) ; -#38785 = VECTOR ( 'NONE', #33551, 1000.000000000000000 ) ; -#38786 = ADVANCED_FACE ( 'NONE', ( #12681 ), #37431, .F. ) ; -#38787 = DIRECTION ( 'NONE', ( 0.0004161288024508938573, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#38788 = ORIENTED_EDGE ( 'NONE', *, *, #31766, .F. ) ; -#38789 = CARTESIAN_POINT ( 'NONE', ( -39.51513552280039931, 119.6153294146334929, 90.20002341431117543 ) ) ; -#38790 = CARTESIAN_POINT ( 'NONE', ( 3.587153585141939605, 136.6967892697166462, 94.23604787298746999 ) ) ; -#38791 = EDGE_CURVE ( 'NONE', #26229, #6484, #36170, .T. ) ; -#38792 = ORIENTED_EDGE ( 'NONE', *, *, #23721, .F. ) ; -#38793 = ADVANCED_FACE ( 'NONE', ( #6940 ), #28434, .T. ) ; -#38794 = EDGE_CURVE ( 'NONE', #5278, #37162, #31294, .T. ) ; -#38795 = CARTESIAN_POINT ( 'NONE', ( 20.49882255135672793, 191.9760415900621808, 101.9090510850346476 ) ) ; -#38796 = ORIENTED_EDGE ( 'NONE', *, *, #18216, .T. ) ; -#38797 = CARTESIAN_POINT ( 'NONE', ( 36.48557081826953663, 191.5952041950502860, 106.3706920858186180 ) ) ; -#38798 = DIRECTION ( 'NONE', ( -0.0006039748319382295299, 5.238646599373848640E-18, -0.9999998176071845934 ) ) ; -#38799 = CARTESIAN_POINT ( 'NONE', ( 25.49921019565536184, 118.1133140256443426, 87.75227232668940758 ) ) ; -#38800 = CARTESIAN_POINT ( 'NONE', ( -12.63400679888185785, 130.2556748615208448, 92.68897315470272247 ) ) ; -#38801 = CARTESIAN_POINT ( 'NONE', ( -37.15110912804633614, 71.94901892143192867, 323.0119659673088677 ) ) ; -#38802 = CARTESIAN_POINT ( 'NONE', ( -3.668404236601097601, 185.3449489774860979, 105.0111528754605530 ) ) ; -#38803 = ORIENTED_EDGE ( 'NONE', *, *, #22810, .T. ) ; -#38804 = LINE ( 'NONE', #35724, #39590 ) ; -#38805 = DIRECTION ( 'NONE', ( 0.7075229308291650643, 0.000000000000000000, 0.7066903864854172657 ) ) ; -#38806 = PLANE ( 'NONE', #35789 ) ; -#38807 = ORIENTED_EDGE ( 'NONE', *, *, #35704, .F. ) ; -#38808 = CARTESIAN_POINT ( 'NONE', ( -20.01736593119981222, 207.8686407175673594, 77.28911966098117148 ) ) ; -#38809 = VERTEX_POINT ( 'NONE', #34928 ) ; -#38810 = DIRECTION ( 'NONE', ( -0.6087614115774880874, -0.7729348350621346730, -0.1788331191967953981 ) ) ; -#38811 = CC_DESIGN_APPROVAL ( #17932, ( #37519 ) ) ; -#38812 = AXIS2_PLACEMENT_3D ( 'NONE', #39181, #17701, #14458 ) ; -#38813 = CARTESIAN_POINT ( 'NONE', ( -3.893460979042753678, 148.0324882923159464, 129.7501302153316090 ) ) ; -#38814 = CARTESIAN_POINT ( 'NONE', ( 5.015789737050391217, 130.9602074356647847, 89.88443790896025121 ) ) ; -#38815 = CIRCLE ( 'NONE', #39466, 2.000000000000011546 ) ; -#38816 = VECTOR ( 'NONE', #3861, 1000.000000000000000 ) ; -#38817 = DIRECTION ( 'NONE', ( -0.0006039748319379697550, -1.040973592985965549E-14, -0.9999998176071845934 ) ) ; -#38818 = LINE ( 'NONE', #3871, #17786 ) ; -#38819 = CONICAL_SURFACE ( 'NONE', #21224, 6.000000000011051604, 0.7853981633778843729 ) ; -#38820 = DIRECTION ( 'NONE', ( -0.0005884949961216158097, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#38821 = CARTESIAN_POINT ( 'NONE', ( 26.14344731694000146, 191.2796326829000009, 106.9994950030999945 ) ) ; -#38822 = CARTESIAN_POINT ( 'NONE', ( 20.48021663872660625, 209.7101073659619601, 73.54617496015868028 ) ) ; -#38823 = CARTESIAN_POINT ( 'NONE', ( 38.58832625067999800, 118.9641734523000025, 90.10804234095999732 ) ) ; -#38824 = VERTEX_POINT ( 'NONE', #28241 ) ; -#38825 = ADVANCED_FACE ( 'NONE', ( #37626 ), #19841, .F. ) ; -#38826 = CARTESIAN_POINT ( 'NONE', ( 15.68164426048544691, 125.5719652010231471, 88.63402203514193900 ) ) ; -#38827 = LINE ( 'NONE', #34792, #36141 ) ; -#38828 = PLANE ( 'NONE', #25118 ) ; -#38829 = EDGE_CURVE ( 'NONE', #16448, #4624, #23785, .T. ) ; -#38830 = CARTESIAN_POINT ( 'NONE', ( 15.94070757266567995, 152.8237909711254190, 181.6389010276846818 ) ) ; -#38831 = DIRECTION ( 'NONE', ( -1.117039843155982209E-18, -1.000000000000000000, 1.110223092091563281E-14 ) ) ; -#38832 = EDGE_CURVE ( 'NONE', #23778, #27521, #8157, .T. ) ; -#38833 = LINE ( 'NONE', #7560, #6250 ) ; -#38834 = ORIENTED_EDGE ( 'NONE', *, *, #20896, .F. ) ; -#38835 = VERTEX_POINT ( 'NONE', #13686 ) ; -#38836 = EDGE_CURVE ( 'NONE', #6773, #26891, #32529, .T. ) ; -#38837 = B_SPLINE_SURFACE_WITH_KNOTS ( 'NONE', 3, 3, ( - ( #37311, #21982, #17867, #11769 ), - ( #21387, #36908, #27538, #15624 ), - ( #39964, #33828, #24659, #16615 ), - ( #31984, #13574, #25860, #28910 ), - ( #28314, #31790, #16223, #22783 ), - ( #19687, #280, #28711, #29114 ), - ( #26054, #12766, #19085, #25458 ), - ( #9706, #6610, #9914, #6815 ), - ( #20709, #39302, #20298, #10920 ), - ( #17216, #35608, #4554, #1704 ), - ( #17628, #39101, #11509, #36031 ), - ( #13768, #29920, #1908, #23784 ), - ( #36241, #33165, #5154, #30119 ) ), - .UNSPECIFIED., .F., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4 ), - ( 4, 4 ), - ( -0.01999999998011999999, 0.000000000000000000, 0.2499829833937000090, 0.4999876733701000275, 0.7499923633463999595, 0.9999960213830000333, 1.000000000000000000, 1.010000000003000054, 1.012500000004000089, 1.015000000004999903, 1.020000000006999974 ), - ( 0.1710241378436999915, 0.8289761189929000240 ), - .UNSPECIFIED. ) ; -#38838 = VERTEX_POINT ( 'NONE', #33090 ) ; -#38839 = DIRECTION ( 'NONE', ( 0.0005884949961231208991, -0.2249510543439063315, 0.9743698870671262391 ) ) ; -#38840 = EDGE_CURVE ( 'NONE', #3287, #1872, #4193, .T. ) ; -#38841 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921729510, -0.2249510932970937294 ) ) ; -#38842 = CARTESIAN_POINT ( 'NONE', ( 5.667111978802364725, 124.2427620186889925, 90.94114045841693894 ) ) ; -#38843 = ORIENTED_EDGE ( 'NONE', *, *, #8830, .T. ) ; -#38844 = AXIS2_PLACEMENT_3D ( 'NONE', #2539, #19468, #28686 ) ; -#38845 = FACE_BOUND ( 'NONE', #39284, .T. ) ; -#38846 = EDGE_CURVE ( 'NONE', #21808, #25434, #12051, .T. ) ; -#38847 = CARTESIAN_POINT ( 'NONE', ( -37.76330523427410668, 161.5949354398074433, 190.7626080688544619 ) ) ; -#38848 = CARTESIAN_POINT ( 'NONE', ( -27.84084126295215000, 134.9153899916640000, 90.81744799035887183 ) ) ; -#38849 = CARTESIAN_POINT ( 'NONE', ( -39.43595796038999879, 119.9338082146999938, 87.70772880011000439 ) ) ; -#38850 = FACE_OUTER_BOUND ( 'NONE', #26603, .T. ) ; -#38851 = AXIS2_PLACEMENT_3D ( 'NONE', #26322, #38973, #17079 ) ; -#38852 = CARTESIAN_POINT ( 'NONE', ( -37.03565995587000970, 117.3953279389999977, 87.62651510543000200 ) ) ; -#38853 = ORIENTED_EDGE ( 'NONE', *, *, #39501, .T. ) ; -#38854 = CONICAL_SURFACE ( 'NONE', #29832, 2.503000000187090901, 0.7853981634530804445 ) ; -#38855 = CARTESIAN_POINT ( 'NONE', ( 3.667815738790128677, 185.3461555468956590, 105.0070005413519993 ) ) ; -#38856 = ORIENTED_EDGE ( 'NONE', *, *, #20059, .F. ) ; -#38857 = PLANE ( 'NONE', #32496 ) ; -#38858 = AXIS2_PLACEMENT_3D ( 'NONE', #6315, #37795, #12654 ) ; -#38859 = CARTESIAN_POINT ( 'NONE', ( -16.11981483129142134, 123.6845644638803208, 173.7931095964873691 ) ) ; -#38860 = CARTESIAN_POINT ( 'NONE', ( 45.24519689809859813, 116.5437060779667036, 124.8975000631534158 ) ) ; -#38861 = ADVANCED_FACE ( 'NONE', ( #7950 ), #29841, .T. ) ; -#38862 = ORIENTED_EDGE ( 'NONE', *, *, #6525, .T. ) ; -#38863 = CARTESIAN_POINT ( 'NONE', ( -1.429285596916000101, 189.2366507591000016, 103.7539362638000000 ) ) ; -#38864 = CARTESIAN_POINT ( 'NONE', ( 25.49183330667664293, 209.2218471681004530, 75.54326001368504251 ) ) ; -#38865 = CARTESIAN_POINT ( 'NONE', ( 28.47200544777919262, 130.2255745777155767, 92.60852335989604001 ) ) ; -#38866 = CARTESIAN_POINT ( 'NONE', ( 31.05302410638193678, 145.1862230213489511, 291.5397886867950206 ) ) ; -#38867 = ORIENTED_EDGE ( 'NONE', *, *, #6715, .F. ) ; -#38868 = CARTESIAN_POINT ( 'NONE', ( -25.49003114136341352, 191.3825488810288107, 106.3975518461934371 ) ) ; -#38869 = DIRECTION ( 'NONE', ( -0.9999998176071847045, 0.000000000000000000, 0.0006039748319350685384 ) ) ; -#38870 = ORIENTED_EDGE ( 'NONE', *, *, #5754, .T. ) ; -#38871 = ORIENTED_EDGE ( 'NONE', *, *, #11907, .T. ) ; -#38872 = ORIENTED_EDGE ( 'NONE', *, *, #31070, .F. ) ; -#38873 = ORIENTED_EDGE ( 'NONE', *, *, #29624, .T. ) ; -#38874 = AXIS2_PLACEMENT_3D ( 'NONE', #37049, #24797, #1427 ) ; -#38875 = LINE ( 'NONE', #29490, #1644 ) ; -#38876 = CARTESIAN_POINT ( 'NONE', ( -20.01179132838112551, 204.1052452926227261, 86.15514299590407177 ) ) ; -#38877 = AXIS2_PLACEMENT_3D ( 'NONE', #11381, #17904, #26736 ) ; -#38878 = ORIENTED_EDGE ( 'NONE', *, *, #19999, .T. ) ; -#38880 = CONICAL_SURFACE ( 'NONE', #14747, 5.499999999948422591, 0.7853981634197699790 ) ; -#38879 = CARTESIAN_POINT ( 'NONE', ( 31.91041241775748105, 138.0070370287062644, 92.00823547631698318 ) ) ; -#38881 = CIRCLE ( 'NONE', #4258, 4.500000000003897327 ) ; -#38882 = VERTEX_POINT ( 'NONE', #23297 ) ; -#38883 = VECTOR ( 'NONE', #11357, 1000.000000000000000 ) ; -#38884 = CARTESIAN_POINT ( 'NONE', ( 26.00422603943780686, 120.1012956696319947, 90.44720422082960454 ) ) ; -#38885 = EDGE_CURVE ( 'NONE', #17944, #6941, #15919, .T. ) ; -#38886 = CARTESIAN_POINT ( 'NONE', ( -14.16977583430312926, 135.9878589137828726, 91.56990267135316230 ) ) ; -#38887 = EDGE_CURVE ( 'NONE', #13652, #34680, #38421, .T. ) ; -#38888 = AXIS2_PLACEMENT_3D ( 'NONE', #37218, #6129, #31090 ) ; -#38889 = EDGE_CURVE ( 'NONE', #38838, #4989, #39432, .T. ) ; -#38891 = CARTESIAN_POINT ( 'NONE', ( -13.49877723215485226, 188.1557838371874709, 103.2596942952441736 ) ) ; -#38890 = CARTESIAN_POINT ( 'NONE', ( 20.48150073456040232, 209.0342438232059692, 75.63892168965546148 ) ) ; -#38892 = ORIENTED_EDGE ( 'NONE', *, *, #36075, .F. ) ; -#38893 = ORIENTED_EDGE ( 'NONE', *, *, #32799, .F. ) ; -#38894 = ADVANCED_FACE ( 'NONE', ( #26181 ), #4678, .F. ) ; -#38895 = CARTESIAN_POINT ( 'NONE', ( -36.13178510555328415, 191.9453641854885859, 104.4190089974630808 ) ) ; -#38896 = FACE_OUTER_BOUND ( 'NONE', #20086, .T. ) ; -#38897 = EDGE_LOOP ( 'NONE', ( #37644, #20040, #39729, #29663 ) ) ; -#38898 = LINE ( 'NONE', #19880, #4117 ) ; -#38899 = ADVANCED_FACE ( 'NONE', ( #38616 ), #6800, .F. ) ; -#38900 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15100, #33890, #28187, #9168 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#38901 = CARTESIAN_POINT ( 'NONE', ( 39.35815683041339952, 128.4401884161088958, 92.36081652595443359 ) ) ; -#38902 = VERTEX_POINT ( 'NONE', #39021 ) ; -#38903 = EDGE_LOOP ( 'NONE', ( #21582, #39854, #38407, #4937 ) ) ; -#38904 = AXIS2_PLACEMENT_3D ( 'NONE', #530, #13025, #13424 ) ; -#38905 = CARTESIAN_POINT ( 'NONE', ( 20.48021663872660625, 209.7101073659619601, 73.54617496015868028 ) ) ; -#38906 = CARTESIAN_POINT ( 'NONE', ( -2.604557554923932816, 194.1237596199664779, 102.8347267027521497 ) ) ; -#38907 = VECTOR ( 'NONE', #19318, 1000.000000000000114 ) ; -#38908 = ORIENTED_EDGE ( 'NONE', *, *, #19491, .F. ) ; -#38909 = CARTESIAN_POINT ( 'NONE', ( -35.76774411862999870, 192.5904637550000018, 106.5722673717000077 ) ) ; -#38910 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2497, #14773, #27258, #14966 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.003386932291534215222 ), - .UNSPECIFIED. ) ; -#38911 = AXIS2_PLACEMENT_3D ( 'NONE', #37848, #9857, #28064 ) ; -#38912 = VECTOR ( 'NONE', #12515, 1000.000000000000114 ) ; -#38913 = CARTESIAN_POINT ( 'NONE', ( 2.897735416623014704, 190.9277563016652550, 106.6392879545087453 ) ) ; -#38914 = ORIENTED_EDGE ( 'NONE', *, *, #9925, .F. ) ; -#38915 = CARTESIAN_POINT ( 'NONE', ( 38.98506659676601060, 118.8295563346720769, 89.67030295764752168 ) ) ; -#38916 = FACE_OUTER_BOUND ( 'NONE', #1733, .T. ) ; -#38917 = DIRECTION ( 'NONE', ( -1.433424368938233622E-14, -0.9743700557873516965, -0.2249510933179768024 ) ) ; -#38918 = CARTESIAN_POINT ( 'NONE', ( 44.04052364156038379, 178.1055087129866479, 148.0270100442815817 ) ) ; -#38919 = ORIENTED_EDGE ( 'NONE', *, *, #35373, .F. ) ; -#38920 = ORIENTED_EDGE ( 'NONE', *, *, #6032, .T. ) ; -#38921 = CARTESIAN_POINT ( 'NONE', ( -16.68652574534681321, 121.9722270641570390, 177.8556191836182450 ) ) ; -#38922 = DIRECTION ( 'NONE', ( 1.437432060320536772E-10, -0.9743700558244570153, -0.2249510931572557271 ) ) ; -#38923 = CARTESIAN_POINT ( 'NONE', ( -0.02657825335728297364, 128.5632152146144449, 291.5585599878308471 ) ) ; -#38924 = VERTEX_POINT ( 'NONE', #4877 ) ; -#38925 = AXIS2_PLACEMENT_3D ( 'NONE', #3468, #15369, #33959 ) ; -#38926 = DIRECTION ( 'NONE', ( 0.0005884949671858177161, -0.2249510543353067382, 0.9743698870691291924 ) ) ; -#38927 = EDGE_CURVE ( 'NONE', #22341, #27218, #32276, .T. ) ; -#38928 = EDGE_CURVE ( 'NONE', #2746, #19509, #1208, .T. ) ; -#38929 = AXIS2_PLACEMENT_3D ( 'NONE', #35858, #4792, #17251 ) ; -#38930 = VECTOR ( 'NONE', #26996, 1000.000000000000000 ) ; -#38932 = CARTESIAN_POINT ( 'NONE', ( -38.02385641131999705, 118.5542190637000033, 90.14964594503000228 ) ) ; -#38931 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971571786 ) ) ; -#38933 = ORIENTED_EDGE ( 'NONE', *, *, #5150, .T. ) ; -#38934 = CARTESIAN_POINT ( 'NONE', ( 38.57701359922251072, 118.4688917518772513, 89.66257366145818253 ) ) ; -#38935 = VERTEX_POINT ( 'NONE', #20006 ) ; -#38937 = VECTOR ( 'NONE', #6711, 1000.000000000000114 ) ; -#38936 = CARTESIAN_POINT ( 'NONE', ( -19.99829785685910011, 119.7153791177249502, 90.38236254249699186 ) ) ; -#38938 = LINE ( 'NONE', #23016, #6255 ) ; -#38939 = CARTESIAN_POINT ( 'NONE', ( 37.82795171624675845, 190.9635177071786813, 106.2837781323803341 ) ) ; -#38940 = CARTESIAN_POINT ( 'NONE', ( -3.418257151934999793, 127.0749628277000056, 91.81488911481000059 ) ) ; -#38941 = VECTOR ( 'NONE', #29187, 1000.000000000000114 ) ; -#38942 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -3.370379598151327408E-34, 0.0006039748319386880390 ) ) ; -#38943 = VERTEX_POINT ( 'NONE', #1409 ) ; -#38944 = ORIENTED_EDGE ( 'NONE', *, *, #35921, .T. ) ; -#38945 = CARTESIAN_POINT ( 'NONE', ( -3.669803043821980637, 182.6274357622465914, 101.8180055092276035 ) ) ; -#38946 = ORIENTED_EDGE ( 'NONE', *, *, #36268, .F. ) ; -#38947 = ORIENTED_EDGE ( 'NONE', *, *, #35227, .T. ) ; -#38948 = CARTESIAN_POINT ( 'NONE', ( -33.70405643010219876, 218.5902260770999987, 76.07886103507885878 ) ) ; -#38949 = PLANE ( 'NONE', #25676 ) ; -#38950 = CARTESIAN_POINT ( 'NONE', ( 30.77752414631618194, 157.1438219166013823, 186.2335371180630830 ) ) ; -#38951 = CARTESIAN_POINT ( 'NONE', ( -2.946865378000000035, 209.3288521576999983, 76.09373086713999612 ) ) ; -#38952 = VERTEX_POINT ( 'NONE', #29638 ) ; -#38953 = CARTESIAN_POINT ( 'NONE', ( 1.447658035571014024, 144.9407251426433447, 129.0349007182348657 ) ) ; -#38954 = DIRECTION ( 'NONE', ( -0.7066905299392121087, -0.1591580245907027735, 0.6893890179736118506 ) ) ; -#38955 = PLANE ( 'NONE', #39133 ) ; -#38956 = CARTESIAN_POINT ( 'NONE', ( 25.83261180745369145, 120.1051782784308841, 90.24386527476539754 ) ) ; -#38957 = CARTESIAN_POINT ( 'NONE', ( -25.83466592350999846, 120.7331548140000024, 87.71422404701002051 ) ) ; -#38958 = EDGE_CURVE ( 'NONE', #23946, #14571, #2249, .T. ) ; -#38959 = ORIENTED_EDGE ( 'NONE', *, *, #22063, .F. ) ; -#38960 = CARTESIAN_POINT ( 'NONE', ( -35.93657502954287253, 192.7057404805565568, 106.3835757455632063 ) ) ; -#38961 = CARTESIAN_POINT ( 'NONE', ( 0.5984374266184000479, 191.0000000000000000, 162.9824824849000322 ) ) ; -#38962 = ORIENTED_EDGE ( 'NONE', *, *, #31292, .T. ) ; -#38963 = CIRCLE ( 'NONE', #18052, 2.499999999996476152 ) ; -#38964 = CARTESIAN_POINT ( 'NONE', ( -20.51799340739946942, 207.9362841214596358, 76.29088018949011030 ) ) ; -#38965 = CARTESIAN_POINT ( 'NONE', ( 16.42900653985290660, 122.6518335374459809, 174.4917712166376873 ) ) ; -#38966 = CIRCLE ( 'NONE', #19384, 10.00000000000000888 ) ; -#38967 = CARTESIAN_POINT ( 'NONE', ( -6.272775202316941190, 163.3805630214683333, 99.94184687166684000 ) ) ; -#38968 = CARTESIAN_POINT ( 'NONE', ( -21.70069621165131224, 182.1648337868624594, 104.4589070693949822 ) ) ; -#38969 = AXIS2_PLACEMENT_3D ( 'NONE', #7548, #11041, #32504 ) ; -#38970 = ORIENTED_EDGE ( 'NONE', *, *, #32488, .T. ) ; -#38971 = CARTESIAN_POINT ( 'NONE', ( 20.00000190450869653, 184.9707748627797912, 102.3447125600660002 ) ) ; -#38972 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36387, #29648, #23507, #32902, #1624, #14113, #26591, #4893, #1835, #11240, #33100, #15128, #3035, #21470, #12443, #9192, #27615, #36995, #40046, #21670 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1249999999999487632, 0.1874999999999337474, 0.2187499999999377998, 0.2343749999999398537, 0.2499999999999418798, 0.4999999999999397149, 0.6249999999999382716, 0.6874999999999377165, 0.7187499999999319433, 0.7343749999999324984, 0.7499999999999329425, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#38973 = DIRECTION ( 'NONE', ( -0.0005884949961184574203, 0.2249510543439044719, -0.9743698870671267942 ) ) ; -#38974 = CARTESIAN_POINT ( 'NONE', ( 8.470678308075262564, 161.4201748467667983, 97.42774225087779882 ) ) ; -#38975 = VECTOR ( 'NONE', #39506, 1000.000000000000114 ) ; -#38976 = EDGE_CURVE ( 'NONE', #21181, #15150, #1614, .T. ) ; -#38977 = ORIENTED_EDGE ( 'NONE', *, *, #16540, .T. ) ; -#38978 = DIRECTION ( 'NONE', ( 0.6087611434179117653, -0.7728348325624405657, -0.1792657018023829929 ) ) ; -#38979 = CARTESIAN_POINT ( 'NONE', ( -25.37711299161999889, 191.2846165128000280, 104.4837167168000178 ) ) ; -#38980 = FACE_OUTER_BOUND ( 'NONE', #22152, .T. ) ; -#38981 = CARTESIAN_POINT ( 'NONE', ( 15.10588229656246639, 129.6118588884834537, 89.56705289901165656 ) ) ; -#38982 = DIRECTION ( 'NONE', ( 0.7075388627048109225, 2.466988180792839033E-19, 0.7066744354809949558 ) ) ; -#38983 = DIRECTION ( 'NONE', ( 0.6982900371914136928, 0.000000000000000000, 0.7158149369489394953 ) ) ; -#38984 = ORIENTED_EDGE ( 'NONE', *, *, #38612, .T. ) ; -#38985 = ADVANCED_FACE ( 'NONE', ( #24526 ), #12686, .F. ) ; -#38986 = ADVANCED_FACE ( 'NONE', ( #15309 ), #33493, .T. ) ; -#38987 = DIRECTION ( 'NONE', ( -0.0006039748319391913256, 0.000000000000000000, -0.9999998176071847045 ) ) ; -#38988 = LINE ( 'NONE', #8334, #3531 ) ; -#38989 = CARTESIAN_POINT ( 'NONE', ( -16.54486418118989022, 122.1240419071647523, 174.7656150134046413 ) ) ; -#38990 = EDGE_CURVE ( 'NONE', #34917, #29659, #30318, .T. ) ; -#38991 = CIRCLE ( 'NONE', #24009, 5.000000000000007994 ) ; -#38992 = CARTESIAN_POINT ( 'NONE', ( -14.78424366467106665, 136.1377412980438351, 93.65748546644259420 ) ) ; -#38993 = DIRECTION ( 'NONE', ( -0.0005884949961212385073, 0.2249510543439022514, -0.9743698870671273493 ) ) ; -#38994 = DIRECTION ( 'NONE', ( 0.0005884949961230292841, -0.2249510543439062205, 0.9743698870671264611 ) ) ; -#38995 = CARTESIAN_POINT ( 'NONE', ( -16.89287681940586339, 152.3621173710822916, 181.9638245443325388 ) ) ; -#38996 = CARTESIAN_POINT ( 'NONE', ( 21.17532367120271530, 115.6972542624342992, 90.25499547431961389 ) ) ; -#38997 = CIRCLE ( 'NONE', #3075, 1.749999999939591433 ) ; -#38998 = VERTEX_POINT ( 'NONE', #36986 ) ; -#38999 = DIRECTION ( 'NONE', ( -0.0002393071182782277790, -0.2252352986010052460, 0.9743043687658488050 ) ) ; -#39000 = CARTESIAN_POINT ( 'NONE', ( -31.72059812955714619, 135.5117662268001197, 90.95743610326634609 ) ) ; -#39001 = ORIENTED_EDGE ( 'NONE', *, *, #24940, .F. ) ; -#39002 = CARTESIAN_POINT ( 'NONE', ( 35.62684683417209897, 82.24867230276376517, 284.3280258707958978 ) ) ; -#39003 = CARTESIAN_POINT ( 'NONE', ( 25.50043400004976490, 118.5815211324333092, 89.75241963774004716 ) ) ; -#39004 = ORIENTED_EDGE ( 'NONE', *, *, #29342, .T. ) ; -#39005 = CARTESIAN_POINT ( 'NONE', ( 6.272186690383747099, 163.3822237695354147, 99.93465344309498732 ) ) ; -#39006 = VERTEX_POINT ( 'NONE', #34098 ) ; -#39007 = CARTESIAN_POINT ( 'NONE', ( 35.04645050414097085, 226.4002260770962778, 75.53733736050621417 ) ) ; -#39008 = CARTESIAN_POINT ( 'NONE', ( 3.632499201418514456, 167.8476872159760376, 101.3812074453261829 ) ) ; -#39009 = FACE_OUTER_BOUND ( 'NONE', #32825, .T. ) ; -#39010 = CYLINDRICAL_SURFACE ( 'NONE', #13715, 10.00000000000000000 ) ; -#39011 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#39012 = ORIENTED_EDGE ( 'NONE', *, *, #17794, .T. ) ; -#39013 = DIRECTION ( 'NONE', ( 0.6188015000093136653, -0.7855473910504848778, 0.000000000000000000 ) ) ; -#39014 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#39015 = PLANE ( 'NONE', #37799 ) ; -#39016 = EDGE_CURVE ( 'NONE', #15694, #20455, #21244, .T. ) ; -#39017 = CIRCLE ( 'NONE', #1818, 2.999999999975996534 ) ; -#39018 = LINE ( 'NONE', #32884, #11866 ) ; -#39019 = EDGE_LOOP ( 'NONE', ( #37176, #29305, #24090, #35975 ) ) ; -#39020 = EDGE_LOOP ( 'NONE', ( #15029, #25243, #17573, #30801 ) ) ; -#39021 = CARTESIAN_POINT ( 'NONE', ( 12.64209925790531308, 131.0231129754641302, 89.89439459407216759 ) ) ; -#39022 = AXIS2_PLACEMENT_3D ( 'NONE', #38482, #1272, #10503 ) ; -#39023 = DIRECTION ( 'NONE', ( -0.0001358647731615390223, -0.9743700655807135957, -0.2249510098688140558 ) ) ; -#39024 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#39025 = ADVANCED_FACE ( 'NONE', ( #5485 ), #5898, .T. ) ; -#39026 = CARTESIAN_POINT ( 'NONE', ( 20.49943975712684008, 154.7948711043053436, 183.6022678106032231 ) ) ; -#39027 = CARTESIAN_POINT ( 'NONE', ( -15.49970617126520445, 160.6260167168586293, 97.25887387978653464 ) ) ; -#39028 = EDGE_CURVE ( 'NONE', #22377, #24370, #6096, .T. ) ; -#39029 = EDGE_CURVE ( 'NONE', #27866, #23690, #10599, .T. ) ; -#39030 = CARTESIAN_POINT ( 'NONE', ( -20.16513161867054649, 160.0945457268390442, 99.53356579039633800 ) ) ; -#39031 = EDGE_CURVE ( 'NONE', #16668, #29541, #12533, .T. ) ; -#39032 = CARTESIAN_POINT ( 'NONE', ( 25.37814744239999953, 191.6834400436999886, 106.2641627654000018 ) ) ; -#39033 = EDGE_CURVE ( 'NONE', #906, #23019, #8792, .T. ) ; -#39034 = CYLINDRICAL_SURFACE ( 'NONE', #15936, 9.999999999999996447 ) ; -#39035 = CYLINDRICAL_SURFACE ( 'NONE', #34378, 2.499999999999999112 ) ; -#39036 = ORIENTED_EDGE ( 'NONE', *, *, #23364, .T. ) ; -#39037 = CARTESIAN_POINT ( 'NONE', ( -40.80719639505100105, 126.7988830470261092, 92.03030911972437877 ) ) ; -#39038 = CARTESIAN_POINT ( 'NONE', ( -0.02993291085645299193, 92.27946995574508549, 297.5585631083172302 ) ) ; -#39039 = CARTESIAN_POINT ( 'NONE', ( 19.84759055312880704, 148.9730819504834756, 184.3419776361884885 ) ) ; -#39040 = CARTESIAN_POINT ( 'NONE', ( -30.96737657860713355, 184.1206350860066152, 102.1792248493828055 ) ) ; -#39041 = CARTESIAN_POINT ( 'NONE', ( -38.46044104337040181, 118.4609804511839286, 89.70916240556151422 ) ) ; -#39042 = ORIENTED_EDGE ( 'NONE', *, *, #15055, .F. ) ; -#39043 = ORIENTED_EDGE ( 'NONE', *, *, #38471, .T. ) ; -#39044 = CYLINDRICAL_SURFACE ( 'NONE', #32038, 6.000000000000008882 ) ; -#39045 = AXIS2_PLACEMENT_3D ( 'NONE', #30440, #14895, #2635 ) ; -#39046 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#39047 = CARTESIAN_POINT ( 'NONE', ( -20.89285663966641238, 176.3787109218369551, 100.3857757381706222 ) ) ; -#39048 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2933, #6007, #22170, #24846 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39049 = CIRCLE ( 'NONE', #37083, 5.500000000011748824 ) ; -#39050 = ORIENTED_EDGE ( 'NONE', *, *, #21096, .F. ) ; -#39051 = CARTESIAN_POINT ( 'NONE', ( 22.49999746303471682, 154.4130087049401254, 95.28531927624969455 ) ) ; -#39052 = EDGE_CURVE ( 'NONE', #16108, #31399, #2236, .T. ) ; -#39053 = DIRECTION ( 'NONE', ( 0.7933533411653074241, 0.5931840316265225566, 0.1368326740407711517 ) ) ; -#39054 = CARTESIAN_POINT ( 'NONE', ( -36.34733598288000422, 115.9999055177000145, 87.64047360899999717 ) ) ; -#39055 = VERTEX_POINT ( 'NONE', #2833 ) ; -#39056 = CARTESIAN_POINT ( 'NONE', ( -19.21661266601579854, 125.6427568102140810, 176.7081128588468175 ) ) ; -#39057 = EDGE_LOOP ( 'NONE', ( #31043, #2670, #26659, #26458 ) ) ; -#39058 = FACE_OUTER_BOUND ( 'NONE', #10926, .T. ) ; -#39059 = CARTESIAN_POINT ( 'NONE', ( 5.669239325943234320, 130.1664129347483652, 92.53175120781416751 ) ) ; -#39060 = LINE ( 'NONE', #20451, #37853 ) ; -#39061 = CARTESIAN_POINT ( 'NONE', ( 27.83965598682951992, 177.7949683626683850, 100.6833510721430542 ) ) ; -#39062 = ORIENTED_EDGE ( 'NONE', *, *, #8875, .T. ) ; -#39063 = CARTESIAN_POINT ( 'NONE', ( -1.680089689788329732, 188.9049530417860296, 103.2619686274020125 ) ) ; -#39064 = CARTESIAN_POINT ( 'NONE', ( 0.7119102185202000888, 189.0148120467000012, 103.6943891261000061 ) ) ; -#39065 = CARTESIAN_POINT ( 'NONE', ( -30.07082631362985836, 134.8398731441967868, 93.36708164982407254 ) ) ; -#39066 = EDGE_CURVE ( 'NONE', #34329, #6692, #36856, .T. ) ; -#39067 = VERTEX_POINT ( 'NONE', #24116 ) ; -#39068 = CARTESIAN_POINT ( 'NONE', ( -25.50870663471662780, 209.7066555246269104, 75.57407794464953099 ) ) ; -#39069 = ORIENTED_EDGE ( 'NONE', *, *, #19062, .T. ) ; -#39070 = ORIENTED_EDGE ( 'NONE', *, *, #27581, .F. ) ; -#39071 = CIRCLE ( 'NONE', #1877, 2.500000000086348706 ) ; -#39072 = EDGE_CURVE ( 'NONE', #2798, #34249, #35392, .T. ) ; -#39073 = EDGE_CURVE ( 'NONE', #21095, #1901, #36572, .T. ) ; -#39074 = CONICAL_SURFACE ( 'NONE', #16880, 4.999999999912411397, 0.7853981634347277918 ) ; -#39075 = ORIENTED_EDGE ( 'NONE', *, *, #27778, .T. ) ; -#39076 = AXIS2_PLACEMENT_3D ( 'NONE', #25041, #12340, #11747 ) ; -#39077 = ORIENTED_EDGE ( 'NONE', *, *, #27707, .F. ) ; -#39078 = CARTESIAN_POINT ( 'NONE', ( -27.40037233577605136, 188.3537917825017303, 103.1543718757085486 ) ) ; -#39079 = CARTESIAN_POINT ( 'NONE', ( -27.86226992038220374, 186.6938930634679537, 105.3320624031430270 ) ) ; -#39080 = VECTOR ( 'NONE', #17662, 1000.000000000000114 ) ; -#39081 = CARTESIAN_POINT ( 'NONE', ( -20.02002437005085511, 209.7095682957761085, 73.07054393135327075 ) ) ; -#39082 = EDGE_CURVE ( 'NONE', #29484, #27835, #1585, .T. ) ; -#39083 = VERTEX_POINT ( 'NONE', #33287 ) ; -#39084 = CARTESIAN_POINT ( 'NONE', ( 29.62444489005903492, 185.2955461511815827, 104.9796392865187613 ) ) ; -#39085 = ORIENTED_EDGE ( 'NONE', *, *, #26681, .F. ) ; -#39086 = CARTESIAN_POINT ( 'NONE', ( 28.22758490474300430, 124.4186838343800048, 91.44260002119000319 ) ) ; -#39087 = CARTESIAN_POINT ( 'NONE', ( 36.95653322929180007, 86.97535859511968681, 287.8064994082558883 ) ) ; -#39089 = CARTESIAN_POINT ( 'NONE', ( 30.10554067372000020, 123.2470639583000178, 152.4718672074000381 ) ) ; -#39088 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921580740, -0.2249510932971585109 ) ) ; -#39090 = ORIENTED_EDGE ( 'NONE', *, *, #6334, .T. ) ; -#39091 = ORIENTED_EDGE ( 'NONE', *, *, #26833, .T. ) ; -#39092 = CARTESIAN_POINT ( 'NONE', ( -36.25534212287539759, 191.8348339277909815, 104.4077102864487756 ) ) ; -#39093 = ORIENTED_EDGE ( 'NONE', *, *, #6680, .T. ) ; -#39094 = CARTESIAN_POINT ( 'NONE', ( 38.93148201702999955, 119.4912731960999963, 90.44571384572999762 ) ) ; -#39095 = FACE_OUTER_BOUND ( 'NONE', #26176, .T. ) ; -#39096 = CIRCLE ( 'NONE', #8453, 2.000000000065532024 ) ; -#39097 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13134, #25614, #22546, #38064 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39098 = CARTESIAN_POINT ( 'NONE', ( -20.51876290927583568, 210.6302914306680805, 75.57087059609588664 ) ) ; -#39099 = CARTESIAN_POINT ( 'NONE', ( 13.76428958127423741, 125.4663756326015402, 174.1938355030699483 ) ) ; -#39100 = CARTESIAN_POINT ( 'NONE', ( -5.669412827411000499, 187.7434695952159132, 103.5134950630966557 ) ) ; -#39101 = CARTESIAN_POINT ( 'NONE', ( 36.22321703693000217, 191.6094071333000102, 104.0120110401999938 ) ) ; -#39102 = ORIENTED_EDGE ( 'NONE', *, *, #33538, .F. ) ; -#39103 = AXIS2_PLACEMENT_3D ( 'NONE', #23051, #37767, #19362 ) ; -#39104 = VERTEX_POINT ( 'NONE', #2443 ) ; -#39105 = CIRCLE ( 'NONE', #2595, 6.499999999889569224 ) ; -#39106 = CARTESIAN_POINT ( 'NONE', ( 22.78045900286099368, 148.0760582945774786, 93.82521474199010925 ) ) ; -#39107 = CARTESIAN_POINT ( 'NONE', ( -29.94780647573006149, 103.6131156702304992, 87.78587210766562521 ) ) ; -#39108 = AXIS2_PLACEMENT_3D ( 'NONE', #13098, #13299, #31913 ) ; -#39109 = CARTESIAN_POINT ( 'NONE', ( 26.22129837218000148, 123.4649048998000183, 88.65453169520000642 ) ) ; -#39110 = ORIENTED_EDGE ( 'NONE', *, *, #33198, .T. ) ; -#39111 = CARTESIAN_POINT ( 'NONE', ( -35.63572620277000169, 192.2657345707000047, 106.7753187434000068 ) ) ; -#39113 = EDGE_CURVE ( 'NONE', #21433, #18878, #9455, .T. ) ; -#39112 = CARTESIAN_POINT ( 'NONE', ( -38.38147336650155239, 118.3854775865508913, 89.70984624231221005 ) ) ; -#39114 = EDGE_CURVE ( 'NONE', #14369, #31713, #2925, .T. ) ; -#39115 = EDGE_CURVE ( 'NONE', #21095, #31941, #22767, .T. ) ; -#39116 = ORIENTED_EDGE ( 'NONE', *, *, #37094, .T. ) ; -#39117 = EDGE_CURVE ( 'NONE', #36005, #17425, #17918, .T. ) ; -#39118 = CARTESIAN_POINT ( 'NONE', ( 2.564076329950748523, 190.9814211239933570, 106.3071458285015183 ) ) ; -#39119 = ORIENTED_EDGE ( 'NONE', *, *, #36932, .T. ) ; -#39120 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#39121 = LINE ( 'NONE', #33387, #27160 ) ; -#39122 = CARTESIAN_POINT ( 'NONE', ( 3.062029414131564931, 193.8169247290821318, 102.7010603508924191 ) ) ; -#39123 = FACE_OUTER_BOUND ( 'NONE', #22099, .T. ) ; -#39124 = ADVANCED_FACE ( 'NONE', ( #28586 ), #3022, .T. ) ; -#39125 = ORIENTED_EDGE ( 'NONE', *, *, #3660, .F. ) ; -#39126 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #10311, #272, #3337, #19481 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39127 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11854, #21667, #39639, #2839 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999992929598684466 ), - .UNSPECIFIED. ) ; -#39128 = DIRECTION ( 'NONE', ( 0.0005884949961238158727, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#39129 = CARTESIAN_POINT ( 'NONE', ( 20.48673967653602901, 211.0896571907997554, 75.54495990469186495 ) ) ; -#39130 = ADVANCED_FACE ( 'NONE', ( #12848 ), #31863, .T. ) ; -#39131 = CIRCLE ( 'NONE', #24807, 2.499999842035334652 ) ; -#39132 = VERTEX_POINT ( 'NONE', #19369 ) ; -#39133 = AXIS2_PLACEMENT_3D ( 'NONE', #7070, #7880, #38741 ) ; -#39134 = CARTESIAN_POINT ( 'NONE', ( 39.71118933309595178, 120.0401689410542332, 87.68449441950606627 ) ) ; -#39135 = AXIS2_PLACEMENT_3D ( 'NONE', #12529, #3924, #37482 ) ; -#39137 = CARTESIAN_POINT ( 'NONE', ( 15.01467670299223656, 158.7773337856645242, 96.30048964586330840 ) ) ; -#39136 = CARTESIAN_POINT ( 'NONE', ( -37.24436734876973532, 107.5967902977559305, 168.6045324416054996 ) ) ; -#39138 = EDGE_CURVE ( 'NONE', #36888, #38809, #6485, .T. ) ; -#39139 = ORIENTED_EDGE ( 'NONE', *, *, #38058, .T. ) ; -#39140 = CARTESIAN_POINT ( 'NONE', ( -4.036264727520263662, 143.6503695267791727, 95.38542116167025142 ) ) ; -#39141 = EDGE_LOOP ( 'NONE', ( #39673, #13625, #26294 ) ) ; -#39142 = FACE_OUTER_BOUND ( 'NONE', #27123, .T. ) ; -#39143 = DIRECTION ( 'NONE', ( 0.3095850547605887848, 0.7852246974590433304, -0.5362641777792332975 ) ) ; -#39144 = DIRECTION ( 'NONE', ( -0.7855473026356902810, -0.6188014303620729128, 0.0004744508866335444284 ) ) ; -#39145 = ORIENTED_EDGE ( 'NONE', *, *, #27591, .F. ) ; -#39146 = ORIENTED_EDGE ( 'NONE', *, *, #34899, .T. ) ; -#39147 = CARTESIAN_POINT ( 'NONE', ( -3.488521955165103883, 182.8912935819007259, 101.8788124086412097 ) ) ; -#39148 = ORIENTED_EDGE ( 'NONE', *, *, #20975, .F. ) ; -#39149 = ORIENTED_EDGE ( 'NONE', *, *, #35536, .F. ) ; -#39150 = FACE_OUTER_BOUND ( 'NONE', #23196, .T. ) ; -#39151 = CARTESIAN_POINT ( 'NONE', ( 2.641714212161000219, 209.5450904688000264, 73.39022784082000328 ) ) ; -#39152 = ORIENTED_EDGE ( 'NONE', *, *, #16231, .T. ) ; -#39153 = CARTESIAN_POINT ( 'NONE', ( 20.50141158344984404, 191.9758728513155575, 106.4093071483684696 ) ) ; -#39154 = CARTESIAN_POINT ( 'NONE', ( -36.33569152581000594, 191.9269841567999890, 104.5567655966000018 ) ) ; -#39155 = CARTESIAN_POINT ( 'NONE', ( 37.78283638816999712, 191.5199205812999992, 104.5101298729999968 ) ) ; -#39156 = CARTESIAN_POINT ( 'NONE', ( -25.66813629712000022, 120.7641189082000039, 87.89123204253000665 ) ) ; -#39157 = AXIS2_PLACEMENT_3D ( 'NONE', #33480, #23901, #27398 ) ; -#39158 = VERTEX_POINT ( 'NONE', #18954 ) ; -#39159 = FACE_OUTER_BOUND ( 'NONE', #37014, .T. ) ; -#39160 = FACE_OUTER_BOUND ( 'NONE', #21596, .T. ) ; -#39161 = VECTOR ( 'NONE', #17215, 1000.000000000000000 ) ; -#39162 = ORIENTED_EDGE ( 'NONE', *, *, #2688, .F. ) ; -#39163 = AXIS2_PLACEMENT_3D ( 'NONE', #2989, #24294, #30621 ) ; -#39164 = CARTESIAN_POINT ( 'NONE', ( 0.6274659588453800341, 188.6153583805931930, 103.1978311820718517 ) ) ; -#39165 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5467, #2219, #30018, #21026 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 1.210202674097414542E-06, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39166 = AXIS2_PLACEMENT_3D ( 'NONE', #39830, #30855, #24937 ) ; -#39167 = CARTESIAN_POINT ( 'NONE', ( -38.45586748819795986, 218.5902260770999987, 73.08173046273398654 ) ) ; -#39168 = EDGE_CURVE ( 'NONE', #6123, #31429, #21850, .T. ) ; -#39169 = EDGE_CURVE ( 'NONE', #11287, #15246, #31027, .T. ) ; -#39170 = CARTESIAN_POINT ( 'NONE', ( -14.16977585978846754, 176.4938143369288355, 100.9214410357033529 ) ) ; -#39171 = AXIS2_PLACEMENT_3D ( 'NONE', #34838, #917, #9740 ) ; -#39172 = CARTESIAN_POINT ( 'NONE', ( -19.53692352085504069, 149.3682945783864113, 181.5378042029076369 ) ) ; -#39173 = VERTEX_POINT ( 'NONE', #15891 ) ; -#39174 = CARTESIAN_POINT ( 'NONE', ( -5.668109640120363224, 183.4491314654635801, 105.0878260507181778 ) ) ; -#39175 = CARTESIAN_POINT ( 'NONE', ( 2.235475728327229739, 189.9035752844333445, 103.9441533979629924 ) ) ; -#39176 = CARTESIAN_POINT ( 'NONE', ( 25.50040748627628773, 118.8155663766999481, 89.75240507814876878 ) ) ; -#39177 = EDGE_LOOP ( 'NONE', ( #12659, #3227, #38456, #36495 ) ) ; -#39178 = CARTESIAN_POINT ( 'NONE', ( -38.87029739955395513, 169.2267822088134892, 183.8778481530477791 ) ) ; -#39179 = ORIENTED_EDGE ( 'NONE', *, *, #19133, .F. ) ; -#39180 = CARTESIAN_POINT ( 'NONE', ( -25.35525560430000169, 191.8359866865000072, 104.5586871365999997 ) ) ; -#39181 = CARTESIAN_POINT ( 'NONE', ( 17.97063383948572124, 149.1908938068557404, 179.6779205776294361 ) ) ; -#39182 = CARTESIAN_POINT ( 'NONE', ( 25.89285108626999943, 192.1487801751000006, 104.0221552793999962 ) ) ; -#39183 = FACE_OUTER_BOUND ( 'NONE', #16266, .T. ) ; -#39184 = VERTEX_POINT ( 'NONE', #358 ) ; -#39185 = PLANE ( 'NONE', #1730 ) ; -#39186 = AXIS2_PLACEMENT_3D ( 'NONE', #16237, #22995, #22400 ) ; -#39187 = EDGE_CURVE ( 'NONE', #12347, #36214, #31242, .T. ) ; -#39188 = DIRECTION ( 'NONE', ( 0.0005884949905463371812, -0.2249510543438333898, 0.9743698870671464451 ) ) ; -#39189 = AXIS2_PLACEMENT_3D ( 'NONE', #37555, #9760, #6465 ) ; -#39190 = CARTESIAN_POINT ( 'NONE', ( -35.94055828177000222, 192.4035622650000334, 104.1758260217000043 ) ) ; -#39191 = DIRECTION ( 'NONE', ( -0.6088835995545407442, -0.7728434649458200134, -0.1788120266761852595 ) ) ; -#39192 = VECTOR ( 'NONE', #28852, 1000.000000000000114 ) ; -#39193 = CARTESIAN_POINT ( 'NONE', ( 37.48996430735000018, 190.8515886636000118, 106.3794466851000067 ) ) ; -#39194 = CARTESIAN_POINT ( 'NONE', ( 45.36467309445081497, 70.87416510410297121, 322.7139789007268291 ) ) ; -#39195 = VECTOR ( 'NONE', #8324, 999.9999999999998863 ) ; -#39196 = CARTESIAN_POINT ( 'NONE', ( -15.10513900131456388, 175.7048190624925610, 103.3056127689209376 ) ) ; -#39197 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621346730, 0.1788331191967953981 ) ) ; -#39198 = DIRECTION ( 'NONE', ( -0.0005884949672441799938, 0.2249510543775923299, -0.9743698870593667793 ) ) ; -#39199 = CARTESIAN_POINT ( 'NONE', ( -38.38765349727361098, 118.8474376092554508, 87.72134797196410716 ) ) ; -#39200 = ORIENTED_EDGE ( 'NONE', *, *, #17874, .T. ) ; -#39201 = CARTESIAN_POINT ( 'NONE', ( 3.671230113708026099, 144.1856367755248982, 93.07912818882560657 ) ) ; -#39202 = CARTESIAN_POINT ( 'NONE', ( -30.70212612791577556, 134.9734613206348399, 90.83254346907035881 ) ) ; -#39203 = ORIENTED_EDGE ( 'NONE', *, *, #1225, .T. ) ; -#39204 = CARTESIAN_POINT ( 'NONE', ( 33.83294458002807659, 83.70316674797169298, 284.1460533327533540 ) ) ; -#39205 = VERTEX_POINT ( 'NONE', #12431 ) ; -#39206 = CARTESIAN_POINT ( 'NONE', ( 23.31785698356683056, 213.5902233258594265, 73.54422726498407314 ) ) ; -#39207 = CARTESIAN_POINT ( 'NONE', ( 30.09291612660999959, 109.6131156702000027, 152.4718672074000381 ) ) ; -#39208 = ORIENTED_EDGE ( 'NONE', *, *, #35445, .T. ) ; -#39209 = CARTESIAN_POINT ( 'NONE', ( 29.05382570111806118, 110.6131156702000027, 87.75023660053001606 ) ) ; -#39210 = CARTESIAN_POINT ( 'NONE', ( 28.90769808291203091, 225.0820812890804348, 73.04104455706797694 ) ) ; -#39211 = CARTESIAN_POINT ( 'NONE', ( -12.63527048312528756, 130.1801778034788413, 92.56815356418299245 ) ) ; -#39212 = ADVANCED_FACE ( 'NONE', ( #9379 ), #24935, .T. ) ; -#39213 = EDGE_CURVE ( 'NONE', #4424, #15600, #554, .T. ) ; -#39214 = CARTESIAN_POINT ( 'NONE', ( 15.05197310825490398, 136.6013035982805661, 91.18072662319218580 ) ) ; -#39215 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #17139, #36377, #24119, #29640 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.002783951876392748090, 0.002790143392383074520 ), - .UNSPECIFIED. ) ; -#39216 = CARTESIAN_POINT ( 'NONE', ( 6.034204648359921208, 177.7921235470974466, 100.6958268401488539 ) ) ; -#39217 = ORIENTED_EDGE ( 'NONE', *, *, #1089, .F. ) ; -#39218 = CARTESIAN_POINT ( 'NONE', ( 76.10630783111388098, 156.2450968845424768, 96.19213091947902683 ) ) ; -#39219 = CONICAL_SURFACE ( 'NONE', #10524, 2.502992089562209976, 0.7853981633619750991 ) ; -#39220 = LINE ( 'NONE', #8367, #24478 ) ; -#39221 = CARTESIAN_POINT ( 'NONE', ( -25.49121842733731569, 191.8361208170296379, 104.4329317390898950 ) ) ; -#39222 = CIRCLE ( 'NONE', #28816, 2.499999999980133225 ) ; -#39223 = AXIS2_PLACEMENT_3D ( 'NONE', #39378, #30199, #32845 ) ; -#39224 = CARTESIAN_POINT ( 'NONE', ( -20.68588240384768540, 105.5805168953082926, 90.28027859384218345 ) ) ; -#39225 = ORIENTED_EDGE ( 'NONE', *, *, #2009, .T. ) ; -#39226 = DIRECTION ( 'NONE', ( 0.7933533411653075351, -0.5930537057989938576, -0.1373964268091553698 ) ) ; -#39227 = CARTESIAN_POINT ( 'NONE', ( -43.10569259267042952, 120.6546256101410819, 92.20669626011783748 ) ) ; -#39228 = CARTESIAN_POINT ( 'NONE', ( 37.96340687623389698, 191.0388351520254560, 103.7347888148996446 ) ) ; -#39229 = DIRECTION ( 'NONE', ( 0.7072734958804502980, 0.6509141195175901506, 0.2758169883050842763 ) ) ; -#39230 = CARTESIAN_POINT ( 'NONE', ( -18.08817325877299353, 126.3818500937895521, 175.0046273759002986 ) ) ; -#39231 = CARTESIAN_POINT ( 'NONE', ( -34.95638759933999040, 226.4002260770912187, 73.57961695570894278 ) ) ; -#39232 = CARTESIAN_POINT ( 'NONE', ( 45.68950646426466733, 77.14301703112153064, 297.5309497125679741 ) ) ; -#39233 = CARTESIAN_POINT ( 'NONE', ( -25.63747034653302137, 209.7120552166697962, 73.44645162493029034 ) ) ; -#39234 = CARTESIAN_POINT ( 'NONE', ( 31.51045601729466483, 191.4722053967683451, 106.4044942133964895 ) ) ; -#39235 = FACE_OUTER_BOUND ( 'NONE', #9582, .T. ) ; -#39236 = ORIENTED_EDGE ( 'NONE', *, *, #11155, .F. ) ; -#39237 = FACE_OUTER_BOUND ( 'NONE', #18577, .T. ) ; -#39238 = DIRECTION ( 'NONE', ( 0.7066905299392121087, 0.1591580245907027735, -0.6893890179736118506 ) ) ; -#39239 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #531, #22436, #31841, #3796 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39240 = CARTESIAN_POINT ( 'NONE', ( -36.24552557991719226, 191.7319245521262303, 106.4277516671341601 ) ) ; -#39241 = CARTESIAN_POINT ( 'NONE', ( -22.60314354626212463, 115.1134007281406610, 87.28143602434546722 ) ) ; -#39242 = CIRCLE ( 'NONE', #22951, 5.249999999999986677 ) ; -#39244 = ORIENTED_EDGE ( 'NONE', *, *, #8257, .T. ) ; -#39243 = CARTESIAN_POINT ( 'NONE', ( 22.49999922077102354, 138.5120027357655204, 91.61734752330174558 ) ) ; -#39245 = ORIENTED_EDGE ( 'NONE', *, *, #27589, .F. ) ; -#39246 = ORIENTED_EDGE ( 'NONE', *, *, #37105, .T. ) ; -#39247 = AXIS2_PLACEMENT_3D ( 'NONE', #19407, #38225, #9832 ) ; -#39248 = VECTOR ( 'NONE', #7404, 1000.000000000000000 ) ; -#39249 = ORIENTED_EDGE ( 'NONE', *, *, #27345, .T. ) ; -#39250 = CARTESIAN_POINT ( 'NONE', ( -20.00089539691495233, 118.1272453392662527, 87.27993277136866368 ) ) ; -#39251 = ADVANCED_FACE ( 'NONE', ( #6289 ), #2279, .T. ) ; -#39252 = LINE ( 'NONE', #17769, #13498 ) ; -#39253 = ORIENTED_EDGE ( 'NONE', *, *, #14621, .T. ) ; -#39254 = CARTESIAN_POINT ( 'NONE', ( -14.16859883678303689, 135.5379567964818648, 93.51864244317933128 ) ) ; -#39255 = EDGE_CURVE ( 'NONE', #18545, #31494, #38195, .T. ) ; -#39256 = CARTESIAN_POINT ( 'NONE', ( -13.49693341779290989, 187.4925040631788420, 105.7867476294317441 ) ) ; -#39257 = CARTESIAN_POINT ( 'NONE', ( -37.59159439311999762, 118.9392194373999985, 87.16591189003000295 ) ) ; -#39258 = ORIENTED_EDGE ( 'NONE', *, *, #36893, .T. ) ; -#39259 = DIRECTION ( 'NONE', ( 8.589097300323509265E-16, -0.9743700557925334405, -0.2249510932955323117 ) ) ; -#39260 = ORIENTED_EDGE ( 'NONE', *, *, #33062, .T. ) ; -#39261 = LINE ( 'NONE', #27239, #7672 ) ; -#39262 = EDGE_CURVE ( 'NONE', #11054, #37554, #25239, .T. ) ; -#39263 = ADVANCED_FACE ( 'NONE', ( #35285 ), #35896, .F. ) ; -#39264 = DIRECTION ( 'NONE', ( -0.9999999713660512324, 5.390041178539432571E-05, -0.0002331579774923554001 ) ) ; -#39265 = CARTESIAN_POINT ( 'NONE', ( -20.51978786315646630, 209.7094320854081104, 73.57086927696296641 ) ) ; -#39266 = PLANE ( 'NONE', #18401 ) ; -#39267 = ADVANCED_FACE ( 'NONE', ( #4216 ), #31659, .F. ) ; -#39268 = VERTEX_POINT ( 'NONE', #8322 ) ; -#39269 = CARTESIAN_POINT ( 'NONE', ( -2.618946344219839517, 189.8260961747400017, 103.4762868850679922 ) ) ; -#39270 = EDGE_CURVE ( 'NONE', #13086, #26477, #2273, .T. ) ; -#39271 = CARTESIAN_POINT ( 'NONE', ( 1.010702454887000057, 188.7857919939000055, 103.3724372331000154 ) ) ; -#39272 = CARTESIAN_POINT ( 'NONE', ( -36.07039677004318889, 191.0804747272522661, 106.8625041541564826 ) ) ; -#39273 = VERTEX_POINT ( 'NONE', #17698 ) ; -#39274 = AXIS2_PLACEMENT_3D ( 'NONE', #13535, #38264, #3908 ) ; -#39275 = CARTESIAN_POINT ( 'NONE', ( 5.696651444342763604, 176.3366686086371828, 152.9217692962174056 ) ) ; -#39276 = ORIENTED_EDGE ( 'NONE', *, *, #35575, .T. ) ; -#39277 = EDGE_LOOP ( 'NONE', ( #12914, #35398, #27389, #15593 ) ) ; -#39278 = AXIS2_PLACEMENT_3D ( 'NONE', #15504, #14904, #162 ) ; -#39279 = AXIS2_PLACEMENT_3D ( 'NONE', #23304, #4272, #26185 ) ; -#39280 = ORIENTED_EDGE ( 'NONE', *, *, #38976, .T. ) ; -#39281 = VERTEX_POINT ( 'NONE', #14456 ) ; -#39282 = PLANE ( 'NONE', #38243 ) ; -#39283 = CARTESIAN_POINT ( 'NONE', ( -20.00621178664383848, 200.3418422895910282, 95.02116311134024329 ) ) ; -#39284 = EDGE_LOOP ( 'NONE', ( #8905, #16812 ) ) ; -#39285 = CARTESIAN_POINT ( 'NONE', ( 25.99877579885739820, 118.1142373747355663, 87.25208168292309097 ) ) ; -#39286 = EDGE_LOOP ( 'NONE', ( #1994, #28712, #14406, #7942, #8866, #36037, #19037, #40308, #696, #28997, #19747, #38984, #1485, #26391, #39258, #25067, #12229, #33340, #34006, #17921, #5548, #18729, #38356, #21085, #31216, #7997, #30113, #1054 ) ) ; -#39287 = CARTESIAN_POINT ( 'NONE', ( 26.93751574495999890, 123.1570194396999938, 91.14867748372999756 ) ) ; -#39288 = CARTESIAN_POINT ( 'NONE', ( -23.01874678158921839, 213.5902083388722303, 75.57231541044464507 ) ) ; -#39290 = CARTESIAN_POINT ( 'NONE', ( 45.27414176412918323, 117.1178249393933726, 122.5865242744168313 ) ) ; -#39289 = FACE_OUTER_BOUND ( 'NONE', #7701, .T. ) ; -#39291 = ORIENTED_EDGE ( 'NONE', *, *, #12704, .T. ) ; -#39292 = VERTEX_POINT ( 'NONE', #5650 ) ; -#39294 = ADVANCED_FACE ( 'NONE', ( #27352 ), #8825, .F. ) ; -#39293 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #13208, #37730, #16057, #19713 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39295 = LINE ( 'NONE', #32565, #36079 ) ; -#39296 = ORIENTED_EDGE ( 'NONE', *, *, #5807, .T. ) ; -#39298 = AXIS2_PLACEMENT_3D ( 'NONE', #30536, #21331, #25009 ) ; -#39297 = CARTESIAN_POINT ( 'NONE', ( -37.67574118798827243, 118.8155645602721222, 87.29053938956874958 ) ) ; -#39299 = EDGE_CURVE ( 'NONE', #22051, #8671, #23263, .T. ) ; -#39300 = CARTESIAN_POINT ( 'NONE', ( 44.87380033613943198, 186.3390555487907818, 107.7765436004285249 ) ) ; -#39301 = CARTESIAN_POINT ( 'NONE', ( -22.78246931443002055, 153.3538690588717941, 97.63697319274456277 ) ) ; -#39302 = CARTESIAN_POINT ( 'NONE', ( 36.21553018070000007, 191.6173947560000101, 104.0137019355999968 ) ) ; -#39303 = EDGE_CURVE ( 'NONE', #28860, #22525, #10768, .T. ) ; -#39304 = VERTEX_POINT ( 'NONE', #36936 ) ; -#39305 = ORIENTED_EDGE ( 'NONE', *, *, #29580, .T. ) ; -#39306 = CARTESIAN_POINT ( 'NONE', ( 19.97967439332015260, 209.7095903781859647, 78.04647941570243574 ) ) ; -#39307 = EDGE_CURVE ( 'NONE', #30145, #27328, #33449, .T. ) ; -#39308 = CARTESIAN_POINT ( 'NONE', ( 14.46550548851596574, 188.1567857891429298, 103.0836035089503611 ) ) ; -#39309 = VERTEX_POINT ( 'NONE', #17900 ) ; -#39310 = EDGE_CURVE ( 'NONE', #12120, #17036, #38815, .T. ) ; -#39311 = VERTEX_POINT ( 'NONE', #36723 ) ; -#39312 = FACE_OUTER_BOUND ( 'NONE', #12263, .T. ) ; -#39313 = DIRECTION ( 'NONE', ( 0.1305261395647899503, 0.9660146223279441058, 0.2231113541237025599 ) ) ; -#39314 = ORIENTED_EDGE ( 'NONE', *, *, #8494, .T. ) ; -#39315 = CARTESIAN_POINT ( 'NONE', ( 19.85164219301282884, 148.9679372099747638, 184.3407892933917651 ) ) ; -#39316 = CARTESIAN_POINT ( 'NONE', ( -12.63810005728112529, 128.5846432257639549, 89.34357918520186104 ) ) ; -#39317 = CARTESIAN_POINT ( 'NONE', ( 20.23755415208006525, 153.0108581511728971, 94.96603911703473955 ) ) ; -#39318 = CARTESIAN_POINT ( 'NONE', ( 22.50176656077194792, 184.2919631277355847, 105.2686329678909516 ) ) ; -#39319 = ORIENTED_EDGE ( 'NONE', *, *, #3159, .F. ) ; -#39320 = FACE_OUTER_BOUND ( 'NONE', #21389, .T. ) ; -#39321 = CYLINDRICAL_SURFACE ( 'NONE', #9743, 5.999999999999998224 ) ; -#39322 = AXIS2_PLACEMENT_3D ( 'NONE', #36582, #39427, #36779 ) ; -#39323 = ORIENTED_EDGE ( 'NONE', *, *, #34137, .F. ) ; -#39324 = CARTESIAN_POINT ( 'NONE', ( 39.62249010496272206, 120.2151953967769060, 87.55390591794386523 ) ) ; -#39325 = CARTESIAN_POINT ( 'NONE', ( 15.49018687885868850, 159.2326036880797346, 96.40530980764773972 ) ) ; -#39326 = ORIENTED_EDGE ( 'NONE', *, *, #4350, .T. ) ; -#39327 = EDGE_LOOP ( 'NONE', ( #17093, #22755, #13708 ) ) ; -#39328 = ORIENTED_EDGE ( 'NONE', *, *, #15282, .T. ) ; -#39329 = ADVANCED_FACE ( 'NONE', ( #33042 ), #13391, .F. ) ; -#39330 = CARTESIAN_POINT ( 'NONE', ( -31.91217790952610756, 137.5486857473001407, 93.99357256101205849 ) ) ; -#39331 = ADVANCED_FACE ( 'NONE', ( #24484 ), #12090, .T. ) ; -#39332 = CARTESIAN_POINT ( 'NONE', ( 22.78189145297202245, 157.6320869253407011, 99.11031191928994133 ) ) ; -#39333 = EDGE_CURVE ( 'NONE', #5478, #11864, #21219, .T. ) ; -#39334 = CARTESIAN_POINT ( 'NONE', ( 14.84511533378980808, 136.7808273136949992, 91.56439923258074032 ) ) ; -#39335 = ORIENTED_EDGE ( 'NONE', *, *, #1544, .F. ) ; -#39336 = ORIENTED_EDGE ( 'NONE', *, *, #4964, .F. ) ; -#39337 = CARTESIAN_POINT ( 'NONE', ( -3.169906973560626895, 184.1222312815566795, 102.1628149875517408 ) ) ; -#39338 = ORIENTED_EDGE ( 'NONE', *, *, #25524, .T. ) ; -#39339 = EDGE_LOOP ( 'NONE', ( #39847, #16753, #35682, #18926 ) ) ; -#39340 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#39341 = CARTESIAN_POINT ( 'NONE', ( 2.544461029613999781, 209.0000000565999869, 73.61327619537000544 ) ) ; -#39342 = ORIENTED_EDGE ( 'NONE', *, *, #4429, .T. ) ; -#39343 = AXIS2_PLACEMENT_3D ( 'NONE', #13759, #1277, #1900 ) ; -#39344 = EDGE_CURVE ( 'NONE', #32791, #8772, #18302, .T. ) ; -#39345 = ORIENTED_EDGE ( 'NONE', *, *, #527, .T. ) ; -#39346 = EDGE_LOOP ( 'NONE', ( #2092, #19177, #32992 ) ) ; -#39347 = CARTESIAN_POINT ( 'NONE', ( -20.00000737806465523, 151.9608748777371545, 94.74793644920653435 ) ) ; -#39348 = CARTESIAN_POINT ( 'NONE', ( -35.32660592495999907, 192.4436246767999990, 103.7337747834999959 ) ) ; -#39350 = VECTOR ( 'NONE', #38157, 1000.000000000000000 ) ; -#39349 = DIRECTION ( 'NONE', ( 0.8142022563026397597, 0.000000000000000000, 0.5805813343810587446 ) ) ; -#39351 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #38706, #23799 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39352 = ORIENTED_EDGE ( 'NONE', *, *, #31578, .T. ) ; -#39353 = CARTESIAN_POINT ( 'NONE', ( -2.937264483321980979, 191.5260295968394928, 103.8719657109621295 ) ) ; -#39354 = ADVANCED_FACE ( 'NONE', ( #14865 ), #5032, .T. ) ; -#39355 = EDGE_LOOP ( 'NONE', ( #32949, #28038, #23957, #4659 ) ) ; -#39356 = CIRCLE ( 'NONE', #834, 5.500000707771594222 ) ; -#39357 = CARTESIAN_POINT ( 'NONE', ( 29.57849398920695094, 202.8601875879691931, 28.89883253923506246 ) ) ; -#39358 = DIRECTION ( 'NONE', ( 0.0006039748319384539597, 1.295170900108887039E-14, 0.9999998176071845934 ) ) ; -#39359 = FACE_OUTER_BOUND ( 'NONE', #33216, .T. ) ; -#39360 = ORIENTED_EDGE ( 'NONE', *, *, #12790, .T. ) ; -#39361 = CARTESIAN_POINT ( 'NONE', ( 0.6972021641108145928, 188.6142014775118128, 103.1975219709808727 ) ) ; -#39362 = CARTESIAN_POINT ( 'NONE', ( 16.56127283256421734, 122.5154997165936521, 174.6307753585464582 ) ) ; -#39363 = LINE ( 'NONE', #23645, #27504 ) ; -#39364 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #15098, #5885, #12232, #27397, #39616, #11631 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 4 ), - ( 0.000000000000000000, 0.3333337457304020313, 0.6666668737132039890, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39365 = CARTESIAN_POINT ( 'NONE', ( -43.21068176890801027, 118.0105506722982369, 104.8630716126889126 ) ) ; -#39366 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #39401, #24097, #30433, #2426 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 3.069965523459847745, 3.070702649259505090 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9999999547204634354, 0.9999999547204634354, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#39367 = EDGE_LOOP ( 'NONE', ( #9780, #11887, #31176, #22383, #15102, #5830 ) ) ; -#39368 = EDGE_CURVE ( 'NONE', #10860, #29915, #8733, .T. ) ; -#39369 = DIRECTION ( 'NONE', ( -0.0006039748319380813194, -1.041532381956747772E-14, -0.9999998176071845934 ) ) ; -#39370 = CARTESIAN_POINT ( 'NONE', ( 1.637629675866425272, 189.3131617310740751, 103.7741813652591247 ) ) ; -#39371 = CARTESIAN_POINT ( 'NONE', ( -28.46687737262882578, 130.4181374544887717, 90.29266601121980784 ) ) ; -#39372 = EDGE_LOOP ( 'NONE', ( #1529, #8821, #3021, #37732 ) ) ; -#39373 = CARTESIAN_POINT ( 'NONE', ( -22.49860963037942341, 157.8259877977732515, 99.01136938669759502 ) ) ; -#39374 = VERTEX_POINT ( 'NONE', #33238 ) ; -#39375 = ORIENTED_EDGE ( 'NONE', *, *, #5050, .F. ) ; -#39376 = CARTESIAN_POINT ( 'NONE', ( -25.91135228618000141, 191.2905648374000123, 103.9456188779000030 ) ) ; -#39377 = CARTESIAN_POINT ( 'NONE', ( -5.668403886066550434, 185.3448273526182959, 105.0123327472739163 ) ) ; -#39378 = CARTESIAN_POINT ( 'NONE', ( -28.46590577390798771, 128.0194952136861275, 91.79150371819520160 ) ) ; -#39379 = AXIS2_PLACEMENT_3D ( 'NONE', #34010, #3333, #10092 ) ; -#39380 = CARTESIAN_POINT ( 'NONE', ( 6.033058578775539083, 135.0436587837527043, 90.99612091764669231 ) ) ; -#39381 = EDGE_LOOP ( 'NONE', ( #12952, #32927, #11786, #39483 ) ) ; -#39382 = CARTESIAN_POINT ( 'NONE', ( 12.63493752644979118, 130.4235786262125032, 90.26909773778339741 ) ) ; -#39383 = VECTOR ( 'NONE', #26915, 1000.000000000000114 ) ; -#39384 = LINE ( 'NONE', #32659, #12687 ) ; -#39385 = CARTESIAN_POINT ( 'NONE', ( 44.64491191134371917, 188.7542347311224376, 105.7690686227471559 ) ) ; -#39386 = EDGE_CURVE ( 'NONE', #4624, #26260, #37811, .T. ) ; -#39387 = CARTESIAN_POINT ( 'NONE', ( -43.28155790953776005, 183.2190586267475680, 137.8991672664744499 ) ) ; -#39388 = DIRECTION ( 'NONE', ( -0.0004270746993281996219, -0.7071067811865993091, -0.7071066522152992251 ) ) ; -#39389 = EDGE_CURVE ( 'NONE', #34119, #32373, #12712, .T. ) ; -#39390 = CARTESIAN_POINT ( 'NONE', ( -26.69810905257040901, 110.6131156702000027, 87.28390928083501876 ) ) ; -#39391 = EDGE_CURVE ( 'NONE', #23133, #35236, #28735, .T. ) ; -#39392 = CARTESIAN_POINT ( 'NONE', ( 21.51436008770080832, 115.4748947878985916, 90.25479070481955546 ) ) ; -#39393 = EDGE_LOOP ( 'NONE', ( #18084, #9095, #30679, #22578 ) ) ; -#39394 = CARTESIAN_POINT ( 'NONE', ( 3.639365772014297118, 144.1947402466412598, 93.04856585393400792 ) ) ; -#39395 = CARTESIAN_POINT ( 'NONE', ( -32.27067804272475371, 136.1434003866072260, 91.10359260027512107 ) ) ; -#39396 = EDGE_CURVE ( 'NONE', #29827, #21279, #18695, .T. ) ; -#39397 = ORIENTED_EDGE ( 'NONE', *, *, #28070, .F. ) ; -#39398 = LINE ( 'NONE', #2420, #12136 ) ; -#39399 = ORIENTED_EDGE ( 'NONE', *, *, #6350, .T. ) ; -#39400 = ADVANCED_FACE ( 'NONE', ( #9938 ), #35524, .F. ) ; -#39401 = CARTESIAN_POINT ( 'NONE', ( 16.23201905896638308, 152.0606143167149185, 181.0564827348360382 ) ) ; -#39402 = CARTESIAN_POINT ( 'NONE', ( -25.49734792034996289, 118.8155664120999973, 94.28318532801205265 ) ) ; -#39403 = CARTESIAN_POINT ( 'NONE', ( 25.99874167938696345, 118.1131156663084738, 87.25205387058410622 ) ) ; -#39404 = ORIENTED_EDGE ( 'NONE', *, *, #22403, .F. ) ; -#39405 = DIRECTION ( 'NONE', ( -0.0006039748319385907860, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#39406 = VECTOR ( 'NONE', #20261, 1000.000000000000227 ) ; -#39407 = CLOSED_SHELL ( 'NONE', ( #35723, #32215, #14115, #26398, #25815, #893, #2338, #10300, #26874, #27062, #25346, #27619, #38740, #8210, #38139, #14281, #13518, #27353, #6361, #38212, #9559, #1892, #21183, #33779, #17719, #14810, #2602, #33907, #12918, #32846, #30203, #8532, #19138, #351, #5147, #7643, #2400, #9247, #2911, #22759, #83, #36730, #3032, #26966, #29000, #20004, #29621, #37147, #3893, #8853, #15760, #16847, #19818, #9463, #15988, #7859, #24297, #9530, #32803, #26314, #21476, #11112, #31432, #36411, #10157, #19861, #2128, #17949, #9885, #33345, #24047, #35316, #20900, #14027, #24662, #21528, #19309, #40051, #2661, #17600, #37245, #9320, #5522, #35890, #16905, #16450, #14182, #2040, #28396, #28324, #34995, #1050, #515, #29808, #27152, #4162, #10535, #15899, #29700, #6181, #33913, #21668, #22349, #16325, #25852, #13495, #14732, #29018, #40285, #13570, #9926, #16139, #35685, #19365, #16783, #38071, #22016, #15103, #4891, #16106, #22780, #10208, #8987, #26777, #29085, #33906, #33306, #20557, #27041, #4962, #38786, #34574, #11298, #24840, #17743, #38735, #19269, #36121, #2087, #6967, #13278, #28409, #7864, #37053, #1465, #29136, #25621, #28299, #39624, #26042, #6582, #30368, #21001, #36826, #9901, #33632, #2361, #11207, #27988, #12417, #3312, #2296, #21422, #29694, #9424, #1560, #17923, #26395, #20312, #19270, #5380, #8634, #13452, #27495, #13517, #670, #39025, #37151, #2399, #31576, #32264, #7357, #23074, #24679, #4809, #38523, #23160, #36782, #40280, #26139, #31348, #22532, #32389, #2702, #5802, #19897, #15569, #18338, #7313, #14691, #8696, #31478, #6071, #7000, #29970, #7779, #23534, #15788, #39212, #38773, #13601, #38793, #20139, #3025, #22165, #16496, #2728, #39329, #2892, #33699, #8878, #13978, #28832, #25806, #36216, #3003, #3529, #2640, #38238, #9329, #35356, #4116, #30706, #26836, #15554, #10395, #39885, #28654, #35716, #4378, #5238, #29353, #8469, #8547, #31867, #25382, #30074, #6087, #14177, #38861, #79, #9051, #22158, #36423, #4862, #6297, #39761, #13341, #4311, #21999, #32842, #22018, #15315, #32441, #7739, #39294, #1498, #10152, #23438, #29646, #16587, #19554, #21388, #25871, #38825, #21928, #32850, #10609, #17279, #23139, #27202, #35634, #13371, #4483, #34943, #13955, #5011, #24022, #25157, #33254, #11484, #34255, #17700, #33419, #2800, #16913, #35736, #33131, #37652, #32391, #1837, #35084, #3850, #1846, #33302, #6314, #17789, #20565, #27665, #10900, #22497, #1129, #29489, #5633, #31665, #17598, #21845, #6762, #2597, #16472, #12753, #25764, #10295, #7549, #22942, #1782, #28522, #12322, #25435, #5140, #26038, #3610, #1606, #5571, #40109, #6506, #25022, #16280, #4994, #25174, #36452, #29858, #20568, #34358, #33625, #25392, #25992, #20089, #26934, #15553, #16768, #14268, #24848, #19127, #39130, #15766, #8364, #8569, #25398, #10841, #25389, #33256, #28082, #35137, #28957, #18432, #37338, #36502, #31817, #22584, #10063, #3793, #16084, #6689, #7784, #38985, #36924, #4451, #29868, #11125, #36136, #18575, #5797, #3381, #6483, #3987, #3800, #9762, #4268, #18891, #26127, #26572, #24001, #34635, #38899, #35186, #34918, #30648, #29583, #18172, #28980, #4736, #13017, #231, #12630, #34809, #26677, #34817, #31916, #36752, #30558, #32538, #22669, #27065, #28349, #18307, #9382, #30425, #11157, #12826, #31078, #40366, #32523, #39584, #11384, #18655, #38566, #29496, #29943, #15411, #1925, #23697, #10290, #12319, #19254, #36971, #37387, #12571, #4767, #7883, #3569, #19363, #15140, #19552, #20518, #24405, #18154, #5529, #40288, #1792, #19535, #36589, #13057, #28669, #22070, #2526, #19122, #9234, #12931, #2185, #26466, #33815, #24431, #13606, #24916, #24244, #33590, #34844, #25123, #8312, #13833, #38745, #26129, #21328, #9788, #6995, #33630, #33022, #6665, #8347, #9637, #2425, #32119, #38696, #14818, #6134, #26299, #21783, #5624, #23648, #25312, #221, #36115, #34898, #28749, #6011, #991, #567, #10064, #16898, #30845, #24502, #32680, #34675, #8834, #36020, #24889, #33544, #3166, #17046, #1404, #18550, #11588, #20061, #16298, #2164, #25212, #3126, #24176, #11596, #30412, #39816, #29261, #13156, #23129, #26321, #29723, #18113, #17267, #36018, #39812, #28254, #24144, #20513, #29171, #7944, #36537, #7590, #31614, #14820, #21876, #32043, #1662, #33860, #9284, #4017, #4269, #649, #17749, #23056, #718, #3909, #32575, #26878, #32461, #7633, #10069, #30798, #27257, #9333, #38384, #20277, #11169, #23525, #10444, #21568, #812, #9991, #30824, #12881, #6346, #29084, #23392, #35269, #12624, #15144, #24524, #7253, #11210, #14959, #39592, #8413, #34865, #12969, #4406, #17869, #36432, #5640, #3076, #1557, #21436, #26545, #9072, #40266, #14030, #17277, #12583, #28515, #38606, #21056, #39716, #29778, #8332, #394, #23388, #9430, #23581, #10859, #35281, #25180, #16850, #37204, #3809, #36706, #7969, #31567, #25741, #9370, #9555, #36256, #38602, #12623, #31438, #15763, #35026, #24482, #10801, #38986, #12530, #5095, #6851, #12679, #34095, #28604, #3160, #26729, #19124, #16750, #22161, #26604, #31612, #34044, #31639, #26350, #16382, #5810, #30649, #10387, #17503, #3522, #344, #10255, #7270, #19700, #31377, #757, #8449, #14535, #4036, #28611, #7598, #22309, #8680, #12399, #905, #22888, #29641, #20713, #31717, #5057, #992, #16845, #19191, #32089, #10384, #13247, #7508, #28123, #14803, #36926, #34534, #24660, #29525, #15943, #1553, #10660, #21324, #24440, #20866, #24801, #21292, #21836, #20577, #1320, #16367, #10014, #179, #2651, #17813, #15167, #15199, #15732, #21830, #39267, #14444, #27514, #3671, #39474, #17609, #20630, #8963, #30151, #34977, #36595, #24856, #10792, #5806, #3117, #8690, #1379, #2860, #8153, #9097, #20505, #1268, #36055, #38601, #23504, #11954, #31391, #22157, #30973, #31019, #33927, #12526, #1883, #36468, #37728, #18155, #34848, #40055, #31382, #36556, #7542, #32046, #10723, #39496, #21182, #620, #19087, #28802, #14122, #9332, #19770, #4567, #30607, #6845, #8786, #22257, #15999, #35920, #27466, #6260, #7927, #25630, #10206, #30416, #31243, #15675, #34417, #23065, #2264, #20898, #15631, #33246, #40287, #8168, #28528, #24346, #15585, #27392, #37826, #32605, #5839, #20913, #19458, #9374, #23256, #16153, #17186, #13223, #28063, #13836, #25678, #20007, #5862, #14978, #10150, #37931, #16327, #37672, #25282, #18204, #11389, #35127, #14758, #34403, #35498, #21184, #24665, #34757, #19217, #32838, #19297, #17973, #15416, #31220, #293, #23359, #14681, #32252, #10993, #22887, #23117, #39263, #34232, #17040, #5108, #11774, #26175, #34766, #27544, #21770, #31716, #20230, #25910, #17095, #20684, #6915, #27179, #2402, #6572, #17133, #33587, #32147, #15848, #1832, #39804, #22988, #32307, #14902, #34767, #39331, #1934, #26199, #37620, #25293, #34804, #23082, #12768, #9838, #11035, #24300, #11630, #37933, #8586, #8605, #17283, #4778, #4398, #1273, #4124, #37392, #21040, #12103, #17226, #13648, #32308, #15242, #39354, #17547, #18943, #5893, #37432, #39932, #30676, #32970, #30034, #4420, #15324, #39251, #35182, #11027, #6077, #31104, #22307, #32760, #23906, #29861, #8117, #37566, #6536, #32609, #15325, #34362, #28804, #10754, #9895, #15509, #11325, #1310, #28775, #29743, #12004, #33854, #6760, #10439, #1124, #35827, #12841, #25765, #10848, #21503, #30949, #17319, #39400, #311, #8684, #27627, #14545, #10827, #30091, #23482, #40147, #16451, #15332, #299, #949, #1720, #2813, #31561, #11787, #7635, #35657, #12158, #4761, #7992, #18980, #31198, #30896, #6081, #894, #12682, #12653, #24893, #20756, #37373, #22392, #37067, #33392, #2697, #15285, #36869, #39491, #24573, #14312, #37110, #26763, #8582, #8867, #13877, #25530, #35035, #17647, #8492, #36829, #19506, #35776, #6532, #2414, #7605, #15407, #39124, #37982, #20266, #21881, #6539, #33259, #14128, #33774, #586, #2601, #33921, #11176, #9602, #20816, #23921, #32035, #5276, #8123, #2350, #8682, #17652, #720, #4777, #16730, #34384, #11524, #8315, #29441, #14861, #12872, #26871, #18706, #22667, #24955, #13793, #21924, #14236, #22026, #23985, #24674, #532, #1600, #29082, #32082, #3384, #6714, #12401, #3161, #23554, #29028, #20763, #21405, #2889, #31803, #25787, #15053, #5610, #24057, #8152, #22071, #5473, #28704, #16867, #19076, #23294, #5606, #31897, #2473, #32805, #11082, #467, #28653, #30129, #21519, #28435, #2126, #2309, #35493, #8919, #767, #28934, #13389, #30274, #20470, #30131, #10935, #29865, #16373, #20810, #21652, #4549, #33777, #10582, #25455, #26179, #32896, #6213, #29414, #13108, #28605, #6746, #1740, #17985, #32890, #33794, #32726, #22912, #27861, #31860, #73, #25438, #18796, #25573, #26184, #3119, #20442, #21878, #3297, #39535, #10045, #21475, #38714, #18252, #40411, #37596, #38251, #38336, #1263, #37780, #18388, #25579, #2817, #1698, #16074, #4859, #27670, #3208, #11436, #19868, #27448, #28580, #7311, #39910, #32860, #14874, #39718, #30927, #4683, #39738, #11872, #9541, #34770, #37739, #31738, #5899, #12394, #11460, #32193, #40357, #25490, #28179, #30354, #4578, #22850, #18345, #38894, #27172, #3766, #2407, #13741, #11689, #15946, #23036, #1842, #29248, #31811, #35042, #32887, #37648, #36379, #25820, #15270, #27686, #36369, #21937, #18479, #6793, #33585, #19042, #33770, #37665, #9186, #39442, #31989, #3183, #38725, #28019, #11628 ) ) ; -#39408 = CARTESIAN_POINT ( 'NONE', ( -14.78542622577100119, 175.8938623147257374, 100.7833030093998303 ) ) ; -#39409 = CARTESIAN_POINT ( 'NONE', ( -12.63530928661225694, 130.1704632573847391, 92.55260706672754623 ) ) ; -#39410 = CONICAL_SURFACE ( 'NONE', #4149, 5.000000000367158748, 0.7853981634347277918 ) ; -#39411 = PLANE ( 'NONE', #9150 ) ; -#39412 = CARTESIAN_POINT ( 'NONE', ( 35.56355292849995209, 196.5784392899758188, 103.8536238432048293 ) ) ; -#39413 = ORIENTED_EDGE ( 'NONE', *, *, #12967, .F. ) ; -#39414 = EDGE_CURVE ( 'NONE', #9171, #32426, #35828, .T. ) ; -#39415 = CARTESIAN_POINT ( 'NONE', ( 39.08686004016000481, 119.9154263329000116, 87.44177325903000053 ) ) ; -#39416 = CARTESIAN_POINT ( 'NONE', ( -5.713599249648267708, 177.7896720772441199, 100.7023539561611614 ) ) ; -#39417 = DIRECTION ( 'NONE', ( -0.0006039748319379697550, -1.040973592985965549E-14, -0.9999998176071845934 ) ) ; -#39418 = ORIENTED_EDGE ( 'NONE', *, *, #8406, .F. ) ; -#39419 = FACE_OUTER_BOUND ( 'NONE', #6993, .T. ) ; -#39420 = ORIENTED_EDGE ( 'NONE', *, *, #11819, .T. ) ; -#39421 = CARTESIAN_POINT ( 'NONE', ( -5.669580876058052610, 184.0115085080416861, 102.6519039031884546 ) ) ; -#39422 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #11243, #36390, #14520, #23510 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39423 = CARTESIAN_POINT ( 'NONE', ( -42.06110200389634457, 121.7334112014321903, 91.09980221838324610 ) ) ; -#39424 = PLANE ( 'NONE', #22240 ) ; -#39425 = CARTESIAN_POINT ( 'NONE', ( -28.65658060520999939, 124.4956071873000099, 91.63016954471000020 ) ) ; -#39426 = CARTESIAN_POINT ( 'NONE', ( -19.99999816303952471, 191.5261162992163690, 103.8822987450886046 ) ) ; -#39427 = DIRECTION ( 'NONE', ( -0.9999998176071845934, -1.540743955509789367E-33, 0.0006039748319385908944 ) ) ; -#39428 = CARTESIAN_POINT ( 'NONE', ( -25.88782727049006382, 209.7107743092203691, 73.19639644311165227 ) ) ; -#39429 = CARTESIAN_POINT ( 'NONE', ( 19.46059643144436535, 126.3442427331793141, 175.5385488862945635 ) ) ; -#39430 = CARTESIAN_POINT ( 'NONE', ( -31.85495644188857156, 155.6854141731122638, 196.1447383889810396 ) ) ; -#39431 = CARTESIAN_POINT ( 'NONE', ( 38.65125684626000435, 119.3002203842000029, 90.41791267192000703 ) ) ; -#39432 = CIRCLE ( 'NONE', #24477, 2.000000000000011546 ) ; -#39433 = AXIS2_PLACEMENT_3D ( 'NONE', #16285, #18941, #16479 ) ; -#39434 = ORIENTED_EDGE ( 'NONE', *, *, #1555, .F. ) ; -#39435 = DIRECTION ( 'NONE', ( -0.0005884949961247159774, 0.2249510543439059984, -0.9743698870671263501 ) ) ; -#39436 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -1.785014166949466476E-16, -0.0006039748319386109522 ) ) ; -#39437 = DIRECTION ( 'NONE', ( 0.0001408404234837714198, -0.2255194953475184727, 0.9742386449849829155 ) ) ; -#39438 = CARTESIAN_POINT ( 'NONE', ( -21.16096952440062751, 115.7114218036305715, 87.28056498737410607 ) ) ; -#39439 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #38220, #16336, #12472, #12676 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 4.205800693865505480, 4.525887359915200747 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9914802524726262778, 0.9914802524726262778, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#39440 = EDGE_CURVE ( 'NONE', #11353, #14571, #943, .T. ) ; -#39441 = AXIS2_PLACEMENT_3D ( 'NONE', #36792, #5912, #12447 ) ; -#39442 = ADVANCED_FACE ( 'NONE', ( #13198 ), #25625, .F. ) ; -#39443 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #12083, #9415, #28230, #198, #37022, #34913, #990, #32289, #15926, #22695 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39444 = DIRECTION ( 'NONE', ( -0.0005884949961198485601, 0.2249510543439084687, -0.9743698870671259060 ) ) ; -#39445 = VERTEX_POINT ( 'NONE', #6242 ) ; -#39446 = ORIENTED_EDGE ( 'NONE', *, *, #36729, .T. ) ; -#39447 = CARTESIAN_POINT ( 'NONE', ( -1.882816931228917801, 189.0601662987910174, 103.3020393482379831 ) ) ; -#39448 = ORIENTED_EDGE ( 'NONE', *, *, #33343, .T. ) ; -#39449 = CARTESIAN_POINT ( 'NONE', ( -23.36147737338983177, 177.1885760160717211, 101.0873909945826341 ) ) ; -#39450 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#39451 = ORIENTED_EDGE ( 'NONE', *, *, #1122, .T. ) ; -#39452 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921582961, 0.2249510932971575394 ) ) ; -#39453 = CARTESIAN_POINT ( 'NONE', ( -38.19787524881999730, 118.4369483671000012, 87.84294828311999481 ) ) ; -#39454 = ORIENTED_EDGE ( 'NONE', *, *, #27943, .T. ) ; -#39455 = CARTESIAN_POINT ( 'NONE', ( -41.90907465551327249, 121.4486244169956279, 92.84837845933365941 ) ) ; -#39456 = EDGE_LOOP ( 'NONE', ( #20604, #27139, #22140, #25810, #26097 ) ) ; -#39457 = CARTESIAN_POINT ( 'NONE', ( -44.98855281372307502, 77.27946979429631824, 312.5857197240631535 ) ) ; -#39458 = CARTESIAN_POINT ( 'NONE', ( -15.99974174651862313, 174.5231975350379514, 99.95452847233616467 ) ) ; -#39459 = DIRECTION ( 'NONE', ( -0.9999998268368094356, -0.0001323825909798406200, 0.0005734118944141585296 ) ) ; -#39460 = DIRECTION ( 'NONE', ( 0.0002393071182785538528, 0.2252352986010040803, -0.9743043687658491381 ) ) ; -#39461 = APPROVAL_PERSON_ORGANIZATION ( #30863, #30192, #37194 ) ; -#39462 = ORIENTED_EDGE ( 'NONE', *, *, #11701, .T. ) ; -#39463 = EDGE_CURVE ( 'NONE', #585, #14957, #14036, .T. ) ; -#39464 = CARTESIAN_POINT ( 'NONE', ( -25.84141903064000090, 190.0987420465000071, 103.9446973517000004 ) ) ; -#39465 = CARTESIAN_POINT ( 'NONE', ( 0.5732737145059999539, 188.9926135734999946, 103.6981316242000162 ) ) ; -#39466 = AXIS2_PLACEMENT_3D ( 'NONE', #17494, #39781, #18098 ) ; -#39467 = VECTOR ( 'NONE', #23904, 1000.000000000000114 ) ; -#39468 = DIRECTION ( 'NONE', ( -0.0005734119072320679154, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#39469 = CARTESIAN_POINT ( 'NONE', ( 26.02962131058879791, 120.6627111924913009, 90.57329420178653834 ) ) ; -#39470 = CONICAL_SURFACE ( 'NONE', #21866, 2.503114778588952483, 0.7853981634133299083 ) ; -#39471 = VERTEX_POINT ( 'NONE', #18904 ) ; -#39472 = LINE ( 'NONE', #14350, #7416 ) ; -#39473 = ORIENTED_EDGE ( 'NONE', *, *, #848, .F. ) ; -#39474 = ADVANCED_FACE ( 'NONE', ( #31401 ), #25277, .F. ) ; -#39475 = VERTEX_POINT ( 'NONE', #28538 ) ; -#39476 = LINE ( 'NONE', #24178, #21087 ) ; -#39478 = ORIENTED_EDGE ( 'NONE', *, *, #13662, .F. ) ; -#39477 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38971, #13832, #17282, #10379 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39479 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #22228, #12400, #22423, #13217, #9344, #22628, #519, #19333, #6650, #25702, #37952 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000233147, 0.3750000000000660583, 0.4375000000000756617, 0.4687500000000567324, 0.5000000000000377476, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39480 = CARTESIAN_POINT ( 'NONE', ( -31.91217790274522415, 174.0284854049060073, 102.4155994567338155 ) ) ; -#39481 = DIRECTION ( 'NONE', ( 0.0004161288024777938348, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#39482 = CARTESIAN_POINT ( 'NONE', ( 6.272186697316835868, 148.2050572955672862, 96.43072783368462808 ) ) ; -#39483 = ORIENTED_EDGE ( 'NONE', *, *, #36599, .F. ) ; -#39484 = FACE_OUTER_BOUND ( 'NONE', #31208, .T. ) ; -#39485 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #21227, #9162, #40417, #3005 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 4.854478445487932390E-07, 0.0007736064448116313549 ), - .UNSPECIFIED. ) ; -#39486 = CARTESIAN_POINT ( 'NONE', ( -5.670692261820892810, 181.9297596791197975, 101.9891440848351181 ) ) ; -#39487 = ORIENTED_EDGE ( 'NONE', *, *, #30743, .F. ) ; -#39488 = CARTESIAN_POINT ( 'NONE', ( 28.53189929785749968, 124.6104551036400068, 91.48497847473261402 ) ) ; -#39489 = CARTESIAN_POINT ( 'NONE', ( 20.00162197757413196, 118.5784925787999953, 90.25570436073203950 ) ) ; -#39490 = EDGE_CURVE ( 'NONE', #25663, #24195, #14430, .T. ) ; -#39491 = ADVANCED_FACE ( 'NONE', ( #504 ), #38136, .T. ) ; -#39493 = FACE_OUTER_BOUND ( 'NONE', #10803, .T. ) ; -#39492 = CARTESIAN_POINT ( 'NONE', ( -17.99970575250096516, 135.0477809104833966, 91.35518170534504634 ) ) ; -#39494 = CC_DESIGN_SECURITY_CLASSIFICATION ( #26440, ( #37519 ) ) ; -#39495 = CIRCLE ( 'NONE', #29709, 6.500000000118505206 ) ; -#39496 = ADVANCED_FACE ( 'NONE', ( #7041 ), #36884, .F. ) ; -#39497 = VERTEX_POINT ( 'NONE', #13787 ) ; -#39498 = FACE_OUTER_BOUND ( 'NONE', #21828, .T. ) ; -#39499 = AXIS2_PLACEMENT_3D ( 'NONE', #27141, #34235, #6044 ) ; -#39500 = ORIENTED_EDGE ( 'NONE', *, *, #31380, .T. ) ; -#39501 = EDGE_CURVE ( 'NONE', #31188, #6720, #4884, .T. ) ; -#39502 = VECTOR ( 'NONE', #24753, 1000.000000000000000 ) ; -#39503 = ORIENTED_EDGE ( 'NONE', *, *, #8111, .F. ) ; -#39504 = CARTESIAN_POINT ( 'NONE', ( -28.25630607419124019, 186.6792666402525640, 104.3077506217996131 ) ) ; -#39505 = CARTESIAN_POINT ( 'NONE', ( -20.51863885680050359, 209.7097602209678939, 75.57089512796630970 ) ) ; -#39506 = DIRECTION ( 'NONE', ( 0.0001408278996873626944, -0.2255194025968528804, 0.9742386664569731014 ) ) ; -#39507 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7071067167008887600, 0.7071068456722005013 ) ) ; -#39508 = ORIENTED_EDGE ( 'NONE', *, *, #256, .T. ) ; -#39509 = ORIENTED_EDGE ( 'NONE', *, *, #27949, .F. ) ; -#39510 = CARTESIAN_POINT ( 'NONE', ( -39.69707251849492025, 114.7084905227599450, 151.9490217007608805 ) ) ; -#39511 = CARTESIAN_POINT ( 'NONE', ( 25.90705744506000485, 121.8343370017999945, 87.93600534850999395 ) ) ; -#39512 = ORIENTED_EDGE ( 'NONE', *, *, #24829, .T. ) ; -#39513 = EDGE_LOOP ( 'NONE', ( #14418, #15308, #1406, #7564 ) ) ; -#39514 = CARTESIAN_POINT ( 'NONE', ( 3.069989720717164694, 190.8891895217091417, 106.8081807335384212 ) ) ; -#39515 = ORIENTED_EDGE ( 'NONE', *, *, #23409, .T. ) ; -#39516 = CARTESIAN_POINT ( 'NONE', ( 18.00147123748612898, 176.9877420030217365, 103.0686512058572788 ) ) ; -#39517 = DIRECTION ( 'NONE', ( -0.0005884949961206531466, 0.2249510543439048327, -0.9743698870671267942 ) ) ; -#39518 = AXIS2_PLACEMENT_3D ( 'NONE', #15561, #28054, #24 ) ; -#39519 = AXIS2_PLACEMENT_3D ( 'NONE', #18147, #38469, #26025 ) ; -#39520 = DIRECTION ( 'NONE', ( -0.0006039748319368648446, -1.157494911401840404E-14, -0.9999998176071845934 ) ) ; -#39521 = CARTESIAN_POINT ( 'NONE', ( 3.720974031714894714, 145.7221224061216844, 93.29327717358505367 ) ) ; -#39522 = AXIS2_PLACEMENT_3D ( 'NONE', #28946, #35049, #923 ) ; -#39523 = EDGE_CURVE ( 'NONE', #12603, #19108, #20282, .T. ) ; -#39524 = ORIENTED_EDGE ( 'NONE', *, *, #29027, .T. ) ; -#39525 = AXIS2_PLACEMENT_3D ( 'NONE', #9115, #27938, #34041 ) ; -#39526 = PLANE ( 'NONE', #31022 ) ; -#39527 = FACE_OUTER_BOUND ( 'NONE', #39540, .T. ) ; -#39528 = EDGE_CURVE ( 'NONE', #36287, #4731, #909, .T. ) ; -#39529 = EDGE_LOOP ( 'NONE', ( #17618, #30255, #241, #1234 ) ) ; -#39530 = FACE_OUTER_BOUND ( 'NONE', #37278, .T. ) ; -#39531 = EDGE_CURVE ( 'NONE', #12675, #35226, #31964, .T. ) ; -#39532 = EDGE_CURVE ( 'NONE', #34118, #21690, #16603, .T. ) ; -#39534 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971542088 ) ) ; -#39533 = CARTESIAN_POINT ( 'NONE', ( 13.05874798126192715, 135.0013260624673421, 90.81254608138048923 ) ) ; -#39535 = ADVANCED_FACE ( 'NONE', ( #16642 ), #29141, .F. ) ; -#39536 = ORIENTED_EDGE ( 'NONE', *, *, #1186, .T. ) ; -#39537 = VERTEX_POINT ( 'NONE', #26076 ) ; -#39538 = DIRECTION ( 'NONE', ( -0.0005884949961250434064, 0.2249510543439061094, -0.9743698870671263501 ) ) ; -#39539 = EDGE_CURVE ( 'NONE', #25223, #28955, #38517, .T. ) ; -#39540 = EDGE_LOOP ( 'NONE', ( #29769, #36373, #29720, #33190 ) ) ; -#39541 = CARTESIAN_POINT ( 'NONE', ( 3.173484558985000259, 209.3707192315999919, 76.22248684881000713 ) ) ; -#39542 = AXIS2_PLACEMENT_3D ( 'NONE', #35867, #7674, #20134 ) ; -#39543 = CARTESIAN_POINT ( 'NONE', ( 36.89975980456834037, 191.2518832777249997, 106.3227935573031289 ) ) ; -#39544 = CARTESIAN_POINT ( 'NONE', ( 29.05503365078199707, 110.6131156702000027, 89.75023623571587450 ) ) ; -#39545 = CARTESIAN_POINT ( 'NONE', ( -10.03744067672847606, 144.0996504514500884, 93.44016182556791250 ) ) ; -#39546 = ORIENTED_EDGE ( 'NONE', *, *, #25384, .T. ) ; -#39547 = AXIS2_PLACEMENT_3D ( 'NONE', #7158, #38633, #6958 ) ; -#39548 = ORIENTED_EDGE ( 'NONE', *, *, #444, .T. ) ; -#39549 = DIRECTION ( 'NONE', ( 0.9999999713660511214, -5.390041178570922545E-05, 0.0002331579774915894113 ) ) ; -#39550 = VERTEX_POINT ( 'NONE', #10538 ) ; -#39551 = ORIENTED_EDGE ( 'NONE', *, *, #1479, .T. ) ; -#39552 = CARTESIAN_POINT ( 'NONE', ( 18.00176548498901141, 129.6183187699430164, 92.64570812446640957 ) ) ; -#39553 = DIRECTION ( 'NONE', ( 0.0006039748319386249384, 0.000000000000000000, 0.9999998176071845934 ) ) ; -#39554 = CYLINDRICAL_SURFACE ( 'NONE', #36331, 2.500000000000002220 ) ; -#39555 = CARTESIAN_POINT ( 'NONE', ( 2.510969621544000052, 209.3808403806999934, 73.56099024588000646 ) ) ; -#39556 = CARTESIAN_POINT ( 'NONE', ( -2.437851586972803020, 194.2771770550226336, 102.8997479777824537 ) ) ; -#39557 = CIRCLE ( 'NONE', #38911, 4.500000040501689114 ) ; -#39558 = ORIENTED_EDGE ( 'NONE', *, *, #24619, .F. ) ; -#39559 = ORIENTED_EDGE ( 'NONE', *, *, #23963, .F. ) ; -#39560 = CARTESIAN_POINT ( 'NONE', ( 5.666638401078976983, 126.6906950807946686, 89.41150218689625717 ) ) ; -#39561 = CARTESIAN_POINT ( 'NONE', ( -35.96708566011999864, 191.9661441250000280, 104.3089233010000072 ) ) ; -#39562 = CARTESIAN_POINT ( 'NONE', ( 36.57765404231000161, 191.8474788542000056, 104.5077614389000047 ) ) ; -#39563 = ORIENTED_EDGE ( 'NONE', *, *, #25583, .T. ) ; -#39564 = CARTESIAN_POINT ( 'NONE', ( -25.50087462243000047, 120.6586440635999935, 88.03806651040000020 ) ) ; -#39565 = EDGE_LOOP ( 'NONE', ( #19634, #39882, #23417, #11534 ) ) ; -#39566 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319384538513 ) ) ; -#39567 = CARTESIAN_POINT ( 'NONE', ( -40.09967836303732014, 190.2663693115700880, 106.6916270309068580 ) ) ; -#39568 = ORIENTED_EDGE ( 'NONE', *, *, #36604, .F. ) ; -#39569 = CARTESIAN_POINT ( 'NONE', ( -6.037602912117780996, 134.6461054605402410, 93.47636828169308387 ) ) ; -#39570 = DIRECTION ( 'NONE', ( -0.7075229308291650643, 0.000000000000000000, -0.7066903864854172657 ) ) ; -#39571 = CARTESIAN_POINT ( 'NONE', ( -3.600972167898018217, 167.8303938013165180, 101.4140376877321188 ) ) ; -#39572 = ORIENTED_EDGE ( 'NONE', *, *, #39925, .F. ) ; -#39573 = CARTESIAN_POINT ( 'NONE', ( -35.93866694401108219, 194.2771771401957324, 102.9199814310981935 ) ) ; -#39574 = CARTESIAN_POINT ( 'NONE', ( 2.240107920744488723, 189.9106889621689334, 103.9462041502783620 ) ) ; -#39575 = DIRECTION ( 'NONE', ( 1.124971246646958780E-13, -0.9743700557921585181, -0.2249510932971562072 ) ) ; -#39576 = EDGE_CURVE ( 'NONE', #30329, #3915, #5558, .T. ) ; -#39577 = EDGE_LOOP ( 'NONE', ( #32770, #15020, #19689, #35831 ) ) ; -#39578 = DIRECTION ( 'NONE', ( 0.5986917825334768795, 0.8009794122048727871, -0.0003615948347011540827 ) ) ; -#39579 = EDGE_LOOP ( 'NONE', ( #8012, #31642, #14628, #39524, #15483, #7457, #19837, #6199, #33747, #2559, #39487, #32866, #17520, #33772, #6971, #8513, #8211, #12531, #12269, #39451, #6462, #29813, #27669, #19546, #15531, #14943, #4262, #6263, #31544, #16365, #8885, #18582, #24184, #25451, #36818, #2810, #25576, #13749, #24449, #10634, #10876, #25705, #28525, #25186, #17355, #3515, #2958, #31479, #859, #29972, #35436, #26705, #28234, #37332, #3232, #6863, #9987, #7462, #8510, #30563, #29289, #19146, #144, #6221, #39260, #19695, #24669, #22052, #5309, #17199, #17798, #15513, #14224, #19664, #37347, #33694, #32530, #14843, #2753 ) ) ; -#39580 = CARTESIAN_POINT ( 'NONE', ( 8.189646485733250714, 150.7151143592648737, 97.35116360727698748 ) ) ; -#39581 = AXIS2_PLACEMENT_3D ( 'NONE', #2005, #5459, #39599 ) ; -#39582 = CARTESIAN_POINT ( 'NONE', ( 36.21095379737665354, 191.6236208997618746, 104.0193308707671491 ) ) ; -#39583 = CARTESIAN_POINT ( 'NONE', ( 25.63260490920000478, 192.0990437881999924, 104.2855897946000141 ) ) ; -#39584 = ADVANCED_FACE ( 'NONE', ( #29335 ), #4225, .F. ) ; -#39585 = CARTESIAN_POINT ( 'NONE', ( -28.81944710292443546, 225.0820812887928071, 73.07591030630263162 ) ) ; -#39586 = VERTEX_POINT ( 'NONE', #35629 ) ; -#39587 = AXIS2_PLACEMENT_3D ( 'NONE', #6509, #28606, #7114 ) ; -#39588 = EDGE_CURVE ( 'NONE', #30585, #15817, #7646, .T. ) ; -#39589 = CARTESIAN_POINT ( 'NONE', ( -0.0004786142364818587623, 136.5649596138779884, 181.4686487119677167 ) ) ; -#39590 = VECTOR ( 'NONE', #20407, 1000.000000000000000 ) ; -#39591 = LINE ( 'NONE', #28152, #9628 ) ; -#39592 = ADVANCED_FACE ( 'NONE', ( #22542 ), #38260, .T. ) ; -#39593 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#39594 = CARTESIAN_POINT ( 'NONE', ( -16.77991322171150301, 122.0828549981512623, 174.9337942664223249 ) ) ; -#39595 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #32534, #29471, #26412, #20251, #4716, #1659, #39059, #15540, #39668, #21499, #40269 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000004229395, 0.3750000000006343814, 0.4375000000007119860, 0.4687500000006832312, 0.5000000000006543655, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39596 = CARTESIAN_POINT ( 'NONE', ( 20.00000190450869653, 184.9707748627797912, 102.3447125600660002 ) ) ; -#39597 = LINE ( 'NONE', #5044, #24196 ) ; -#39598 = CARTESIAN_POINT ( 'NONE', ( -13.73975480782840286, 149.7280840183181283, 179.8128424031934003 ) ) ; -#39599 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743043966640313469, 0.2252353050503802523 ) ) ; -#39600 = ORIENTED_EDGE ( 'NONE', *, *, #11288, .T. ) ; -#39601 = CARTESIAN_POINT ( 'NONE', ( 3.667815739890954330, 183.5629855106878381, 104.5953232237532688 ) ) ; -#39602 = FACE_OUTER_BOUND ( 'NONE', #21622, .T. ) ; -#39603 = VECTOR ( 'NONE', #15707, 1000.000000000000000 ) ; -#39604 = ORIENTED_EDGE ( 'NONE', *, *, #30352, .F. ) ; -#39605 = CARTESIAN_POINT ( 'NONE', ( 5.665211763448865234, 181.8706688165354137, 101.8856771814886315 ) ) ; -#39606 = CARTESIAN_POINT ( 'NONE', ( -21.48405399125571336, 115.4938544794857194, 90.28076066947326694 ) ) ; -#39607 = AXIS2_PLACEMENT_3D ( 'NONE', #1028, #35757, #32325 ) ; -#39608 = VERTEX_POINT ( 'NONE', #38057 ) ; -#39610 =( BOUNDED_SURFACE ( ) B_SPLINE_SURFACE ( 3, 2, ( - ( #36538, #36339, #11810 ), - ( #17712, #8542, #30207 ), - ( #17910, #26953, #23668 ), - ( #2001, #8337, #33459 ) ), - .UNSPECIFIED., .F., .F., .F. ) - B_SPLINE_SURFACE_WITH_KNOTS ( ( 4, 4 ), - ( 3, 3 ), - ( 0.5322943122596603960, 0.5323199423158530008 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) - GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_SURFACE ( ( - ( 1.000000000000000000, 0.7510960344373828201, 1.000000000000000000), - ( 1.000000000000000000, 0.7511072375234925103, 1.000000000000000000), - ( 1.000000000000000000, 0.7511184402484004652, 1.000000000000000000), - ( 1.000000000000000000, 0.7511296426121506498, 1.000000000000000000) ) ) - REPRESENTATION_ITEM ( '' ) SURFACE ( ) ); -#39609 = LINE ( 'NONE', #34272, #12436 ) ; -#39611 = AXIS2_PLACEMENT_3D ( 'NONE', #25786, #10245, #22713 ) ; -#39612 = FACE_OUTER_BOUND ( 'NONE', #39739, .T. ) ; -#39613 = ORIENTED_EDGE ( 'NONE', *, *, #28070, .T. ) ; -#39614 = CARTESIAN_POINT ( 'NONE', ( 35.66555862191038528, 192.0488609114880774, 106.9001169760940542 ) ) ; -#39615 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921584071, 0.2249510932971566790 ) ) ; -#39616 = CARTESIAN_POINT ( 'NONE', ( -38.49678016213000831, 119.1204962500000022, 90.30251346168999760 ) ) ; -#39617 = CARTESIAN_POINT ( 'NONE', ( 39.06246240375268997, 183.7310523487591354, 102.0469865154631322 ) ) ; -#39618 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178662923876E-05, -0.0002331579774918193435 ) ) ; -#39619 = EDGE_LOOP ( 'NONE', ( #23746, #32513 ) ) ; -#39620 = CARTESIAN_POINT ( 'NONE', ( 38.52263288177000078, 118.6682988694000045, 87.79308722659999376 ) ) ; -#39621 = CARTESIAN_POINT ( 'NONE', ( 12.63705158234716919, 181.9329688235127378, 101.9799032954709617 ) ) ; -#39622 = DIRECTION ( 'NONE', ( 0.0004161288024532937930, -0.8480480897973873278, 0.5299191110233921753 ) ) ; -#39623 = EDGE_CURVE ( 'NONE', #37866, #6712, #6566, .T. ) ; -#39625 = ORIENTED_EDGE ( 'NONE', *, *, #39414, .F. ) ; -#39624 = ADVANCED_FACE ( 'NONE', ( #9459 ), #13323, .T. ) ; -#39626 = CARTESIAN_POINT ( 'NONE', ( -13.46631090406734543, 154.2041329885244352, 95.43294494049737864 ) ) ; -#39627 = EDGE_LOOP ( 'NONE', ( #10359, #32039, #23492, #29964 ) ) ; -#39628 = EDGE_CURVE ( 'NONE', #23190, #13580, #9481, .T. ) ; -#39629 = VERTEX_POINT ( 'NONE', #12507 ) ; -#39630 = CARTESIAN_POINT ( 'NONE', ( 16.00200912906086614, 173.8361395730204322, 102.8554915256801650 ) ) ; -#39631 = FACE_OUTER_BOUND ( 'NONE', #33788, .T. ) ; -#39632 = FACE_BOUND ( 'NONE', #28107, .T. ) ; -#39633 = CARTESIAN_POINT ( 'NONE', ( 13.50176626422246606, 137.8359581293988469, 94.54561789153326856 ) ) ; -#39634 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#39635 = EDGE_CURVE ( 'NONE', #39184, #14606, #31136, .T. ) ; -#39636 = LINE ( 'NONE', #27416, #32113 ) ; -#39637 = CARTESIAN_POINT ( 'NONE', ( -25.63981584361267707, 209.7119832914303288, 73.44410892234432708 ) ) ; -#39638 = CIRCLE ( 'NONE', #23987, 6.000000000000007994 ) ; -#39639 = CARTESIAN_POINT ( 'NONE', ( 15.00009851376446868, 183.1875483699981828, 102.1070925222888093 ) ) ; -#39640 = EDGE_CURVE ( 'NONE', #23821, #35918, #34264, .T. ) ; -#39641 = DIRECTION ( 'NONE', ( 1.000000000000000000, 0.000000000000000000, 0.000000000000000000 ) ) ; -#39642 = CARTESIAN_POINT ( 'NONE', ( 25.99214530618421648, 205.1071296100486450, 76.08915040447824651 ) ) ; -#39643 = VERTEX_POINT ( 'NONE', #439 ) ; -#39644 = FACE_OUTER_BOUND ( 'NONE', #9664, .T. ) ; -#39645 = CARTESIAN_POINT ( 'NONE', ( 40.92144267131096314, 126.9198679979903517, 91.49572650408431684 ) ) ; -#39646 = DIRECTION ( 'NONE', ( 0.0005884949961252157946, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#39647 = CARTESIAN_POINT ( 'NONE', ( -35.95366953737766380, 209.7096538831000032, 78.08022010983800953 ) ) ; -#39648 = ORIENTED_EDGE ( 'NONE', *, *, #35628, .F. ) ; -#39649 = CARTESIAN_POINT ( 'NONE', ( 37.28741399843698900, 124.9789241431960392, 93.24647550195996359 ) ) ; -#39650 = ORIENTED_EDGE ( 'NONE', *, *, #37790, .F. ) ; -#39651 = VERTEX_POINT ( 'NONE', #37659 ) ; -#39652 = LINE ( 'NONE', #17968, #17954 ) ; -#39653 = ORIENTED_EDGE ( 'NONE', *, *, #7688, .F. ) ; -#39654 = CARTESIAN_POINT ( 'NONE', ( 47.95588820319697021, 137.8288108841867938, 291.5295797804309359 ) ) ; -#39655 = FACE_OUTER_BOUND ( 'NONE', #33319, .T. ) ; -#39656 = EDGE_LOOP ( 'NONE', ( #7040, #23547, #24654, #7461 ) ) ; -#39657 = FACE_OUTER_BOUND ( 'NONE', #5972, .T. ) ; -#39658 = CARTESIAN_POINT ( 'NONE', ( -20.24838124913999948, 144.4613572835999946, 95.83902025839000771 ) ) ; -#39659 = CARTESIAN_POINT ( 'NONE', ( -13.49529623641413068, 187.5771546723863423, 105.9222156747747761 ) ) ; -#39660 = CARTESIAN_POINT ( 'NONE', ( -20.99836224703339838, 128.8472059438258555, 92.32018788974323797 ) ) ; -#39661 = PLANE ( 'NONE', #33378 ) ; -#39662 = ORIENTED_EDGE ( 'NONE', *, *, #17567, .T. ) ; -#39663 = DIRECTION ( 'NONE', ( -0.7730662169443226484, -0.5272861007345266415, -0.3526159273084134571 ) ) ; -#39664 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26745, #23265, #20800, #2411, #21011, #20594, #14881, #14272, #39392, #38996, #33058, #33257, #11610, #17716, #36127, #14683, #33463, #29605, #30210, #27170 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 2, 2, 2, 1, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000252853, 0.1875000000000367761, 0.2187500000000425215, 0.2343750000000454081, 0.2500000000000482947, 0.5000000000000808242, 0.6250000000000933698, 0.6875000000000954792, 0.7187500000000928146, 0.7343750000000875966, 0.7500000000000823785, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39665 = VECTOR ( 'NONE', #4306, 1000.000000000000114 ) ; -#39666 = CARTESIAN_POINT ( 'NONE', ( 12.31735976862525561, 134.2421354939541800, 93.71979015959720982 ) ) ; -#39667 = CARTESIAN_POINT ( 'NONE', ( -33.21561771824055143, 142.2211279827451733, 287.8488816290605996 ) ) ; -#39668 = CARTESIAN_POINT ( 'NONE', ( 5.669429426318635556, 130.0958497786469366, 92.41882637154506597 ) ) ; -#39669 = FACE_OUTER_BOUND ( 'NONE', #34747, .T. ) ; -#39670 = CARTESIAN_POINT ( 'NONE', ( -3.330101313777913408, 186.7657347127359344, 102.7732021051896680 ) ) ; -#39671 = CONICAL_SURFACE ( 'NONE', #16805, 2.502997546632800940, 0.7853981634134501455 ) ; -#39672 = CARTESIAN_POINT ( 'NONE', ( 44.95760039392538943, 114.7448431369936230, 133.6882517851541650 ) ) ; -#39673 = ORIENTED_EDGE ( 'NONE', *, *, #39396, .F. ) ; -#39674 = CARTESIAN_POINT ( 'NONE', ( -28.67959411740000064, 187.5200541186000009, 102.8237240085999957 ) ) ; -#39675 = CARTESIAN_POINT ( 'NONE', ( 0.8182017989226511023, 189.0227397806419845, 103.7000179739869878 ) ) ; -#39676 = CARTESIAN_POINT ( 'NONE', ( 27.79802923844109230, 124.0706386133946495, 91.35900831036548198 ) ) ; -#39677 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #25405, #637, #22734, #13125, #19438, #31936, #7979, #16963, #1438, #20444, #17575, #38847, #26809, #14333, #23333, #1646, #11258, #35762, #30076, #23736, #36187, #22932 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.001939772655765043810, 0.002909658983647559535, 0.003879545311530075476, 0.005819317967295106926, 0.007759090623060138810, 0.009698863278825171561, 0.01066874960670771352, 0.01163863593459025549, 0.01357840859035542788, 0.01551818124612059854 ), - .UNSPECIFIED. ) ; -#39678 = VERTEX_POINT ( 'NONE', #31533 ) ; -#39679 = EDGE_CURVE ( 'NONE', #15031, #853, #34177, .T. ) ; -#39680 = EDGE_LOOP ( 'NONE', ( #86, #32453, #4186, #36807 ) ) ; -#39681 = DIRECTION ( 'NONE', ( -0.9999998176059869959, -1.547563064684605134E-06, 0.0006039748319373232453 ) ) ; -#39682 = EDGE_CURVE ( 'NONE', #23984, #8550, #16635, .T. ) ; -#39683 = EDGE_LOOP ( 'NONE', ( #15290, #22438, #18079, #25863 ) ) ; -#39684 = ORIENTED_EDGE ( 'NONE', *, *, #14212, .T. ) ; -#39685 = ORIENTED_EDGE ( 'NONE', *, *, #3019, .F. ) ; -#39686 = CARTESIAN_POINT ( 'NONE', ( -21.18256684378343024, 163.8812283386195361, 152.8157487814327169 ) ) ; -#39687 = CARTESIAN_POINT ( 'NONE', ( 15.00165026029782567, 175.6217250206921392, 103.0971961977437701 ) ) ; -#39688 = CARTESIAN_POINT ( 'NONE', ( 20.50100932471902482, 118.1127835883590365, 89.75563873136169946 ) ) ; -#39689 = ORIENTED_EDGE ( 'NONE', *, *, #17415, .F. ) ; -#39690 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #112, #9325, #39779, #24066 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39691 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921584071, -0.2249510932971563737 ) ) ; -#39692 = ORIENTED_EDGE ( 'NONE', *, *, #35500, .T. ) ; -#39693 = CARTESIAN_POINT ( 'NONE', ( 27.92742672377000090, 124.9274734904000042, 91.04345423159000461 ) ) ; -#39694 = AXIS2_PLACEMENT_3D ( 'NONE', #8199, #17779, #17174 ) ; -#39695 = CARTESIAN_POINT ( 'NONE', ( -39.72145289206626018, 121.0205764120224785, 124.6541090863944561 ) ) ; -#39696 = AXIS2_PLACEMENT_3D ( 'NONE', #39545, #20955, #5405 ) ; -#39698 = CARTESIAN_POINT ( 'NONE', ( -30.31843640017305574, 185.4672666245481025, 102.6607780480165246 ) ) ; -#39697 = LINE ( 'NONE', #2508, #25056 ) ; -#39699 = VERTEX_POINT ( 'NONE', #18629 ) ; -#39700 = EDGE_CURVE ( 'NONE', #21974, #3435, #26468, .T. ) ; -#39701 = PLANE ( 'NONE', #9293 ) ; -#39702 = EDGE_LOOP ( 'NONE', ( #21012, #21408, #2851 ) ) ; -#39703 = ORIENTED_EDGE ( 'NONE', *, *, #17394, .T. ) ; -#39704 = CARTESIAN_POINT ( 'NONE', ( 25.49947988276563393, 121.6390597818636934, 88.23326451243598001 ) ) ; -#39705 = CARTESIAN_POINT ( 'NONE', ( -15.99998378297181745, 127.7446958148473186, 89.15477705487283799 ) ) ; -#39706 = CARTESIAN_POINT ( 'NONE', ( 30.47672985551892566, 130.0726362972774552, 89.66414815853718778 ) ) ; -#39707 = EDGE_LOOP ( 'NONE', ( #26653, #39512, #10305, #2356 ) ) ; -#39708 = ORIENTED_EDGE ( 'NONE', *, *, #18793, .F. ) ; -#39709 = LINE ( 'NONE', #17631, #18485 ) ; -#39710 = LINE ( 'NONE', #20714, #19406 ) ; -#39711 = CARTESIAN_POINT ( 'NONE', ( 27.02806058983000526, 124.3665689137999948, 88.69107529613999930 ) ) ; -#39712 = ORIENTED_EDGE ( 'NONE', *, *, #37343, .T. ) ; -#39713 = CARTESIAN_POINT ( 'NONE', ( -36.29352938653000393, 191.1151839267000128, 106.6914996188999964 ) ) ; -#39714 = AXIS2_PLACEMENT_3D ( 'NONE', #13239, #22043, #25722 ) ; -#39715 = ORIENTED_EDGE ( 'NONE', *, *, #90, .T. ) ; -#39716 = ADVANCED_FACE ( 'NONE', ( #3492 ), #35555, .T. ) ; -#39717 = CARTESIAN_POINT ( 'NONE', ( 2.203927780028000161, 189.2284287703000132, 106.2182838559999993 ) ) ; -#39718 = ADVANCED_FACE ( 'NONE', ( #18827 ), #32647, .F. ) ; -#39719 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #26470, #10725, #33179, #32789 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999982996988420192 ), - .UNSPECIFIED. ) ; -#39720 = DIRECTION ( 'NONE', ( 7.494005416303299686E-14, 0.9743700557921596284, 0.2249510932971514887 ) ) ; -#39721 = VECTOR ( 'NONE', #38489, 1000.000000000000227 ) ; -#39722 = DIRECTION ( 'NONE', ( 0.0005884949961243157984, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#39723 = CARTESIAN_POINT ( 'NONE', ( -28.42925635489000413, 115.9590670145843205, 152.9217693939943388 ) ) ; -#39724 = CARTESIAN_POINT ( 'NONE', ( 19.47142695153164382, 148.9116984539020621, 183.2032397300831406 ) ) ; -#39725 = EDGE_CURVE ( 'NONE', #4191, #21584, #21757, .T. ) ; -#39726 = ORIENTED_EDGE ( 'NONE', *, *, #3756, .F. ) ; -#39727 = CARTESIAN_POINT ( 'NONE', ( -15.10535409822645647, 135.6520233040683934, 94.05869708244797778 ) ) ; -#39728 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178662923876E-05, -0.0002331579774918193435 ) ) ; -#39729 = ORIENTED_EDGE ( 'NONE', *, *, #36326, .F. ) ; -#39730 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5488, #36776, #14507, #2241 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 0.9999999706564445257 ), - .UNSPECIFIED. ) ; -#39731 = CARTESIAN_POINT ( 'NONE', ( 30.04402159321136523, 126.8238645745600195, 89.08542214068437204 ) ) ; -#39732 = ORIENTED_EDGE ( 'NONE', *, *, #28086, .F. ) ; -#39734 = DIRECTION ( 'NONE', ( 0.7066840230495562425, 0.09324023112872850683, -0.7013586463896738232 ) ) ; -#39733 = FACE_OUTER_BOUND ( 'NONE', #22224, .T. ) ; -#39735 = ORIENTED_EDGE ( 'NONE', *, *, #37098, .T. ) ; -#39736 = AXIS2_PLACEMENT_3D ( 'NONE', #45, #233, #34173 ) ; -#39737 = EDGE_LOOP ( 'NONE', ( #928, #40181, #39887, #15240, #20624, #36800 ) ) ; -#39738 = ADVANCED_FACE ( 'NONE', ( #19234 ), #7558, .F. ) ; -#39739 = EDGE_LOOP ( 'NONE', ( #35888, #28344, #3292, #23385 ) ) ; -#39740 = CARTESIAN_POINT ( 'NONE', ( 3.098523672063000056, 209.6781939275000184, 76.19310875697000540 ) ) ; -#39741 = VECTOR ( 'NONE', #33283, 1000.000000000000000 ) ; -#39742 = CARTESIAN_POINT ( 'NONE', ( -25.50006284340070906, 118.1130153187805689, 89.78316558933853742 ) ) ; -#39743 = DIRECTION ( 'NONE', ( -0.1305263947813612435, 0.9660168765824662662, 0.2231014442428296274 ) ) ; -#39744 = CARTESIAN_POINT ( 'NONE', ( 43.53807108224319222, 185.3499265735169388, 107.5016931662128314 ) ) ; -#39745 = CIRCLE ( 'NONE', #12328, 17.00000000000409273 ) ; -#39746 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#39747 = ORIENTED_EDGE ( 'NONE', *, *, #18656, .T. ) ; -#39748 = ORIENTED_EDGE ( 'NONE', *, *, #3526, .T. ) ; -#39749 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921729510, 0.2249510932970937294 ) ) ; -#39750 = AXIS2_PLACEMENT_3D ( 'NONE', #30457, #39634, #8785 ) ; -#39751 = VERTEX_POINT ( 'NONE', #26814 ) ; -#39752 = ORIENTED_EDGE ( 'NONE', *, *, #13476, .T. ) ; -#39753 = CARTESIAN_POINT ( 'NONE', ( 9.152074098956999748, 130.1605700231000071, 92.51966563137000321 ) ) ; -#39754 = CARTESIAN_POINT ( 'NONE', ( -30.07200330635009067, 135.2897752519686776, 91.41834187752364471 ) ) ; -#39755 = VERTEX_POINT ( 'NONE', #11065 ) ; -#39756 = EDGE_CURVE ( 'NONE', #19097, #36316, #4914, .T. ) ; -#39757 = EDGE_LOOP ( 'NONE', ( #6005, #18317, #21367, #23625, #14640, #27026, #36427, #33428, #1953, #31260, #19086, #36330, #22357, #5190 ) ) ; -#39758 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921590732, 0.2249510932971544308 ) ) ; -#39759 = CARTESIAN_POINT ( 'NONE', ( -36.35461825064000152, 191.9119039205000092, 104.5553151795000133 ) ) ; -#39760 = CARTESIAN_POINT ( 'NONE', ( -25.83697249613999958, 120.9034817377000053, 87.75236535515999492 ) ) ; -#39761 = ADVANCED_FACE ( 'NONE', ( #22938 ), #35366, .T. ) ; -#39762 = ORIENTED_EDGE ( 'NONE', *, *, #32737, .F. ) ; -#39763 = DIRECTION ( 'NONE', ( 0.9999998268368048837, 0.0001323825927785599152, -0.0005734119022073677499 ) ) ; -#39764 = CARTESIAN_POINT ( 'NONE', ( 40.51913295777573154, 190.1118463211006713, 106.6948265151217043 ) ) ; -#39765 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29932, #26877, #29135, #26269 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39766 = EDGE_LOOP ( 'NONE', ( #26631, #4305, #16986, #39236 ) ) ; -#39767 = CARTESIAN_POINT ( 'NONE', ( 1.525580299011169094, 188.7959628186811472, 103.2389845710508922 ) ) ; -#39768 = EDGE_CURVE ( 'NONE', #22555, #2629, #29050, .T. ) ; -#39769 = CARTESIAN_POINT ( 'NONE', ( 20.50113023862372330, 193.2795108210584658, 106.2344642539453901 ) ) ; -#39770 = EDGE_CURVE ( 'NONE', #3835, #654, #12115, .T. ) ; -#39771 = FACE_OUTER_BOUND ( 'NONE', #37483, .T. ) ; -#39772 = CARTESIAN_POINT ( 'NONE', ( -19.32892285413511502, 125.6991259445026401, 176.5170428066118404 ) ) ; -#39773 = VECTOR ( 'NONE', #34908, 1000.000000000000227 ) ; -#39774 = EDGE_CURVE ( 'NONE', #26941, #9438, #35767, .T. ) ; -#39775 = DIRECTION ( 'NONE', ( 0.0005884949961156549746, -0.2249510543439098842, 0.9743698870671255730 ) ) ; -#39776 = CARTESIAN_POINT ( 'NONE', ( -4.037049386316590827, 137.0919393097333341, 92.50288271244329508 ) ) ; -#39777 = VECTOR ( 'NONE', #18951, 1000.000000000000114 ) ; -#39778 = VERTEX_POINT ( 'NONE', #26212 ) ; -#39779 = CARTESIAN_POINT ( 'NONE', ( -38.25208811840489886, 118.7131440739753145, 87.71519576191549561 ) ) ; -#39780 = ORIENTED_EDGE ( 'NONE', *, *, #39774, .F. ) ; -#39781 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#39782 = CARTESIAN_POINT ( 'NONE', ( -45.24641625685059410, 116.3183880878488026, 125.9207951598621236 ) ) ; -#39783 = VECTOR ( 'NONE', #36673, 1000.000000000000227 ) ; -#39784 = CARTESIAN_POINT ( 'NONE', ( 38.09311553484000257, 118.1689180522000129, 89.80818930495999552 ) ) ; -#39785 = CARTESIAN_POINT ( 'NONE', ( 6.031183397126417489, 135.0056560870253293, 90.93530534527089060 ) ) ; -#39786 = ORIENTED_EDGE ( 'NONE', *, *, #23163, .T. ) ; -#39787 = FACE_OUTER_BOUND ( 'NONE', #31424, .T. ) ; -#39788 = EDGE_CURVE ( 'NONE', #14171, #26024, #38450, .T. ) ; -#39789 = DIRECTION ( 'NONE', ( 0.0006039748319385907860, -0.000000000000000000, 0.9999998176071844824 ) ) ; -#39790 = CARTESIAN_POINT ( 'NONE', ( 20.00184274542656837, 191.5977749577908469, 106.9093594267342553 ) ) ; -#39791 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921595173, 0.2249510932971519606 ) ) ; -#39792 = CARTESIAN_POINT ( 'NONE', ( -16.17928014215196342, 122.0409702652264770, 178.1070844152368409 ) ) ; -#39793 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.7071067167008887600, -0.7071068456722005013 ) ) ; -#39794 = FACE_OUTER_BOUND ( 'NONE', #38709, .T. ) ; -#39795 = DIRECTION ( 'NONE', ( 0.0005884949961241158715, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#39796 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #29190, #4020, #1159, #31654, #22254, #22852, #13636, #13043, #25523, #35283, #37978, #955, #9980, #6480, #16486, #10585 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 4 ), - ( 1.743224475509949456E-16, 0.0004902371348658318565, 0.0009804742697314893733, 0.001470711404597146782, 0.001960948539462804407, 0.002451185674328461815, 0.002941422809194119223, 0.003921897078925437943 ), - .UNSPECIFIED. ) ; -#39797 = CARTESIAN_POINT ( 'NONE', ( -14.59022374134706901, 128.1503308081717876, 179.4782974412063936 ) ) ; -#39798 = VERTEX_POINT ( 'NONE', #7775 ) ; -#39799 = CARTESIAN_POINT ( 'NONE', ( 28.46384604140109076, 184.1285027467395992, 102.1451462732341469 ) ) ; -#39801 = CONICAL_SURFACE ( 'NONE', #15009, 2.500000000149071866, 0.7853981634165752013 ) ; -#39800 = DIRECTION ( 'NONE', ( -0.9999999713660511214, 5.390041178662923876E-05, -0.0002331579774918193435 ) ) ; -#39802 = AXIS2_PLACEMENT_3D ( 'NONE', #27727, #37500, #12174 ) ; -#39803 = FACE_OUTER_BOUND ( 'NONE', #17878, .T. ) ; -#39804 = ADVANCED_FACE ( 'NONE', ( #32923 ), #10669, .T. ) ; -#39805 = CIRCLE ( 'NONE', #37199, 2.000000000040586645 ) ; -#39806 = EDGE_LOOP ( 'NONE', ( #3730, #15146, #18516, #5842 ) ) ; -#39807 = CARTESIAN_POINT ( 'NONE', ( 36.93409409893962447, 81.15548715763938503, 284.6050387078826134 ) ) ; -#39808 = CARTESIAN_POINT ( 'NONE', ( -20.59735040706742737, 116.2729919401682963, 90.28022512272735867 ) ) ; -#39809 = AXIS2_PLACEMENT_3D ( 'NONE', #4476, #10243, #19802 ) ; -#39810 = VERTEX_POINT ( 'NONE', #10271 ) ; -#39811 = CARTESIAN_POINT ( 'NONE', ( -38.38766615763000090, 118.8474237676000058, 87.72136322883000048 ) ) ; -#39812 = ADVANCED_FACE ( 'NONE', ( #16773 ), #4507, .T. ) ; -#39813 = CARTESIAN_POINT ( 'NONE', ( -5.665227795303835023, 130.9595288923176497, 89.94317851865588409 ) ) ; -#39814 = VERTEX_POINT ( 'NONE', #14141 ) ; -#39815 = FACE_OUTER_BOUND ( 'NONE', #17727, .T. ) ; -#39816 = ADVANCED_FACE ( 'NONE', ( #4095 ), #20448, .F. ) ; -#39817 = DIRECTION ( 'NONE', ( 2.081668171179845313E-15, 0.9743700557921582961, 0.2249510932971568178 ) ) ; -#39818 = CARTESIAN_POINT ( 'NONE', ( 16.44924844292772548, 122.1484196991176674, 174.6452774711495977 ) ) ; -#39819 = CARTESIAN_POINT ( 'NONE', ( -12.15421709199686617, 125.0604765512531884, 178.7580882214065525 ) ) ; -#39820 = CARTESIAN_POINT ( 'NONE', ( -5.670628684832168531, 124.6625218183467325, 88.84338314838811357 ) ) ; -#39821 = EDGE_CURVE ( 'NONE', #734, #19175, #14945, .T. ) ; -#39822 = ORIENTED_EDGE ( 'NONE', *, *, #22890, .T. ) ; -#39823 = CARTESIAN_POINT ( 'NONE', ( 38.31413649313999770, 118.8386230496000024, 87.57166059187001395 ) ) ; -#39824 = CARTESIAN_POINT ( 'NONE', ( 22.77977433793355999, 158.3069438176785582, 96.18720162681876218 ) ) ; -#39825 = DIRECTION ( 'NONE', ( 0.9999998176071845934, -5.029100735414826696E-18, -0.0006039748319369899615 ) ) ; -#39826 = CARTESIAN_POINT ( 'NONE', ( 9.583319590155999990, 188.0453190888999870, 103.3173941805000169 ) ) ; -#39827 = VERTEX_POINT ( 'NONE', #13925 ) ; -#39828 = CARTESIAN_POINT ( 'NONE', ( -20.50092100153493746, 194.2771564787859120, 102.9104786413515740 ) ) ; -#39829 = CARTESIAN_POINT ( 'NONE', ( -43.04878996311859396, 120.9978486867018290, 90.91681167607129055 ) ) ; -#39830 = CARTESIAN_POINT ( 'NONE', ( 22.50029346826903165, 160.6303563642724441, 97.23692471953465599 ) ) ; -#39831 = CIRCLE ( 'NONE', #25472, 5.499999999954135355 ) ; -#39832 = CARTESIAN_POINT ( 'NONE', ( 36.13152553141821954, 113.7323836164099475, 89.72779640660465361 ) ) ; -#39833 = CARTESIAN_POINT ( 'NONE', ( 20.00003498291988180, 122.7399499535855796, 87.97762771590346631 ) ) ; -#39834 = VECTOR ( 'NONE', #19525, 999.9999999999998863 ) ; -#39835 = DIRECTION ( 'NONE', ( 0.0005884949961253487178, -0.2249510543439069699, 0.9743698870671261281 ) ) ; -#39836 = AXIS2_PLACEMENT_3D ( 'NONE', #9275, #12524, #19056 ) ; -#39837 = CARTESIAN_POINT ( 'NONE', ( -12.63072017624268106, 177.7897717398484474, 100.7065154983451407 ) ) ; -#39838 = DIRECTION ( 'NONE', ( 0.5988681445390194868, -0.8008476418498040594, 0.000000000000000000 ) ) ; -#39839 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #30594, #30386, #2780, #27554, #20984, #9318, #2381, #17886, #39980, #18491 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 1, 1, 1, 1, 4 ), - ( 0.000000000000000000, 0.3333332752604695748, 0.6666665448735527022, 0.7500002575778695890, 0.8333339702820865558, 0.9166676829865233467, 0.9583345393386918376, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39840 = APPROVAL_DATE_TIME ( #2662, #30192 ) ; -#39841 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.8480480714602456338, -0.5299193037553528995 ) ) ; -#39842 = DIRECTION ( 'NONE', ( -0.0005884949961247158690, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#39843 = CARTESIAN_POINT ( 'NONE', ( 43.75332147006468375, 113.4509643667920500, 129.6325400527374541 ) ) ; -#39844 = CARTESIAN_POINT ( 'NONE', ( -20.07226483837147413, 184.3007399386575287, 105.2172045278962571 ) ) ; -#39845 = CARTESIAN_POINT ( 'NONE', ( -35.79114221331672496, 138.5178166623233267, 284.1865182878368046 ) ) ; -#39846 = CARTESIAN_POINT ( 'NONE', ( -15.46973598943061567, 173.3940168970194975, 152.4730246110422058 ) ) ; -#39847 = ORIENTED_EDGE ( 'NONE', *, *, #13016, .T. ) ; -#39849 = VERTEX_POINT ( 'NONE', #29272 ) ; -#39848 = FACE_OUTER_BOUND ( 'NONE', #22803, .T. ) ; -#39850 =( BOUNDED_CURVE ( ) B_SPLINE_CURVE ( 3, ( #30458, #14915, #27806, #2042 ), - .UNSPECIFIED., .F., .T. ) - B_SPLINE_CURVE_WITH_KNOTS ( ( 4, 4 ), - ( 0.8865655149750637509, 1.570796326794942965 ), - .UNSPECIFIED. ) - CURVE ( ) GEOMETRIC_REPRESENTATION_ITEM ( ) RATIONAL_B_SPLINE_CURVE ( ( 1.000000000000000000, 0.9613647307355848159, 0.9613647307355848159, 1.000000000000000000 ) ) - REPRESENTATION_ITEM ( '' ) ); -#39851 = ORIENTED_EDGE ( 'NONE', *, *, #39635, .F. ) ; -#39852 = ORIENTED_EDGE ( 'NONE', *, *, #25857, .T. ) ; -#39853 = CARTESIAN_POINT ( 'NONE', ( -22.78398997282901917, 148.0700263536807597, 93.85134194385574347 ) ) ; -#39854 = ORIENTED_EDGE ( 'NONE', *, *, #18020, .F. ) ; -#39855 = CARTESIAN_POINT ( 'NONE', ( 20.39856762060049178, 126.8504759496277501, 91.59777357230447592 ) ) ; -#39856 = EDGE_CURVE ( 'NONE', #12644, #6270, #5665, .T. ) ; -#39857 = EDGE_CURVE ( 'NONE', #8051, #72, #27135, .T. ) ; -#39858 = CARTESIAN_POINT ( 'NONE', ( 18.60795789290834179, 125.1298367273077616, 178.8296990479766748 ) ) ; -#39859 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921588512, 0.2249510932971545141 ) ) ; -#39860 = EDGE_CURVE ( 'NONE', #13945, #20521, #12082, .T. ) ; -#39861 = EDGE_CURVE ( 'NONE', #4577, #9860, #23952, .T. ) ; -#39862 = VERTEX_POINT ( 'NONE', #2272 ) ; -#39863 = CARTESIAN_POINT ( 'NONE', ( -39.69649258124999847, 119.2917748880999937, 89.64400856733000467 ) ) ; -#39864 = AXIS2_PLACEMENT_3D ( 'NONE', #13922, #23335, #35764 ) ; -#39865 = DIRECTION ( 'NONE', ( -0.9999998268368048837, -0.0001323826010358517924, 0.0005734119003052979939 ) ) ; -#39866 = CARTESIAN_POINT ( 'NONE', ( -2.952854088960068069, 209.7096538831000032, 78.06028844423795476 ) ) ; -#39867 = ORIENTED_EDGE ( 'NONE', *, *, #21614, .F. ) ; -#39868 = EDGE_CURVE ( 'NONE', #8838, #30783, #3188, .T. ) ; -#39869 = CARTESIAN_POINT ( 'NONE', ( 17.25785173553822460, 152.3545783266395688, 183.2781740268191868 ) ) ; -#39870 = CONICAL_SURFACE ( 'NONE', #3289, 2.250000000020516921, 0.7853981633778843729 ) ; -#39871 = CONICAL_SURFACE ( 'NONE', #9858, 2.503158050545156055, 0.7853981633914167704 ) ; -#39872 = LINE ( 'NONE', #34332, #32517 ) ; -#39873 = CARTESIAN_POINT ( 'NONE', ( -45.28489926060583315, 117.1104644663301428, 122.6183640757826225 ) ) ; -#39874 = CARTESIAN_POINT ( 'NONE', ( -4.725727965766024496, 188.1628219710171948, 103.0965880957095209 ) ) ; -#39875 = FACE_OUTER_BOUND ( 'NONE', #34877, .T. ) ; -#39876 = EDGE_CURVE ( 'NONE', #12120, #28767, #21288, .T. ) ; -#39877 = VERTEX_POINT ( 'NONE', #5931 ) ; -#39878 = CARTESIAN_POINT ( 'NONE', ( 44.86515336672587040, 186.3325894068457274, 107.7750559962146752 ) ) ; -#39879 = CARTESIAN_POINT ( 'NONE', ( 0.8179840527628020608, 189.0240481013839826, 103.7016792968739907 ) ) ; -#39880 = CARTESIAN_POINT ( 'NONE', ( -18.71851310314255556, 125.9964326179262883, 174.7342168340691444 ) ) ; -#39881 = CARTESIAN_POINT ( 'NONE', ( -35.44284610461649976, 192.5525937778500349, 106.9110644015157874 ) ) ; -#39882 = ORIENTED_EDGE ( 'NONE', *, *, #21619, .F. ) ; -#39883 = CARTESIAN_POINT ( 'NONE', ( -26.00760980898482799, 207.8686442861051376, 77.29275028086965449 ) ) ; -#39884 = ORIENTED_EDGE ( 'NONE', *, *, #19557, .T. ) ; -#39885 = ADVANCED_FACE ( 'NONE', ( #30489 ), #8414, .T. ) ; -#39886 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #8988, #15120, #33094, #17546 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39887 = ORIENTED_EDGE ( 'NONE', *, *, #10668, .T. ) ; -#39888 = VERTEX_POINT ( 'NONE', #21496 ) ; -#39889 = CARTESIAN_POINT ( 'NONE', ( -36.23826762833000714, 191.7567847793000055, 105.8251259594999993 ) ) ; -#39890 = PLANE ( 'NONE', #17563 ) ; -#39891 = CIRCLE ( 'NONE', #24896, 5.000000000000022204 ) ; -#39892 = CARTESIAN_POINT ( 'NONE', ( -25.51533646434189961, 211.0902259025884007, 73.57326538444725372 ) ) ; -#39893 = AXIS2_PLACEMENT_3D ( 'NONE', #694, #13378, #492 ) ; -#39894 = ORIENTED_EDGE ( 'NONE', *, *, #30521, .F. ) ; -#39895 = CARTESIAN_POINT ( 'NONE', ( 46.08001025735557477, 185.2443139781923094, 105.4710248038584410 ) ) ; -#39896 = CARTESIAN_POINT ( 'NONE', ( -12.63715494630207736, 134.7931114243770878, 93.38774708601914654 ) ) ; -#39897 = ORIENTED_EDGE ( 'NONE', *, *, #5547, .T. ) ; -#39898 = AXIS2_PLACEMENT_3D ( 'NONE', #16465, #28959, #737 ) ; -#39899 = CARTESIAN_POINT ( 'NONE', ( 25.63602418784000037, 121.4763877717000042, 90.24810266935999437 ) ) ; -#39900 = CONICAL_SURFACE ( 'NONE', #6590, 6.502999999910944240, 0.7853981633952109576 ) ; -#39901 = DIRECTION ( 'NONE', ( 0.0005884949961222141809, -0.2249510543439070531, 0.9743698870671262391 ) ) ; -#39903 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#39902 = FACE_OUTER_BOUND ( 'NONE', #21815, .T. ) ; -#39904 = VERTEX_POINT ( 'NONE', #18387 ) ; -#39905 = CARTESIAN_POINT ( 'NONE', ( 3.789323313120610326, 143.5973985926711407, 95.62144737670534766 ) ) ; -#39906 = ORIENTED_EDGE ( 'NONE', *, *, #27662, .F. ) ; -#39907 = EDGE_CURVE ( 'NONE', #33001, #7231, #4909, .T. ) ; -#39908 = CARTESIAN_POINT ( 'NONE', ( 19.99941580399983110, 118.1025156334579265, 87.25545403306659864 ) ) ; -#39909 = DIRECTION ( 'NONE', ( -0.0005734119072323276903, 0.000000000000000000, -0.9999998355993787724 ) ) ; -#39910 = ADVANCED_FACE ( 'NONE', ( #33735 ), #21080, .T. ) ; -#39911 = EDGE_CURVE ( 'NONE', #726, #10860, #2865, .T. ) ; -#39912 = ORIENTED_EDGE ( 'NONE', *, *, #14295, .T. ) ; -#39913 = CARTESIAN_POINT ( 'NONE', ( -30.45076006172021721, 127.0987129872037116, 89.01436239194951838 ) ) ; -#39914 = CARTESIAN_POINT ( 'NONE', ( -15.99998878844695938, 127.1155804165569094, 89.00952866523211071 ) ) ; -#39915 = DIRECTION ( 'NONE', ( -0.7069870866307825796, 0.6508451585900837388, 0.2767125564139931715 ) ) ; -#39916 = CARTESIAN_POINT ( 'NONE', ( 12.64035708966239469, 130.9607540069779361, 89.93343061172069497 ) ) ; -#39917 = CARTESIAN_POINT ( 'NONE', ( -12.64460002090920199, 134.9330247580281821, 90.83373639382720910 ) ) ; -#39918 = ORIENTED_EDGE ( 'NONE', *, *, #36237, .T. ) ; -#39919 = EDGE_CURVE ( 'NONE', #13582, #38161, #15342, .T. ) ; -#39920 = ORIENTED_EDGE ( 'NONE', *, *, #10307, .F. ) ; -#39921 = CARTESIAN_POINT ( 'NONE', ( -1.852806604127735790, 189.5547471265975332, 103.8459406374928022 ) ) ; -#39922 = PLANE ( 'NONE', #34432 ) ; -#39923 = VECTOR ( 'NONE', #22345, 1000.000000000000227 ) ; -#39924 = CARTESIAN_POINT ( 'NONE', ( 16.03566890003928691, 121.9740942863827797, 174.5072303276584194 ) ) ; -#39925 = EDGE_CURVE ( 'NONE', #15817, #9960, #11262, .T. ) ; -#39926 = ORIENTED_EDGE ( 'NONE', *, *, #21345, .F. ) ; -#39927 = LINE ( 'NONE', #27286, #397 ) ; -#39928 = VECTOR ( 'NONE', #30398, 1000.000000000000114 ) ; -#39929 = CARTESIAN_POINT ( 'NONE', ( 0.5641597396262441055, 188.3807571526811842, 106.2295656640635997 ) ) ; -#39930 = EDGE_LOOP ( 'NONE', ( #14980, #716, #16234, #31366 ) ) ; -#39931 = CARTESIAN_POINT ( 'NONE', ( -20.51954544737882813, 208.5436959433371840, 73.72443719612235213 ) ) ; -#39932 = ADVANCED_FACE ( 'NONE', ( #33526 ), #40069, .F. ) ; -#39933 = CARTESIAN_POINT ( 'NONE', ( 13.50012729195547934, 124.7429919913152929, 88.95710818440272760 ) ) ; -#39934 = CARTESIAN_POINT ( 'NONE', ( -23.32513133998376631, 121.2983238336744733, 152.0219650958596560 ) ) ; -#39935 = CARTESIAN_POINT ( 'NONE', ( 5.025754754826063930, 148.2514616712418558, 93.87643320611178410 ) ) ; -#39936 = ORIENTED_EDGE ( 'NONE', *, *, #16990, .F. ) ; -#39937 = DIRECTION ( 'NONE', ( 0.0005734119072320679154, 0.000000000000000000, 0.9999998355993787724 ) ) ; -#39938 = CARTESIAN_POINT ( 'NONE', ( -5.668109638569103659, 123.6908915871893129, 91.29154949463998037 ) ) ; -#39939 = ORIENTED_EDGE ( 'NONE', *, *, #40041, .T. ) ; -#39940 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921586292, 0.2249510932971561239 ) ) ; -#39941 = VERTEX_POINT ( 'NONE', #5519 ) ; -#39943 = CARTESIAN_POINT ( 'NONE', ( -41.21889173341337909, 77.14301703112138853, 286.7120891191068495 ) ) ; -#39942 = DIRECTION ( 'NONE', ( -0.6087611434179117653, 0.7728348325624403437, 0.1792657018023851578 ) ) ; -#39944 = ORIENTED_EDGE ( 'NONE', *, *, #29914, .F. ) ; -#39945 = VECTOR ( 'NONE', #2189, 1000.000000000000000 ) ; -#39946 = ORIENTED_EDGE ( 'NONE', *, *, #11253, .T. ) ; -#39947 = AXIS2_PLACEMENT_3D ( 'NONE', #4030, #1171, #35486 ) ; -#39948 = ORIENTED_EDGE ( 'NONE', *, *, #32022, .T. ) ; -#39949 = CARTESIAN_POINT ( 'NONE', ( 3.108838874058000190, 209.6469810035999899, 76.19428017209001780 ) ) ; -#39950 = CARTESIAN_POINT ( 'NONE', ( 39.32082689945465148, 128.7843916429683588, 92.44030466315589933 ) ) ; -#39951 = CARTESIAN_POINT ( 'NONE', ( 28.36925001313300143, 160.2013931541194722, 186.9397811580082021 ) ) ; -#39952 = CARTESIAN_POINT ( 'NONE', ( -12.52440953105373467, 125.9311653633099155, 282.5627442275269914 ) ) ; -#39953 = EDGE_CURVE ( 'NONE', #13040, #35915, #1583, .T. ) ; -#39954 = ORIENTED_EDGE ( 'NONE', *, *, #7766, .F. ) ; -#39955 = EDGE_CURVE ( 'NONE', #11331, #37167, #27024, .T. ) ; -#39956 = VERTEX_POINT ( 'NONE', #14752 ) ; -#39957 = CARTESIAN_POINT ( 'NONE', ( -20.00004361580415591, 118.8155695144462669, 87.27991261026372172 ) ) ; -#39958 = ORIENTED_EDGE ( 'NONE', *, *, #15156, .T. ) ; -#39959 = ORIENTED_EDGE ( 'NONE', *, *, #9520, .F. ) ; -#39960 = DIRECTION ( 'NONE', ( -0.0005559617634689729363, 0.3907311284899303572, -0.9205046855586902499 ) ) ; -#39961 = DIRECTION ( 'NONE', ( 0.000000000000000000, 1.000000000000000000, 0.000000000000000000 ) ) ; -#39962 = CARTESIAN_POINT ( 'NONE', ( -15.49892152314593474, 126.3880536741664713, 90.72282109318840071 ) ) ; -#39963 = CARTESIAN_POINT ( 'NONE', ( 14.72298203570611363, 123.1221558600993973, 178.3646181999850455 ) ) ; -#39964 = CARTESIAN_POINT ( 'NONE', ( 35.54969460229000333, 192.2381900686000051, 103.8743573426999944 ) ) ; -#39965 = ORIENTED_EDGE ( 'NONE', *, *, #5895, .F. ) ; -#39966 = VERTEX_POINT ( 'NONE', #8197 ) ; -#39967 = ORIENTED_EDGE ( 'NONE', *, *, #38111, .F. ) ; -#39968 = CARTESIAN_POINT ( 'NONE', ( -5.675513023005390956, 123.6907347205156924, 91.29157260444318922 ) ) ; -#39969 = EDGE_CURVE ( 'NONE', #14254, #7718, #36833, .T. ) ; -#39970 = CARTESIAN_POINT ( 'NONE', ( -35.82907652810000343, 191.7614052614000002, 104.0414502677000144 ) ) ; -#39971 = EDGE_LOOP ( 'NONE', ( #10835, #22179, #39715, #26035 ) ) ; -#39972 = CARTESIAN_POINT ( 'NONE', ( 39.73110239298318191, 165.1365825546612882, 181.9150604281450114 ) ) ; -#39973 = ORIENTED_EDGE ( 'NONE', *, *, #22234, .F. ) ; -#39974 = LINE ( 'NONE', #2578, #36953 ) ; -#39975 = LINE ( 'NONE', #36918, #19301 ) ; -#39976 = CARTESIAN_POINT ( 'NONE', ( -41.00789709315080245, 189.3422338137688712, 107.0789350927375949 ) ) ; -#39977 = EDGE_LOOP ( 'NONE', ( #14550, #31553, #33675, #31809, #21657, #788, #38595, #18061, #19004, #20142, #14437 ) ) ; -#39978 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #35066, #7072, #19737, #23231, #32047, #10368, #23037, #32626, #4004, #35664 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.2500000000000000000, 0.5000000000000000000, 0.7500000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#39979 = CARTESIAN_POINT ( 'NONE', ( 20.50141158344984404, 191.9758728513155575, 106.4093071483684696 ) ) ; -#39980 = CARTESIAN_POINT ( 'NONE', ( 38.66881667660670274, 119.1641615024088736, 90.25890836112429838 ) ) ; -#39981 = VECTOR ( 'NONE', #18427, 1000.000000000000227 ) ; -#39982 = DIRECTION ( 'NONE', ( 0.6087613186456907188, 0.7730177010543248795, 0.1784749023741044327 ) ) ; -#39983 = EDGE_CURVE ( 'NONE', #2174, #12564, #23186, .T. ) ; -#39984 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#39985 = DIRECTION ( 'NONE', ( -0.0002393071182776102175, -0.2252352986010028590, 0.9743043687658493601 ) ) ; -#39986 = ORIENTED_EDGE ( 'NONE', *, *, #18358, .F. ) ; -#39987 = DIRECTION ( 'NONE', ( -0.9914446600486714889, -0.1273122826259382723, -0.02879355402772574776 ) ) ; -#39988 = ORIENTED_EDGE ( 'NONE', *, *, #5296, .F. ) ; -#39989 = CARTESIAN_POINT ( 'NONE', ( 8.048542122852918368, 150.7638762473669658, 97.53355711752999468 ) ) ; -#39990 = CARTESIAN_POINT ( 'NONE', ( -14.22265864990228401, 129.0629248693782074, 176.7848948385215806 ) ) ; -#39991 = CARTESIAN_POINT ( 'NONE', ( 37.37535261800000086, 117.3179660600000034, 89.81729445893999753 ) ) ; -#39992 = DIRECTION ( 'NONE', ( -0.9999998176071844824, -3.370379598151327408E-34, 0.0006039748319386880390 ) ) ; -#39993 = ORIENTED_EDGE ( 'NONE', *, *, #2345, .T. ) ; -#39994 = EDGE_CURVE ( 'NONE', #11012, #20699, #20786, .T. ) ; -#39995 = PLANE ( 'NONE', #21404 ) ; -#39996 = EDGE_CURVE ( 'NONE', #25396, #13070, #19256, .T. ) ; -#39997 = AXIS2_PLACEMENT_3D ( 'NONE', #31016, #34257, #27968 ) ; -#39998 = ORIENTED_EDGE ( 'NONE', *, *, #32348, .T. ) ; -#39999 = CARTESIAN_POINT ( 'NONE', ( -21.10558147345552271, 175.5300362219209944, 102.9267844786626682 ) ) ; -#40000 = CARTESIAN_POINT ( 'NONE', ( 21.71195827823497737, 154.2857483248134542, 95.25948025584419554 ) ) ; -#40001 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; -#40002 = CARTESIAN_POINT ( 'NONE', ( -15.99970515225999179, 151.9770228117144484, 94.74935186622352035 ) ) ; -#40003 = DIRECTION ( 'NONE', ( 0.7933530821295674551, 0.5932640870152211532, 0.1364866665045049998 ) ) ; -#40004 = EDGE_CURVE ( 'NONE', #18505, #13844, #14170, .T. ) ; -#40005 = CONICAL_SURFACE ( 'NONE', #6036, 2.500000000051350035, 0.7853981633778843729 ) ; -#40006 = CARTESIAN_POINT ( 'NONE', ( -17.26224783785864147, 152.3522462518728560, 183.2690931728076009 ) ) ; -#40007 = EDGE_CURVE ( 'NONE', #29513, #31494, #26641, .T. ) ; -#40008 = FACE_OUTER_BOUND ( 'NONE', #36728, .T. ) ; -#40009 = EDGE_LOOP ( 'NONE', ( #11247, #35010, #20985, #28706, #25195 ) ) ; -#40010 = EDGE_CURVE ( 'NONE', #4584, #10555, #11092, .T. ) ; -#40011 = DIRECTION ( 'NONE', ( -0.7933533411653084233, 0.5930537057989933025, 0.1373964268091529273 ) ) ; -#40012 = FACE_OUTER_BOUND ( 'NONE', #22324, .T. ) ; -#40013 = CIRCLE ( 'NONE', #2808, 5.999999999929131356 ) ; -#40014 = CARTESIAN_POINT ( 'NONE', ( 44.73086057231284229, 168.6464848246152144, 183.7642316016321899 ) ) ; -#40015 = ORIENTED_EDGE ( 'NONE', *, *, #26703, .T. ) ; -#40016 = CARTESIAN_POINT ( 'NONE', ( -23.36589107377781005, 134.9158523539519194, 90.81477344275025132 ) ) ; -#40017 = CARTESIAN_POINT ( 'NONE', ( 36.54456757410444112, 191.0204932105091018, 106.6271468414739729 ) ) ; -#40018 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #24708, #30626, #21822, #34262, #2616, #6265, #18718, #15086, #31219, #13618, #1135, #6865, #19533, #22828, #736, #16859, #13021, #7459, #19925, #31834, #13419, #29164, #28754, #7261 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 2, 2, 2, 2, 2, 1, 1, 2, 2, 2, 4 ), - ( 0.000000000000000000, 0.1250000000000151545, 0.1875000000000228428, 0.2187500000000260347, 0.2500000000000292544, 0.3750000000000328626, 0.4375000000000357492, 0.4687500000000371370, 0.4843750000000389688, 0.4921875000000313083, 0.5000000000000236478, 0.7500000000000118794, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#40019 = ORIENTED_EDGE ( 'NONE', *, *, #14389, .F. ) ; -#40020 = CARTESIAN_POINT ( 'NONE', ( -38.46836053098000008, 118.9254552666999984, 87.72568244094999557 ) ) ; -#40021 = CARTESIAN_POINT ( 'NONE', ( 30.44899542203640408, 126.4319227165660635, 91.90255272003975051 ) ) ; -#40022 = FACE_OUTER_BOUND ( 'NONE', #9356, .T. ) ; -#40023 = ORIENTED_EDGE ( 'NONE', *, *, #39788, .F. ) ; -#40024 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.000000000000000000, 1.000000000000000000 ) ) ; -#40025 = CARTESIAN_POINT ( 'NONE', ( -43.86878163833967648, 122.3260230262551005, 88.14364713971215792 ) ) ; -#40026 = CARTESIAN_POINT ( 'NONE', ( -26.12281312345999851, 191.2058208288000003, 107.0187681231000028 ) ) ; -#40027 = CARTESIAN_POINT ( 'NONE', ( -35.95487748704000097, 225.9002260771000010, 76.08022047461976456 ) ) ; -#40028 = CARTESIAN_POINT ( 'NONE', ( -35.92250688068352105, 148.9769121975630242, 291.4743218914980503 ) ) ; -#40029 = VERTEX_POINT ( 'NONE', #4739 ) ; -#40030 = CARTESIAN_POINT ( 'NONE', ( 38.93086770562999988, 120.1677338017999972, 87.23041171529000337 ) ) ; -#40031 = DIRECTION ( 'NONE', ( 0.6087614115774880874, 0.7729348350621345620, 0.1788331191967953704 ) ) ; -#40032 = VECTOR ( 'NONE', #466, 1000.000000000000000 ) ; -#40033 = CARTESIAN_POINT ( 'NONE', ( 36.75525778864385984, 191.6314878030200930, 104.3442272597018246 ) ) ; -#40034 = CARTESIAN_POINT ( 'NONE', ( -16.56513926556643668, 151.9899594182569160, 182.4590145884489516 ) ) ; -#40035 = ORIENTED_EDGE ( 'NONE', *, *, #21975, .F. ) ; -#40036 = CONICAL_SURFACE ( 'NONE', #3450, 48.00000000001436007, 0.7853981633972800802 ) ; -#40037 = CARTESIAN_POINT ( 'NONE', ( 17.99646903002095044, 132.9726891188946922, 90.34121599450540430 ) ) ; -#40038 = CYLINDRICAL_SURFACE ( 'NONE', #31728, 2.000000000000011546 ) ; -#40039 = AXIS2_PLACEMENT_3D ( 'NONE', #10914, #3944, #38687 ) ; -#40040 = CARTESIAN_POINT ( 'NONE', ( -24.53444877736164997, 213.7106621591174473, 73.07332227467423991 ) ) ; -#40041 = EDGE_CURVE ( 'NONE', #6684, #19312, #13958, .T. ) ; -#40042 = FACE_OUTER_BOUND ( 'NONE', #23296, .T. ) ; -#40043 = CARTESIAN_POINT ( 'NONE', ( 6.042240099596939196, 177.1173855813495948, 103.6190021212635770 ) ) ; -#40044 = EDGE_CURVE ( 'NONE', #39608, #12175, #7020, .T. ) ; -#40045 = APPROVAL_DATE_TIME ( #5712, #25220 ) ; -#40046 = CARTESIAN_POINT ( 'NONE', ( 5.342233081412309126, 181.6904643235373840, 101.5962455245849014 ) ) ; -#40047 = LINE ( 'NONE', #3427, #13947 ) ; -#40048 = FACE_OUTER_BOUND ( 'NONE', #23678, .T. ) ; -#40049 = CARTESIAN_POINT ( 'NONE', ( -20.51880467302672173, 211.0905570380611493, 75.57084890002228406 ) ) ; -#40050 = CARTESIAN_POINT ( 'NONE', ( -39.71442208983258837, 169.2236437704519574, 164.3192996581971101 ) ) ; -#40051 = ADVANCED_FACE ( 'NONE', ( #36010 ), #38880, .F. ) ; -#40052 = CARTESIAN_POINT ( 'NONE', ( -35.94634188048999590, 134.2394347308982674, 93.74516030698919167 ) ) ; -#40053 = ORIENTED_EDGE ( 'NONE', *, *, #12838, .T. ) ; -#40054 = ORIENTED_EDGE ( 'NONE', *, *, #5184, .F. ) ; -#40055 = ADVANCED_FACE ( 'NONE', ( #17405 ), #19200, .F. ) ; -#40056 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921581851, 0.2249510932971576227 ) ) ; -#40057 = EDGE_CURVE ( 'NONE', #33034, #6999, #12781, .T. ) ; -#40058 = LINE ( 'NONE', #30258, #22900 ) ; -#40059 = AXIS2_PLACEMENT_3D ( 'NONE', #14920, #17758, #17557 ) ; -#40060 = FACE_OUTER_BOUND ( 'NONE', #14408, .T. ) ; -#40061 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749388340, 132.8602140592406045, 90.82839891340712768 ) ) ; -#40062 = CIRCLE ( 'NONE', #38116, 2.000000000000011546 ) ; -#40063 = ORIENTED_EDGE ( 'NONE', *, *, #12135, .F. ) ; -#40064 = CARTESIAN_POINT ( 'NONE', ( 13.50164015315887411, 187.2961052408047067, 105.4512425975207464 ) ) ; -#40065 = VECTOR ( 'NONE', #7525, 1000.000000000000000 ) ; -#40066 = CARTESIAN_POINT ( 'NONE', ( -15.99998378297181745, 127.7446958148473186, 89.15477705487283799 ) ) ; -#40067 = CARTESIAN_POINT ( 'NONE', ( -18.61079839510214029, 126.0371735097383095, 174.9248182282352957 ) ) ; -#40068 = ORIENTED_EDGE ( 'NONE', *, *, #38832, .F. ) ; -#40069 = CYLINDRICAL_SURFACE ( 'NONE', #33568, 2.000000000000000000 ) ; -#40070 = FACE_OUTER_BOUND ( 'NONE', #2955, .T. ) ; -#40071 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 1, - ( #16350, #21910 ), - .UNSPECIFIED., .F., .F., - ( 2, 2 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#40072 = CARTESIAN_POINT ( 'NONE', ( -40.52667274848001000, 173.3654007757000102, 152.4718672074000381 ) ) ; -#40073 = CARTESIAN_POINT ( 'NONE', ( -13.01264633640278312, 134.9181483276104245, 90.80908945356310369 ) ) ; -#40074 = FACE_OUTER_BOUND ( 'NONE', #37637, .T. ) ; -#40075 = EDGE_LOOP ( 'NONE', ( #40035, #36434, #19395, #2147 ) ) ; -#40076 = EDGE_LOOP ( 'NONE', ( #34097, #40019, #27539, #19287 ) ) ; -#40077 = CARTESIAN_POINT ( 'NONE', ( -18.96028624430033105, 148.4102203051928939, 183.7254338880509010 ) ) ; -#40078 = CARTESIAN_POINT ( 'NONE', ( 3.006846131046999826, 190.4615416249000077, 103.6219035456000057 ) ) ; -#40079 = CARTESIAN_POINT ( 'NONE', ( 21.70190315701263017, 123.1837599801819465, 176.5257127422096914 ) ) ; -#40080 = ORIENTED_EDGE ( 'NONE', *, *, #31813, .F. ) ; -#40081 = DIRECTION ( 'NONE', ( -0.0005884949961256158652, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#40082 = ORIENTED_EDGE ( 'NONE', *, *, #9410, .F. ) ; -#40083 = VECTOR ( 'NONE', #18402, 1000.000000000000227 ) ; -#40084 = AXIS2_PLACEMENT_3D ( 'NONE', #7104, #19574, #13459 ) ; -#40085 = EDGE_CURVE ( 'NONE', #5335, #21013, #23978, .T. ) ; -#40086 = EDGE_CURVE ( 'NONE', #8550, #38531, #30945, .T. ) ; -#40087 = EDGE_CURVE ( 'NONE', #24036, #18328, #33356, .T. ) ; -#40088 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825922896761066, 0.0005734119023223271158 ) ) ; -#40089 = VECTOR ( 'NONE', #22114, 1000.000000000000114 ) ; -#40090 = CARTESIAN_POINT ( 'NONE', ( -37.05652687719999960, 191.1891292050000004, 105.7508132630999995 ) ) ; -#40091 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921590732, -0.2249510932971544308 ) ) ; -#40092 = CARTESIAN_POINT ( 'NONE', ( -36.61650759155055113, 191.3591673295911733, 106.3831752203444267 ) ) ; -#40093 = CIRCLE ( 'NONE', #27725, 2.250000000041461945 ) ; -#40094 = EDGE_CURVE ( 'NONE', #7297, #7762, #23768, .T. ) ; -#40095 = CARTESIAN_POINT ( 'NONE', ( 36.06588537441000142, 194.9391275604999976, 107.7152975676000040 ) ) ; -#40096 = CARTESIAN_POINT ( 'NONE', ( 18.00000000000099476, 177.0629346110185338, 100.5202509416223506 ) ) ; -#40097 = EDGE_LOOP ( 'NONE', ( #475, #20334, #24857, #32220, #32189, #25254 ) ) ; -#40098 = DIRECTION ( 'NONE', ( -0.9999998176071844824, 0.000000000000000000, 0.0006039748319389023857 ) ) ; -#40099 = CARTESIAN_POINT ( 'NONE', ( -26.01326056281665089, 211.0902258159713085, 76.07393268928584007 ) ) ; -#40100 = FACE_OUTER_BOUND ( 'NONE', #3461, .T. ) ; -#40102 = DIRECTION ( 'NONE', ( -0.0002393071182785117316, -0.2252352986010040803, 0.9743043687658491381 ) ) ; -#40101 = CARTESIAN_POINT ( 'NONE', ( 15.66686102866751362, 185.8347106091287628, 102.8888882241695342 ) ) ; -#40103 = EDGE_CURVE ( 'NONE', #23762, #22787, #20693, .T. ) ; -#40104 = ORIENTED_EDGE ( 'NONE', *, *, #20155, .F. ) ; -#40105 = ORIENTED_EDGE ( 'NONE', *, *, #7705, .T. ) ; -#40106 = CIRCLE ( 'NONE', #939, 59.40509898897000340 ) ; -#40107 = CARTESIAN_POINT ( 'NONE', ( 39.55110128785999990, 119.8420530485000199, 90.51490709511000432 ) ) ; -#40108 = FACE_OUTER_BOUND ( 'NONE', #19050, .T. ) ; -#40109 = ADVANCED_FACE ( 'NONE', ( #33147 ), #12684, .F. ) ; -#40110 = CARTESIAN_POINT ( 'NONE', ( -35.69675826569999799, 199.6921533858000259, 89.52312211516000673 ) ) ; -#40111 = FACE_OUTER_BOUND ( 'NONE', #29989, .T. ) ; -#40112 = DIRECTION ( 'NONE', ( -0.0005884949961252157946, 0.2249510543439060817, -0.9743698870671263501 ) ) ; -#40113 = VECTOR ( 'NONE', #14104, 1000.000000000000000 ) ; -#40114 = AXIS2_PLACEMENT_3D ( 'NONE', #20619, #5071, #26979 ) ; -#40115 = LINE ( 'NONE', #2905, #21706 ) ; -#40116 = ORIENTED_EDGE ( 'NONE', *, *, #23912, .T. ) ; -#40117 = ORIENTED_EDGE ( 'NONE', *, *, #15074, .F. ) ; -#40118 = CARTESIAN_POINT ( 'NONE', ( 3.064236136099508290, 190.8512031035150471, 106.7914583158460573 ) ) ; -#40119 = CIRCLE ( 'NONE', #13362, 2.000000000383225451 ) ; -#40120 = CARTESIAN_POINT ( 'NONE', ( -23.39890890703999915, 142.7284776650000140, 28.07991271570000080 ) ) ; -#40121 = CARTESIAN_POINT ( 'NONE', ( 16.12678657333407628, 122.0322087771653088, 174.5413712490106093 ) ) ; -#40122 = ORIENTED_EDGE ( 'NONE', *, *, #38958, .F. ) ; -#40123 = ORIENTED_EDGE ( 'NONE', *, *, #17326, .F. ) ; -#40124 = CARTESIAN_POINT ( 'NONE', ( 35.99069571327236616, 209.7096533915727434, 75.59255538986752754 ) ) ; -#40125 = CARTESIAN_POINT ( 'NONE', ( 36.46831602377621806, 265.1087381855853664, 205.0355407830140848 ) ) ; -#40126 = CARTESIAN_POINT ( 'NONE', ( 2.740375152715848195, 189.5745065435120580, 106.5097161501692682 ) ) ; -#40127 = CARTESIAN_POINT ( 'NONE', ( -25.60482124379134916, 148.7605381266695588, 204.9143772677416564 ) ) ; -#40128 = FACE_OUTER_BOUND ( 'NONE', #39286, .T. ) ; -#40129 = DIRECTION ( 'NONE', ( 0.0006039748319391913256, 0.000000000000000000, 0.9999998176071847045 ) ) ; -#40130 = DIRECTION ( 'NONE', ( -0.0006039748319394905654, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#40131 = EDGE_CURVE ( 'NONE', #29958, #24799, #4528, .T. ) ; -#40132 = EDGE_CURVE ( 'NONE', #36524, #15841, #33659, .T. ) ; -#40133 = ORIENTED_EDGE ( 'NONE', *, *, #4499, .T. ) ; -#40134 = CARTESIAN_POINT ( 'NONE', ( 25.99096411850820942, 206.5437039761336564, 74.14227870554802280 ) ) ; -#40135 = EDGE_CURVE ( 'NONE', #34329, #29279, #3118, .T. ) ; -#40136 = CARTESIAN_POINT ( 'NONE', ( -35.75152918212248920, 165.7724375289338354, 188.2119208754558599 ) ) ; -#40137 = VECTOR ( 'NONE', #11537, 1000.000000000000000 ) ; -#40138 = AXIS2_PLACEMENT_3D ( 'NONE', #22007, #3169, #31810 ) ; -#40139 = EDGE_LOOP ( 'NONE', ( #30291, #13740, #17824, #36676 ) ) ; -#40140 = EDGE_CURVE ( 'NONE', #32027, #18851, #27045, .T. ) ; -#40141 = CARTESIAN_POINT ( 'NONE', ( -5.668304492375956016, 188.0633424520996755, 103.3136157537519466 ) ) ; -#40142 = VERTEX_POINT ( 'NONE', #21314 ) ; -#40143 = AXIS2_PLACEMENT_3D ( 'NONE', #6254, #11808, #9140 ) ; -#40145 = CARTESIAN_POINT ( 'NONE', ( 35.61358792416734786, 192.0416364148001662, 103.8993421123607419 ) ) ; -#40144 = LINE ( 'NONE', #33185, #14183 ) ; -#40146 = ORIENTED_EDGE ( 'NONE', *, *, #34721, .F. ) ; -#40147 = ADVANCED_FACE ( 'NONE', ( #33761 ), #27159, .T. ) ; -#40148 = ORIENTED_EDGE ( 'NONE', *, *, #30882, .F. ) ; -#40149 = VERTEX_POINT ( 'NONE', #21104 ) ; -#40150 = CARTESIAN_POINT ( 'NONE', ( 2.921857347780000058, 209.0164851424000005, 76.05359827459000144 ) ) ; -#40151 = CARTESIAN_POINT ( 'NONE', ( -15.10714335758950888, 136.3268993782255620, 91.13559034338766196 ) ) ; -#40152 = CARTESIAN_POINT ( 'NONE', ( 12.63907793505734567, 177.5251405050551341, 100.8594170221115007 ) ) ; -#40153 = EDGE_LOOP ( 'NONE', ( #8035, #6646, #2257, #16257 ) ) ; -#40154 = ORIENTED_EDGE ( 'NONE', *, *, #11383, .F. ) ; -#40155 = ORIENTED_EDGE ( 'NONE', *, *, #2771, .T. ) ; -#40156 = VERTEX_POINT ( 'NONE', #5760 ) ; -#40157 = LINE ( 'NONE', #33204, #5422 ) ; -#40158 = CARTESIAN_POINT ( 'NONE', ( -19.40198027091592081, 124.9165765156423760, 177.8474014814652264 ) ) ; -#40159 = DIRECTION ( 'NONE', ( 0.0005884931661380672164, -0.2249510543440760013, 0.9743698870681923863 ) ) ; -#40160 = CARTESIAN_POINT ( 'NONE', ( 23.67998985452990368, 134.9222885997251637, 90.78792508986444432 ) ) ; -#40161 = EDGE_LOOP ( 'NONE', ( #29885, #3388, #25907, #26968 ) ) ; -#40162 = VERTEX_POINT ( 'NONE', #30912 ) ; -#40163 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921582961, -0.2249510932971573174 ) ) ; -#40164 = CARTESIAN_POINT ( 'NONE', ( -13.83171258093479672, 150.2818367448051049, 180.5307641806243453 ) ) ; -#40165 = ORIENTED_EDGE ( 'NONE', *, *, #8830, .F. ) ; -#40166 = LINE ( 'NONE', #39972, #25531 ) ; -#40167 = ORIENTED_EDGE ( 'NONE', *, *, #16494, .F. ) ; -#40168 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921589622, 0.2249510932971540422 ) ) ; -#40169 = DIRECTION ( 'NONE', ( -0.0006039748319383739456, 3.094196748328522329E-15, -0.9999998176071845934 ) ) ; -#40170 = ORIENTED_EDGE ( 'NONE', *, *, #15854, .T. ) ; -#40171 = VECTOR ( 'NONE', #12717, 1000.000000000000000 ) ; -#40172 = AXIS2_PLACEMENT_3D ( 'NONE', #17231, #35834, #26671 ) ; -#40173 = CONICAL_SURFACE ( 'NONE', #21988, 2.499999999949844565, 0.7853981633810270813 ) ; -#40174 = CONICAL_SURFACE ( 'NONE', #22570, 2.502999999909521822, 0.7853981633426256881 ) ; -#40175 = CARTESIAN_POINT ( 'NONE', ( -30.45076006172021721, 127.0987129872037116, 89.01436239194951838 ) ) ; -#40176 = DIRECTION ( 'NONE', ( -0.0005559617633316433355, 0.3907311284892692194, -0.9205046855589709143 ) ) ; -#40177 = CARTESIAN_POINT ( 'NONE', ( 10.03597125221916642, 167.8227034468253294, 101.4738597986363118 ) ) ; -#40178 = CARTESIAN_POINT ( 'NONE', ( -4.037441716908935163, 137.2418790766312782, 91.85329641515465937 ) ) ; -#40179 = VERTEX_POINT ( 'NONE', #9436 ) ; -#40180 = CARTESIAN_POINT ( 'NONE', ( 25.62068700201966109, 116.5989192260994542, 90.25231058625922742 ) ) ; -#40181 = ORIENTED_EDGE ( 'NONE', *, *, #18850, .T. ) ; -#40182 = EDGE_CURVE ( 'NONE', #18677, #5503, #5586, .T. ) ; -#40183 = CARTESIAN_POINT ( 'NONE', ( 3.044162730076025447, 208.9211496123335507, 73.11923083669719858 ) ) ; -#40184 = EDGE_CURVE ( 'NONE', #1066, #28925, #18009, .T. ) ; -#40185 = CARTESIAN_POINT ( 'NONE', ( -38.23875393712000204, 119.2562791585999946, 87.40938009561999422 ) ) ; -#40186 = CARTESIAN_POINT ( 'NONE', ( 25.99211731546482795, 209.7096512574500480, 76.04280604205342797 ) ) ; -#40187 = DIRECTION ( 'NONE', ( -0.7856246811335054758, -0.6187033702784218159, 0.000000000000000000 ) ) ; -#40188 = ORIENTED_EDGE ( 'NONE', *, *, #5904, .T. ) ; -#40189 = CARTESIAN_POINT ( 'NONE', ( -0.0002942474978707994683, 155.7928101624881378, 98.18628735359374105 ) ) ; -#40190 = ORIENTED_EDGE ( 'NONE', *, *, #26448, .F. ) ; -#40191 = DIRECTION ( 'NONE', ( 0.0005884949961234677354, -0.2249510543439058596, 0.9743698870671263501 ) ) ; -#40192 = CONICAL_SURFACE ( 'NONE', #3072, 2.499999999942751128, 0.7853981634230097209 ) ; -#40193 = AXIS2_PLACEMENT_3D ( 'NONE', #3687, #5964, #6359 ) ; -#40194 = VECTOR ( 'NONE', #26135, 1000.000000000000227 ) ; -#40195 = CARTESIAN_POINT ( 'NONE', ( 6.272186697316835868, 148.2050572955672862, 96.43072783368462808 ) ) ; -#40196 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #1985, #39373, #8319, #40380 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#40197 = ORIENTED_EDGE ( 'NONE', *, *, #15515, .F. ) ; -#40199 = AXIS2_PLACEMENT_3D ( 'NONE', #35068, #1547, #4005 ) ; -#40198 = CARTESIAN_POINT ( 'NONE', ( 13.50176803575202378, 185.2342124180282212, 105.4914585805791347 ) ) ; -#40200 = CARTESIAN_POINT ( 'NONE', ( -0.4543644846839952622, 210.9999999999920988, 75.55877896313789677 ) ) ; -#40201 = AXIS2_PLACEMENT_3D ( 'NONE', #6518, #12466, #25358 ) ; -#40202 = DIRECTION ( 'NONE', ( 0.7066795775021788018, -2.105283132027209225E-15, -0.7075337269285062458 ) ) ; -#40203 = CARTESIAN_POINT ( 'NONE', ( -39.28819007159129484, 119.6036315730871280, 87.80683070790931311 ) ) ; -#40204 = ORIENTED_EDGE ( 'NONE', *, *, #10397, .F. ) ; -#40205 = DIRECTION ( 'NONE', ( -1.387778780732453075E-15, -0.9743700557921584071, -0.2249510932971565402 ) ) ; -#40206 = EDGE_CURVE ( 'NONE', #1917, #407, #2709, .T. ) ; -#40207 = FACE_OUTER_BOUND ( 'NONE', #534, .T. ) ; -#40208 = EDGE_LOOP ( 'NONE', ( #21882, #27384, #32942, #33211 ) ) ; -#40209 = CARTESIAN_POINT ( 'NONE', ( 30.06905116326987937, 134.5124848999242602, 93.54214650380033902 ) ) ; -#40210 = ORIENTED_EDGE ( 'NONE', *, *, #20741, .T. ) ; -#40211 = CARTESIAN_POINT ( 'NONE', ( 30.07038801303579234, 136.6840993378064866, 94.26968325502151913 ) ) ; -#40212 = CARTESIAN_POINT ( 'NONE', ( -3.645810450028442506, 143.5597328077978716, 95.76474948167305001 ) ) ; -#40213 = LINE ( 'NONE', #17525, #18991 ) ; -#40214 = ORIENTED_EDGE ( 'NONE', *, *, #12252, .T. ) ; -#40215 = CARTESIAN_POINT ( 'NONE', ( -21.10566240416878259, 135.9749471196982995, 93.79477015577090526 ) ) ; -#40216 = CARTESIAN_POINT ( 'NONE', ( 13.92061689211388043, 122.0377087247195647, 152.1917184006619266 ) ) ; -#40217 = CARTESIAN_POINT ( 'NONE', ( 19.98271301993268523, 207.8686081833218111, 77.26500776042075813 ) ) ; -#40218 = CIRCLE ( 'NONE', #21308, 2.000000000000011546 ) ; -#40219 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#40220 = CARTESIAN_POINT ( 'NONE', ( 3.467226270562823398, 125.5966026506509792, 88.64708724200714585 ) ) ; -#40221 = ORIENTED_EDGE ( 'NONE', *, *, #1315, .T. ) ; -#40222 = ORIENTED_EDGE ( 'NONE', *, *, #26361, .T. ) ; -#40223 = CARTESIAN_POINT ( 'NONE', ( 46.04655628321543759, 186.9737579288344307, 105.3571666265285245 ) ) ; -#40224 = CARTESIAN_POINT ( 'NONE', ( 13.50176626421484904, 123.6934293455507543, 91.28055725774082418 ) ) ; -#40225 = DIRECTION ( 'NONE', ( -0.0006039748319369898531, 0.000000000000000000, -0.9999998176071844824 ) ) ; -#40226 = VECTOR ( 'NONE', #4140, 1000.000000000000114 ) ; -#40227 = DIRECTION ( 'NONE', ( 0.0006039748319481906373, 1.291365685536979971E-14, 0.9999998176071844824 ) ) ; -#40228 = VECTOR ( 'NONE', #14551, 1000.000000000000114 ) ; -#40229 = EDGE_CURVE ( 'NONE', #12094, #12603, #23115, .T. ) ; -#40230 = ORIENTED_EDGE ( 'NONE', *, *, #4506, .T. ) ; -#40231 = CARTESIAN_POINT ( 'NONE', ( 38.81252283515213009, 118.9905809030176727, 89.96796132571387261 ) ) ; -#40232 = EDGE_CURVE ( 'NONE', #21146, #28773, #8643, .T. ) ; -#40233 = CARTESIAN_POINT ( 'NONE', ( -28.46937268146193745, 181.4099652016123514, 104.2887163838427824 ) ) ; -#40234 = DIRECTION ( 'NONE', ( 0.9999998176071844824, 0.000000000000000000, -0.0006039748319386905326 ) ) ; -#40235 = DIRECTION ( 'NONE', ( -0.0004161288024548141697, 0.8480480897963675879, -0.5299191110250242032 ) ) ; -#40236 = CARTESIAN_POINT ( 'NONE', ( -25.84017943814999896, 190.8761150004999934, 106.6436162250000024 ) ) ; -#40237 = CARTESIAN_POINT ( 'NONE', ( -23.36160746070781613, 128.4700731989668157, 89.83983640152801797 ) ) ; -#40238 = CARTESIAN_POINT ( 'NONE', ( -35.95425951663850839, 207.4083918145487075, 77.10339231471580490 ) ) ; -#40239 = CARTESIAN_POINT ( 'NONE', ( -23.36055974375966571, 134.8407614670647661, 93.36323390285753021 ) ) ; -#40240 = LINE ( 'NONE', #25137, #1075 ) ; -#40241 = ORIENTED_EDGE ( 'NONE', *, *, #29751, .F. ) ; -#40242 = CARTESIAN_POINT ( 'NONE', ( -1.216565595234769148, 139.4623718050729053, 175.9799232390552390 ) ) ; -#40243 = CARTESIAN_POINT ( 'NONE', ( -20.26936642627390128, 184.3467633459427759, 105.0257816482483264 ) ) ; -#40244 = CIRCLE ( 'NONE', #14152, 6.000000000000001776 ) ; -#40245 = DIRECTION ( 'NONE', ( 0.0005884948869652767856, -0.2249510543002911089, 0.9743698870772615761 ) ) ; -#40246 = CARTESIAN_POINT ( 'NONE', ( 36.36530002739970513, 191.8380058348319892, 104.3412478323679835 ) ) ; -#40247 = CONICAL_SURFACE ( 'NONE', #4343, 48.00000000003070255, 0.7853981633973031729 ) ; -#40248 = CARTESIAN_POINT ( 'NONE', ( 36.54410887896000304, 191.3422811494999962, 106.4620144481000068 ) ) ; -#40249 = VECTOR ( 'NONE', #26588, 1000.000000000000227 ) ; -#40250 = ORIENTED_EDGE ( 'NONE', *, *, #12544, .T. ) ; -#40251 = ORIENTED_EDGE ( 'NONE', *, *, #7830, .T. ) ; -#40252 = DIRECTION ( 'NONE', ( -0.0002393071182784392798, -0.2252352986010042191, 0.9743043687658491381 ) ) ; -#40253 = EDGE_CURVE ( 'NONE', #6809, #25237, #30517, .T. ) ; -#40254 = CARTESIAN_POINT ( 'NONE', ( 39.04524183112422975, 209.7096538831000032, 73.53492182592451343 ) ) ; -#40255 = CONICAL_SURFACE ( 'NONE', #15468, 6.500001368651339817, 0.7853982200635908351 ) ; -#40256 = CARTESIAN_POINT ( 'NONE', ( 35.56535286263039808, 192.7868339794035251, 106.8337704962199268 ) ) ; -#40257 = FACE_OUTER_BOUND ( 'NONE', #13918, .T. ) ; -#40258 = CIRCLE ( 'NONE', #8857, 40.00000000000000000 ) ; -#40259 = VERTEX_POINT ( 'NONE', #14971 ) ; -#40260 = CARTESIAN_POINT ( 'NONE', ( -39.41844532849000160, 119.6025715269000074, 90.24298619069000438 ) ) ; -#40261 = DIRECTION ( 'NONE', ( 5.286776307738854230E-15, 0.9743700557921585181, 0.2249510932971559851 ) ) ; -#40262 = CARTESIAN_POINT ( 'NONE', ( -20.51767729163077547, 205.5669979433283743, 76.31342074382325791 ) ) ; -#40263 = DIRECTION ( 'NONE', ( 0.7856637146670527594, -0.6186538025871723967, 0.000000000000000000 ) ) ; -#40264 = ORIENTED_EDGE ( 'NONE', *, *, #26267, .T. ) ; -#40265 = LINE ( 'NONE', #12276, #11471 ) ; -#40266 = ADVANCED_FACE ( 'NONE', ( #27656 ), #3087, .T. ) ; -#40267 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.2249510932970937294, -0.9743700557921729510 ) ) ; -#40268 = CARTESIAN_POINT ( 'NONE', ( 23.36938019816961898, 177.0806351751306238, 103.5466879961430635 ) ) ; -#40269 = CARTESIAN_POINT ( 'NONE', ( 5.667964583423158231, 129.9727540529065948, 92.22183313054385678 ) ) ; -#40270 = CARTESIAN_POINT ( 'NONE', ( 0.5641566566382231196, 188.3875244742078223, 106.2241826925672257 ) ) ; -#40271 = FACE_OUTER_BOUND ( 'NONE', #19189, .T. ) ; -#40272 = VERTEX_POINT ( 'NONE', #24988 ) ; -#40273 = ORIENTED_EDGE ( 'NONE', *, *, #9550, .F. ) ; -#40274 = EDGE_CURVE ( 'NONE', #6653, #30059, #24146, .T. ) ; -#40275 = CARTESIAN_POINT ( 'NONE', ( -28.65284063177000462, 187.5359740265000141, 102.8273832512000041 ) ) ; -#40276 = CARTESIAN_POINT ( 'NONE', ( 2.674351632222999875, 190.4735952899999916, 103.9537630802000052 ) ) ; -#40277 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#40278 = AXIS2_PLACEMENT_3D ( 'NONE', #6223, #37316, #9507 ) ; -#40279 = ORIENTED_EDGE ( 'NONE', *, *, #13054, .F. ) ; -#40280 = ADVANCED_FACE ( 'NONE', ( #40294 ), #18603, .T. ) ; -#40281 = ORIENTED_EDGE ( 'NONE', *, *, #1784, .T. ) ; -#40282 = DIRECTION ( 'NONE', ( -0.9914446600668047616, -0.1273122756936073130, -0.02879358405500737073 ) ) ; -#40283 = CIRCLE ( 'NONE', #8219, 2.000000000000011546 ) ; -#40284 = ORIENTED_EDGE ( 'NONE', *, *, #16703, .F. ) ; -#40285 = ADVANCED_FACE ( 'NONE', ( #12487 ), #38032, .F. ) ; -#40286 = CIRCLE ( 'NONE', #37687, 22.50000000000899902 ) ; -#40287 = ADVANCED_FACE ( 'NONE', ( #19806 ), #4560, .F. ) ; -#40288 = ADVANCED_FACE ( 'NONE', ( #35139 ), #25187, .T. ) ; -#40289 = FACE_OUTER_BOUND ( 'NONE', #30180, .T. ) ; -#40290 = CARTESIAN_POINT ( 'NONE', ( -34.31311594311140567, 218.5902260770998282, 61.07922615589730952 ) ) ; -#40291 = CARTESIAN_POINT ( 'NONE', ( -13.73941655725531596, 125.3344943124112802, 174.7635725153712372 ) ) ; -#40292 = CARTESIAN_POINT ( 'NONE', ( -37.30470697817465009, 191.0308624572352869, 106.3365180619626784 ) ) ; -#40293 = PLANE ( 'NONE', #17725 ) ; -#40294 = FACE_OUTER_BOUND ( 'NONE', #7, .T. ) ; -#40295 = CARTESIAN_POINT ( 'NONE', ( -36.48933695153999679, 190.8968829416000119, 106.6933567144999984 ) ) ; -#40296 = ORIENTED_EDGE ( 'NONE', *, *, #28173, .F. ) ; -#40297 = CARTESIAN_POINT ( 'NONE', ( -0.4358427445845766135, 188.3875244028057807, 106.2247867227265630 ) ) ; -#40298 = CARTESIAN_POINT ( 'NONE', ( -35.74149330666463698, 191.6983459860854282, 103.9240585978979396 ) ) ; -#40299 = DIRECTION ( 'NONE', ( -0.7942820423213363679, -0.5918950211223027447, -0.1370267171630251690 ) ) ; -#40300 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #5845, #11991, #14859, #24476, #21188, #6236 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( -0.002831826805589694306, -0.001066225054260792546, 0.0006993766970681092147 ), - .UNSPECIFIED. ) ; -#40302 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971559851 ) ) ; -#40301 = CARTESIAN_POINT ( 'NONE', ( 18.00029424749897444, 179.6299767373378700, 101.6260513915634363 ) ) ; -#40303 = EDGE_CURVE ( 'NONE', #9411, #11556, #15949, .T. ) ; -#40304 = VERTEX_POINT ( 'NONE', #6742 ) ; -#40305 = VECTOR ( 'NONE', #10474, 1000.000000000000000 ) ; -#40306 = CARTESIAN_POINT ( 'NONE', ( -20.49970533150650454, 174.4001369415204863, 100.4419005550919906 ) ) ; -#40307 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#40308 = ORIENTED_EDGE ( 'NONE', *, *, #22435, .T. ) ; -#40309 = CARTESIAN_POINT ( 'NONE', ( 39.65655516771000322, 119.6738006429000052, 90.21213854658999765 ) ) ; -#40310 = DIRECTION ( 'NONE', ( 0.0005884949961244347353, -0.2249510543439056098, 0.9743698870671265722 ) ) ; -#40311 = PLANE ( 'NONE', #10380 ) ; -#40312 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060539, 0.9743698870671263501 ) ) ; -#40313 = LINE ( 'NONE', #14987, #32146 ) ; -#40314 = EDGE_LOOP ( 'NONE', ( #23058, #8217, #6898, #9759 ) ) ; -#40315 = EDGE_CURVE ( 'NONE', #7971, #645, #34541, .T. ) ; -#40316 = ORIENTED_EDGE ( 'NONE', *, *, #40044, .F. ) ; -#40317 = DIRECTION ( 'NONE', ( 0.7933533411653072021, -0.5930537057989940797, -0.1373964268091564245 ) ) ; -#40318 = CARTESIAN_POINT ( 'NONE', ( 13.53821688301358783, 110.1833198944638639, 152.0219651185704492 ) ) ; -#40319 = VERTEX_POINT ( 'NONE', #28443 ) ; -#40320 = EDGE_CURVE ( 'NONE', #8802, #3689, #6510, .T. ) ; -#40321 = CARTESIAN_POINT ( 'NONE', ( -36.18076212721910423, 190.9506060006740142, 106.8439620012120201 ) ) ; -#40322 = CARTESIAN_POINT ( 'NONE', ( -22.32836078412000091, 134.7284225427999900, 93.84982713985000657 ) ) ; -#40323 = EDGE_CURVE ( 'NONE', #22377, #32129, #26496, .T. ) ; -#40324 = VERTEX_POINT ( 'NONE', #11043 ) ; -#40325 = ORIENTED_EDGE ( 'NONE', *, *, #23305, .F. ) ; -#40326 = CARTESIAN_POINT ( 'NONE', ( 2.086697738779999867, 189.3871111185999894, 106.0559732620999966 ) ) ; -#40327 = EDGE_CURVE ( 'NONE', #9096, #19822, #31727, .T. ) ; -#40328 = CARTESIAN_POINT ( 'NONE', ( 13.49906568490447434, 124.5683833206837363, 88.67767665987204850 ) ) ; -#40329 = CARTESIAN_POINT ( 'NONE', ( -37.70496166274256922, 218.5902260770999987, 74.58127720802590943 ) ) ; -#40330 = CARTESIAN_POINT ( 'NONE', ( 5.219784935304125462, 148.4721570845296412, 93.92726757689347039 ) ) ; -#40331 = ORIENTED_EDGE ( 'NONE', *, *, #20500, .F. ) ; -#40332 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #36120, #14469, #5040, #30205, #29599, #24080, #8539, #11197, #10999, #4440 ), - .UNSPECIFIED., .F., .F., - ( 4, 1, 1, 2, 2, 4 ), - ( 0.000000000000000000, 0.2499999999999653055, 0.3749999999999281686, 0.4374999999999095168, 0.4999999999998909761, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#40333 = DIRECTION ( 'NONE', ( 0.7933533411653073131, -0.5930537057989907490, -0.1373964268091705798 ) ) ; -#40334 = AXIS2_PLACEMENT_3D ( 'NONE', #29956, #8283, #11964 ) ; -#40335 = DIRECTION ( 'NONE', ( -0.5605692184766052355, -0.5785654711199512690, 0.5924729081774768868 ) ) ; -#40336 = VERTEX_POINT ( 'NONE', #16943 ) ; -#40337 = PLANE ( 'NONE', #2557 ) ; -#40338 = ORIENTED_EDGE ( 'NONE', *, *, #7485, .T. ) ; -#40340 = CARTESIAN_POINT ( 'NONE', ( -2.435581690730916016, 190.9709058671855360, 106.3075837308457352 ) ) ; -#40339 = CARTESIAN_POINT ( 'NONE', ( -8.285764499747434897, 124.3653823074882467, 88.36991397916445123 ) ) ; -#40341 = VERTEX_POINT ( 'NONE', #14516 ) ; -#40342 = VERTEX_POINT ( 'NONE', #14112 ) ; -#40343 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #20824, #20196, #33277, #32686 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#40344 = VERTEX_POINT ( 'NONE', #5297 ) ; -#40345 = CARTESIAN_POINT ( 'NONE', ( 3.075208719997000184, 209.7418877938000037, 76.19223627437000346 ) ) ; -#40346 = DIRECTION ( 'NONE', ( 0.0005884949961246526600, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#40347 = ORIENTED_EDGE ( 'NONE', *, *, #8001, .T. ) ; -#40348 = ORIENTED_EDGE ( 'NONE', *, *, #39066, .T. ) ; -#40349 = VERTEX_POINT ( 'NONE', #29245 ) ; -#40350 = LINE ( 'NONE', #19080, #17812 ) ; -#40351 = PLANE ( 'NONE', #30893 ) ; -#40352 = CARTESIAN_POINT ( 'NONE', ( 30.05202364328564713, 126.8409241029907832, 91.48406572326082653 ) ) ; -#40353 = CARTESIAN_POINT ( 'NONE', ( 13.50283896178331311, 187.3734514894470351, 105.5750215595898283 ) ) ; -#40354 = DIRECTION ( 'NONE', ( 0.0002393071182785117316, 0.2252352986010040803, -0.9743043687658490271 ) ) ; -#40355 = CARTESIAN_POINT ( 'NONE', ( 16.84365520870601785, 125.8129638753691069, 178.9888696437699878 ) ) ; -#40356 = ORIENTED_EDGE ( 'NONE', *, *, #30743, .T. ) ; -#40357 = ADVANCED_FACE ( 'NONE', ( #26590 ), #39034, .F. ) ; -#40358 = ORIENTED_EDGE ( 'NONE', *, *, #38289, .F. ) ; -#40359 = EDGE_CURVE ( 'NONE', #36048, #4358, #23506, .T. ) ; -#40360 = AXIS2_PLACEMENT_3D ( 'NONE', #26717, #11171, #13826 ) ; -#40361 = VERTEX_POINT ( 'NONE', #29647 ) ; -#40362 = DIRECTION ( 'NONE', ( -0.7075227810178097432, 0.1590644159616022568, -0.6885564798298096090 ) ) ; -#40363 = EDGE_CURVE ( 'NONE', #6684, #29822, #23314, .T. ) ; -#40364 = FACE_OUTER_BOUND ( 'NONE', #13107, .T. ) ; -#40365 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921587402, -0.2249510932971550137 ) ) ; -#40366 = ADVANCED_FACE ( 'NONE', ( #14313 ), #24498, .F. ) ; -#40367 = CARTESIAN_POINT ( 'NONE', ( 6.065815740701999914, 163.2729245447999915, 152.4718672074000381 ) ) ; -#40368 = AXIS2_PLACEMENT_3D ( 'NONE', #85, #31174, #22178 ) ; -#40369 = ORIENTED_EDGE ( 'NONE', *, *, #27943, .F. ) ; -#40370 = CARTESIAN_POINT ( 'NONE', ( 1.447658031000570666, 152.0519508845351595, 130.6788418773748219 ) ) ; -#40371 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.3907310681030378707, 0.9205048790848744389 ) ) ; -#40372 = ORIENTED_EDGE ( 'NONE', *, *, #10984, .F. ) ; -#40373 = EDGE_CURVE ( 'NONE', #21410, #35217, #29444, .T. ) ; -#40374 = CARTESIAN_POINT ( 'NONE', ( -28.52670407937950969, 187.4270078119665754, 102.9410870260050928 ) ) ; -#40375 = DIRECTION ( 'NONE', ( 0.000000000000000000, -0.9743700557921586292, -0.2249510932971555410 ) ) ; -#40376 = EDGE_CURVE ( 'NONE', #30873, #23757, #1623, .T. ) ; -#40377 = CARTESIAN_POINT ( 'NONE', ( -37.47510786252718162, 212.6956757039803279, 73.24780480550954564 ) ) ; -#40378 = DIRECTION ( 'NONE', ( -0.1632030863883330296, 0.3417424275059343097, -0.9255143790539797077 ) ) ; -#40379 = ORIENTED_EDGE ( 'NONE', *, *, #15412, .F. ) ; -#40380 = CARTESIAN_POINT ( 'NONE', ( -22.49859347127474152, 158.2257569248202458, 98.76156587771905038 ) ) ; -#40381 = CARTESIAN_POINT ( 'NONE', ( 37.93821029086635122, 79.16788325310130858, 289.8002325176965996 ) ) ; -#40382 = CARTESIAN_POINT ( 'NONE', ( 22.78075325035244703, 147.9635827673721451, 94.31239968548003105 ) ) ; -#40383 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #38605, #16331, #6723, #7126 ), - .UNSPECIFIED., .F., .F., - ( 4, 4 ), - ( 0.000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#40384 = CARTESIAN_POINT ( 'NONE', ( 37.16421317187000284, 117.4633363709999969, 90.10791008674000580 ) ) ; -#40385 = VECTOR ( 'NONE', #37413, 1000.000000000000114 ) ; -#40386 = CARTESIAN_POINT ( 'NONE', ( 45.24519689809859813, 116.5437060779667036, 124.8975000631534158 ) ) ; -#40387 = EDGE_LOOP ( 'NONE', ( #6759, #37249, #5774, #34247 ) ) ; -#40388 = CARTESIAN_POINT ( 'NONE', ( 2.562147502058854442, 194.2771767931535294, 102.8967287192651696 ) ) ; -#40389 = ORIENTED_EDGE ( 'NONE', *, *, #5103, .T. ) ; -#40390 = DIRECTION ( 'NONE', ( 0.000000000000000000, 0.9743700557921578520, 0.2249510932971596766 ) ) ; -#40391 = VECTOR ( 'NONE', #1871, 1000.000000000000114 ) ; -#40392 = AXIS2_PLACEMENT_3D ( 'NONE', #17447, #1513, #4381 ) ; -#40393 = CARTESIAN_POINT ( 'NONE', ( -19.40844160272963137, 149.2436093538031514, 181.3008671212579088 ) ) ; -#40394 = AXIS2_PLACEMENT_3D ( 'NONE', #34528, #37825, #22103 ) ; -#40395 = CARTESIAN_POINT ( 'NONE', ( -38.19661910378999892, 118.7283168909000040, 90.15060258514999703 ) ) ; -#40396 = CARTESIAN_POINT ( 'NONE', ( 29.05352371370200615, 110.6131156702000027, 87.25023669171606855 ) ) ; -#40397 = CARTESIAN_POINT ( 'NONE', ( 38.57248824100825857, 118.4600016709538295, 89.66247826865570403 ) ) ; -#40398 = ORIENTED_EDGE ( 'NONE', *, *, #21370, .F. ) ; -#40399 = PLANE ( 'NONE', #18566 ) ; -#40400 = CARTESIAN_POINT ( 'NONE', ( -0.03375341898833555260, -31.76863880746333280, 137.4221703796379188 ) ) ; -#40401 = DIRECTION ( 'NONE', ( -0.9999998268368047727, -0.0001323825953879981883, 0.0005734119016092298913 ) ) ; -#40402 = PLANE ( 'NONE', #24704 ) ; -#40403 = CARTESIAN_POINT ( 'NONE', ( 17.27169418602116480, 122.3509344318320444, 172.9165784783710933 ) ) ; -#40404 = CARTESIAN_POINT ( 'NONE', ( -36.21229146569522328, 116.0839334804960856, 90.28965615584912996 ) ) ; -#40405 = EDGE_LOOP ( 'NONE', ( #38077, #38244, #38497, #30201 ) ) ; -#40406 = CARTESIAN_POINT ( 'NONE', ( 5.667895119723127095, 187.8687646092461421, 103.4296389354537524 ) ) ; -#40407 = CARTESIAN_POINT ( 'NONE', ( -30.07038801302202913, 174.6765699328746564, 103.0772613391864354 ) ) ; -#40408 = CARTESIAN_POINT ( 'NONE', ( 35.65259997913155132, 138.3326317399398988, 284.1430326337134602 ) ) ; -#40409 = ORIENTED_EDGE ( 'NONE', *, *, #7632, .T. ) ; -#40410 = FACE_OUTER_BOUND ( 'NONE', #30915, .T. ) ; -#40411 = ADVANCED_FACE ( 'NONE', ( #5087 ), #32707, .T. ) ; -#40412 = CARTESIAN_POINT ( 'NONE', ( 15.99999293039724257, 151.9655111556795362, 94.72726368743165892 ) ) ; -#40413 = EDGE_CURVE ( 'NONE', #20649, #21381, #11239, .T. ) ; -#40414 = ORIENTED_EDGE ( 'NONE', *, *, #30469, .F. ) ; -#40415 = DIRECTION ( 'NONE', ( -0.5669487081581161547, -0.8237530954830113439, 0.000000000000000000 ) ) ; -#40416 = VECTOR ( 'NONE', #28368, 1000.000000000000227 ) ; -#40417 = CARTESIAN_POINT ( 'NONE', ( -43.10734247109012784, 121.9064515807241804, 87.96659200322474703 ) ) ; -#40418 = EDGE_LOOP ( 'NONE', ( #8287, #2577 ) ) ; -#40419 = CARTESIAN_POINT ( 'NONE', ( 36.31872422425588098, 190.9500732230917777, 106.7935857671626820 ) ) ; -#40420 = VECTOR ( 'NONE', #25323, 1000.000000000000227 ) ; -#40421 = CARTESIAN_POINT ( 'NONE', ( 22.50029346826757859, 151.8610258625533049, 95.21236487778058688 ) ) ; -#40422 = CARTESIAN_POINT ( 'NONE', ( -26.15709881241999923, 190.6415270226000018, 106.8956296771000041 ) ) ; -#40423 = CARTESIAN_POINT ( 'NONE', ( 30.07151160793498690, 176.9174375397160475, 103.2802541386858053 ) ) ; -#40424 = CONICAL_SURFACE ( 'NONE', #5160, 7.002965970566410014, 0.7854058041637707044 ) ; -#40425 = FACE_OUTER_BOUND ( 'NONE', #39656, .T. ) ; -#40426 = ORIENTED_EDGE ( 'NONE', *, *, #19094, .T. ) ; -#40427 = DIRECTION ( 'NONE', ( -0.0005884949961235566400, 0.2249510543439049437, -0.9743698870671267942 ) ) ; -#40428 = CARTESIAN_POINT ( 'NONE', ( -19.26392064910394808, 124.3392765983403621, 178.4079915668605736 ) ) ; -#40429 = CARTESIAN_POINT ( 'NONE', ( -13.73975480784592307, 125.4641165510608261, 174.2036076504483901 ) ) ; -#40430 = CARTESIAN_POINT ( 'NONE', ( -37.30377723581143812, 168.2094018080552189, 182.6166685593908596 ) ) ; -#40431 = ORIENTED_EDGE ( 'NONE', *, *, #623, .F. ) ; -#40432 = CARTESIAN_POINT ( 'NONE', ( 22.64037623556000156, 158.4942800668000018, 96.48711187617001883 ) ) ; -#40433 = B_SPLINE_CURVE_WITH_KNOTS ( 'NONE', 3, - ( #2903, #34373, #9257, #9055, #18823, #30534 ), - .UNSPECIFIED., .F., .F., - ( 4, 2, 4 ), - ( 0.000000000000000000, 0.5000000000000000000, 1.000000000000000000 ), - .UNSPECIFIED. ) ; -#40434 = DIRECTION ( 'NONE', ( 0.0005884949961247158690, -0.2249510543439060817, 0.9743698870671263501 ) ) ; -#40435 = FACE_OUTER_BOUND ( 'NONE', #15966, .T. ) ; -#40436 = EDGE_CURVE ( 'NONE', #8964, #30098, #15313, .T. ) ; -#40437 = LINE ( 'NONE', #3225, #16116 ) ; -#40438 = CARTESIAN_POINT ( 'NONE', ( -27.14440137765999950, 187.2725072407000084, 105.4703439821000046 ) ) ; -#40439 = CARTESIAN_POINT ( 'NONE', ( -12.64230137995684444, 181.7534649825922770, 101.7124881005001669 ) ) ; -#40440 = AXIS2_PLACEMENT_3D ( 'NONE', #3157, #21598, #40371 ) ; -#40441 = CARTESIAN_POINT ( 'NONE', ( 1.561641312891000055, 129.8597348847000035, 92.71137285944000439 ) ) ; -#40442 = CARTESIAN_POINT ( 'NONE', ( -23.36190171889894529, 184.1216419186529833, 102.1748637788761727 ) ) ; -#40443 = CARTESIAN_POINT ( 'NONE', ( 30.18297413640002702, 185.3389242632447917, 102.7656572717241374 ) ) ; -#40444 = FACE_OUTER_BOUND ( 'NONE', #22921, .T. ) ; -#40445 = CARTESIAN_POINT ( 'NONE', ( -37.56217811679143637, 145.6431275960571838, 282.5778664123586168 ) ) ; -#40446 = AXIS2_PLACEMENT_3D ( 'NONE', #11861, #11245, #14923 ) ; -#40447 = CARTESIAN_POINT ( 'NONE', ( -24.42595481105102451, 104.1131156702295186, 90.28253750387099785 ) ) ; -#40448 = CARTESIAN_POINT ( 'NONE', ( 36.18973506411000329, 192.0171769533999964, 105.0450383464999931 ) ) ; -#40449 = AXIS2_PLACEMENT_3D ( 'NONE', #11319, #26071, #7641 ) ; -#40450 = AXIS2_PLACEMENT_3D ( 'NONE', #27417, #36166, #11437 ) ; -#40452 = VERTEX_POINT ( 'NONE', #13901 ) ; -#40451 = CARTESIAN_POINT ( 'NONE', ( 36.44358477468000501, 191.0363251205000097, 106.6791379425000059 ) ) ; -#40453 = ORIENTED_EDGE ( 'NONE', *, *, #22339, .F. ) ; -#40454 = EDGE_LOOP ( 'NONE', ( #18618, #22192, #17234, #33126 ) ) ; -#40455 = ORIENTED_EDGE ( 'NONE', *, *, #32022, .F. ) ; -#40456 = DIRECTION ( 'NONE', ( 0.6974473308752756617, 0.000000000000000000, -0.7166360447639747999 ) ) ; -#40457 = CARTESIAN_POINT ( 'NONE', ( 20.48041080035920558, 211.0898936264048587, 74.21271871319238755 ) ) ; -#40458 = PLANE ( 'NONE', #20621 ) ; -#40459 = DIRECTION ( 'NONE', ( -0.7857167650892390443, 0.6185862428610306996, 0.0004745532376930882020 ) ) ; -#40460 = EDGE_CURVE ( 'NONE', #26477, #35520, #20516, .T. ) ; -#40461 = EDGE_CURVE ( 'NONE', #22722, #33491, #11455, .T. ) ; -#40462 = ORIENTED_EDGE ( 'NONE', *, *, #30050, .F. ) ; -#40463 = CARTESIAN_POINT ( 'NONE', ( 36.04770605913999759, 191.4287702289000208, 103.6964475062000162 ) ) ; -#40464 = CARTESIAN_POINT ( 'NONE', ( -15.99974174651862313, 174.5231975350379514, 99.95452847233616467 ) ) ; -#40465 = FACE_BOUND ( 'NONE', #708, .T. ) ; -ENDSEC; -END-ISO-10303-21;